diff --git a/.github/workflows/compile-rtk-everywhere.yml b/.github/workflows/compile-rtk-everywhere.yml index 6abbfafff..e17b5047e 100644 --- a/.github/workflows/compile-rtk-everywhere.yml +++ b/.github/workflows/compile-rtk-everywhere.yml @@ -6,11 +6,7 @@ on: env: FILENAME_PREFIX: RTK_Everywhere_Firmware FIRMWARE_VERSION_MAJOR: 2 - FIRMWARE_VERSION_MINOR: 2 - POINTPERFECT_LBAND_TOKEN: ${{ secrets.POINTPERFECT_LBAND_TOKEN }} - POINTPERFECT_IP_TOKEN: ${{ secrets.POINTPERFECT_IP_TOKEN }} - POINTPERFECT_LBAND_IP_TOKEN: ${{ secrets.POINTPERFECT_LBAND_IP_TOKEN }} - POINTPERFECT_RTCM_TOKEN: ${{ secrets.POINTPERFECT_RTCM_TOKEN }} + FIRMWARE_VERSION_MINOR: 3 CORE_VERSION: 3.0.7 jobs: @@ -54,116 +50,49 @@ jobs: echo "DEBUG_LEVEL=error" >> "$GITHUB_ENV" fi - - name: Setup Arduino CLI - uses: arduino/setup-arduino-cli@v1 - - - name: Start config file - run: arduino-cli config init --additional-urls "https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json,https://espressif.github.io/arduino-esp32/package_esp32_dev_index.json" - - - name: Update core index - run: arduino-cli core update-index - - - name: Update library index - run: arduino-cli lib update-index - - - name: Install platform - run: arduino-cli core install esp32:esp32@${{ env.CORE_VERSION }} - - - name: Get IDF version + - name: Run Dockerfile and copy files + # The --quiet suppresses the build output, keeping the secrets safe run: | - cd /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs - IDF_VERSION=$(ls | grep idf-release) - echo "ESP_IDF=${IDF_VERSION}" >> "$GITHUB_ENV" - - - name: Get Known Libraries - run: arduino-cli lib install - ArduinoJson@7.0.4 - ESP32Time@2.0.0 - ESP32_BleSerial@2.0.1 - "ESP32-OTA-Pull"@1.0.0 - JC_Button@2.1.2 - PubSubClient@2.8.0 - "SdFat"@2.1.1 - "SparkFun LIS2DH12 Arduino Library"@1.0.3 - "SparkFun MAX1704x Fuel Gauge Arduino Library"@1.0.4 - "SparkFun u-blox GNSS v3"@3.1.8 - "SparkFun Qwiic OLED Arduino Library"@1.0.13 - SSLClientESP32@2.0.0 - "SparkFun Extensible Message Parser"@1.0.2 - "SparkFun BQ40Z50 Battery Manager Arduino Library"@1.0.0 - "ArduinoMqttClient"@0.1.8 - "SparkFun u-blox PointPerfect Library"@1.11.4 - "SparkFun IM19 IMU Arduino Library"@1.0.1 - "SparkFun UM980 Triband RTK GNSS Arduino Library"@1.0.4 - "SparkFun LG290P Quadband RTK GNSS Arduino Library"@1.0.8 - "SparkFun I2C Expander Arduino Library"@1.0.1 - - - name: Patch libmbedtls - run: | - cd Firmware/RTK_Everywhere/Patch/ - cp libmbedtls.a /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs/${{ env.ESP_IDF }}/esp32/lib/libmbedtls.a - cp libmbedtls_2.a /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs/${{ env.ESP_IDF }}/esp32/lib/libmbedtls_2.a - cp libmbedcrypto.a /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs/${{ env.ESP_IDF }}/esp32/lib/libmbedcrypto.a - cp libmbedx509.a /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs/${{ env.ESP_IDF }}/esp32/lib/libmbedx509.a - - - name: Patch NetworkEvents - run: | - cd Firmware/RTK_Everywhere/Patch/ - cp NetworkEvents.* /home/runner/.arduino15/packages/esp32/hardware/esp32/${{ env.CORE_VERSION }}/libraries/Network/src/ - - - name: Setup Python - uses: actions/setup-python@v4 - with: - python-version: '3.10' - - # Configure Python - now we have Python installed, we need to provide everything needed by esptool otherwise the compile fails - - name: Configure Python - run: | - pip3 install pyserial - - - name: Update index_html - run: | - cd Firmware/Tools - python index_html_zipper.py ../RTK_Everywhere/AP-Config/index.html ../RTK_Everywhere/form.h - - - name: Update main_js - run: | - cd Firmware/Tools - python main_js_zipper.py ../RTK_Everywhere/AP-Config/src/main.js ../RTK_Everywhere/form.h + cd ./Firmware + echo "*** The docker build is quiet to protect the GitHub secrets ***" + docker build -t rtk_everywhere_firmware --no-cache --quiet \ + --build-arg CORE_VERSION=${{ env.CORE_VERSION }} \ + --build-arg FIRMWARE_VERSION_MAJOR=${{ env.FIRMWARE_VERSION_MAJOR }} \ + --build-arg FIRMWARE_VERSION_MINOR=${{ env.FIRMWARE_VERSION_MINOR }} \ + --build-arg POINTPERFECT_LBAND_TOKEN="${{ secrets.POINTPERFECT_LBAND_TOKEN }}" \ + --build-arg POINTPERFECT_IP_TOKEN="${{ secrets.POINTPERFECT_IP_TOKEN }}" \ + --build-arg POINTPERFECT_LBAND_IP_TOKEN="${{ secrets.POINTPERFECT_LBAND_IP_TOKEN }}" \ + --build-arg POINTPERFECT_RTCM_TOKEN="${{ secrets.POINTPERFECT_RTCM_TOKEN }}" \ + --build-arg ENABLE_DEVELOPER=${{ env.ENABLE_DEVELOPER }} \ + --build-arg DEBUG_LEVEL=${{ env.DEBUG_LEVEL }} \ + . + docker create --name=rtk_everywhere rtk_everywhere_firmware:latest + mkdir ./build + docker cp rtk_everywhere:/RTK_Everywhere.ino.bin ./build + docker cp rtk_everywhere:/RTK_Everywhere.ino.elf ./build + docker cp rtk_everywhere:/RTK_Everywhere/form.h ./RTK_Everywhere + docker container rm rtk_everywhere - name: Commit and push form.h - uses: actions-js/push@master - with: - github_token: ${{ secrets.GITHUB_TOKEN }} - directory: ./Firmware/RTK_Everywhere - branch: ${{ env.BRANCH }} - message: 'Update form.h via Python' - - - name: Copy custom RTKEverywhere.csv - run: - # Compile the source using the 16MB partition file. Other platforms (ie, the 8MB Postcard) use - # the same binary but use a different partition binary during the upload phase. - # View the different RTK partition files used during upload here: - # https://github.com/sparkfun/SparkFun_RTK_Firmware_Uploader/tree/main/RTK_Firmware_Uploader/resource - cp Firmware/RTKEverywhere.csv /home/runner/.arduino15/packages/esp32/hardware/esp32/${{ env.CORE_VERSION }}/tools/partitions/RTKEverywhere.csv - - - name: Compile Sketch - run: arduino-cli compile --fqbn "esp32:esp32:esp32":DebugLevel=${{ env.DEBUG_LEVEL }},PSRAM=enabled ./Firmware/RTK_Everywhere/RTK_Everywhere.ino - --build-property build.partitions=RTKEverywhere - --build-property upload.maximum_size=4055040 - --build-property "compiler.cpp.extra_flags=-MMD -c \"-DPOINTPERFECT_LBAND_TOKEN=$POINTPERFECT_LBAND_TOKEN\" \"-DPOINTPERFECT_IP_TOKEN=$POINTPERFECT_IP_TOKEN\" \"-DPOINTPERFECT_LBAND_IP_TOKEN=$POINTPERFECT_LBAND_IP_TOKEN\" \"-DPOINTPERFECT_RTCM_TOKEN=$POINTPERFECT_RTCM_TOKEN\" \"-DFIRMWARE_VERSION_MAJOR=$FIRMWARE_VERSION_MAJOR\" \"-DFIRMWARE_VERSION_MINOR=$FIRMWARE_VERSION_MINOR\" \"-DENABLE_DEVELOPER=${{ env.ENABLE_DEVELOPER }}\"" - --export-binaries + run: | + git config --local user.email "github-actions[bot]@users.noreply.github.com" + git config --local user.name "github-actions[bot]" + git add ./Firmware/RTK_Everywhere/form.h + git commit -m "Update form.h via Python" + git push origin ${{ env.BRANCH }} + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} - name: Rename binary run: | - cd Firmware/RTK_Everywhere/build/esp32.esp32.esp32/ + cd ./Firmware/build mv RTK_Everywhere.ino.bin ${{ env.FILENAME_PREFIX }}${{ env.FILE_ENDING_UNDERSCORE }}.bin - name: Upload binary to action uses: actions/upload-artifact@v4 with: name: ${{ env.FILENAME_PREFIX }}${{ env.FILE_ENDING_UNDERSCORE }} - path: ./Firmware/RTK_Everywhere/build/esp32.esp32.esp32/${{ env.FILENAME_PREFIX }}${{ env.FILE_ENDING_UNDERSCORE }}.bin + path: ./Firmware/build/${{ env.FILENAME_PREFIX }}${{ env.FILE_ENDING_UNDERSCORE }}.bin - name: Push binary to Binaries Repo @@ -172,7 +101,7 @@ jobs: env: API_TOKEN_GITHUB: ${{ secrets.PUSH_BINARIES_REPO }} with: - source_file: ./Firmware/RTK_Everywhere/build/esp32.esp32.esp32/${{ env.FILENAME_PREFIX }}${{ env.FILE_ENDING_UNDERSCORE }}.bin + source_file: ./Firmware/build/${{ env.FILENAME_PREFIX }}${{ env.FILE_ENDING_UNDERSCORE }}.bin destination_repo: 'sparkfun/SparkFun_RTK_Everywhere_Firmware_Binaries' destination_folder: '' user_email: 'nathan@sparkfun.com' diff --git a/.github/workflows/non-release-build.yml b/.github/workflows/non-release-build.yml index 7756986d8..8802349b5 100644 --- a/.github/workflows/non-release-build.yml +++ b/.github/workflows/non-release-build.yml @@ -7,9 +7,6 @@ env: FILENAME_PREFIX: RTK_Everywhere_Firmware FIRMWARE_VERSION_MAJOR: 99 FIRMWARE_VERSION_MINOR: 99 - POINTPERFECT_LBAND_TOKEN: ${{ secrets.POINTPERFECT_LBAND_TOKEN }} - POINTPERFECT_IP_TOKEN: ${{ secrets.POINTPERFECT_IP_TOKEN }} - POINTPERFECT_LBAND_IP_TOKEN: ${{ secrets.POINTPERFECT_LBAND_IP_TOKEN }} CORE_VERSION: 3.0.7 jobs: @@ -50,105 +47,41 @@ jobs: echo "JSON_ENDING=-${{ steps.dateNoScores.outputs.dateNoScores }}" >> "$GITHUB_ENV" echo "JSON_FILE_NAME=RTK-Everywhere-RC-Firmware.json" >> "$GITHUB_ENV" echo "ENABLE_DEVELOPER=true" >> "$GITHUB_ENV" - echo "DEBUG_LEVEL=debug" >> "$GITHUB_ENV" + echo "DEBUG_LEVEL=error" >> "$GITHUB_ENV" fi - - name: Setup Arduino CLI - uses: arduino/setup-arduino-cli@v1 - - - name: Start config file - run: arduino-cli config init --additional-urls "https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json,https://espressif.github.io/arduino-esp32/package_esp32_dev_index.json" - - - name: Update core index - run: arduino-cli core update-index - - - name: Update library index - run: arduino-cli lib update-index - - - name: Install platform - run: arduino-cli core install esp32:esp32@${{ env.CORE_VERSION }} - - - name: Get IDF version - run: | - cd /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs - IDF_VERSION=$(ls | grep idf-release) - echo "ESP_IDF=${IDF_VERSION}" >> "$GITHUB_ENV" - - - name: Get Known Libraries - run: arduino-cli lib install - ArduinoJson@7.0.4 - ESP32Time@2.0.0 - ESP32_BleSerial@2.0.1 - "ESP32-OTA-Pull"@1.0.0 - JC_Button@2.1.2 - PubSubClient@2.8.0 - "SdFat"@2.1.1 - "SparkFun LIS2DH12 Arduino Library"@1.0.3 - "SparkFun MAX1704x Fuel Gauge Arduino Library"@1.0.4 - "SparkFun u-blox GNSS v3"@3.1.8 - "SparkFun Qwiic OLED Arduino Library"@1.0.13 - SSLClientESP32@2.0.0 - "SparkFun Extensible Message Parser"@1.0.2 - "SparkFun BQ40Z50 Battery Manager Arduino Library"@1.0.0 - "ArduinoMqttClient"@0.1.8 - "SparkFun u-blox PointPerfect Library"@1.11.4 - "SparkFun IM19 IMU Arduino Library"@1.0.1 - "SparkFun UM980 Triband RTK GNSS Arduino Library"@1.0.4 - "SparkFun LG290P Quadband RTK GNSS Arduino Library"@1.0.7 - "SparkFun I2C Expander Arduino Library"@1.0.1 - - - name: Patch libmbedtls - run: | - cd Firmware/RTK_Everywhere/Patch/ - cp libmbedtls.a /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs/${{ env.ESP_IDF }}/esp32/lib/libmbedtls.a - cp libmbedtls_2.a /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs/${{ env.ESP_IDF }}/esp32/lib/libmbedtls_2.a - cp libmbedcrypto.a /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs/${{ env.ESP_IDF }}/esp32/lib/libmbedcrypto.a - cp libmbedx509.a /home/runner/.arduino15/packages/esp32/tools/esp32-arduino-libs/${{ env.ESP_IDF }}/esp32/lib/libmbedx509.a - - - name: Patch NetworkEvents - run: | - cd Firmware/RTK_Everywhere/Patch/ - cp NetworkEvents.* /home/runner/.arduino15/packages/esp32/hardware/esp32/${{ env.CORE_VERSION }}/libraries/Network/src/ - - - name: Setup Python - uses: actions/setup-python@v4 - with: - python-version: '3.10' - - # Configure Python - now we have Python installed, we need to provide everything needed by esptool otherwise the compile fails - - name: Configure Python + - name: Run Dockerfile and copy files + # The --quiet suppresses the build output, keeping the secrets safe run: | - pip3 install pyserial - - - name: Update index_html - run: | - cd Firmware/Tools - python index_html_zipper.py ../RTK_Everywhere/AP-Config/index.html ../RTK_Everywhere/form.h - - - name: Update main_js - run: | - cd Firmware/Tools - python main_js_zipper.py ../RTK_Everywhere/AP-Config/src/main.js ../RTK_Everywhere/form.h + cd ./Firmware + echo "*** The docker build is quiet to protect the GitHub secrets ***" + docker build -t rtk_everywhere_firmware --no-cache --quiet \ + --build-arg CORE_VERSION=${{ env.CORE_VERSION }} \ + --build-arg FIRMWARE_VERSION_MAJOR=${{ env.FIRMWARE_VERSION_MAJOR }} \ + --build-arg FIRMWARE_VERSION_MINOR=${{ env.FIRMWARE_VERSION_MINOR }} \ + --build-arg POINTPERFECT_LBAND_TOKEN="${{ secrets.POINTPERFECT_LBAND_TOKEN }}" \ + --build-arg POINTPERFECT_IP_TOKEN="${{ secrets.POINTPERFECT_IP_TOKEN }}" \ + --build-arg POINTPERFECT_LBAND_IP_TOKEN="${{ secrets.POINTPERFECT_LBAND_IP_TOKEN }}" \ + --build-arg POINTPERFECT_RTCM_TOKEN="${{ secrets.POINTPERFECT_RTCM_TOKEN }}" \ + --build-arg ENABLE_DEVELOPER=${{ env.ENABLE_DEVELOPER }} \ + --build-arg DEBUG_LEVEL=${{ env.DEBUG_LEVEL }} \ + . + docker create --name=rtk_everywhere rtk_everywhere_firmware:latest + mkdir ./build + docker cp rtk_everywhere:/RTK_Everywhere.ino.bin ./build + docker cp rtk_everywhere:/RTK_Everywhere.ino.elf ./build + docker cp rtk_everywhere:/RTK_Everywhere/form.h ./RTK_Everywhere + docker container rm rtk_everywhere - name: Commit and push form.h - uses: actions-js/push@master - with: - github_token: ${{ secrets.GITHUB_TOKEN }} - directory: ./Firmware/RTK_Everywhere - branch: ${{ env.BRANCH }} - message: 'Update form.h via Python' - - - name: Copy custom RTKEverywhere.csv - run: - # Use the 16MB partitions by default. 8MB (Postcard) partitions must be compiled separately - cp Firmware/RTKEverywhere.csv /home/runner/.arduino15/packages/esp32/hardware/esp32/${{ env.CORE_VERSION }}/tools/partitions/RTKEverywhere.csv - - - name: Compile Sketch - run: arduino-cli compile --fqbn "esp32:esp32:esp32":DebugLevel=${{ env.DEBUG_LEVEL }},PSRAM=enabled ./Firmware/RTK_Everywhere/RTK_Everywhere.ino - --build-property build.partitions=RTKEverywhere - --build-property upload.maximum_size=4055040 - --build-property "compiler.cpp.extra_flags=-MMD -c \"-DPOINTPERFECT_LBAND_TOKEN=$POINTPERFECT_LBAND_TOKEN\" \"-DPOINTPERFECT_IP_TOKEN=$POINTPERFECT_IP_TOKEN\" \"-DPOINTPERFECT_LBAND_IP_TOKEN=$POINTPERFECT_LBAND_IP_TOKEN\" \"-DFIRMWARE_VERSION_MAJOR=$FIRMWARE_VERSION_MAJOR\" \"-DFIRMWARE_VERSION_MINOR=$FIRMWARE_VERSION_MINOR\" \"-DENABLE_DEVELOPER=${{ env.ENABLE_DEVELOPER }}\"" - --export-binaries + run: | + git config --local user.email "github-actions[bot]@users.noreply.github.com" + git config --local user.name "github-actions[bot]" + git add ./Firmware/RTK_Everywhere/form.h + git commit -m "Update form.h via Python" + git push origin ${{ env.BRANCH }} + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} - name: Create artifact name run: | @@ -156,13 +89,14 @@ jobs: - name: Create artifact directory run: | - cd Firmware/RTK_Everywhere/build/esp32.esp32.esp32/ + cd ./Firmware/build mkdir ${{ env.ARTIFACT }} mv RTK_Everywhere.ino.bin ${{ env.ARTIFACT }} + mv RTK_Everywhere.ino.elf ${{ env.ARTIFACT }} - name: Upload artifact directory to action - avoid double-zip - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: ${{ env.ARTIFACT }} - path: Firmware/RTK_Everywhere/build/esp32.esp32.esp32/${{ env.ARTIFACT }} + path: ./Firmware/build/${{ env.ARTIFACT }} retention-days: 7 diff --git a/Firmware/Dockerfile b/Firmware/Dockerfile new file mode 100644 index 000000000..e687f0841 --- /dev/null +++ b/Firmware/Dockerfile @@ -0,0 +1,139 @@ +FROM ubuntu:latest AS upstream + +ARG DEBIAN_FRONTEND=noninteractive + +ARG CORE_VERSION=3.0.7 + +ARG FIRMWARE_VERSION_MAJOR=99 +ARG FIRMWARE_VERSION_MINOR=99 + +# ESP32 Core Debug Level +# We use "none" for releases and "error" for release_candidate +# You may find "verbose" useful while you are debugging your changes +ARG DEBUG_LEVEL=error + +# Developer Mode +# You may find "true" useful while you are making changes +# Set to false for releases +ARG ENABLE_DEVELOPER=true + +# arduino-cli warnings: none default more all +ARG WARNINGS=default + +# If you have your own u-blox PointPerfect token(s), define them here +# or pass in as args when building the Dockerfile +# POINTPERFECT_LBAND_TOKEN is the token for the deprecated u-blox L-band SPARTN service +# POINTPERFECT_IP_TOKEN is the token for the deprecated u-blox IP SPARTN service +# POINTPERFECT_LBAND_IP_TOKEN is the token for the deprecated u-blox combined L-band and IP SPARTN service +# POINTPERFECT_RTCM_TOKEN is the token for the u-blox RTCM over NTRIP service +ARG POINTPERFECT_LBAND_TOKEN=0xAA,0xBB,0xCC,0xDD,0x00,0x11,0x22,0x33,0x0A,0x0B,0x0C,0x0D,0x00,0x01,0x02,0x03 +ARG POINTPERFECT_IP_TOKEN=0xAA,0xBB,0xCC,0xDD,0x00,0x11,0x22,0x33,0x0A,0x0B,0x0C,0x0D,0x00,0x01,0x02,0x03 +ARG POINTPERFECT_LBAND_IP_TOKEN=0xAA,0xBB,0xCC,0xDD,0x00,0x11,0x22,0x33,0x0A,0x0B,0x0C,0x0D,0x00,0x01,0x02,0x03 +ARG POINTPERFECT_RTCM_TOKEN=0xAA,0xBB,0xCC,0xDD,0x00,0x11,0x22,0x33,0x0A,0x0B,0x0C,0x0D,0x00,0x01,0x02,0x03 + +# Get curl and python3 +RUN apt-get update \ + && apt-get install -y curl python3 python3-pip python3-venv \ + && apt-get clean \ + && rm -rf /var/lib/apt/lists/* + +# Avoid the externally managed environment constraint +RUN PYTHON_VER=$(ls /usr/lib | grep python3.) \ + && echo "Python version: ${PYTHON_VER}" \ + && rm /usr/lib/${PYTHON_VER}/EXTERNALLY-MANAGED + +# Install Python dependencies - esptool needs pyserial +#RUN python3 -m pip install --upgrade pip && \ +RUN pip install pyserial + +# Setup Arduino CLI +#RUN curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh +RUN curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | sh + +# Start config file +RUN arduino-cli config init --additional-urls https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json,https://espressif.github.io/arduino-esp32/package_esp32_dev_index.json + +# Update core index +RUN arduino-cli core update-index + +# Update library index +RUN arduino-cli lib update-index + +# Install platform +RUN arduino-cli core install "esp32:esp32@${CORE_VERSION}" + +# Get Known Libraries +RUN arduino-cli lib install ArduinoJson@7.0.4 +RUN arduino-cli lib install ESP32Time@2.0.0 +RUN arduino-cli lib install ESP32_BleSerial@2.0.1 +RUN arduino-cli lib install "ESP32-OTA-Pull"@1.0.0 +RUN arduino-cli lib install JC_Button@2.1.2 +RUN arduino-cli lib install PubSubClient@2.8.0 +RUN arduino-cli lib install "SdFat"@2.1.1 +RUN arduino-cli lib install "SparkFun LIS2DH12 Arduino Library"@1.0.3 +RUN arduino-cli lib install "SparkFun MAX1704x Fuel Gauge Arduino Library"@1.0.4 +RUN arduino-cli lib install "SparkFun u-blox GNSS v3"@3.1.10 +RUN arduino-cli lib install "SparkFun Qwiic OLED Arduino Library"@1.0.13 +RUN arduino-cli lib install SSLClientESP32@2.0.0 +RUN arduino-cli lib install "SparkFun Extensible Message Parser"@1.0.4 +RUN arduino-cli lib install "SparkFun BQ40Z50 Battery Manager Arduino Library"@1.0.0 +RUN arduino-cli lib install "ArduinoMqttClient"@0.1.8 +RUN arduino-cli lib install "SparkFun u-blox PointPerfect Library"@1.11.4 +RUN arduino-cli lib install "SparkFun IM19 IMU Arduino Library"@1.0.1 +RUN arduino-cli lib install "SparkFun UM980 Triband RTK GNSS Arduino Library"@1.0.5 +RUN arduino-cli lib install "SparkFun LG290P Quadband RTK GNSS Arduino Library"@1.0.8 +RUN arduino-cli lib install "SparkFun I2C Expander Arduino Library"@1.0.1 +RUN arduino-cli lib install "SparkFun Apple Accessory Arduino Library"@3.0.9 +RUN arduino-cli lib install "SparkFun Authentication Coprocessor Arduino Library"@1.0.0 +RUN arduino-cli lib install "SparkFun Toolkit"@1.0.6 + +# Copy RTK_Everywhere and build deployment image +FROM upstream AS deployment + +# Add the source files +ADD . . + +# Patch libmbedtls and libbt +RUN cd ./RTK_Everywhere/Patch \ + && ESP_IDF=$(ls /root/.arduino15/packages/esp32/tools/esp32-arduino-libs | grep idf-release) \ + && echo "ESP IDF Version: ${ESP_IDF}" \ + && cp libmbedtls.a "/root/.arduino15/packages/esp32/tools/esp32-arduino-libs/${ESP_IDF}/esp32/lib/libmbedtls.a" \ + && cp libmbedtls_2.a "/root/.arduino15/packages/esp32/tools/esp32-arduino-libs/${ESP_IDF}/esp32/lib/libmbedtls_2.a" \ + && cp libmbedcrypto.a "/root/.arduino15/packages/esp32/tools/esp32-arduino-libs/${ESP_IDF}/esp32/lib/libmbedcrypto.a" \ + && cp libmbedx509.a "/root/.arduino15/packages/esp32/tools/esp32-arduino-libs/${ESP_IDF}/esp32/lib/libmbedx509.a" \ + && cp libbt.a "/root/.arduino15/packages/esp32/tools/esp32-arduino-libs/${ESP_IDF}/esp32/lib/libbt.a" + +# Patch NetworkEvents +RUN cd ./RTK_Everywhere/Patch \ + && cp NetworkEvents.* "/root/.arduino15/packages/esp32/hardware/esp32/${CORE_VERSION}/libraries/Network/src/" + +# Update form.h with index_html and main_js +RUN cd ./Tools \ + && python3 index_html_zipper.py ../RTK_Everywhere/AP-Config/index.html ../RTK_Everywhere/form.h \ + && python3 main_js_zipper.py ../RTK_Everywhere/AP-Config/src/main.js ../RTK_Everywhere/form.h + +# Copy custom RTKEverywhere.csv +# Use the 16MB partitions by default. 8MB (Postcard) partitions must be compiled separately +RUN cp RTKEverywhere.csv "/root/.arduino15/packages/esp32/hardware/esp32/${CORE_VERSION}/tools/partitions/RTKEverywhere.csv" + +# Compile Sketch +RUN cd ./RTK_Everywhere \ + && arduino-cli compile --fqbn "esp32:esp32:esp32":DebugLevel=${DEBUG_LEVEL},PSRAM=enabled \ + --warnings ${WARNINGS} \ + ./RTK_Everywhere.ino \ + --build-property build.partitions=RTKEverywhere \ + --build-property upload.maximum_size=4055040 \ + --build-property "compiler.cpp.extra_flags=-MMD -c \ + \"-DPOINTPERFECT_LBAND_TOKEN=${POINTPERFECT_LBAND_TOKEN}\" \ + \"-DPOINTPERFECT_IP_TOKEN=${POINTPERFECT_IP_TOKEN}\" \ + \"-DPOINTPERFECT_LBAND_IP_TOKEN=${POINTPERFECT_LBAND_IP_TOKEN}\" \ + \"-DPOINTPERFECT_RTCM_TOKEN=${POINTPERFECT_RTCM_TOKEN}\" \ + \"-DFIRMWARE_VERSION_MAJOR=${FIRMWARE_VERSION_MAJOR}\" \ + \"-DFIRMWARE_VERSION_MINOR=${FIRMWARE_VERSION_MINOR}\" \ + \"-DENABLE_DEVELOPER=${ENABLE_DEVELOPER}\"" \ + --export-binaries + +# Copy the compile output. List the files +FROM deployment AS output +COPY --from=deployment ./RTK_Everywhere/build/esp32.esp32.esp32 / +CMD echo $(ls /*.*) diff --git a/Firmware/RTK_Everywhere/AP-Config/index.html b/Firmware/RTK_Everywhere/AP-Config/index.html index 4a024b7d9..9e7c8c0a8 100644 --- a/Firmware/RTK_Everywhere/AP-Config/index.html +++ b/Firmware/RTK_Everywhere/AP-Config/index.html @@ -313,11 +313,12 @@
- - - - +
@@ -361,6 +362,46 @@
+
+
+ +
+ +

+
+
+
+
+ +
+
+ + + + + +
+ +
+
+ +
+ +

+
+
+
@@ -458,11 +499,11 @@
+ onClick="resetToSurveyingDefaults()">Reset to Defaults
+ onClick="resetToLoggingDefaults()">Reset to PPP Logging

@@ -1256,49 +1297,6 @@

- -
-
- - - - - -
-
- -
-
- - - - - -
- -
- - - - - -
-
-
- - @@ -1680,6 +1678,17 @@ +
+ + + + + +

@@ -1704,24 +1713,22 @@

+
+ + + + + +

- -
- - - - - -
- @@ -1954,7 +1961,7 @@
- + v0.0
@@ -2059,7 +2066,7 @@ @@ -2070,18 +2077,26 @@
-

+
+ + + + + +
+
-
@@ -2112,7 +2127,7 @@ diff --git a/Firmware/RTK_Everywhere/AP-Config/src/main.js b/Firmware/RTK_Everywhere/AP-Config/src/main.js index f1852ac82..20d0e4088 100644 --- a/Firmware/RTK_Everywhere/AP-Config/src/main.js +++ b/Firmware/RTK_Everywhere/AP-Config/src/main.js @@ -78,6 +78,8 @@ const CoordinateTypes = { var convertedCoordinate = 0.0; var coordinateInputType = CoordinateTypes.COORDINATE_INPUT_TYPE_DD; +var initialSettings = {}; + function parseIncoming(msg) { //console.log("Incoming message: " + msg); @@ -112,16 +114,17 @@ function parseIncoming(msg) { hide("externalPortOptions"); show("logToSDCard"); hide("galileoHasSetting"); + hide("lg290pGnssSettings"); hide("tiltConfig"); hide("beeperControl"); - show("useAssistNowCheckbox"); show("measurementRateInput"); hide("mosaicNMEAStreamDropdowns"); show("surveyInSettings"); - show("useLocalizedDistributionCheckbox"); + show("useEnableExtCorrRadio"); show("extCorrRadioSPARTNSourceDropdown"); hide("enableNmeaOnRadio"); + hide("shutdownNoChargeTimeoutMinutesCheckboxDetail"); hide("constellationNavic"); //Not supported on ZED @@ -131,7 +134,9 @@ function parseIncoming(msg) { select.add(newOption, undefined); newOption = new Option('Flex NTRIP/RTCM', '1'); select.add(newOption, undefined); - newOption = new Option('Flex L-Band North America', '2'); + newOption = new Option('Flex L-Band North America (Deprecated)', '2'); + select.add(newOption, undefined); + newOption = new Option('Flex MQTT (Deprecated)', '5'); select.add(newOption, undefined); } else if ((platformPrefix == "Facet v2") || (platformPrefix == "Facet v2 LBand")) { @@ -143,13 +148,12 @@ function parseIncoming(msg) { show("externalPortOptions"); show("logToSDCard"); hide("galileoHasSetting"); + hide("lg290pGnssSettings"); hide("tiltConfig"); hide("beeperControl"); - show("useAssistNowCheckbox"); show("measurementRateInput"); hide("mosaicNMEAStreamDropdowns"); show("surveyInSettings"); - show("useLocalizedDistributionCheckbox"); show("useEnableExtCorrRadio"); show("extCorrRadioSPARTNSourceDropdown"); hide("enableNmeaOnRadio"); @@ -165,13 +169,13 @@ function parseIncoming(msg) { show("externalPortOptions"); show("logToSDCard"); hide("galileoHasSetting"); + hide("lg290pGnssSettings"); hide("tiltConfig"); hide("beeperControl"); - hide("useAssistNowCheckbox"); hide("measurementRateInput"); show("mosaicNMEAStreamDropdowns"); hide("surveyInSettings"); - hide("useLocalizedDistributionCheckbox"); + show("useEnableExtCorrRadio"); hide("extCorrRadioSPARTNSourceDropdown"); show("enableNmeaOnRadio"); @@ -203,7 +207,9 @@ function parseIncoming(msg) { select.add(newOption, undefined); newOption = new Option('Flex NTRIP/RTCM', '1'); select.add(newOption, undefined); - newOption = new Option('Flex L-Band North America', '2'); + newOption = new Option('Flex L-Band North America (Deprecated)', '2'); + select.add(newOption, undefined); + newOption = new Option('Flex MQTT (Deprecated)', '5'); select.add(newOption, undefined); } else if (platformPrefix == "Torch") { @@ -222,7 +228,9 @@ function parseIncoming(msg) { hide("constellationSbas"); //Not supported on UM980 hide("constellationNavic"); //Not supported on UM980 - show("useAssistNowCheckbox"); //Does the PPL use MGA? Not sure... + show("galileoHasSetting"); + hide("lg290pGnssSettings"); + show("measurementRateInput"); show("loraConfig"); @@ -242,6 +250,8 @@ function parseIncoming(msg) { select.add(newOption, undefined); newOption = new Option('Flex NTRIP/RTCM', '1'); select.add(newOption, undefined); + newOption = new Option('Flex MQTT (Deprecated)', '5'); + select.add(newOption, undefined); } else if (platformPrefix == "Postcard") { show("baseConfig"); @@ -252,15 +262,14 @@ function parseIncoming(msg) { show("externalPortOptions"); show("logToSDCard"); - hide("galileoHasSetting"); + show("galileoHasSetting"); + show("lg290pGnssSettings"); hide("tiltConfig"); hide("beeperControl"); - show("useAssistNowCheckbox"); show("measurementRateInput"); hide("mosaicNMEAStreamDropdowns"); show("surveyInSettings"); - show("useLocalizedDistributionCheckbox"); show("useEnableExtCorrRadio"); hide("extCorrRadioSPARTNSourceDropdown"); show("enableNmeaOnRadio"); @@ -269,8 +278,8 @@ function parseIncoming(msg) { show("constellationNavic"); hide("dynamicModelDropdown"); //Not supported on LG290P - hide("minElevConfig"); //Not supported on LG290P - hide("minCNOConfig"); //Not supported on LG290P + show("minElevConfig"); + show("minCNOConfig"); ge("rtcmRateInfoText").setAttribute('data-bs-original-title', 'RTCM is transmitted by the base at a default of 1Hz for messages 1005, 1074, 1084, 1094, 1114, 1124, 1134. This can be lowered for radios with low bandwidth or tailored to transmit any/all RTCM messages. Limits: 0 to 20. Note: The measurement rate is overridden to 1Hz when in Base mode.'); @@ -279,8 +288,9 @@ function parseIncoming(msg) { select.add(newOption, undefined); newOption = new Option('Flex NTRIP/RTCM', '1'); select.add(newOption, undefined); + newOption = new Option('Flex MQTT (Deprecated)', '5'); + select.add(newOption, undefined); - console.log("Change baud list"); ge("radioPortBaud").options.length = 0; //Remove all from list select = ge("radioPortBaud"); newOption = new Option('9600', '9600'); @@ -307,6 +317,48 @@ function parseIncoming(msg) { newOption = new Option('921600', '921600'); select.add(newOption, undefined); } + else if (platformPrefix == "Torch X2") { + show("baseConfig"); + show("ppConfig"); + hide("ethernetConfig"); + hide("ntpConfig"); + show("portsConfig"); + + // No RADIO port on Torch X2 + // No DATA port on Torch X2 + hide("externalPortOptions"); + + hide("logToSDCard"); //No SD card on Torch + + hide("constellationSbas"); //Not supported on LG290P + show("constellationNavic"); + show("galileoHasSetting"); + show("lg290pGnssSettings"); + hide("tiltConfig"); //Not supported on Torch X2 + + show("measurementRateInput"); + + hide("mosaicNMEAStreamDropdowns"); + show("surveyInSettings"); + + hide("useEnableExtCorrRadio"); //No External Radio connector on Torch X2 + hide("extCorrRadioSPARTNSourceDropdown"); + hide("enableNmeaOnRadio"); + + hide("dynamicModelDropdown"); //Not supported on LG290P + show("minElevConfig"); + show("minCNOConfig"); + + ge("rtcmRateInfoText").setAttribute('data-bs-original-title', 'RTCM is transmitted by the base at a default of 1Hz for messages 1005, 1074, 1084, 1094, 1124, and 0.1Hz for 1033. This can be lowered for radios with low bandwidth or tailored to transmit any/all RTCM messages. Limits: 0 to 20. Note: The measurement rate is overridden to 1Hz when in Base mode.'); + + select = ge("pointPerfectService"); + newOption = new Option('Disabled', '0'); + select.add(newOption, undefined); + newOption = new Option('Flex NTRIP/RTCM', '1'); + select.add(newOption, undefined); + newOption = new Option('Flex MQTT (Deprecated)', '5'); + select.add(newOption, undefined); + } } else if (id.includes("gnssFirmwareVersionInt")) { //Modify settings due to firmware limitations @@ -461,6 +513,23 @@ function parseIncoming(msg) { messageText += "

"; messageText += "
"; } + else if (id.includes("messageRatePQTM")) { + // messageRatePQTM_EPE + var messageName = id; + var messageNameLabel = ""; + + var messageData = messageName.split('_'); + messageNameLabel = messageData[1]; + + messageText += "
"; + messageText += ""; + messageText += ""; + messageText += "
"; + + // Save the name and value as we can't set 'checked' yet. messageText has not yet been added to innerHTML + savedCheckboxNames.push(messageName); + savedCheckboxValues.push(val); + } else if (id.includes("messageRate") || id.includes("messageIntervalRTCM")) { // messageRateNMEA_GPDTM // messageRateRTCMRover_RTCM1001 @@ -647,7 +716,7 @@ function parseIncoming(msg) { ge("enableARPLogging").dispatchEvent(new CustomEvent('change')); ge("enableAutoFirmwareUpdate").dispatchEvent(new CustomEvent('change')); ge("enableAutoReset").dispatchEvent(new CustomEvent('change')); - ge("useLocalizedDistribution").dispatchEvent(new CustomEvent('change')); + ge("enableGalileoHas").dispatchEvent(new CustomEvent('change')); updateECEFList(); updateGeodeticList(); @@ -657,9 +726,38 @@ function parseIncoming(msg) { dhcpEthernet(); updateLatLong(); updateCorrectionsPriorities(); + + // Create copy of settings, send only changes when 'Save Configuration' is pressed + saveInitialSettings(); } } +// Save the current state of settings +function saveInitialSettings() { + initialSettings = {}; // Clear previous settings + + // Save input boxes and dropdowns + var clsElements = document.querySelectorAll(".form-control, .form-dropdown"); + for (let x = 0; x < clsElements.length; x++) { + initialSettings[clsElements[x].id] = clsElements[x].value; + } + + // Save checkboxes and radio buttons + clsElements = document.querySelectorAll(".form-check-input:not(.fileManagerCheck), .form-radio"); + for (let x = 0; x < clsElements.length; x++) { + // Store boolean values for easy comparison + initialSettings[clsElements[x].id] = clsElements[x].checked.toString(); + } + + // Save corrections priorities + for (let x = 0; x < numCorrectionsSources; x++) { + initialSettings["correctionsPriority_" + correctionsSourceNames[x]] = correctionsSourcePriorities[x].toString(); + } + + // Note: recordsECEF and recordsGeodetic change very little so instead + // of creating copy here, we will resend any entered coordinates every time. +} + function hide(id) { ge(id).style.display = "none"; } @@ -668,39 +766,69 @@ function show(id) { ge(id).style.display = "block"; } -//Create CSV of all setting data +function isElementShown(id) { + if (ge(id).style.display == "block") { + return (true); + } + return (false); +} + +//Create CSV of all setting data that has changed from the original given to us function sendData() { var settingCSV = ""; + var changedCount = 0; - //Input boxes + // Check input boxes and dropdowns var clsElements = document.querySelectorAll(".form-control, .form-dropdown"); for (let x = 0; x < clsElements.length; x++) { - settingCSV += clsElements[x].id + "," + clsElements[x].value + ","; + var id = clsElements[x].id; + var currentValue = clsElements[x].value; + if (initialSettings[id] !== currentValue) { + settingCSV += id + "," + currentValue + ","; + changedCount++; + } } - //Check boxes, radio buttons - //Remove file manager files + // Check boxes, radio buttons clsElements = document.querySelectorAll(".form-check-input:not(.fileManagerCheck), .form-radio"); for (let x = 0; x < clsElements.length; x++) { - settingCSV += clsElements[x].id + "," + clsElements[x].checked + ","; + var id = clsElements[x].id; + // Store boolean as string 'true'/'false' for consistent comparison with initialSettings + var currentValue = clsElements[x].checked.toString(); + if (initialSettings[id] !== currentValue) { + settingCSV += id + "," + currentValue + ","; + changedCount++; + } } + // Records (ECEF and Geodetic) - For simplicity, we send the full list if any list element exists. for (let x = 0; x < recordsECEF.length; x++) { settingCSV += "stationECEF" + x + ',' + recordsECEF[x] + ","; } - for (let x = 0; x < recordsGeodetic.length; x++) { settingCSV += "stationGeodetic" + x + ',' + recordsGeodetic[x] + ","; } + // Corrections Priorities for (let x = 0; x < correctionsSourceNames.length; x++) { - settingCSV += "correctionsPriority_" + correctionsSourceNames[x] + ',' + correctionsSourcePriorities[x] + ","; + var id = "correctionsPriority_" + correctionsSourceNames[x]; + var currentValue = correctionsSourcePriorities[x].toString(); + if (initialSettings[id] !== currentValue) { + settingCSV += id + ',' + currentValue + ","; + changedCount++; + } } - console.log("Sending: " + settingCSV); - websocket.send(settingCSV); + console.log("Sending " + changedCount + " changed settings: " + settingCSV); - sendDataTimeout = setTimeout(sendData, 2000); + // Only send if there are changes (plus the always-sent records) + if (settingCSV.length > 0) { + websocket.send(settingCSV); + sendDataTimeout = setTimeout(sendData, 2000); + } else { + // If nothing changed, immediately report success. + showSuccess('saveBtn', "No changes detected."); + } } function showError(id, errorText) { @@ -759,6 +887,14 @@ function checkMessageValueUM980Base(id) { checkElementValue(id, 0, 65, "Must be between 0 and 65", "collapseGNSSConfigMsgBase"); } +function checkMessageValueLG290P01(id) { + checkElementValue(id, 0, 1, "Must be between 0 and 1", "collapseGNSSConfigMsg"); +} + +function checkMessageValueLG290P01200(id) { + checkElementValue(id, 0, 1200, "Must be between 0 and 1200", "collapseGNSSConfigMsg"); +} + function collapseSection(section, caret) { ge(section).classList.remove('show'); ge(caret).classList.remove('icon-caret-down'); @@ -795,7 +931,12 @@ function validateFields() { checkElementValue("minElev", 0, 90, "Must be between 0 and 90", "collapseGNSSConfig"); checkElementValue("minCNO", 0, 90, "Must be between 0 and 90", "collapseGNSSConfig"); - + if (isElementShown("lg290pGnssSettings") == true) { + checkElementValue("rtcmMinElev", -90, 90, "Must be between -90 and 90", "collapseGNSSConfig"); + } + if (isElementShown("configurePppSetting") == true) { + checkElementStringSpacesNoCommas("configurePPP", 1, 30, "Must be 1 to 30 characters. Separated by spaces. Commas not allowed", "collapseGNSSConfig"); + } if (ge("enableNtripClient").checked == true) { checkElementString("ntripClientCasterHost", 1, 45, "Must be 1 to 45 characters", "collapseGNSSConfig"); checkElementValue("ntripClientCasterPort", 1, 99999, "Must be 1 to 99999", "collapseGNSSConfig"); @@ -862,6 +1003,25 @@ function validateFields() { } } + //Check all LG290P message boxes + else if ((platformPrefix == "Postcard") || (platformPrefix == "Torch X2")) { + var messages = document.querySelectorAll('input[id^=messageRateNMEA_]'); + for (let x = 0; x < messages.length; x++) { + var messageName = messages[x].id; + checkMessageValueLG290P01(messageName); + } + var messages = document.querySelectorAll('input[id^=messageRateRTCMRover_]'); + for (let x = 0; x < messages.length; x++) { + var messageName = messages[x].id; + checkMessageValueLG290P01200(messageName); + } + var messages = document.querySelectorAll('input[id^=messageRateRTCMBase_]'); + for (let x = 0; x < messages.length; x++) { + var messageName = messages[x].id; + checkMessageValueLG290P01200(messageName); + } + } + //Base Config if (ge("baseTypeSurveyIn").checked == true) { checkElementValue("observationSeconds", 60, 600, "Must be between 60 to 600", "collapseBaseConfig"); @@ -1003,8 +1163,8 @@ function validateFields() { //System Config if (ge("enableLogging").checked == true) { - checkElementValue("maxLogTime", 1, 1051200, "Must be 1 to 1,051,200", "collapseSystemConfig"); - checkElementValue("maxLogLength", 1, 1051200, "Must be 1 to 1,051,200", "collapseSystemConfig"); + checkElementValue("maxLogTime", 0, 1051200, "Must be 0 to 1,051,200", "collapseSystemConfig"); + checkElementValue("maxLogLength", 0, 2880, "Must be 0 to 2880", "collapseSystemConfig"); } else { clearElement("maxLogTime", 60 * 24); @@ -1279,6 +1439,19 @@ function checkElementString(id, min, max, errorText, collapseID) { clearError(id); } +function checkElementStringSpacesNoCommas(id, min, max, errorText, collapseID) { + value = ge(id).value; + var commas = value.split(','); + var spaces = value.split(' '); + if ((value.length < min) || (value.length > max) || (commas.length > 1) || (spaces.length == 1)) { + ge(id + 'Error').innerHTML = 'Error: ' + errorText; + ge(collapseID).classList.add('show'); + errorCount++; + } + else + clearError(id); +} + function checkElementIPAddress(id, errorText, collapseID) { value = ge(id).value; var data = value.split('.'); @@ -1378,6 +1551,12 @@ function zeroMessages() { var messageName = messages[x].id; ge(messageName).checked = false; } + //match messageRatePQTM_ + messages = document.querySelectorAll('input[id^=messageRatePQTM_]'); + for (let x = 0; x < messages.length; x++) { + var messageName = messages[x].id; + ge(messageName).checked = false; + } } function zeroBaseMessages() { @@ -1434,6 +1613,15 @@ function resetToSurveyingDefaults() { ge("messageIntervalRTCMRover_RTCM1033").value = 10.0; } + else if ((platformPrefix == "Postcard") || (platformPrefix == "Torch X2")) { + ge("messageRateNMEA_GPRMC").value = 1; + ge("messageRateNMEA_GPGGA").value = 1; + ge("messageRateNMEA_GPGSV").value = 1; + ge("messageRateNMEA_GPGSA").value = 1; + ge("messageRateNMEA_GPVTG").value = 1; + ge("messageRateNMEA_GPGLL").value = 1; + ge("messageRateNMEA_GPGST").value = 1; //Supported on >= v4 + } } function resetToLoggingDefaults() { zeroMessages(); @@ -1448,16 +1636,40 @@ function resetToLoggingDefaults() { ge("ubxMessageRate_RXM_SFRBX").value = 1; } else if (platformPrefix == "Torch") { - ge("messageRateNMEA_GPGGA").value = 0.5; - ge("messageRateNMEA_GPGSA").value = 0.5; - ge("messageRateNMEA_GPGST").value = 0.5; - ge("messageRateNMEA_GPGSV").value = 1.0; - ge("messageRateNMEA_GPRMC").value = 0.5; - - ge("messageRateRTCMRover_RTCM1019").value = 1.0; - ge("messageRateRTCMRover_RTCM1020").value = 1.0; - ge("messageRateRTCMRover_RTCM1042").value = 1.0; - ge("messageRateRTCMRover_RTCM1046").value = 1.0; + ge("messageRateNMEA_GPGGA").value = 1; + ge("messageRateNMEA_GPGSA").value = 1; + ge("messageRateNMEA_GPGST").value = 1; + ge("messageRateNMEA_GPGSV").value = 5; // Limit to 1 per 5 seconds + ge("messageRateNMEA_GPRMC").value = 1; + + ge("messageRateRTCMRover_RTCM1019").value = 30; + ge("messageRateRTCMRover_RTCM1020").value = 30; + ge("messageRateRTCMRover_RTCM1042").value = 30; + ge("messageRateRTCMRover_RTCM1046").value = 30; + + ge("messageRateRTCMRover_RTCM1074").value = 30; + ge("messageRateRTCMRover_RTCM1084").value = 30; + ge("messageRateRTCMRover_RTCM1094").value = 30; + ge("messageRateRTCMRover_RTCM1124").value = 30; + } + else if ((platformPrefix == "Postcard") || (platformPrefix == "Torch X2")) { + ge("messageRateNMEA_GPRMC").value = 1; + ge("messageRateNMEA_GPGGA").value = 1; + ge("messageRateNMEA_GPGSV").value = 1; + ge("messageRateNMEA_GPGSA").value = 1; + ge("messageRateNMEA_GPVTG").value = 1; + ge("messageRateNMEA_GPGLL").value = 1; + ge("messageRateNMEA_GPGST").value = 1; // Supported on >= v4 + + ge("messageRateRTCMRover_RTCM1019").value = 30; + ge("messageRateRTCMRover_RTCM1020").value = 30; + ge("messageRateRTCMRover_RTCM1042").value = 30; + ge("messageRateRTCMRover_RTCM1046").value = 30; + + ge("messageRateRTCMRover_RTCM107X").value = 30; + ge("messageRateRTCMRover_RTCM108X").value = 30; + ge("messageRateRTCMRover_RTCM109X").value = 30; + ge("messageRateRTCMRover_RTCM112X").value = 30; } else if (platformPrefix == "Facet mosaicX5") { ge("streamIntervalNMEA_0").value = 6; //msec500 @@ -1742,15 +1954,6 @@ document.addEventListener("DOMContentLoaded", (event) => { } }); - ge("useLocalizedDistribution").addEventListener("change", function () { - if (ge("useLocalizedDistribution").checked) { - show("localizedDistributionTileLevelDropdown"); - } - else { - hide("localizedDistributionTileLevelDropdown"); - } - }); - ge("enableExternalPulse").addEventListener("change", function () { if (ge("enableExternalPulse").checked == true) { show("externalPulseConfigDetails"); @@ -1861,6 +2064,20 @@ document.addEventListener("DOMContentLoaded", (event) => { adjustHAE(); }); + ge("enableGalileoHas").addEventListener("change", function () { + if ((isElementShown("galileoHasSetting") == true) && (isElementShown("lg290pGnssSettings") == true)) { + if (ge("enableGalileoHas").checked == true) { + show("configurePppSetting"); + } + else { + hide("configurePppSetting"); + } + } + else { + hide("configurePppSetting"); // Hide on Torch UM980 - i.e. non-LG290P + } + }); + for (let y = 0; y < numCorrectionsSources; y++) { var buttonName = "corrPrioButton" + y; ge(buttonName).addEventListener("click", function () { diff --git a/Firmware/RTK_Everywhere/AuthCoPro.ino b/Firmware/RTK_Everywhere/AuthCoPro.ino new file mode 100644 index 000000000..0b2c9f1e0 --- /dev/null +++ b/Firmware/RTK_Everywhere/AuthCoPro.ino @@ -0,0 +1,127 @@ +#ifdef COMPILE_AUTHENTICATION + +const char *manufacturer = "SparkFun Electronics"; +const char *hardwareVersion = "1.0.0"; +const char *EAProtocol = "com.sparkfun.rtk"; +//const char *BTTransportName = "com.sparkfun.bt"; +const char *BTTransportName = "Bluetooth"; +const char *LIComponentName = "com.sparkfun.li"; +const char *productPlanUID = + "0123456789ABCDEF"; // This comes from the MFi Portal, when you register the product with Apple + +extern BTSerialInterface *bluetoothSerialSpp; + +void transportConnected(bool *isConnected) +{ + *isConnected = bluetoothSerialSpp->connected(); +} + +void transportDisconnect(bool *disconnected) +{ + bluetoothSerialSpp->disconnect(); +} + +void beginAuthCoPro(TwoWire *i2cBus) +{ + if (i2cBus == nullptr) + return; // Return silently if the Co Pro was not detected during beginI2C + + appleAccessory = new SparkFunAppleAccessoryDriver; + + appleAccessory->usePSRAM(online.psram); + + if (!appleAccessory->begin(*i2cBus)) + { + systemPrintln("Could not initialize the authentication coprocessor"); + return; + } + + if (settings.debugNetworkLayer) + appleAccessory->enableDebug(&Serial); // Enable debug prints to Serial + + // Pass Identity Information, Protocols and Names into the accessory driver + appleAccessory->setAccessoryName(deviceName); + appleAccessory->setModelIdentifier(platformPrefix); + appleAccessory->setManufacturer(manufacturer); + appleAccessory->setSerialNumber(serialNumber); + appleAccessory->setFirmwareVersion(deviceFirmware); + appleAccessory->setHardwareVersion(hardwareVersion); + appleAccessory->setExternalAccessoryProtocol(EAProtocol); + appleAccessory->setBluetoothTransportName(BTTransportName); + appleAccessory->setBluetoothMacAddress(btMACAddress); + appleAccessory->setLocationInfoComponentName(LIComponentName); + appleAccessory->setProductPlanUID(productPlanUID); + + // Pass the pointers for the latest NMEA data into the Accessory driver + latestGPGGA = (char *)rtkMalloc(latestNmeaMaxLen, "AuthCoPro"); + latestGPRMC = (char *)rtkMalloc(latestNmeaMaxLen, "AuthCoPro"); + latestGPGST = (char *)rtkMalloc(latestNmeaMaxLen, "AuthCoPro"); + latestGPVTG = (char *)rtkMalloc(latestNmeaMaxLen, "AuthCoPro"); + appleAccessory->setNMEApointers(latestGPGGA, latestGPRMC, latestGPGST, latestGPVTG); + + // Pass the pointer for additional GSA / GSV EA Session data + latestEASessionData = (char *)rtkMalloc(latestEASessionDataMaxLen, "AuthCoPro"); + appleAccessory->setEASessionPointer(latestEASessionData); + + // Pass the transport connected and disconnect methods into the accessory driver + appleAccessory->setTransportConnectedMethod(&transportConnected); + appleAccessory->setTransportDisconnectMethod(&transportDisconnect); + + online.authenticationCoPro = true; + systemPrintln("Authentication coprocessor online"); +} + +extern char *bda2str(esp_bd_addr_t bda, char *str, size_t size); + +void updateAuthCoPro() +{ + // bluetoothStart is called during STATE_ROVER_NOT_STARTED and STATE_BASE_NOT_STARTED + // appleAccessory.update() will use &transportConnected to learn if BT SPP is running + + if (online.authenticationCoPro) // Coprocessor must be present and online + { + if ((bluetoothGetState() > BT_OFF) && (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE)) + { + appleAccessory->update(); // Update the Accessory driver + + // Check for a new device connection + // Note: aclConnected is a one-shot + // The internal flag is automatically cleared when aclConnected returns true + if (bluetoothSerialSpp->aclConnected() == true) + { + char bda_str[18]; + systemPrintf("Apple Device %s found\r\n", bda2str(bluetoothSerialSpp->aclGetAddress(), bda_str, 18)); + + // We need to connect _almost_ immediately for a successful pairing + // This is really brittle. + // Having core debug enabled adds enough delay to make this work. + // With debug set to none, we need to insert a _small_ delay... + // Too much delay and we get Connection Unsuccessful. + delay(2); + + int channel = 1; + if (settings.debugNetworkLayer) + systemPrintf("Connecting on channel %d\r\n", channel); + + bluetoothSerialSpp->connect(bluetoothSerialSpp->aclGetAddress(), channel); // Blocking for READY_TIMEOUT + + if (bluetoothSerialSpp->connected()) + { + systemPrintln("Connected. Sending handshake..."); + appleAccessory->startHandshake((Stream *)bluetoothSerialSpp); + } + else + { + systemPrintln("Connection failed / timed out! Handshake will be sent if device connects..."); + sendAccessoryHandshakeOnBtConnect = true; + } + } + + // That's all folks! + // If a timeout occurred, Handshake is sent by bluetoothUpdate() + // Everything else is handled by the Apple Accessory Library + } + } +} + +#endif \ No newline at end of file diff --git a/Firmware/RTK_Everywhere/Begin.ino b/Firmware/RTK_Everywhere/Begin.ino index ed582782d..c3f27a07a 100644 --- a/Firmware/RTK_Everywhere/Begin.ino +++ b/Firmware/RTK_Everywhere/Begin.ino @@ -72,11 +72,11 @@ void identifyBoard() getMacAddresses(wifiMACAddress, "wifiMACAddress", ESP_MAC_WIFI_STA, true); getMacAddresses(btMACAddress, "btMACAddress", ESP_MAC_BT, true); getMacAddresses(ethernetMACAddress, "ethernetMACAddress", ESP_MAC_ETH, true); + snprintf(serialNumber, sizeof(serialNumber), "%02X%02X", btMACAddress[4], btMACAddress[5]); // First, test for devices that do not have ID resistors if (productVariant == RTK_UNKNOWN) { - // Torch // Check if unique ICs are on the I2C bus if (i2c_0 == nullptr) i2c_0 = new TwoWire(0); @@ -94,19 +94,27 @@ void identifyBoard() // 0x08 - HUSB238 - USB C PD Sink Controller bool husb238Present = i2cIsDevicePresent(i2c_0, 0x08); - i2c_0->end(); + // 0x10 -MFI343S00177 Authentication Coprocessor + bool mfiPresent = i2cIsDevicePresent(i2c_0, 0x10); - if (bq40z50Present || mp2762aPresent || husb238Present) - productVariant = RTK_TORCH; + i2c_0->end(); - if (productVariant == RTK_TORCH && bq40z50Present == false) - systemPrintln("Error: Torch ID'd with no BQ40Z50 present"); + // Proceed with Torch ID only if MFi is absent (Torch X2 has MFi, and ID resistors) + if (mfiPresent == false) + { + if (bq40z50Present || mp2762aPresent || husb238Present) + { + productVariant = RTK_TORCH; + if (bq40z50Present == false) + systemPrintln("Error: Torch ID'd with no BQ40Z50 present"); - if (productVariant == RTK_TORCH && mp2762aPresent == false) - systemPrintln("Error: Torch ID'd with no MP2762A present"); + if (mp2762aPresent == false) + systemPrintln("Error: Torch ID'd with no MP2762A present"); - if (productVariant == RTK_TORCH && husb238Present == false) - systemPrintln("Error: Torch ID'd with no HUSB238 present"); + if (husb238Present == false) + systemPrintln("Error: Torch ID'd with no HUSB238 present"); + } + } } if (productVariant == RTK_UNKNOWN) @@ -139,13 +147,27 @@ void identifyBoard() else if (idWithAdc(idValue, 12.1, 1.5, 8.5)) productVariant = RTK_FACET_V2_LBAND; - // Facet v2: 10.0/2.7 --> 612mV < 702mV < 801mV (8.5% tolerance) - else if (idWithAdc(idValue, 10.0, 2.7, 8.5)) - productVariant = RTK_FACET_V2; + // Flex: 10.0/20.0 --> 2071mV < 2200mV < 2322mV (8.5% tolerance) + else if (idWithAdc(idValue, 10.0, 20.0, 8.5)) + productVariant = RTK_FLEX; // Postcard: 3.3/10 --> 2371mV < 2481mV < 2582mV (8.5% tolerance) else if (idWithAdc(idValue, 3.3, 10, 8.5)) productVariant = RTK_POSTCARD; + + // Torch X2: 8.2/3.3 --> 836mV < 947mV < 1067mV (8.5% tolerance) + else if (idWithAdc(idValue, 8.2, 3.3, 8.5)) + productVariant = RTK_TORCH_X2; + +#ifdef FLEX_OVERRIDE + systemPrintln("<<<<<<<<<< !!!!!!!!!! FLEX OVERRIDE !!!!!!!!!! >>>>>>>>>>"); + productVariant = RTK_FLEX; // TODO remove once v1.1 Flex has ID resistors +#endif + +#ifdef TORCH_X2_OVERRIDE + systemPrintln("<<<<<<<<<< !!!!!!!!!! TORCH X2 OVERRIDE !!!!!!!!!! >>>>>>>>>>"); + productVariant = RTK_TORCH_X2; // TODO remove once v1.1 Torch X2 has ID resistors +#endif } if (ENABLE_DEVELOPER) @@ -273,7 +295,7 @@ void beginBoard() pinMode(pin_GNSS_TimePulse, INPUT); pinMode(pin_GNSS_DR_Reset, OUTPUT); - um980Boot(); // Tell UM980 and DR to boot + gnssBoot(); // Tell UM980 and DR to boot pinMode(pin_powerAdapterDetect, INPUT); // Has 10k pullup @@ -305,6 +327,7 @@ void beginBoard() gnss = (GNSS *)new GNSS_ZED(); #else // COMPILE_ZED gnss = (GNSS *)new GNSS_None(); + systemPrintln("<<<<<<<<<< !!!!!!!!!! ZED NOT COMPILED !!!!!!!!!! >>>>>>>>>>"); #endif // COMPILE_ZED present.brand = BRAND_SPARKFUN; @@ -358,12 +381,12 @@ void beginBoard() pin_Cellular_RX = 14; // 30, D18 : SPI SCK --> Ethernet, microSD card - // 31, D19 : SPI POCI + // 31, D19 : SPI POCI --> microSD card SDO // 33, D21 : I2C0 SDA --> ZED, NEO, USB2514B, TP, I/O connector pin_I2C0_SDA = 21; // 36, D22 : I2C0 SCL pin_I2C0_SCL = 22; - // 37, D23 : SPI PICO + // 37, D23 : SPI PICO --> microSD card SDI // 10, D25 : GNSS RX --> ZED UART1 TXO pin_GnssUart_RX = 25; // 11, D26 : LARA_PWR_ON @@ -386,8 +409,8 @@ void beginBoard() // 5, A39 : Ethernet Interrupt pin_Ethernet_Interrupt = 39; - pin_PICO = 23; - pin_POCI = 19; + pin_PICO = 23; // SPI PICO --> microSD card SDI + pin_POCI = 19; // SPI POCI --> microSD card SDO pin_SCK = 18; // Disable the Ethernet controller @@ -435,6 +458,7 @@ void beginBoard() gnss = (GNSS *)new GNSS_ZED(); #else // COMPILE_ZED gnss = (GNSS *)new GNSS_None(); + systemPrintln("<<<<<<<<<< !!!!!!!!!! ZED NOT COMPILED !!!!!!!!!! >>>>>>>>>>"); #endif // COMPILE_ZED present.brand = BRAND_SPARKPNT; @@ -466,10 +490,10 @@ void beginBoard() pin_GnssUart_RX = 14; pin_microSD_CardDetect = 15; // 30, D18 : SPI SCK --> microSD card - // 31, D19 : SPI POCI --> microSD card + // 31, D19 : SPI POCI --> microSD card SDO pin_I2C0_SDA = 21; pin_I2C0_SCL = 22; - // 37, D23 : SPI PICO --> microSD card + // 37, D23 : SPI PICO --> microSD card SDI pin_microSD_CS = 25; pin_muxDAC = 26; pin_peripheralPowerControl = 27; @@ -478,8 +502,8 @@ void beginBoard() pin_chargerLED = 34; pin_chargerLED2 = 36; pin_muxADC = 39; - pin_PICO = 23; - pin_POCI = 19; + pin_PICO = 23; // SPI PICO --> microSD card SDI + pin_POCI = 19; // SPI POCI --> microSD card SDO pin_SCK = 18; pinMode(pin_muxA, OUTPUT); @@ -517,6 +541,7 @@ void beginBoard() gnss = (GNSS *)new GNSS_ZED(); #else // COMPILE_ZED gnss = (GNSS *)new GNSS_None(); + systemPrintln("<<<<<<<<<< !!!!!!!!!! ZED NOT COMPILED !!!!!!!!!! >>>>>>>>>>"); #endif // COMPILE_ZED present.brand = BRAND_SPARKPNT; @@ -545,11 +570,11 @@ void beginBoard() pin_GnssUart_TX = 13; pin_GnssUart_RX = 14; pin_microSD_CardDetect = 15; - // 30, D18 : SPI SCK --> microSD card - // 31, D19 : SPI POCI --> microSD card + // 30, D18 : SPI SCK --> microSD card SCK + // 31, D19 : SPI POCI --> microSD card SDO pin_I2C0_SDA = 21; pin_I2C0_SCL = 22; - // 37, D23 : SPI PICO --> microSD card + // 37, D23 : SPI PICO --> microSD card SDI pin_microSD_CS = 25; pin_muxDAC = 26; pin_peripheralPowerControl = 27; @@ -558,8 +583,8 @@ void beginBoard() pin_chargerLED = 34; pin_chargerLED2 = 36; pin_muxADC = 39; - pin_PICO = 23; - pin_POCI = 19; + pin_PICO = 23; // SPI PICO --> microSD card SDI + pin_POCI = 19; // SPI POCI --> microSD card SDO pin_SCK = 18; pinMode(pin_muxA, OUTPUT); @@ -606,6 +631,8 @@ void beginBoard() // mosaic COM3 is connected to the Data connector - via the multiplexer // mosaic COM3 is available as a generic COM port. The firmware configures the baud. Nothing else. + // NOTE: Flex with mosaic-X5 is VERY different! + // Specify the GNSS radio #ifdef COMPILE_MOSAICX5 gnss = (GNSS *)new GNSS_MOSAIC(); @@ -630,10 +657,12 @@ void beginBoard() present.invertedFastPowerOff = true; present.gnss_to_uart = true; present.gnss_to_uart2 = true; - present.needsExternalPpl = true; // Uses the PointPerfect Library + present.mosaicMicroSd = true; present.microSdCardDetectLow = true; // Except microSD is connected to mosaic... present.microSd is false + present.minCno = true; present.minElevation = true; + present.needsExternalPpl = true; // Uses the PointPerfect Library for L-Band present.dynamicModel = true; pin_muxA = 2; @@ -685,10 +714,10 @@ void beginBoard() systemPrintln("<<<<<<<<<< !!!!!!!!!! LG290P NOT COMPILED !!!!!!!!!! >>>>>>>>>>"); #endif // COMPILE_LGP290P - present.brand = BRAND_SPARKPNT; + present.brand = BRAND_SPARKFUN; present.psram_2mb = true; present.gnss_lg290p = true; - present.antennaPhaseCenter_mm = 42.0; // Default to SPK6618H APC, average of L1/L2 + present.antennaPhaseCenter_mm = 37.5; // APC of SPK-6E helical L1/L2/L5 antenna present.needsExternalPpl = true; // Uses the PointPerfect Library present.gnss_to_uart = true; @@ -697,9 +726,10 @@ void beginBoard() present.fuelgauge_max17048 = true; present.display_i2c0 = true; present.i2c0BusSpeed_400 = true; // Run display bus at higher speed + present.i2c1 = true; // Qwiic bus present.display_type = DISPLAY_128x64; present.microSd = true; - present.gpioExpander = true; + present.gpioExpanderButtons = true; present.microSdCardDetectGpioExpanderHigh = true; // CD is on GPIO 5 of expander. High = SD in place. // We can't enable here because we don't know if lg290pFirmwareVersion is >= v05 @@ -709,15 +739,18 @@ void beginBoard() pin_I2C0_SDA = 7; pin_I2C0_SCL = 20; + pin_I2C1_SDA = 13; + pin_I2C1_SCL = 19; + pin_GnssUart_RX = 21; pin_GnssUart_TX = 22; pin_GNSS_Reset = 33; pin_GNSS_TimePulse = 36; // PPS on LG290P + pin_PICO = 26; // SPI PICO --> microSD card SDI + pin_POCI = 25; // SPI POCI --> microSD card SDO pin_SCK = 32; - pin_POCI = 25; - pin_PICO = 26; pin_microSD_CS = 27; pin_gpioExpanderInterrupt = 14; // Pin 'AOI' (Analog Output Input) on Portability Shield @@ -734,16 +767,183 @@ void beginBoard() pinMode(pin_GNSS_TimePulse, INPUT); pinMode(pin_GNSS_Reset, OUTPUT); - lg290pBoot(); // Tell LG290P to boot + gnssBoot(); // Tell LG290P to boot + + // Disable the microSD card + pinMode(pin_microSD_CS, OUTPUT); + sdDeselectCard(); + } + + else if (productVariant == RTK_FLEX) + { + present.brand = BRAND_SPARKPNT; + present.psram_2mb = true; + + present.antennaPhaseCenter_mm = 62.0; // APC from drawings + present.radio_lora = true; + present.fuelgauge_bq40z50 = true; + present.charger_mp2762a = true; + + present.button_powerLow = true; // Button is pressed when high + // present.button_mode = true; //TODO remove comment. This won't be available until v1.1 of hardware + present.beeper = true; + present.gnss_to_uart = true; + + present.gpioExpanderSwitches = true; + // present.microSd = true; // TODO remove comment out - v1.0 hardware does not have pullup on #CD so card detection does not work + present.microSdCardDetectLow = true; + + present.display_i2c0 = true; + present.i2c0BusSpeed_400 = true; // Run display bus at higher speed + present.display_type = DISPLAY_128x64; + present.displayInverted = true; + present.tiltPossible = true; + + pin_I2C0_SDA = 15; + pin_I2C0_SCL = 4; + + pin_GnssUart_RX = 26; + pin_GnssUart_TX = 27; + + pin_powerSenseAndControl = 34; + // pin_modeButton = 25; //TODO remove comment. This won't be available until v1.1 of hardware + + pin_IMU_RX = 14; // ESP32 UART2 + pin_IMU_TX = 17; + + pin_powerAdapterDetect = 36; // Goes low when USB cable is plugged in + + pin_bluetoothStatusLED = 32; + pin_gnssStatusLED = 13; + + pin_beeper = 33; + + pin_PICO = 21; // SPI PICO --> microSD card SDI + pin_POCI = 19; // SPI POCI --> microSD card SDO + pin_SCK = 18; // SPI SCK --> microSD card SCK + pin_microSD_CS = 22; + pin_microSD_CardDetect = 39; + + pin_gpioExpanderInterrupt = + 2; // TODO remove on v1.1 hardware. Not used since all GPIO expanded pins are outputs + + DMW_if systemPrintf("pin_bluetoothStatusLED: %d\r\n", pin_bluetoothStatusLED); + pinMode(pin_bluetoothStatusLED, OUTPUT); + + DMW_if systemPrintf("pin_gnssStatusLED: %d\r\n", pin_gnssStatusLED); + pinMode(pin_gnssStatusLED, OUTPUT); + + pinMode(pin_microSD_CardDetect, INPUT_PULLUP); // Disable the microSD card pinMode(pin_microSD_CS, OUTPUT); sdDeselectCard(); + + // Turn on Bluetooth, GNSS, and Battery LEDs to indicate power on + bluetoothLedOn(); + gnssStatusLedOn(); + + pinMode(pin_beeper, OUTPUT); + beepOff(); + + pinMode(pin_powerSenseAndControl, INPUT); + + pinMode(pin_powerAdapterDetect, INPUT); // Has 10k pullup + + // We don't disable peripherals (aka set pins on the GPIO expander) here because I2C has not yet been started + + // GNSS receiver type is determined later in gnssDetectReceiverType() + } + + else if (productVariant == RTK_TORCH_X2) + { + // Specify the GNSS radio +#ifdef COMPILE_LG290P + gnss = (GNSS *)new GNSS_LG290P(); +#else // COMPILE_UM980 + gnss = (GNSS *)new GNSS_None(); + systemPrintln("<<<<<<<<<< !!!!!!!!!! LG290P NOT COMPILED !!!!!!!!!! >>>>>>>>>>"); +#endif // COMPILE_UM980 + + present.brand = BRAND_SPARKPNT; + present.psram_2mb = true; + present.gnss_lg290p = true; + present.antennaPhaseCenter_mm = 116.5; // Default to Torch helical APC, average of L1/L2 + present.fuelgauge_bq40z50 = true; + present.charger_mp2762a = true; + present.button_powerHigh = true; // Button is pressed when high + present.beeper = true; + present.gnss_to_uart = true; + present.needsExternalPpl = true; // Uses the PointPerfect Library + + // We can't enable GNSS features here because we don't know if lg290pFirmwareVersion is >= v05 + // present.minElevation = true; + // present.minCno = true; + + pin_I2C0_SDA = 15; + pin_I2C0_SCL = 4; + + pin_GnssUart_RX = 14; // Torch X2 uses UART2 of ESP32 to communicate with LG290P + pin_GnssUart_TX = 17; + pin_GNSS_DR_Reset = 22; // Push low to reset GNSS/DR. + + pin_GNSS_TimePulse = 39; // PPS on UM980 + + pin_usbSelect = 12; // Controls U18 switch between ESP UART0 to USB or GNSS UART1 + pin_powerAdapterDetect = 36; // Goes low when USB cable is plugged in + + pin_batteryStatusLED = 0; + pin_bluetoothStatusLED = 32; + pin_gnssStatusLED = 13; + + pin_beeper = 33; + + pin_powerButton = 34; + // pin_powerSenseAndControl = 18; // PWRKILL + + pin_loraRadio_power = 19; // LoRa_EN + // pin_loraRadio_boot = 23; // LoRa_BOOT0 + // pin_loraRadio_reset = 5; // LoRa_NRST + + DMW_if systemPrintf("pin_bluetoothStatusLED: %d\r\n", pin_bluetoothStatusLED); + pinMode(pin_bluetoothStatusLED, OUTPUT); + + DMW_if systemPrintf("pin_gnssStatusLED: %d\r\n", pin_gnssStatusLED); + pinMode(pin_gnssStatusLED, OUTPUT); + + DMW_if systemPrintf("pin_batteryStatusLED: %d\r\n", pin_batteryStatusLED); + pinMode(pin_batteryStatusLED, OUTPUT); + + // Turn on Bluetooth, GNSS, and Battery LEDs to indicate power on + bluetoothLedOn(); + gnssStatusLedOn(); + batteryStatusLedOn(); + + pinMode(pin_beeper, OUTPUT); + beepOff(); + + pinMode(pin_powerButton, INPUT); + + pinMode(pin_GNSS_TimePulse, INPUT); + + pinMode(pin_GNSS_DR_Reset, OUTPUT); + gnssBoot(); // Tell GNSS to boot + + pinMode(pin_powerAdapterDetect, INPUT); // Has 10k pullup + + pinMode(pin_usbSelect, OUTPUT); + digitalWrite(pin_usbSelect, LOW); // Keep ESP32 connected to CH342 (not GNSS UART1) + + // LoRa not mounted in X2, but power down to be sure + pinMode(pin_loraRadio_power, OUTPUT); + loraPowerOff(); // Keep LoRa powered down for now } } void beginVersion() { + firmwareVersionGet(deviceFirmware, sizeof(deviceFirmware), false); + char versionString[21]; firmwareVersionGet(versionString, sizeof(versionString), true); @@ -843,10 +1043,10 @@ void beginSD() gotSemaphore = false; - while (settings.enableSD == true) + while (settings.enableSD == true) // Note: settings.enableSD is never set to false { // Setup SD card access semaphore - if (sdCardSemaphore == nullptr) + if (sdCardSemaphore == NULL) sdCardSemaphore = xSemaphoreCreateMutex(); else if (xSemaphoreTake(sdCardSemaphore, fatSemaphore_shortWait_ms) != pdPASS) { @@ -862,7 +1062,7 @@ void beginSD() break; // Give up on loop // If an SD card is present, allow SdFat to take over - log_d("SD card detected"); + systemPrintf("SD card detected @ %s\r\n", getTimeStamp()); // Allocate the data structure that manages the microSD card if (!sd) @@ -930,7 +1130,7 @@ void beginSD() sdCardSize = 0; outOfSDSpace = true; - systemPrintln("microSD: Online"); + systemPrintf("microSD: Online @ %s\r\n", getTimeStamp()); online.microSD = true; break; } @@ -951,7 +1151,7 @@ void endSD(bool alreadyHaveSemaphore, bool releaseSemaphore) sd->end(); online.microSD = false; - systemPrintln("microSD: Offline"); + systemPrintf("microSD: Offline @ %s\r\n", getTimeStamp()); } // Free the caches for the microSD card @@ -1019,6 +1219,37 @@ void beginGnssUart() } } +void forceGnssCommunicationRate(uint32_t &platformGnssCommunicationRate) +{ + if (productVariant == RTK_TORCH) + { + // Override user setting. Required because beginGnssUart() is called before beginBoard(). + platformGnssCommunicationRate = 115200; + } + else if (productVariant == RTK_POSTCARD || productVariant == RTK_TORCH_X2) + { + // LG290P communicates at 460800bps. + platformGnssCommunicationRate = 115200 * 4; + } + else if (productVariant == RTK_FLEX) + { + if (settings.detectedGnssReceiver == GNSS_RECEIVER_LG290P) + { + // LG290P communicates at 460800bps. + platformGnssCommunicationRate = 115200 * 4; + } + else if (settings.detectedGnssReceiver == GNSS_RECEIVER_MOSAIC_X5) + { + // Mosaic defaults to 115200, but mosaicIsPresentOnFlex() increases COM1 to 460800bps + platformGnssCommunicationRate = 115200 * 4; + } + else + { + // If we don't know the GNSS receiver, default to 115200 + platformGnssCommunicationRate = 115200; + } + } +} // Assign GNSS UART interrupts to the core that started the task. See: // https://github.com/espressif/arduino-esp32/issues/3386 void pinGnssUartTask(void *pvParameters) @@ -1040,16 +1271,7 @@ void pinGnssUartTask(void *pvParameters) settings.dataPortBaud; // Default to 230400bps for ZED. This limits GNSS fixes at 4Hz but allows SD buffer to be // reduced to 6k. - if (productVariant == RTK_TORCH) - { - // Override user setting. Required because beginGnssUart() is called before beginBoard(). - platformGnssCommunicationRate = 115200; - } - else if (productVariant == RTK_POSTCARD) - { - // LG290P communicates at 460800bps. - platformGnssCommunicationRate = 115200 * 4; - } + forceGnssCommunicationRate(platformGnssCommunicationRate); serialGNSS->begin(platformGnssCommunicationRate, SERIAL_8N1, pin_GnssUart_RX, pin_GnssUart_TX); // Start UART on platform dependent pins for SPP. The GNSS will be @@ -1283,7 +1505,7 @@ void beginCharger() void beginButtons() { if (present.button_powerHigh == false && present.button_powerLow == false && present.button_mode == false && - present.gpioExpander == false) + present.gpioExpanderButtons == false) return; TaskHandle_t taskHandle; @@ -1296,18 +1518,21 @@ void beginButtons() buttonCount++; if (present.button_mode == true) buttonCount++; - if (present.gpioExpander == true) + if (present.gpioExpanderButtons == true) buttonCount++; if (buttonCount > 1) reportFatalError("Illegal button assignment."); // Postcard button uses an I2C expander // Avoid using the button library - if (present.gpioExpander == true) + if (present.gpioExpanderButtons == true) { - if (beginGpioExpander(0x20) == false) + if (beginGpioExpanderButtons(0x20) == false) // This updates online.gpioExpanderButtons { - systemPrintln("Directional pad not detected"); + systemPrintln("Portability Shield not detected"); + + present.microSd = false; + return; } } @@ -1323,7 +1548,7 @@ void beginButtons() userBtn = new Button(pin_powerButton, 25, true, false); // Turn off inversion. Needed for buttons that are high when pressed. - // EVK mode button + // EVK/Flex user button (Mode or Fn) if (present.button_mode == true) userBtn = new Button(pin_modeButton); @@ -1337,7 +1562,7 @@ void beginButtons() online.button = true; } - if (online.button == true || online.gpioExpander == true) + if (online.button == true || online.gpioExpanderButtons == true) { // Starts task for monitoring button presses if (!task.buttonCheckTaskRunning) @@ -1398,10 +1623,6 @@ void beginSystemState() // Return to either Base or Rover Not Started. The last state previous to power down. systemState = settings.lastState; - - // If the setting is not set, override with default - if (settings.antennaPhaseCenter_mm == 0.0) - settings.antennaPhaseCenter_mm = present.antennaPhaseCenter_mm; } else if (productVariant == RTK_POSTCARD) { @@ -1412,6 +1633,23 @@ void beginSystemState() if (systemState == STATE_BASE_NOT_STARTED) firstRoverStart = false; } + else if (productVariant == RTK_FLEX) + { + // Return to either Rover or Base Not Started. The last state previous to power down. + systemState = settings.lastState; + + firstRoverStart = true; // Allow user to enter test screen during first rover start + if (systemState == STATE_BASE_NOT_STARTED) + firstRoverStart = false; + } + else if (productVariant == RTK_TORCH_X2) + { + // Do not allow user to enter test screen during first rover start because there is no screen + firstRoverStart = false; + + // Return to either Base or Rover Not Started. The last state previous to power down. + systemState = settings.lastState; + } else { systemPrintf("beginSystemState: Unknown product variant: %d\r\n", productVariant); @@ -1592,6 +1830,12 @@ bool i2cBusInitialization(TwoWire *i2cBus, int sda, int scl, int clockKHz) break; } + case 0x10: { + systemPrintf(" 0x%02X - MFI343S00177 Authentication Coprocessor\r\n", addr); + i2cAuthCoPro = i2cBus; // Record the bus + break; + } + case 0x18: { systemPrintf(" 0x%02X - PCA9557 GPIO Expander with Reset\r\n", addr); break; @@ -1603,7 +1847,12 @@ bool i2cBusInitialization(TwoWire *i2cBus, int sda, int scl, int clockKHz) } case 0x20: { - systemPrintf(" 0x%02X - PCA9554 GPIO Expander with Interrupt\r\n", addr); + systemPrintf(" 0x%02X - PCA9554 GPIO Expander with Interrupt (Postcard)\r\n", addr); + break; + } + + case 0x21: { + systemPrintf(" 0x%02X - PCA9554 GPIO Expander with Interrupt (Flex)\r\n", addr); break; } @@ -1617,13 +1866,18 @@ bool i2cBusInitialization(TwoWire *i2cBus, int sda, int scl, int clockKHz) break; } + case 0x3C: { + systemPrintf(" 0x%02X - SSD1306 OLED Driver (Flex)\r\n", addr); + break; + } + case 0x3D: { - systemPrintf(" 0x%02X - SSD1306 OLED Driver\r\n", addr); + systemPrintf(" 0x%02X - SSD1306 OLED Driver (Postcard/EVK/mosaic)\r\n", addr); break; } case 0x42: { - systemPrintf(" 0x%02X - u-blox ZED-F9P GNSS Receiver\r\n", addr); + systemPrintf(" 0x%02X - u-blox GNSS Receiver\r\n", addr); break; } @@ -1653,7 +1907,7 @@ bool i2cBusInitialization(TwoWire *i2cBus, int sda, int scl, int clockKHz) // Determine if any devices are on the bus if (deviceFound == false) { - systemPrintln("No devices found on the I2C bus"); + systemPrintln("No devices found on this I2C bus"); return false; } return true; @@ -1699,12 +1953,12 @@ void tpISR() { if (online.rtc) // Only sync if the RTC has been set via PVT first { - if (timTpUpdated) // Only sync if timTpUpdated is true + if (timTpUpdated) // Only sync if timTpUpdated is true - set by storeTIMTPdata on ZED platforms only { - if (millisNow - lastRTCSync > + if ((millisNow - lastRTCSync) > syncRTCInterval) // Only sync if it is more than syncRTCInterval since the last sync { - if (millisNow < (timTpArrivalMillis + 999)) // Only sync if the GNSS time is not stale + if ((millisNow - timTpArrivalMillis) < 999) // Only sync if the GNSS time is not stale { if (gnss->isFullyResolved()) // Only sync if GNSS time is fully resolved { diff --git a/Firmware/RTK_Everywhere/Bluetooth.ino b/Firmware/RTK_Everywhere/Bluetooth.ino index a63de0f94..72f62e411 100644 --- a/Firmware/RTK_Everywhere/Bluetooth.ino +++ b/Firmware/RTK_Everywhere/Bluetooth.ino @@ -29,10 +29,16 @@ static volatile BTState bluetoothState = BT_OFF; +BluetoothRadioType_e bluetoothRadioPreviousOnType = BLUETOOTH_RADIO_OFF; + #ifdef COMPILE_BT -BTSerialInterface *bluetoothSerialSpp; -BTSerialInterface *bluetoothSerialBle; -BTSerialInterface *bluetoothSerialBleCommands; // Second BLE serial for CLI interface to mobile app + +#include + +BTSerialInterface *bluetoothSerialSpp = nullptr; +BTSerialInterface *bluetoothSerialBle = nullptr; +BTSerialInterface *bluetoothSerialBleCommands = nullptr; // Second BLE serial for CLI interface to mobile app +BleBatteryService bluetoothBatteryService; #define BLE_SERVICE_UUID "6e400001-b5a3-f393-e0a9-e50e24dcca9e" #define BLE_RX_UUID "6e400002-b5a3-f393-e0a9-e50e24dcca9e" @@ -55,7 +61,7 @@ void bluetoothUpdate() { #ifdef COMPILE_BT static uint32_t lastCheck = millis(); // Check if connected every 100ms - if (millis() > (lastCheck + 100)) + if ((millis() - lastCheck) > 100) { lastCheck = millis(); @@ -68,6 +74,14 @@ void bluetoothUpdate() // LED is controlled by tickerBluetoothLedUpdate() btPrintEchoExit = false; // Reset the exiting of config menus and/or command modes + +#ifdef COMPILE_AUTHENTICATION + if (sendAccessoryHandshakeOnBtConnect) + { + appleAccessory->startHandshake((Stream *)bluetoothSerialSpp); + sendAccessoryHandshakeOnBtConnect = false; // One-shot + } +#endif } else if ((bluetoothState == BT_CONNECTED) && (!bluetoothIsConnected())) @@ -108,6 +122,41 @@ bool bluetoothIsConnected() if (bluetoothSerialBle->connected() == true || bluetoothSerialBleCommands->connected() == true) return (true); } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + { + if (bluetoothSerialSpp->connected() == true) + return (true); + } +#endif // COMPILE_BT + + return (false); +} + +// Return true if the BLE Command channel is connected +bool bluetoothCommandIsConnected() +{ +#ifdef COMPILE_BT + if (bluetoothGetState() == BT_OFF) + return (false); + + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) + { + if (bluetoothSerialBleCommands->connected() == true) + return (true); + } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP) + { + return (false); + } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) + { + if (bluetoothSerialBleCommands->connected() == true) + return (true); + } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + { + return (false); + } #endif // COMPILE_BT return (false); @@ -127,6 +176,9 @@ byte bluetoothGetState() int bluetoothRead(uint8_t *buffer, int length) { #ifdef COMPILE_BT + if (bluetoothGetState() == BT_OFF) + return 0; + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) { int bytesRead = 0; @@ -145,6 +197,8 @@ int bluetoothRead(uint8_t *buffer, int length) return bluetoothSerialSpp->readBytes(buffer, length); else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) return bluetoothSerialBle->readBytes(buffer, length); + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + return 0; // Nothing to do here. SDP takes care of everything... return 0; @@ -174,6 +228,9 @@ int bluetoothCommandRead(uint8_t *buffer, int length) uint8_t bluetoothRead() { #ifdef COMPILE_BT + if (bluetoothGetState() == BT_OFF) + return 0; + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) { // Give incoming BLE the priority @@ -186,6 +243,8 @@ uint8_t bluetoothRead() return bluetoothSerialSpp->read(); else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) return bluetoothSerialBle->read(); + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + return 0; // Nothing to do here. SDP takes care of everything... return 0; #else // COMPILE_BT @@ -210,6 +269,9 @@ uint8_t bluetoothCommandRead() int bluetoothRxDataAvailable() { #ifdef COMPILE_BT + if (bluetoothGetState() == BT_OFF) + return 0; + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) { // Give incoming BLE the priority @@ -222,6 +284,8 @@ int bluetoothRxDataAvailable() return bluetoothSerialSpp->available(); else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) return bluetoothSerialBle->available(); + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + return 0; // Nothing to do here. SDP takes care of everything... return (0); #else // COMPILE_BT @@ -242,26 +306,13 @@ int bluetoothCommandAvailable() #endif // COMPILE_BT } -// Pass a command string to the BLE Serial interface -void bluetoothProcessCommand(char *rxData) -{ -#ifdef COMPILE_BT - // Direct output to Bluetooth Command - PrintEndpoint originalPrintEndpoint = printEndpoint; - - printEndpoint = PRINT_ENDPOINT_BLUETOOTH_COMMAND; - processCommand(rxData); // Send command proccesor output to BLE - printEndpoint = originalPrintEndpoint; - -#else // COMPILE_BT - processCommand(rxData); // Send command proccesor output to Serial -#endif // COMPILE_BT -} - // Write data to the Bluetooth device int bluetoothWrite(const uint8_t *buffer, int length) { #ifdef COMPILE_BT + if (bluetoothGetState() == BT_OFF) + return length; // Avoid buffer full warnings + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) { // Write to both interfaces @@ -286,6 +337,8 @@ int bluetoothWrite(const uint8_t *buffer, int length) return bluetoothSerialBle->write(buffer, length); return 0; } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + return length; // Nothing to do here. SDP takes care of everything... return (0); #else // COMPILE_BT @@ -313,6 +366,8 @@ int bluetoothCommandWrite(const uint8_t *buffer, int length) return bluetoothSerialBleCommands->write(buffer, length); return 0; } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + return length; // Nothing to do here. SDP takes care of everything... return (0); #else // COMPILE_BT @@ -324,6 +379,9 @@ int bluetoothCommandWrite(const uint8_t *buffer, int length) int bluetoothWrite(uint8_t value) { #ifdef COMPILE_BT + if (bluetoothGetState() == BT_OFF) + return 1; // Avoid buffer full warnings + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) { // Write to both interfaces @@ -345,6 +403,8 @@ int bluetoothWrite(uint8_t value) { return bluetoothSerialBle->write(value); } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + return 1; // Nothing to do here. SDP takes care of everything... return (0); #else // COMPILE_BT @@ -356,82 +416,141 @@ int bluetoothWrite(uint8_t value) void bluetoothFlush() { #ifdef COMPILE_BT + if (bluetoothGetState() == BT_OFF) + return; + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) { bluetoothSerialBle->flush(); + bluetoothSerialBleCommands->flush(); // Complete any transfers bluetoothSerialSpp->flush(); } else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP) bluetoothSerialSpp->flush(); else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) + { bluetoothSerialBle->flush(); -#else // COMPILE_BT + bluetoothSerialBleCommands->flush(); // Complete any transfers + } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + bluetoothSerialSpp->flush(); // Needed? Not sure... TODO +#else // COMPILE_BT return; -#endif // COMPILE_BT +#endif // COMPILE_BT +} + +void BTConfirmRequestCallback(uint32_t numVal) { + if (bluetoothGetState() == BT_OFF) + return; + + // TODO: if the RTK device has an OLED, we should display the PIN so user can confirm + systemPrintf("Device sent PIN: %06lu. Sending confirmation\r\n", numVal); +#ifdef COMPILE_BT + bluetoothSerialSpp->confirmReply(true); // AUTO_PAIR - equivalent to enableSSP(false, true); +#endif // COMPILE_BT +} + +void deviceNameSpacesToUnderscores() +{ + for (size_t i = 0; i < strlen(deviceName); i++) + { + if (deviceName[i] == ' ') + deviceName[i] = '_'; + } +} + +void deviceNameUnderscoresToSpaces() +{ + for (size_t i = 0; i < strlen(deviceName); i++) + { + if (deviceName[i] == '_') + deviceName[i] = ' '; + } } -// Get MAC, start radio -// Tack device's MAC address to end of friendly broadcast name -// This allows multiple units to be on at same time +// Begin Bluetooth with a broadcast name of 'SparkFun Postcard-XXXX' or 'SparkPNT Facet mosaicX5-XXXX' +// Add 4 characters of device's MAC address to end of the broadcast name +// This allows users to discern between multiple devices in the local area void bluetoothStart() +{ + bluetoothStart(false); +} +void bluetoothStartSkipOnlineCheck() +{ + bluetoothStart(true); +} +void bluetoothStart(bool skipOnlineCheck) { if (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) return; -#ifdef COMPILE_BT - if (!online.bluetooth) + if (!skipOnlineCheck) { - bluetoothState = BT_OFF; - char stateName[11] = {0}; - if (inRoverMode() == true) - strncpy(stateName, "Rover-", sizeof(stateName) - 1); - else if (inBaseMode() == true) - strncpy(stateName, "Base-", sizeof(stateName) - 1); - else + if (online.bluetooth) { - strncpy(stateName, "Rover-", sizeof(stateName) - 1); - log_d("State out of range for Bluetooth Broadcast: %d", systemState); + return; } + } + +#ifdef COMPILE_BT + { // Maintain the indentation for now. TODO: delete the braces and correct indentation + bluetoothState = BT_OFF; // Indicate to tasks that BT is unavailable char productName[50] = {0}; strncpy(productName, platformPrefix, sizeof(productName)); - // BLE is limited to ~28 characters in the device name. Shorten platformPrefix if needed. - if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE || - settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) - { - if (strcmp(productName, "Facet L-Band Direct") == 0) - { - strncpy(productName, "Facet L-Band", sizeof(productName)); - } - } - - snprintf(deviceName, sizeof(deviceName), "%s %s%02X%02X", productName, stateName, btMACAddress[4], + // Longest platform prefix is currently "Facet mosaicX5". We are just OK. + // We currently don't need this: + // // BLE is limited to ~28 characters in the device name. Shorten platformPrefix if needed. + // if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE || + // settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) + // { + // if (strcmp(productName, "LONG PLATFORM PREFIX") == 0) + // { + // strncpy(productName, "SHORTER PREFIX", sizeof(productName)); + // } + // } + + RTKBrandAttribute *brandAttributes = getBrandAttributeFromBrand(present.brand); + + snprintf(deviceName, sizeof(deviceName), "%s %s-%02X%02X", brandAttributes->name, productName, btMACAddress[4], btMACAddress[5]); - if (strlen(deviceName) > 28) + if (strlen(deviceName) > 28) // "SparkPNT Facet mosaicX5-ABCD" = 28 chars. We are just OK { - if (ENABLE_DEVELOPER) - systemPrintf( - "Warning! The Bluetooth device name '%s' is %d characters long. It may not work in BLE mode.\r\n", - deviceName, strlen(deviceName)); + // BLE will fail quietly if broadcast name is more than 28 characters + systemPrintf( + "ERROR! The Bluetooth device name \"%s\" is %d characters long. It will not work in BLE mode.\r\n", + deviceName, strlen(deviceName)); + reportFatalError("Bluetooth device name is longer than 28 characters."); } // Select Bluetooth setup - if (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) - return; - else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) { - bluetoothSerialSpp = new BTClassicSerial(); - bluetoothSerialBle = new BTLESerial(); - bluetoothSerialBleCommands = new BTLESerial(); + if (bluetoothSerialSpp == nullptr) + bluetoothSerialSpp = new BTClassicSerial(); + if (bluetoothSerialBle == nullptr) + bluetoothSerialBle = new BTLESerial(); + if (bluetoothSerialBleCommands == nullptr) + bluetoothSerialBleCommands = new BTLESerial(); } else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP) - bluetoothSerialSpp = new BTClassicSerial(); + { + if (bluetoothSerialSpp == nullptr) + bluetoothSerialSpp = new BTClassicSerial(); + } else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) { - bluetoothSerialBle = new BTLESerial(); - bluetoothSerialBleCommands = new BTLESerial(); + if (bluetoothSerialBle == nullptr) + bluetoothSerialBle = new BTLESerial(); + if (bluetoothSerialBleCommands == nullptr) + bluetoothSerialBleCommands = new BTLESerial(); + } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + { + if (bluetoothSerialSpp == nullptr) + bluetoothSerialSpp = new BTClassicSerial(); } // Not yet implemented @@ -464,6 +583,7 @@ void bluetoothStart() deviceName, false, false, settings.sppRxQueueSize, settings.sppTxQueueSize, BLE_COMMAND_SERVICE_UUID, BLE_COMMAND_RX_UUID, BLE_COMMAND_TX_UUID); // localName, isMaster, disableBLE, rxBufferSize, // txBufferSize, serviceID, rxID, txID + bluetoothBatteryService.begin(); } else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP) { @@ -483,7 +603,67 @@ void bluetoothStart() beginSuccess &= bluetoothSerialBleCommands->begin( deviceName, false, false, settings.sppRxQueueSize, settings.sppTxQueueSize, BLE_COMMAND_SERVICE_UUID, BLE_COMMAND_RX_UUID, BLE_COMMAND_TX_UUID); // localName, isMaster, disableBLE, rxBufferSize, - // txBufferSize, serviceID, rxID, txID + // txBufferSize, serviceID, rxID, txID + + bluetoothBatteryService.begin(); + } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + { + // Uncomment the next line to force deletion of all paired (bonded) devices + // (This should only be necessary if you have changed the SSP pairing type) + //settings.clearBtPairings = true; + + // Enable secure pairing without PIN : + // iPhone displays Connection Unsuccessful - but then connects anyway... + bluetoothSerialSpp->enableSSP(false, false); + + // Enable secure pairing with PIN : + //bluetoothSerialSpp->enableSSP(false, true); + + // Accessory Protocol recommends using a PIN + // Support Apple Accessory: Device to Accessory + // 1. Search for an accessory from the device and initiate pairing. + // 2. Verify pairing is successful after exchanging a pin code. + //bluetoothSerialSpp->enableSSP(true, true); // Enable secure pairing with PIN + //bluetoothSerialSpp->onConfirmRequest(&BTConfirmRequestCallback); // Callback to verify the PIN + + beginSuccess &= bluetoothSerialSpp->begin( + deviceName, true, true, settings.sppRxQueueSize, settings.sppTxQueueSize, 0, 0, + 0); // localName, isMaster, disableBLE, rxBufferSize, txBufferSize, serviceID, rxID, txID + + if (beginSuccess) + { + // bluetoothSerialSpp.getBtAddress(btMACAddress); // Read the ESP32 BT MAC Address + + if (settings.clearBtPairings) + { + // Paired / bonded devices are stored in flash. Only a full flash erase + // or deleteAllBondedDevices() will clear them all. They can be deleted + // individually, but that would need a menu and more functions added to + // the BT classes. + // Deleting all bonded devices after a factory reset seems sensible. + // TODO: test all the possibilities / overlap of this and "Forget Device" + if (settings.debugNetworkLayer) + systemPrintln("Deleting all bonded devices"); + bluetoothSerialSpp->deleteAllBondedDevices(); // Must be called after begin + settings.clearBtPairings = false; + recordSystemSettings(); + } + + esp_sdp_init(); + + esp_bluetooth_sdp_hdr_overlay_t record = {(esp_bluetooth_sdp_types_t)0}; + record.type = ESP_SDP_TYPE_RAW; + record.uuid.len = sizeof(UUID_IAP2); + memcpy(record.uuid.uuid.uuid128, UUID_IAP2, sizeof(UUID_IAP2)); + //record.service_name_length = strlen(sdp_service_name) + 1; + //record.service_name = (char *)sdp_service_name; + // Use the same EIR Local Name parameter as the Name in the IdentificationInformation + record.service_name_length = strlen(deviceName) + 1; + record.service_name = (char *)deviceName; + // record.rfcomm_channel_number = 1; // Doesn't seem to help the failed connects + esp_sdp_create_record((esp_bluetooth_sdp_record_t *)&record); + } } if (beginSuccess == false) @@ -534,6 +714,10 @@ void bluetoothStart() bluetoothSerialBle->setTimeout(10); bluetoothSerialBleCommands->setTimeout(10); // Using 10 from BleSerial example } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + { + bluetoothSerialSpp->setTimeout(250); // Needed? Not sure... TODO + } if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) systemPrint("Bluetooth SPP and BLE broadcasting as: "); @@ -541,6 +725,8 @@ void bluetoothStart() systemPrint("Bluetooth SPP broadcasting as: "); else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) systemPrint("Bluetooth Low-Energy broadcasting as: "); + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + systemPrint("Bluetooth SPP (Accessory Mode) broadcasting as: "); systemPrintln(deviceName); @@ -568,7 +754,8 @@ void bluetoothStart() bluetoothState = BT_NOTCONNECTED; reportHeapNow(false); online.bluetooth = true; - } + bluetoothRadioPreviousOnType = settings.bluetoothRadioType; + } // if (1) #endif // COMPILE_BT } @@ -597,40 +784,85 @@ void bluetoothStop() #ifdef COMPILE_BT if (online.bluetooth) { + if (settings.debugNetworkLayer) + systemPrintln("Bluetooth turning off"); + + bluetoothState = BT_OFF; // Indicate to tasks that BT is unavailable + + // Stop BLE Command Task if BLE is enabled + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE || + settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) + { + task.bluetoothCommandTaskStopRequest = true; + while (task.bluetoothCommandTaskRunning == true) + delay(1); + } + + // end and delete BT instances if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) { bluetoothSerialBle->flush(); // Complete any transfers bluetoothSerialBle->disconnect(); // Drop any clients bluetoothSerialBle->end(); // Release resources + //delete bluetoothSerialBle; + //bluetoothSerialBle = nullptr; bluetoothSerialBleCommands->flush(); // Complete any transfers bluetoothSerialBleCommands->disconnect(); // Drop any clients bluetoothSerialBleCommands->end(); // Release resources + //delete bluetoothSerialBleCommands; + //bluetoothSerialBleCommands = nullptr; bluetoothSerialSpp->flush(); // Complete any transfers bluetoothSerialSpp->disconnect(); // Drop any clients + bluetoothSerialSpp->register_callback(nullptr); bluetoothSerialSpp->end(); // Release resources + bluetoothSerialSpp->memrelease(); // Release memory + //delete bluetoothSerialSpp; + //bluetoothSerialSpp = nullptr; + + bluetoothBatteryService.end(); } else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP) { bluetoothSerialSpp->flush(); // Complete any transfers bluetoothSerialSpp->disconnect(); // Drop any clients + bluetoothSerialSpp->register_callback(nullptr); bluetoothSerialSpp->end(); // Release resources + bluetoothSerialSpp->memrelease(); // Release memory + //delete bluetoothSerialSpp; + //bluetoothSerialSpp = nullptr; } else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) { bluetoothSerialBle->flush(); // Complete any transfers bluetoothSerialBle->disconnect(); // Drop any clients bluetoothSerialBle->end(); // Release resources + //delete bluetoothSerialBle; + //bluetoothSerialBle = nullptr; bluetoothSerialBleCommands->flush(); // Complete any transfers bluetoothSerialBleCommands->disconnect(); // Drop any clients bluetoothSerialBleCommands->end(); // Release resources + //delete bluetoothSerialBleCommands; + //bluetoothSerialBleCommands = nullptr; + + bluetoothBatteryService.end(); + } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + { + bluetoothSerialSpp->flush(); // Complete any transfers + bluetoothSerialSpp->disconnect(); // Drop any clients + bluetoothSerialSpp->register_callback(nullptr); + bluetoothSerialSpp->end(); // Release resources + bluetoothSerialSpp->memrelease(); // Release memory + //delete bluetoothSerialSpp; + //bluetoothSerialSpp = nullptr; } - log_d("Bluetooth turned off"); + if (settings.debugNetworkLayer) + systemPrintln("Bluetooth turned off"); - bluetoothState = BT_OFF; reportHeapNow(false); online.bluetooth = false; } @@ -638,53 +870,10 @@ void bluetoothStop() bluetoothIncomingRTCM = false; } -// Test the bidirectional communication through UART connected to GNSS -// TODO Make this not ZED centric -void bluetoothTest(bool runTest) +// Print the current Bluetooth radio configuration and connection status +void bluetoothPrintStatus() { - // Verify the ESP UART can communicate TX/RX to ZED UART1 - const char *bluetoothStatusText; - - if (online.gnss == true) - { - if (runTest && (zedUartPassed == false)) - { - tasksStopGnssUart(); // Stop absorbing serial via task from GNSS receiver - - gnss->setBaudrate(115200 * 2); - - serialGNSS->begin(115200 * 2, SERIAL_8N1, pin_GnssUart_RX, - pin_GnssUart_TX); // Start UART on platform depedent pins for SPP. The GNSS will be - // configured to output NMEA over its UART at the same rate. - -#ifdef COMPILE_ZED - SFE_UBLOX_GNSS_SERIAL myGNSS; - if (myGNSS.begin(*serialGNSS) == true) // begin() attempts 3 connections - { - zedUartPassed = true; - bluetoothStatusText = (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) ? "Off" : "Online"; - } - else - bluetoothStatusText = "Offline"; -#endif // COMPILE_ZED - - gnss->setBaudrate(settings.dataPortBaud); - - serialGNSS->begin(settings.dataPortBaud, SERIAL_8N1, pin_GnssUart_RX, - pin_GnssUart_TX); // Start UART on platform depedent pins for SPP. The GNSS will be - // configured to output NMEA over its UART at the same rate. - - tasksStartGnssUart(); // Return to normal operation - } - else - bluetoothStatusText = (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) ? "Off" : "Online"; - } - else - bluetoothStatusText = "GNSS Offline"; - // Display Bluetooth MAC address and test results - char macAddress[5]; - snprintf(macAddress, sizeof(macAddress), "%02X%02X", btMACAddress[4], btMACAddress[5]); systemPrint("Bluetooth "); if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_AND_BLE) systemPrint("SPP and Low Energy "); @@ -692,11 +881,39 @@ void bluetoothTest(bool runTest) systemPrint("SPP "); else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) systemPrint("Low Energy "); + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + systemPrint("SPP Accessory Mode "); else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) systemPrint("Off "); + char macAddress[5]; + snprintf(macAddress, sizeof(macAddress), "%02X%02X", btMACAddress[4], btMACAddress[5]); systemPrint("("); systemPrint(macAddress); - systemPrint("): "); - systemPrintln(bluetoothStatusText); + systemPrint(")"); + + if (settings.bluetoothRadioType != BLUETOOTH_RADIO_OFF) + { + systemPrint(": "); + if (bluetoothIsConnected() == false) + systemPrint("Not "); + systemPrint("Connected"); + } + + systemPrintln(); } + +// Send over dedicated BLE service +void bluetoothSendBatteryPercent(int batteryLevelPercent) +{ +#ifdef COMPILE_BT + if (bluetoothGetState() == BT_OFF) + return; + + if ((settings.bluetoothRadioType != BLUETOOTH_RADIO_SPP_AND_BLE) && + (settings.bluetoothRadioType != BLUETOOTH_RADIO_BLE)) + return; + + bluetoothBatteryService.reportBatteryPercent(batteryLevelPercent); +#endif // COMPILE_BT +} \ No newline at end of file diff --git a/Firmware/RTK_Everywhere/Buttons.ino b/Firmware/RTK_Everywhere/Buttons.ino index 76c240300..6485fcc36 100644 --- a/Firmware/RTK_Everywhere/Buttons.ino +++ b/Firmware/RTK_Everywhere/Buttons.ino @@ -82,7 +82,7 @@ void IRAM_ATTR gpioExpanderISR() } // Start the I2C expander if possible -bool beginGpioExpander(uint8_t padAddress) +bool beginGpioExpanderButtons(uint8_t padAddress) { // Initialize the PCA95xx with its default I2C address if (io.begin(padAddress, *i2c_0) == true) @@ -99,7 +99,7 @@ bool beginGpioExpander(uint8_t padAddress) systemPrintln("Directional pad online"); - online.gpioExpander = true; + online.gpioExpanderButtons = true; return (true); } return (false); @@ -114,12 +114,12 @@ void buttonRead() userBtn->read(); // Check directional pad once interrupt has occurred - if (online.gpioExpander == true && gpioChanged == true) + if (online.gpioExpanderButtons == true && gpioChanged == true) { gpioChanged = false; // Get all the pins in one read - uint8_t currentState = io.getInputRegister() & 0b00111111; // Ignore unconnected GPIO6/7 + uint8_t currentState = io.getInputRegister() & 0b00011111; // Mask the five buttons. Ignore SD detect if (currentState != gpioExpander_previousState) { @@ -155,7 +155,7 @@ bool buttonReleased() return (userBtn->wasReleased()); // Check directional pad - if (online.gpioExpander == true) + if (online.gpioExpanderButtons == true) { // Check for any button press on the directional pad for (int buttonNumber = 0; buttonNumber < 5; buttonNumber++) @@ -179,7 +179,7 @@ bool buttonReleased(uint8_t buttonNumber) return (false); // Check directional pad - if (online.gpioExpander == true) + if (online.gpioExpanderButtons == true) { if (gpioExpander_wasReleased[buttonNumber] == true) { @@ -206,7 +206,7 @@ bool buttonPressedFor(uint16_t maxTime) bool buttonPressedFor(uint8_t buttonNumber, uint16_t maxTime) { // Check directional pad - if (online.gpioExpander == true) + if (online.gpioExpanderButtons == true) { // Check if the time has started for this button if (gpioExpander_holdStart[buttonNumber] > 0) diff --git a/Firmware/RTK_Everywhere/Developer.ino b/Firmware/RTK_Everywhere/Developer.ino index f0d9d31f8..75ce977f5 100644 --- a/Firmware/RTK_Everywhere/Developer.ino +++ b/Firmware/RTK_Everywhere/Developer.ino @@ -9,8 +9,9 @@ // Ethernet //---------------------------------------- -bool ethernetLinkUp() {return false;} -void menuEthernet() {systemPrintln("**Ethernet not compiled**");} +bool ethernetLinkUp() {return false;} +void menuEthernet() {systemPrintln("**Ethernet not compiled**");} +void ethernetUpdate() {} bool ntpLogIncreasing = false; @@ -171,9 +172,12 @@ bool webServerStart(int httpPort = 80) bool parseIncomingSettings() {return false;} void sendStringToWebsocket(const char* stringToSend) {} void stopWebServer() {} +bool webServerSettingsCheckAndFree() {return false;} +void webServerSettingsClone() {} void webServerStop() {} void webServerUpdate() {} void webServerVerifyTables() {} +bool wifiAfterCommand(int cmdIndex){return false;} void wifiSettingsClone() {} bool webServerIsRunning() {return false;} @@ -185,15 +189,15 @@ bool webServerIsRunning() {return false;} #ifndef COMPILE_ESPNOW -bool espNowGetState() {return ESPNOW_OFF;} bool espNowIsPaired() {return false;} +bool espNowIsPairing() {return false;} +bool espNowIsBroadcasting() {return false;} void espNowProcessRTCM(byte incoming) {} bool espNowProcessRxPairedMessage() {return true;} esp_err_t espNowRemovePeer(const uint8_t *peerMac) {return ESP_OK;} esp_err_t espNowSendPairMessage(const uint8_t *sendToMac) {return ESP_OK;} bool espNowSetChannel(uint8_t channelNumber) {return false;} bool espNowStart() {return true;} -void espNowStaticPairing() {} bool espNowStop() {return true;} void espNowUpdate() {} @@ -210,9 +214,10 @@ void wifiDisplayNetworkData() {} void wifiDisplaySoftApStatus() {} bool wifiEspNowOff(const char * fileName, uint32_t lineNumber) {return true;} bool wifiEspNowOn(const char * fileName, uint32_t lineNumber) {return false;} -void wifiEspNowSetChannel(WIFI_CHANNEL_t channel) {} +void wifiEspNowChannelSet(WIFI_CHANNEL_t channel) {} int wifiNetworkCount() {return 0;} void wifiResetTimeout() {} +IPAddress wifiSoftApGetBroadcastIpAddress() {return IPAddress((uint32_t)0);} IPAddress wifiSoftApGetIpAddress() {return IPAddress((uint32_t)0);} const char * wifiSoftApGetSsid() {return "";} bool wifiSoftApOff(const char * fileName, uint32_t lineNumber) {return true;} @@ -264,6 +269,7 @@ void nmeaExtractStdDeviations(char *nmeaSentence, int arraySize) {} void processNonSBFData(SEMP_PARSE_STATE *parse) {} void processUart1SBF(SEMP_PARSE_STATE *parse, uint16_t type) {} void processUart1SPARTN(SEMP_PARSE_STATE *parse, uint16_t type) {} +void menuLogMosaic() {} #endif // COMPILE_MOSAICX5 @@ -288,10 +294,8 @@ void pointperfectPrintKeyInformation(const char *requestedBy) {systemPrintln("** #ifndef COMPILE_LG290P -void lg290pBoot() {} void lg290pHandler(uint8_t * buffer, int length) {} bool lg290pMessageEnabled(char *nmeaSentence, int sentenceLength) {return false;} -void lg290pReset() {} #endif // COMPILE_LG290P @@ -308,3 +312,14 @@ void convertGnssTimeToEpoch(uint32_t *epochSecs, uint32_t *epochMicros) { } #endif // COMPILE_ZED + +//---------------------------------------- +// MFi authentication coprocessor +//---------------------------------------- + +#ifndef COMPILE_AUTHENTICATION + +void beginAuthCoPro(TwoWire *i2cBus) {systemPrintln("**MFi Authentication Not Compiled**");} +void updateAuthCoPro() {} + +#endif // COMPILE_AUTHENTICATION \ No newline at end of file diff --git a/Firmware/RTK_Everywhere/Display.ino b/Firmware/RTK_Everywhere/Display.ino index 3f112cba7..bcb1ef59a 100644 --- a/Firmware/RTK_Everywhere/Display.ino +++ b/Firmware/RTK_Everywhere/Display.ino @@ -84,10 +84,10 @@ enum ICON_POSITION_t }; // WiFi icons -const iconProperty * wifiIconTable[ICON_POSITION_MAX][4] -{ // 0 1 2 3 - {&WiFiSymbol0Left64x48, &WiFiSymbol1Left64x48, &WiFiSymbol2Left64x48, &WiFiSymbol3Left64x48}, - {&WiFiSymbol0128x64, &WiFiSymbol1128x64, &WiFiSymbol2128x64, &WiFiSymbol3128x64}, +const iconProperty *wifiIconTable[ICON_POSITION_MAX][4]{ + // 0 1 2 3 + {&WiFiSymbol0Left64x48, &WiFiSymbol1Left64x48, &WiFiSymbol2Left64x48, &WiFiSymbol3Left64x48}, + {&WiFiSymbol0128x64, &WiFiSymbol1128x64, &WiFiSymbol2128x64, &WiFiSymbol3128x64}, {&WiFiSymbol0Right64x48, &WiFiSymbol1Right64x48, &WiFiSymbol2Right64x48, &WiFiSymbol3Right64x48}, }; //---------------------------------------- @@ -97,9 +97,9 @@ const iconProperty * wifiIconTable[ICON_POSITION_MAX][4] static QwiicCustomOLED *oled = nullptr; // Fonts +#include #include #include -#include #include // Icons @@ -149,6 +149,10 @@ void beginDisplay(TwoWire *i2cBus) if (present.display_type == DISPLAY_128x64) { i2cAddress = kOLEDMicroDefaultAddress; + + if (productVariant == RTK_FLEX) + i2cAddress = 0x3C; + if (oled == nullptr) oled = new QwiicCustomOLED; if (!oled) @@ -178,6 +182,12 @@ void beginDisplay(TwoWire *i2cBus) systemPrintln("Display started"); + if (present.displayInverted == true) + { + oled->flipVertical(true); + oled->flipHorizontal(true); + } + // Display the brand LOGO RTKBrandAttribute *brandAttribute = getBrandAttributeFromBrand(present.brand); oled->erase(); @@ -202,17 +212,18 @@ void displayUpdate() if (online.display == true) { static unsigned long lastDisplayUpdate = 0; - if (millis() - lastDisplayUpdate > 500 || forceDisplayUpdate == true) // Update display at 2Hz + if (((millis() - lastDisplayUpdate) > 500) || (forceDisplayUpdate == true)) // Update display at 2Hz { lastDisplayUpdate = millis(); forceDisplayUpdate = false; - oled->reset(false); // Incase of previous corruption, force re-alignment of CGRAM. Do not init buffers as it - // takes time and causes screen to blink. + if (present.displayInverted == false) + oled->reset(false); // Incase of previous corruption, force re-alignment of CGRAM. Do not init buffers as it + // takes time and causes screen to blink. oled->erase(); - iconPropertyList.clear(); // Redundant? + iconPropertyList.clear(); // Redundant? switch (systemState) { @@ -367,7 +378,8 @@ void displayUpdate() break; case (STATE_NTPSERVER_NOT_STARTED): - case (STATE_NTPSERVER_NO_SYNC): { + case (STATE_NTPSERVER_NO_SYNC): + { paintClock(&iconPropertyList, true); // Blink displaySivVsOpenShort(&iconPropertyList); @@ -388,7 +400,8 @@ void displayUpdate() } break; - case (STATE_NTPSERVER_SYNC): { + case (STATE_NTPSERVER_SYNC): + { paintClock(&iconPropertyList, false); // No blink displaySivVsOpenShort(&iconPropertyList); paintLogging(&iconPropertyList, false, true); // No pulse, NTP @@ -653,15 +666,15 @@ void setRadioIcons(std::vector *iconList) if (present.display_type == DISPLAY_64x48) { // There are three spots for icons in the Wireless area, left/center/right - // There are three radios that could be active: Bluetooth (always indicated), WiFi (if enabled), ESP-Now (if + // There are three radios that could be active: Bluetooth (always indicated), WiFi (if enabled), ESP-NOW (if // enabled) Because of lack of space we will indicate the Base/Rover if only two radios or less are active // // Top left corner - Radio icon indicators take three spots (left/center/right) // Allowed icon combinations: // Bluetooth + Rover/Base // WiFi + Bluetooth + Rover/Base - // ESP-Now + Bluetooth + Rover/Base - // ESP-Now + Bluetooth + WiFi + // ESP-NOW + Bluetooth + Rover/Base + // ESP-NOW + Bluetooth + WiFi // Count the number of radios in use uint8_t numberOfRadios = 1; // Bluetooth always indicated. @@ -750,7 +763,7 @@ void setRadioIcons(std::vector *iconList) // WiFi : Columns 34 - 46 if (wifiStationRunning && networkInterfaceHasInternet(NETWORK_WIFI_STATION)) { - //Display solid icon based on RSSI + // Display solid icon based on RSSI displayWiFiIcon(iconList, prop, ICON_POSITION_CENTER, 0b11111111); } else if (wifiStationRunning && (networkInterfaceHasInternet(NETWORK_WIFI_STATION) == false)) @@ -758,7 +771,7 @@ void setRadioIcons(std::vector *iconList) // We are not connected, blink icon displayWiFiFullIcon(iconList, prop, ICON_POSITION_CENTER, 0b01010101); } - else if(wifiSoftApRunning) + else if (wifiSoftApRunning) { // We are in AP mode, solid WiFi icon displayWiFiIcon(iconList, prop, ICON_POSITION_CENTER, 0b11111111); @@ -904,19 +917,22 @@ void setRadioIcons(std::vector *iconList) paintDynamicModel(iconList); break; case (STATE_BASE_TEMP_SETTLE): - case (STATE_BASE_TEMP_SURVEY_STARTED): { + case (STATE_BASE_TEMP_SURVEY_STARTED): + { prop.duty = 0b00001111; prop.icon = BaseTemporaryProperties.iconDisplay[present.display_type]; iconList->push_back(prop); } break; - case (STATE_BASE_TEMP_TRANSMITTING): { + case (STATE_BASE_TEMP_TRANSMITTING): + { prop.duty = 0b11111111; prop.icon = BaseTemporaryProperties.iconDisplay[present.display_type]; iconList->push_back(prop); } break; - case (STATE_BASE_FIXED_TRANSMITTING): { + case (STATE_BASE_FIXED_TRANSMITTING): + { prop.duty = 0b11111111; prop.icon = BaseFixedProperties.iconDisplay[present.display_type]; iconList->push_back(prop); @@ -1254,21 +1270,24 @@ void setModeIcon(std::vector *iconList) case (STATE_BASE_NOT_STARTED): // Do nothing. Static display shown during state change. break; - case (STATE_BASE_TEMP_SETTLE): { + case (STATE_BASE_TEMP_SETTLE): + { iconPropertyBlinking prop; prop.duty = 0b00001111; prop.icon = BaseTemporaryProperties.iconDisplay[present.display_type]; iconList->push_back(prop); } break; - case (STATE_BASE_TEMP_SURVEY_STARTED): { + case (STATE_BASE_TEMP_SURVEY_STARTED): + { iconPropertyBlinking prop; prop.duty = 0b00001111; prop.icon = BaseTemporaryProperties.iconDisplay[present.display_type]; iconList->push_back(prop); } break; - case (STATE_BASE_TEMP_TRANSMITTING): { + case (STATE_BASE_TEMP_TRANSMITTING): + { iconPropertyBlinking prop; prop.duty = 0b11111111; prop.icon = BaseTemporaryProperties.iconDisplay[present.display_type]; @@ -1278,7 +1297,8 @@ void setModeIcon(std::vector *iconList) case (STATE_BASE_FIXED_NOT_STARTED): // Do nothing. Static display shown during state change. break; - case (STATE_BASE_FIXED_TRANSMITTING): { + case (STATE_BASE_FIXED_TRANSMITTING): + { iconPropertyBlinking prop; prop.duty = 0b11111111; prop.icon = BaseFixedProperties.iconDisplay[present.display_type]; @@ -1728,7 +1748,7 @@ void nudgeAndPrintSIV(displayCoords textCoords, uint8_t siv) { // On 128x64, there's no need to nudge oled->setCursor(textCoords.x, textCoords.y); // x, y - oled->print(siv); // 1 or 2 digits + oled->print(siv); // 1 or 2 digits } } @@ -1904,7 +1924,7 @@ void paintRTCM(std::vector *iconList) if (present.display_type == DISPLAY_64x48) yPos = yPos - 1; // Move text up by 1 pixel on 64x48. Note: this is brittle. - if(settings.baseCasterOverride == true) + if (settings.baseCasterOverride == true) printTextAt("BaseCast", xPos + 4, yPos, QW_FONT_8X16, 1); // text, y, font type, kerning else if (casting) printTextAt("Casting", xPos + 4, yPos, QW_FONT_8X16, 1); // text, y, font type, kerning @@ -1972,7 +1992,7 @@ void paintIPAddress() char ipAddress[16]; snprintf(ipAddress, sizeof(ipAddress), "%s", #ifdef COMPILE_ETHERNET - ETH.localIP().toString()); + ETH.localIP().toString().c_str()); #else // COMPILE_ETHERNET "0.0.0.0"); #endif // COMPILE_ETHERNET @@ -2012,7 +2032,7 @@ void displayFullIPAddress(std::vector *iconList) // Bottom { static IPAddress ipAddress; NetPriority_t priority; - static NetPriority_t previousPriority; + static NetPriority_t previousPriority = NETWORK_NONE; // Max width: 15*6 = 90 pixels (6 pixels per character, nnn.nnn.nnn.nnn) if (present.display_type == DISPLAY_128x64) @@ -2032,7 +2052,7 @@ void displayFullIPAddress(std::vector *iconList) // Bottom // Display the IP address when it is available if (ipAddress != IPAddress((uint32_t)0)) { - snprintf(myAddress, sizeof(myAddress), "%s", ipAddress.toString()); + snprintf(myAddress, sizeof(myAddress), "%s", ipAddress.toString().c_str()); oled->setFont(QW_FONT_5X7); // Set font to smallest oled->setCursor(0, 55); @@ -2315,9 +2335,7 @@ void displaySDFail(uint16_t displayTime) } // Display the full WiFi icon -void displayWiFiFullIcon(std::vector *iconList, - iconPropertyBlinking prop, - uint8_t position, +void displayWiFiFullIcon(std::vector *iconList, iconPropertyBlinking prop, uint8_t position, uint8_t dutyCycle) { prop.duty = dutyCycle; @@ -2326,9 +2344,7 @@ void displayWiFiFullIcon(std::vector *iconList, } // Display the WiFi icon based upon RSSI value -void displayWiFiIcon(std::vector *iconList, - iconPropertyBlinking prop, - uint8_t position, +void displayWiFiIcon(std::vector *iconList, iconPropertyBlinking prop, uint8_t position, uint8_t dutyCycle) { #ifdef COMPILE_WIFI @@ -2403,10 +2419,9 @@ void displayHalt() { oled->erase(); // Clear the display's internal buffer int yPos = (oled->getHeight() - 16) / 2; - QwiicFont * font = (oled->getWidth() > 64) ? (QwiicFont *)&QW_FONT_31X48 - : (QwiicFont *)&QW_FONT_8X16; + QwiicFont *font = (oled->getWidth() > 64) ? (QwiicFont *)&QW_FONT_31X48 : (QwiicFont *)&QW_FONT_8X16; printTextCenter("Halt", yPos, *font, 1, false); // text, y, font type, kerning, inverted - oled->display(); // Push internal buffer to display + oled->display(); // Push internal buffer to display } } @@ -2478,7 +2493,7 @@ void paintSystemTest() if (online.display == true) { // Toggle between two displays - if (millis() - systemTestDisplayTime > 3000) + if ((millis() - systemTestDisplayTime) > 3000) { systemTestDisplayTime = millis(); systemTestDisplayNumber++; @@ -2496,7 +2511,7 @@ void paintSystemTest() drawFrame(); // Outside edge - oled->setFont(QW_FONT_5X7); // Set font to smallest + oled->setFont(QW_FONT_5X7); // Set font to smallest if (present.microSd) { @@ -2657,7 +2672,8 @@ void paintDisplaySetup() { constructSetupDisplay(&setupButtons); // Construct the vector (linked list) of buttons - uint8_t maxButtons = ((present.display_type == DISPLAY_128x64) ? 5 : 4); + uint8_t maxButtons = + ((present.display_type == DISPLAY_128x64) ? 5 : 4); uint8_t printedButtons = 0; @@ -2672,7 +2688,10 @@ void paintDisplaySetup() { if (it->newState == STATE_PROFILE) { - int nameWidth = ((present.display_type == DISPLAY_128x64) ? 17 : 9); + int nameWidth = + ((present.display_type == DISPLAY_128x64) + ? 17 + : 9); char miniProfileName[nameWidth] = {0}; snprintf(miniProfileName, sizeof(miniProfileName), "%d_%s", it->newProfile, it->name); // Prefix with index # @@ -2794,11 +2813,12 @@ void displayMessage(const char *message, uint16_t displayTime) // Count words based on spaces uint8_t wordCount = 0; strncpy(temp, message, sizeof(temp) - 1); // strtok modifies the message so make copy - char *token = strtok(temp, " "); + char *preservedPointer; + char *token = strtok_r(temp, " ", &preservedPointer); while (token != nullptr) { wordCount++; - token = strtok(nullptr, " "); + token = strtok_r(nullptr, " ", &preservedPointer); } uint8_t yPos = (oled->getHeight() / 2) - (fontHeight / 2); @@ -2810,11 +2830,11 @@ void displayMessage(const char *message, uint16_t displayTime) // drawFrame(); strncpy(temp, message, sizeof(temp) - 1); - token = strtok(temp, " "); + token = strtok_r(temp, " ", &preservedPointer); while (token != nullptr) { printTextCenter(token, yPos, QW_FONT_8X16, 1, false); // text, y, font type, kerning, inverted - token = strtok(nullptr, " "); + token = strtok_r(nullptr, " ", &preservedPointer); yPos += fontHeight; } @@ -3072,14 +3092,14 @@ void paintKeyProvisionFail(uint16_t displayTime) } } -// Show screen while ESP-Now is pairing +// Show screen while ESP-NOW is pairing void paintEspNowPairing() { - displayMessage("ESP-Now Pairing", 0); + displayMessage("ESP-NOW Pairing", 2000); } void paintEspNowPaired() { - displayMessage("ESP-Now Paired", 2000); + displayMessage("ESP-NOW Paired", 2000); } void displayNtpStart(uint16_t displayTime) @@ -3187,7 +3207,7 @@ void displayWebConfig(std::vector &iconPropertyList) // Toggle display back and forth for long SSIDs and IPs // Run the timer no matter what, but load firstHalf/lastHalf with the same thing if strlen < maxWidth - if (millis() - ssidDisplayTimer > 2000) + if ((millis() - ssidDisplayTimer) > 2000) { ssidDisplayTimer = millis(); ssidDisplayFirstHalf = !ssidDisplayFirstHalf; @@ -3198,8 +3218,8 @@ void displayWebConfig(std::vector &iconPropertyList) #ifndef COMPILE_ETHERNET strcpy(mySSID, "!Compiled"); strcpy(myIP, "0.0.0.0"); -#endif // COMPILE_ETHERNET -#else // COMPILE_WIFI +#endif // COMPILE_ETHERNET +#else // COMPILE_WIFI if (wifi.softApOnline()) { setWiFiIcon(&iconPropertyList); // Blink WiFi in center @@ -3218,10 +3238,10 @@ void displayWebConfig(std::vector &iconPropertyList) strcpy(mySSID, "Error"); strcpy(myIP, "0.0.0.0"); } -#endif // COMPILE_ETHERNET -#endif // COMPILE_WIFI +#endif // COMPILE_ETHERNET +#endif // COMPILE_WIFI -#ifdef COMPILE_ETHERNET +#ifdef COMPILE_ETHERNET if (networkInterfaceHasInternet(NETWORK_ETHERNET)) { yPos = displayEthernetIcon(); @@ -3233,13 +3253,13 @@ void displayWebConfig(std::vector &iconPropertyList) #ifdef COMPILE_WIFI setWiFiIcon(&iconPropertyList); // Blink WiFi in center displaySsid = false; -#else // COMPILE_WIFI +#else // COMPILE_WIFI yPos = displayEthernetIcon(); -#endif // COMPILE_WIFI +#endif // COMPILE_WIFI strcpy(mySSID, "Error"); strcpy(myIP, "0.0.0.0"); } -#endif // COMPILE_ETHERNET +#endif // COMPILE_ETHERNET // Trim SSID to a max length mySSID[SSID_LENGTH] = 0; @@ -3269,3 +3289,30 @@ void displayWebConfig(std::vector &iconPropertyList) printTextCenter(myIP, yPos, QW_FONT_5X7, 1, false); } + +// Show GNSS update - button exit +void paintGnssUpdate() +{ + paintGenericUpdate("GNSS"); +} +void paintLoRaUpdate() +{ + paintGenericUpdate("LoRa"); +} +void paintGenericUpdate(const char *device) +{ + if (online.display) + { + oled->erase(); // Clear the display's internal buffer + int yPos = (oled->getHeight() - 38) / 2; + uint8_t fontHeight = 8; + printTextCenter(device, yPos, QW_FONT_5X7, 1, false); // text, y, font type, kerning, inverted + yPos = yPos + fontHeight + 1; + printTextCenter("Update", yPos, QW_FONT_5X7, 1, false); + yPos = yPos + fontHeight + 3; + printTextCenter("Button", yPos, QW_FONT_5X7, 1, true); // text, y, font type, kerning, inverted + yPos = yPos + fontHeight + 1; + printTextCenter("To Exit", yPos, QW_FONT_5X7, 1, true); + oled->display(); // Push internal buffer to display + } +} diff --git a/Firmware/RTK_Everywhere/ESPNOW.ino b/Firmware/RTK_Everywhere/ESPNOW.ino index 3a444e985..f7b8c2e49 100644 --- a/Firmware/RTK_Everywhere/ESPNOW.ino +++ b/Firmware/RTK_Everywhere/ESPNOW.ino @@ -21,6 +21,8 @@ frame is not critical. **********************************************************************/ +bool espnowRequestPair = false; // Modified by states.ino, menuRadio, or CLI + #ifdef COMPILE_ESPNOW //**************************************** @@ -47,6 +49,7 @@ uint8_t espNowOutgoing[250]; // ESP NOW has max of 250 characters uint8_t espNowOutgoingSpot; // ESP Now has a max of 250 characters uint8_t espNowReceivedMAC[6]; // Holds the MAC received during pairing ESPNOWState espNowState; +ESPNOWState espNowPrePairingState; //********************************************************************* // Add a peer to the ESP-NOW network @@ -83,7 +86,7 @@ esp_err_t espNowAddPeer(const uint8_t *peerMac) } //********************************************************************* -// Start ESP-Now if needed, put ESP-Now into broadcast state +// Start ESP-NOW if needed, put ESP-NOW into broadcast state void espNowBeginPairing() { if (settings.enableEspNow == false) @@ -96,9 +99,25 @@ void espNowBeginPairing() } // Start ESP-NOW if necessary - // If no peers are on file, automatically add the broadcast MAC to the peer list wifiEspNowOn(__FILE__, __LINE__); + // If this device has been paired to other units, the broadcastMAC is not yet enabled. Enable it for pairing. + if (esp_now_is_peer_exist(espNowBroadcastAddr) == false) + { + // Add the broadcast peer + esp_err_t result = espNowAddPeer(espNowBroadcastAddr); + if (settings.debugEspNow == true) + { + if (result != ESP_OK) + systemPrintln("Failed to add broadcast peer"); + else + systemPrintln("Broadcast peer added"); + } + } + + espNowPrePairingState = + espNowState; // Once pairing is completed or canceled, we will need to return to the original state + espNowSetState(ESPNOW_PAIRING); } @@ -109,6 +128,16 @@ bool espNowIsPaired() return (espNowState == ESPNOW_PAIRED); } +bool espNowIsPairing() +{ + return (espNowState == ESPNOW_PAIRING); +} + +bool espNowIsBroadcasting() +{ + return (espNowState == ESPNOW_BROADCASTING); +} + //********************************************************************* // Callback when data is received void espNowOnDataReceived(const esp_now_recv_info *mac, const uint8_t *incomingData, int len) @@ -155,12 +184,13 @@ void espNowOnDataReceived(const esp_now_recv_info *mac, const uint8_t *incomingD { espNowRSSI = packetRSSI; // Record this packet's RSSI as an ESP NOW packet - // We've just received ESP-Now data. We assume this is RTCM and push it directly to the GNSS. + // We've just received ESP-NOW data. We assume this is RTCM and push it directly to the GNSS. // Determine if ESPNOW is the correction source if (correctionLastSeen(CORR_ESPNOW)) { // Pass RTCM bytes (presumably) from ESP NOW out ESP32-UART to GNSS gnss->pushRawData((uint8_t *)incomingData, len); + sempParseNextBytes(rtcmParse, (uint8_t *)incomingData, len); // Parse the data for RTCM1005/1006 if ((settings.debugEspNow == true || settings.debugCorrections == true) && !inMainMenu) systemPrintf("ESPNOW received %d RTCM bytes, pushed to GNSS, RSSI: %d\r\n", len, espNowRSSI); @@ -248,46 +278,6 @@ void espNowProcessRTCM(byte incoming) // ESPNOW_PAIRED states. //********************************************************************* -//********************************************************************* -// Regularly call during pairing to see if we've received a Pairing message -bool espNowProcessRxPairedMessage() -{ - if (espNowState != ESPNOW_MAC_RECEIVED) - return false; - - // Remove broadcast peer - espNowRemovePeer(espNowBroadcastAddr); - - // Is the received MAC already paired? - if (esp_now_is_peer_exist(espNowReceivedMAC) == true) - { - // Yes, already paired - if (settings.debugEspNow == true) - systemPrintln("Peer already exists"); - } - else - { - // No, add new peer to system - espNowAddPeer(espNowReceivedMAC); - - // Record this MAC to peer list - memcpy(settings.espnowPeers[settings.espnowPeerCount], espNowReceivedMAC, 6); - settings.espnowPeerCount++; - settings.espnowPeerCount %= ESPNOW_MAX_PEERS; - } - - // Send message directly to the received MAC (not unicast), then exit - espNowSendPairMessage(espNowReceivedMAC); - - // Enable radio. User may have arrived here from the setup menu rather than serial menu. - settings.enableEspNow = true; - - // Record enableEspNow and espnowPeerCount to NVM - recordSystemSettings(); - espNowSetState(ESPNOW_PAIRED); - return (true); -} - //********************************************************************* // Remove a given MAC address from the peer list esp_err_t espNowRemovePeer(const uint8_t *peerMac) @@ -322,6 +312,9 @@ esp_err_t espNowSendPairMessage(const uint8_t *sendToMac) for (int x = 0; x < 6; x++) pairMessage.crc += wifiMACAddress[x]; + if (settings.debugEspNow == true && !inMainMenu) + systemPrintln("ESPNOW send pair message\r\n"); + return (esp_now_send(sendToMac, (uint8_t *)&pairMessage, sizeof(pairMessage))); // Send packet to given MAC } @@ -399,6 +392,11 @@ bool espNowStart() break; } + // Using ESP-NOW, a receiver will receive all packets addressed to its MAC and the broadcast MAC + // with no peers added. It is the transmitter that needs peers assigned to filter out packets. + // Therefore, if ESP-NOW is enabled, we add the broadcast MAC to the peer list by default to allow + // the link to function without pairing, and allow pairing messages if pairing is started. + // Check for peers listed in settings if (settings.espnowPeerCount == 0) { @@ -423,7 +421,7 @@ bool espNowStart() } espNowSetState(ESPNOW_BROADCASTING); } - else + else // settings.espnowPeerCount > 0 { // If we have peers, move to paired state espNowSetState(ESPNOW_PAIRED); @@ -484,50 +482,6 @@ bool espNowStart() return started; } -//********************************************************************* -// A blocking function that is used to pair two devices -// either through the serial menu or AP config -void espNowStaticPairing() -{ - systemPrintln("Begin ESP NOW Pairing"); - - // Start ESP-Now if needed, put ESP-Now into broadcast state - espNowBeginPairing(); - - // Begin sending our MAC every 250ms until a remote device sends us there info - randomSeed(millis()); - - systemPrintln("Begin pairing. Place other unit in pairing mode. Press any key to exit."); - clearBuffer(); - - bool exitPair = false; - while (exitPair == false) - { - if (systemAvailable()) - { - systemPrintln("User pressed button. Pairing canceled."); - break; - } - - int timeout = 1000 + random(0, 100); // Delay 1000 to 1100ms - for (int x = 0; x < timeout; x++) - { - delay(1); - - if (espNowProcessRxPairedMessage() == true) // Check if we've received a pairing message - { - systemPrintln("Pairing compete"); - exitPair = true; - break; - } - } - - espNowSendPairMessage(espNowBroadcastAddr); // Send unit's MAC address over broadcast, no ack, no encryption - - systemPrintln("Scanning for other radio..."); - } -} - //********************************************************************* // Stop ESP-NOW layer bool espNowStop() @@ -650,38 +604,142 @@ bool espNowStop() //********************************************************************* // Called from main loop +// Update the ESP-NOW state machine to allow for broadcasting partial packets, pairing, etc. // Control incoming/outgoing RTCM data from internal ESP NOW radio -// Use the ESP32 to directly transmit/receive RTCM over 2.4GHz (no WiFi needed) void espNowUpdate() { - if (settings.enableEspNow == true) + // Override setting because user has initiated pairing via the display menu or CLI + // We don't save settings here; they are saved after successful pairing. + if (espnowRequestPair == true && settings.enableEspNow == false) + settings.enableEspNow = true; + + switch (espNowState) { - if (espNowState == ESPNOW_PAIRED || espNowState == ESPNOW_BROADCASTING) + case ESPNOW_OFF: + if (settings.enableEspNow == true) + { + wifiEspNowOn(__FILE__, __LINE__); // Turn on ESP-NOW hardware + + if (settings.espnowPeerCount == 0) + espNowSetState(ESPNOW_BROADCASTING); + else + espNowSetState(ESPNOW_PAIRED); + } + + break; + + case ESPNOW_PAIRED: + case ESPNOW_BROADCASTING: + if (settings.enableEspNow == false) + { + wifiEspNowOff(__FILE__, __LINE__); // Turn off ESP-NOW hardware + espNowSetState(ESPNOW_OFF); + } + + // If it's been longer than 50ms since we last added a byte to the buffer + // then we've reached the end of the RTCM stream. Send partial buffer. + if ((espNowOutgoingSpot > 0) && ((millis() - espNowLastAdd) > 50)) { - // If it's been longer than a few ms since we last added a byte to the buffer - // then we've reached the end of the RTCM stream. Send partial buffer. - if (espNowOutgoingSpot > 0 && (millis() - espNowLastAdd) > 50) + if (espNowState == ESPNOW_PAIRED) + esp_now_send(0, (uint8_t *)&espNowOutgoing, espNowOutgoingSpot); // Send partial packet to all peers + else // if (espNowState == ESPNOW_BROADCASTING) + esp_now_send(espNowBroadcastAddr, (uint8_t *)&espNowOutgoing, + espNowOutgoingSpot); // Send packet via broadcast + + if (settings.debugEspNow == true && !inMainMenu) + systemPrintf("ESPNOW transmitted %d RTCM bytes\r\n", espNowBytesSent + espNowOutgoingSpot); + espNowBytesSent = 0; + espNowOutgoingSpot = 0; // Reset + } + + // If we don't receive an ESP NOW packet after some time, set RSSI to very negative + // This removes the ESPNOW icon from the display when the link goes down + if (((millis() - espNowLastRssiUpdate) > 5000) && (espNowRSSI > -255)) + espNowRSSI = -255; + + // The display menu, serial menu, or CLI may request pairing be started + if (espnowRequestPair == true) + { + // Start ESP-NOW if needed, put ESP-NOW into broadcast state + espNowBeginPairing(); + } + break; + + case ESPNOW_PAIRING: + if (settings.enableEspNow == false) + { + wifiEspNowOff(__FILE__, __LINE__); // Turn off ESP-NOW hardware + espNowSetState(ESPNOW_OFF); + } + + if (espnowRequestPair == false) // The menuRadio can cancel a pairing request. We also end once paired. + { + espNowSetState(espNowPrePairingState); // Return to the original state + } + else + { + // Send our MAC at random intervals until we receive a remote MAC + randomSeed(millis()); + static unsigned long lastMacSend = millis(); + static int timeout = 1000 + random(0, 100); // Pick a random number between 1000 to 1100ms + if ((millis() - lastMacSend) > timeout) { - if (espNowState == ESPNOW_PAIRED) - esp_now_send(0, (uint8_t *)&espNowOutgoing, espNowOutgoingSpot); // Send partial packet to all peers - else // if (espNowState == ESPNOW_BROADCASTING) - esp_now_send(espNowBroadcastAddr, (uint8_t *)&espNowOutgoing, - espNowOutgoingSpot); // Send packet via broadcast + lastMacSend = millis(); + espNowSendPairMessage( + espNowBroadcastAddr); // Send unit's MAC address over broadcast, no ack, no encryption - if (!inMainMenu) - { - if (settings.debugEspNow == true) - systemPrintf("ESPNOW transmitted %d RTCM bytes\r\n", espNowBytesSent + espNowOutgoingSpot); - } - espNowBytesSent = 0; - espNowOutgoingSpot = 0; // Reset + systemPrintln("Scanning for other radio..."); } - // If we don't receive an ESP NOW packet after some time, set RSSI to very negative - // This removes the ESPNOW icon from the display when the link goes down - if (millis() - espNowLastRssiUpdate > 5000 && espNowRSSI > -255) - espNowRSSI = -255; + // Callback espNowOnDataReceived() will change state if a MAC is received } + + break; + + case ESPNOW_MAC_RECEIVED: + if (settings.enableEspNow == false) + { + wifiEspNowOff(__FILE__, __LINE__); // Turn off ESP-NOW hardware + espNowSetState(ESPNOW_OFF); + } + + paintEspNowPaired(); + + // Remove broadcast peer + espNowRemovePeer(espNowBroadcastAddr); + + // Is the received MAC already paired? + if (esp_now_is_peer_exist(espNowReceivedMAC) == true) + { + // Yes, already paired + if (settings.debugEspNow == true) + systemPrintln("Peer already exists"); + } + else + { + // No, add new peer to system + espNowAddPeer(espNowReceivedMAC); + + // Record this MAC to peer list + memcpy(settings.espnowPeers[settings.espnowPeerCount], espNowReceivedMAC, 6); + settings.espnowPeerCount++; + settings.espnowPeerCount %= ESPNOW_MAX_PEERS; + } + + // Send message directly to the received MAC (not unicast) + espNowSendPairMessage(espNowReceivedMAC); + + // Report success to the CLI + commandSendStringOkResponse((char *)"SPEXE", (char *)"UPDATEPAIR", (char *)"SUCCESS"); + + // Record enableEspNow setting and espnowPeerCount to NVM + recordSystemSettings(); + + espNowSetState(ESPNOW_PAIRED); + + systemPrintln("Pairing complete"); + espnowRequestPair = false; + break; } } diff --git a/Firmware/RTK_Everywhere/Ethernet.ino b/Firmware/RTK_Everywhere/Ethernet.ino index 387037fed..3469dafe7 100644 --- a/Firmware/RTK_Everywhere/Ethernet.ino +++ b/Firmware/RTK_Everywhere/Ethernet.ino @@ -188,6 +188,9 @@ void ethernetEvent(arduino_event_id_t event, arduino_event_info_t info) case ARDUINO_EVENT_ETH_DISCONNECTED: if (settings.enablePrintEthernetDiag && (!inMainMenu)) systemPrintln("ETH Disconnected"); + + ethernetRestartRequested = true; // Perform ETH.end() to disconnect TCP resources + break; case ARDUINO_EVENT_ETH_STOP: @@ -236,6 +239,20 @@ const char *ethernetGetEventName(arduino_event_id_t event) } } +//---------------------------------------- +// Update Ethernet. Restart if requested +//---------------------------------------- +void ethernetUpdate() +{ + if (ethernetRestartRequested) + { + if (settings.enablePrintEthernetDiag && (!inMainMenu)) + systemPrintln("Restarting Ethernet"); + ethernetRestart(); + ethernetRestartRequested = false; + } +} + //---------------------------------------- // Restart the Ethernet controller //---------------------------------------- diff --git a/Firmware/RTK_Everywhere/GNSS.h b/Firmware/RTK_Everywhere/GNSS.h index 54c3997b7..5628a90a4 100644 --- a/Firmware/RTK_Everywhere/GNSS.h +++ b/Firmware/RTK_Everywhere/GNSS.h @@ -9,396 +9,397 @@ GNSS.h class GNSS { - protected: - float _altitude; // Altitude in meters - float _horizontalAccuracy; // Horizontal position accuracy in meters - double _latitude; // Latitude in degrees - double _longitude; // Longitude in degrees - - uint8_t _day; // Day number - uint8_t _month; // Month number - uint16_t _year; - uint8_t _hour; // Hours for 24 hour clock - uint8_t _minute; - uint8_t _second; - uint8_t _leapSeconds; - uint16_t _millisecond; // Limited to first two digits - uint32_t _nanosecond; - - uint8_t _satellitesInView; - uint8_t _fixType; - uint8_t _carrierSolution; - - bool _validDate; // True when date is valid - bool _validTime; // True when time is valid - bool _confirmedDate; - bool _confirmedTime; - bool _fullyResolved; - uint32_t _tAcc; - - unsigned long _pvtArrivalMillis; - bool _pvtUpdated; - - bool _corrRadioExtPortEnabled = false; - - unsigned long _autoBaseStartTimer; // Tracks how long the base auto / averaging mode has been running - - // Setup the general configuration of the GNSS - // Not Rover or Base specific (ie, baud rates) - // Outputs: - // Returns true if successfully configured and false upon failure - virtual bool configureGNSS(); - - // Set the minimum satellite signal level for navigation. - virtual bool setMinCnoRadio(uint8_t cnoValue); +protected: + float _altitude; // Altitude in meters + float _horizontalAccuracy; // Horizontal position accuracy in meters + double _latitude; // Latitude in degrees + double _longitude; // Longitude in degrees + + uint8_t _day; // Day number + uint8_t _month; // Month number + uint16_t _year; + uint8_t _hour; // Hours for 24 hour clock + uint8_t _minute; + uint8_t _second; + uint8_t _leapSeconds; + uint16_t _millisecond; // Limited to first two digits + uint32_t _nanosecond; + + uint8_t _satellitesInView; + uint8_t _fixType; + uint8_t _carrierSolution; + + bool _validDate; // True when date is valid + bool _validTime; // True when time is valid + bool _confirmedDate; + bool _confirmedTime; + bool _fullyResolved; + uint32_t _tAcc; + + unsigned long _pvtArrivalMillis; + bool _pvtUpdated; + + bool _corrRadioExtPortEnabled = false; + + unsigned long _autoBaseStartTimer; // Tracks how long the base auto / averaging mode has been running + + // Setup the general configuration of the GNSS + // Not Rover or Base specific (ie, baud rates) + // Outputs: + // Returns true if successfully configured and false upon failure + virtual bool configureGNSS(); + + // Set the minimum satellite signal level for navigation. + virtual bool setMinCnoRadio(uint8_t cnoValue); - public: - // Constructor - GNSS() : _leapSeconds(18), _pvtArrivalMillis(0), _pvtUpdated(0), _satellitesInView(0) - { - } - - // If we have decryption keys, configure module - // Note: don't check online.lband_neo here. We could be using ip corrections - virtual void applyPointPerfectKeys(); +public: + // Constructor + GNSS() : _leapSeconds(18), _pvtArrivalMillis(0), _pvtUpdated(0), _satellitesInView(0) + { + } + + // If we have decryption keys, configure module + // Note: don't check online.lband_neo here. We could be using ip corrections + virtual void applyPointPerfectKeys(); - // Set RTCM for base mode to defaults (1005/1074/1084/1094/1124 1Hz & 1230 0.1Hz) - virtual void baseRtcmDefault(); + // Set RTCM for base mode to defaults (1005/1074/1084/1094/1124 1Hz & 1230 0.1Hz) + virtual void baseRtcmDefault(); - // Reset to Low Bandwidth Link (1074/1084/1094/1124 0.5Hz & 1005/1230 0.1Hz) - virtual void baseRtcmLowDataRate(); + // Reset to Low Bandwidth Link (1074/1084/1094/1124 0.5Hz & 1005/1230 0.1Hz) + virtual void baseRtcmLowDataRate(); - // Check if a given baud rate is supported by this module - virtual bool baudIsAllowed(uint32_t baudRate); - virtual uint32_t baudGetMinimum(); - virtual uint32_t baudGetMaximum(); + // Check if a given baud rate is supported by this module + virtual bool baudIsAllowed(uint32_t baudRate); + virtual uint32_t baudGetMinimum(); + virtual uint32_t baudGetMaximum(); - // Connect to GNSS and identify particulars - virtual void begin(); + // Connect to GNSS and identify particulars + virtual void begin(); - // Setup TM2 time stamp input as need - // Outputs: - // Returns true when an external event occurs and false if no event - virtual bool beginExternalEvent(); + // Setup TM2 time stamp input as need + // Outputs: + // Returns true when an external event occurs and false if no event + virtual bool beginExternalEvent(); - // Setup the timepulse output on the PPS pin for external triggering - // Outputs - // Returns true if the pin was successfully setup and false upon - // failure - virtual bool beginPPS(); + // Setup the timepulse output on the PPS pin for external triggering + // Outputs + // Returns true if the pin was successfully setup and false upon + // failure + virtual bool beginPPS(); - virtual bool checkNMEARates(); + virtual bool checkNMEARates(); - virtual bool checkPPPRates(); + virtual bool checkPPPRates(); - // Setup the general configuration of the GNSS - // Not Rover or Base specific (ie, baud rates) - // Outputs: - // Returns true if successfully configured and false upon failure - bool configure(); + // Setup the general configuration of the GNSS + // Not Rover or Base specific (ie, baud rates) + // Outputs: + // Returns true if successfully configured and false upon failure + bool configure(); - // Configure the Base - // Outputs: - // Returns true if successfully configured and false upon failure - virtual bool configureBase(); + // Configure the Base + // Outputs: + // Returns true if successfully configured and false upon failure + virtual bool configureBase(); - // Configure specific aspects of the receiver for NTP mode - virtual bool configureNtpMode(); + // Configure specific aspects of the receiver for NTP mode + virtual bool configureNtpMode(); - // Configure the Rover - // Outputs: - // Returns true if successfully configured and false upon failure - virtual bool configureRover(); + // Configure the Rover + // Outputs: + // Returns true if successfully configured and false upon failure + virtual bool configureRover(); - // Responds with the messages supported on this platform - // Inputs: - // returnText: String to receive message names - // Returns message names in the returnText string - virtual void createMessageList(String &returnText); + // Responds with the messages supported on this platform + // Inputs: + // returnText: String to receive message names + // Returns message names in the returnText string + virtual void createMessageList(String &returnText); - // Responds with the RTCM/Base messages supported on this platform - // Inputs: - // returnText: String to receive message names - // Returns message names in the returnText string - virtual void createMessageListBase(String &returnText); + // Responds with the RTCM/Base messages supported on this platform + // Inputs: + // returnText: String to receive message names + // Returns message names in the returnText string + virtual void createMessageListBase(String &returnText); - virtual void debuggingDisable(); + virtual void debuggingDisable(); - virtual void debuggingEnable(); + virtual void debuggingEnable(); - virtual void enableGgaForNtrip(); + virtual void enableGgaForNtrip(); - // Enable RTCM 1230. This is the GLONASS bias sentence and is transmitted - // even if there is no GPS fix. We use it to test serial output. - // Outputs: - // Returns true if successfully started and false upon failure - virtual bool enableRTCMTest(); + // Enable RTCM 1230. This is the GLONASS bias sentence and is transmitted + // even if there is no GPS fix. We use it to test serial output. + // Outputs: + // Returns true if successfully started and false upon failure + virtual bool enableRTCMTest(); - // Restore the GNSS to the factory settings - virtual void factoryReset(); + // Restore the GNSS to the factory settings + virtual void factoryReset(); - virtual uint16_t fileBufferAvailable(); + virtual uint16_t fileBufferAvailable(); - virtual uint16_t fileBufferExtractData(uint8_t *fileBuffer, int fileBytesToRead); + virtual uint16_t fileBufferExtractData(uint8_t *fileBuffer, int fileBytesToRead); - // Start the base using fixed coordinates - // Outputs: - // Returns true if successfully started and false upon failure - virtual bool fixedBaseStart(); + // Start the base using fixed coordinates + // Outputs: + // Returns true if successfully started and false upon failure + virtual bool fixedBaseStart(); - // Return the number of active/enabled messages - virtual uint8_t getActiveMessageCount(); + // Return the number of active/enabled messages + virtual uint8_t getActiveMessageCount(); - // Return the number of active/enabled RTCM messages - virtual uint8_t getActiveRtcmMessageCount(); + // Return the number of active/enabled RTCM messages + virtual uint8_t getActiveRtcmMessageCount(); - // Get the altitude - // Outputs: - // Returns the altitude in meters or zero if the GNSS is offline - virtual double getAltitude(); + // Get the altitude + // Outputs: + // Returns the altitude in meters or zero if the GNSS is offline + virtual double getAltitude(); - // Returns the carrier solution or zero if not online - virtual uint8_t getCarrierSolution(); + // Returns the carrier solution or zero if not online + virtual uint8_t getCarrierSolution(); - virtual uint32_t getDataBaudRate(); + virtual uint32_t getDataBaudRate(); - // Returns the day number or zero if not online - virtual uint8_t getDay(); + // Returns the day number or zero if not online + virtual uint8_t getDay(); - // Return the number of milliseconds since GNSS data was last updated - virtual uint16_t getFixAgeMilliseconds(); + // Return the number of milliseconds since GNSS data was last updated + virtual uint16_t getFixAgeMilliseconds(); - // Returns the fix type or zero if not online - virtual uint8_t getFixType(); + // Returns the fix type or zero if not online + virtual uint8_t getFixType(); - // Returns the hours of 24 hour clock or zero if not online - virtual uint8_t getHour(); + // Returns the hours of 24 hour clock or zero if not online + virtual uint8_t getHour(); - // Get the horizontal position accuracy - // Outputs: - // Returns the horizontal position accuracy or zero if offline - virtual float getHorizontalAccuracy(); + // Get the horizontal position accuracy + // Outputs: + // Returns the horizontal position accuracy or zero if offline + virtual float getHorizontalAccuracy(); - virtual const char *getId(); + virtual const char *getId(); - // Get the latitude value - // Outputs: - // Returns the latitude value or zero if not online - virtual double getLatitude(); + // Get the latitude value + // Outputs: + // Returns the latitude value or zero if not online + virtual double getLatitude(); - // Query GNSS for current leap seconds - virtual uint8_t getLeapSeconds(); + // Query GNSS for current leap seconds + virtual uint8_t getLeapSeconds(); - // Return the type of logging that matches the enabled messages - drives the logging icon - virtual uint8_t getLoggingType(); + // Return the type of logging that matches the enabled messages - drives the logging icon + virtual uint8_t getLoggingType(); - // Get the longitude value - // Outputs: - // Returns the longitude value or zero if not online - virtual double getLongitude(); + // Get the longitude value + // Outputs: + // Returns the longitude value or zero if not online + virtual double getLongitude(); - // Returns two digits of milliseconds or zero if not online - virtual uint8_t getMillisecond(); + // Returns two digits of milliseconds or zero if not online + virtual uint8_t getMillisecond(); - // Get the minimum satellite signal level for navigation. - uint8_t getMinCno(); + // Get the minimum satellite signal level for navigation. + uint8_t getMinCno(); - // Returns minutes or zero if not online - virtual uint8_t getMinute(); + // Returns minutes or zero if not online + virtual uint8_t getMinute(); - // Returns month number or zero if not online - virtual uint8_t getMonth(); + // Returns month number or zero if not online + virtual uint8_t getMonth(); - // Returns nanoseconds or zero if not online - virtual uint32_t getNanosecond(); + // Returns nanoseconds or zero if not online + virtual uint32_t getNanosecond(); - virtual uint32_t getRadioBaudRate(); + virtual uint32_t getRadioBaudRate(); - // Returns the seconds between solutions - virtual double getRateS(); + // Returns the seconds between solutions + virtual double getRateS(); - virtual const char *getRtcmDefaultString(); + virtual const char *getRtcmDefaultString(); - virtual const char *getRtcmLowDataRateString(); + virtual const char *getRtcmLowDataRateString(); - // Returns the number of satellites in view or zero if offline - virtual uint8_t getSatellitesInView(); + // Returns the number of satellites in view or zero if offline + virtual uint8_t getSatellitesInView(); - // Returns seconds or zero if not online - virtual uint8_t getSecond(); + // Returns seconds or zero if not online + virtual uint8_t getSecond(); - // Get the survey-in mean accuracy - // Outputs: - // Returns the mean accuracy or zero (0) - virtual float getSurveyInMeanAccuracy(); + // Get the survey-in mean accuracy + // Outputs: + // Returns the mean accuracy or zero (0) + virtual float getSurveyInMeanAccuracy(); - // Return the number of seconds the survey-in process has been running - virtual int getSurveyInObservationTime(); + // Return the number of seconds the survey-in process has been running + virtual int getSurveyInObservationTime(); - float getSurveyInStartingAccuracy(); + float getSurveyInStartingAccuracy(); - // Returns timing accuracy or zero if not online - virtual uint32_t getTimeAccuracy(); + // Returns timing accuracy or zero if not online + virtual uint32_t getTimeAccuracy(); - // Returns full year, ie 2023, not 23. - virtual uint16_t getYear(); + // Returns full year, ie 2023, not 23. + virtual uint16_t getYear(); - // Antenna Short / Open detection - virtual bool isAntennaShorted(); - virtual bool isAntennaOpen(); + // Antenna Short / Open detection + virtual bool isAntennaShorted(); + virtual bool isAntennaOpen(); - virtual bool isBlocking(); + virtual bool isBlocking(); - // Date is confirmed once we have GNSS fix - virtual bool isConfirmedDate(); + // Date is confirmed once we have GNSS fix + virtual bool isConfirmedDate(); - // Date is confirmed once we have GNSS fix - virtual bool isConfirmedTime(); + // Date is confirmed once we have GNSS fix + virtual bool isConfirmedTime(); - // Returns true if data is arriving on the Radio Ext port - virtual bool isCorrRadioExtPortActive(); + // Returns true if data is arriving on the Radio Ext port + virtual bool isCorrRadioExtPortActive(); - // Return true if GNSS receiver has a higher quality DGPS fix than 3D - virtual bool isDgpsFixed(); + // Return true if GNSS receiver has a higher quality DGPS fix than 3D + virtual bool isDgpsFixed(); - // Some functions (L-Band area frequency determination) merely need - // to know if we have a valid fix, not what type of fix - // This function checks to see if the given platform has reached - // sufficient fix type to be considered valid - virtual bool isFixed(); + // Some functions (L-Band area frequency determination) merely need + // to know if we have a valid fix, not what type of fix + // This function checks to see if the given platform has reached + // sufficient fix type to be considered valid + virtual bool isFixed(); - // Used in tpISR() for time pulse synchronization - virtual bool isFullyResolved(); + // Used in tpISR() for time pulse synchronization + virtual bool isFullyResolved(); - virtual bool isPppConverged(); + virtual bool isPppConverged(); - virtual bool isPppConverging(); + virtual bool isPppConverging(); - // Some functions (L-Band area frequency determination) merely need - // to know if we have an RTK Fix. This function checks to see if the - // given platform has reached sufficient fix type to be considered valid - virtual bool isRTKFix(); + // Some functions (L-Band area frequency determination) merely need + // to know if we have an RTK Fix. This function checks to see if the + // given platform has reached sufficient fix type to be considered valid + virtual bool isRTKFix(); - // Some functions (L-Band area frequency determination) merely need - // to know if we have an RTK Float. This function checks to see if - // the given platform has reached sufficient fix type to be considered - // valid - virtual bool isRTKFloat(); + // Some functions (L-Band area frequency determination) merely need + // to know if we have an RTK Float. This function checks to see if + // the given platform has reached sufficient fix type to be considered + // valid + virtual bool isRTKFloat(); - // Determine if the survey-in operation is complete - // Outputs: - // Returns true if the survey-in operation is complete and false - // if the operation is still running - virtual bool isSurveyInComplete(); + // Determine if the survey-in operation is complete + // Outputs: + // Returns true if the survey-in operation is complete and false + // if the operation is still running + virtual bool isSurveyInComplete(); - // Date will be valid if the RTC is reporting (regardless of GNSS fix) - virtual bool isValidDate(); + // Date will be valid if the RTC is reporting (regardless of GNSS fix) + virtual bool isValidDate(); - // Time will be valid if the RTC is reporting (regardless of GNSS fix) - virtual bool isValidTime(); + // Time will be valid if the RTC is reporting (regardless of GNSS fix) + virtual bool isValidTime(); - // Controls the constellations that are used to generate a fix and logged - virtual void menuConstellations(); + // Controls the constellations that are used to generate a fix and logged + virtual void menuConstellations(); - virtual void menuMessageBaseRtcm(); + virtual void menuMessageBaseRtcm(); - // Control the messages that get broadcast over Bluetooth and logged (if enabled) - virtual void menuMessages(); + // Control the messages that get broadcast over Bluetooth and logged (if enabled) + virtual void menuMessages(); - // Print the module type and firmware version - virtual void printModuleInfo(); + // Print the module type and firmware version + virtual void printModuleInfo(); - // Send correction data to the GNSS - // Inputs: - // dataToSend: Address of a buffer containing the data - // dataLength: The number of valid data bytes in the buffer - // Outputs: - // Returns the number of correction data bytes written - virtual int pushRawData(uint8_t *dataToSend, int dataLength); + // Send correction data to the GNSS + // Inputs: + // dataToSend: Address of a buffer containing the data + // dataLength: The number of valid data bytes in the buffer + // Outputs: + // Returns the number of correction data bytes written + virtual int pushRawData(uint8_t *dataToSend, int dataLength); - virtual uint16_t rtcmBufferAvailable(); + virtual uint16_t rtcmBufferAvailable(); - // If LBand is being used, ignore any RTCM that may come in from the GNSS - virtual void rtcmOnGnssDisable(); + // If LBand is being used, ignore any RTCM that may come in from the GNSS + virtual void rtcmOnGnssDisable(); - // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver - virtual void rtcmOnGnssEnable(); + // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver + virtual void rtcmOnGnssEnable(); - virtual uint16_t rtcmRead(uint8_t *rtcmBuffer, int rtcmBytesToRead); + virtual uint16_t rtcmRead(uint8_t *rtcmBuffer, int rtcmBytesToRead); - // Save the current configuration - // Outputs: - // Returns true when the configuration was saved and false upon failure - virtual bool saveConfiguration(); + // Save the current configuration + // Outputs: + // Returns true when the configuration was saved and false upon failure + virtual bool saveConfiguration(); - // Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS - // This just sets the GNSS side - // Used during Bluetooth testing - // Inputs: - // baudRate: The desired baudrate - virtual bool setBaudrate(uint32_t baudRate); + // Enable all the valid constellations and bands for this platform + virtual bool setConstellations(); - // Enable all the valid constellations and bands for this platform - virtual bool setConstellations(); + // Enable / disable corrections protocol(s) on the Radio External port + // Always update if force is true. Otherwise, only update if enable has changed state + virtual bool setCorrRadioExtPort(bool enable, bool force); - // Enable / disable corrections protocol(s) on the Radio External port - // Always update if force is true. Otherwise, only update if enable has changed state - virtual bool setCorrRadioExtPort(bool enable, bool force); + virtual bool setBaudRate(uint8_t uartNumber, uint32_t baudRate); - virtual bool setDataBaudRate(uint32_t baud); + virtual bool setDataBaudRate(uint32_t baud); - // Set the elevation in degrees - // Inputs: - // elevationDegrees: The elevation value in degrees - virtual bool setElevation(uint8_t elevationDegrees); + // Set the elevation in degrees + // Inputs: + // elevationDegrees: The elevation value in degrees + virtual bool setElevation(uint8_t elevationDegrees); - // Enable all the valid messages for this platform - virtual bool setMessages(int maxRetries); + // Enable all the valid messages for this platform + virtual bool setMessages(int maxRetries); - // Enable all the valid messages for this platform over the USB port - virtual bool setMessagesUsb(int maxRetries); + // Enable all the valid messages for this platform over the USB port + virtual bool setMessagesUsb(int maxRetries); - // Set the minimum satellite signal level for navigation. - bool setMinCno(uint8_t cnoValue); + // Set the minimum satellite signal level for navigation. + bool setMinCno(uint8_t cnoValue); - // Set the dynamic model to use for RTK - // Inputs: - // modelNumber: Number of the model to use, provided by radio library - virtual bool setModel(uint8_t modelNumber); + // Set the dynamic model to use for RTK + // Inputs: + // modelNumber: Number of the model to use, provided by radio library + virtual bool setModel(uint8_t modelNumber); - virtual bool setRadioBaudRate(uint32_t baud); + virtual bool setRadioBaudRate(uint32_t baud); - // Specify the interval between solutions - // Inputs: - // secondsBetweenSolutions: Number of seconds between solutions - // Outputs: - // Returns true if the rate was successfully set and false upon - // failure - virtual bool setRate(double secondsBetweenSolutions); + // Specify the interval between solutions + // Inputs: + // secondsBetweenSolutions: Number of seconds between solutions + // Outputs: + // Returns true if the rate was successfully set and false upon + // failure + virtual bool setRate(double secondsBetweenSolutions); - virtual bool setTalkerGNGGA(); + virtual bool setTalkerGNGGA(); - // Hotstart GNSS to try to get RTK lock - virtual bool softwareReset(); + // Hotstart GNSS to try to get RTK lock + virtual bool softwareReset(); - virtual bool standby(); + virtual bool standby(); - // Antenna Short / Open detection - virtual bool supportsAntennaShortOpen(); + // Antenna Short / Open detection + virtual bool supportsAntennaShortOpen(); - // Reset the survey-in operation - // Outputs: - // Returns true if the survey-in operation was reset successfully - // and false upon failure - virtual bool surveyInReset(); + // Reset the survey-in operation + // Outputs: + // Returns true if the survey-in operation was reset successfully + // and false upon failure + virtual bool surveyInReset(); - // Start the survey-in operation - // Outputs: - // Return true if successful and false upon failure - virtual bool surveyInStart(); + // Start the survey-in operation + // Outputs: + // Return true if successful and false upon failure + virtual bool surveyInStart(); - // Poll routine to update the GNSS state - virtual void update(); + // Poll routine to update the GNSS state + virtual void update(); }; +// Update the constellations following a set command +bool gnssCmdUpdateConstellations(int commandIndex); + +// Update the message rates following a set command +bool gnssCmdUpdateMessageRates(int commandIndex); + #endif // __GNSS_H__ diff --git a/Firmware/RTK_Everywhere/GNSS.ino b/Firmware/RTK_Everywhere/GNSS.ino index d4cc47ec9..e7df01f21 100644 --- a/Firmware/RTK_Everywhere/GNSS.ino +++ b/Firmware/RTK_Everywhere/GNSS.ino @@ -46,12 +46,18 @@ float GNSS::getSurveyInStartingAccuracy() //---------------------------------------- // Returns true if the antenna is shorted //---------------------------------------- -bool GNSS::isAntennaShorted() { return false; } +bool GNSS::isAntennaShorted() +{ + return false; +} //---------------------------------------- // Returns true if the antenna is shorted //---------------------------------------- -bool GNSS::isAntennaOpen() { return false; } +bool GNSS::isAntennaOpen() +{ + return false; +} //---------------------------------------- // Set the minimum satellite signal level for navigation. @@ -72,29 +78,386 @@ bool GNSS::supportsAntennaShortOpen() } // Periodically push GGA sentence over NTRIP Client, to Caster, if enabled -void pushGPGGA(char *ggaData) +// We must not push to the Caster while we are reading data from the Caster +// See #695 +// pushGPGGA is called by processUart1Message from gnssReadTask +// ntripClient->read is called by ntripClientUpdate and ntripClientResponse from networkUpdate from loop +// We need to make sure processUart1Message doesn't gatecrash +// If ggaData is provided, store it. If ggaData is nullptr, try to push it +static void pushGPGGA(char *ggaData) { -#ifdef COMPILE_NETWORK - // Wait until the client has been created - if (ntripClient != nullptr) + static char storedGPGGA[100]; + + static SemaphoreHandle_t reentrant = xSemaphoreCreateMutex(); // Create the mutex + + if (xSemaphoreTake(reentrant, 10 / portTICK_PERIOD_MS) == pdPASS) { - // Provide the caster with our current position as needed - if (ntripClient->connected() && settings.ntripClient_TransmitGGA == true) + if (ggaData) { - if (millis() - lastGGAPush > NTRIPCLIENT_MS_BETWEEN_GGA) - { - lastGGAPush = millis(); + snprintf(storedGPGGA, sizeof(storedGPGGA), "%s", ggaData); + xSemaphoreGive(reentrant); + return; + } - if (settings.debugNtripClientRtcm || PERIODIC_DISPLAY(PD_NTRIP_CLIENT_GGA)) +#ifdef COMPILE_NETWORK + // Wait until the client has been created + if (ntripClient != nullptr) + { + // Provide the caster with our current position as needed + if (ntripClient->connected() && settings.ntripClient_TransmitGGA == true) + { + if ((millis() - lastGGAPush) > NTRIPCLIENT_MS_BETWEEN_GGA) { - PERIODIC_CLEAR(PD_NTRIP_CLIENT_GGA); - systemPrintf("NTRIP Client pushing GGA to server: %s", (const char *)ggaData); + lastGGAPush = millis(); + + if ((settings.debugNtripClientRtcm || PERIODIC_DISPLAY(PD_NTRIP_CLIENT_GGA)) && !inMainMenu) + { + PERIODIC_CLEAR(PD_NTRIP_CLIENT_GGA); + systemPrintf("NTRIP Client pushing GGA to server: %s", (const char *)storedGPGGA); + } + + // Push our current GGA sentence to caster + if (strlen(storedGPGGA) > 0) + ntripClient->write((const uint8_t *)storedGPGGA, strlen(storedGPGGA)); } + } + } +#endif // COMPILE_NETWORK - // Push our current GGA sentence to caster - ntripClient->print((const char *)ggaData); + xSemaphoreGive(reentrant); + } +} + +// Detect what type of GNSS receiver module is installed +// using serial or other begin() methods +// To reduce potential false ID's, record the ID to NVM +// If we have a previous ID, use it +void gnssDetectReceiverType() +{ + // Currently only the Flex requires GNSS receiver detection + if (productVariant != RTK_FLEX) + return; + + gnssBoot(); // Tell GNSS to run + + // TODO remove after testing, force retest on each boot + // Note: with this in place, the X5 detection will take a lot longer due to the baud rate change +#ifdef FLEX_OVERRIDE + systemPrintln("<<<<<<<<<< !!!!!!!!!! FLEX FORCED !!!!!!!!!! >>>>>>>>>>"); + // settings.detectedGnssReceiver = GNSS_RECEIVER_UNKNOWN; // This may be causing weirdness on the LG290P. Commenting for now +#endif + + // Start auto-detect if NVM is not yet set + if (settings.detectedGnssReceiver == GNSS_RECEIVER_UNKNOWN) + { + // The COMPILE guards prevent else if + // Use a do while (0) so we can break when GNSS is detected + do + { +#ifdef COMPILE_LG290P + if (lg290pIsPresent() == true) + { + systemPrintln("Auto-detected GNSS receiver: LG290P"); + settings.detectedGnssReceiver = GNSS_RECEIVER_LG290P; + recordSystemSettings(); // Record the detected GNSS receiver and avoid this test in the future + break; } +#else // COMPILE_LGP290P + systemPrintln("<<<<<<<<<< !!!!!!!!!! LG290P NOT COMPILED !!!!!!!!!! >>>>>>>>>>"); +#endif // COMPILE_LGP290P + +#ifdef COMPILE_MOSAICX5 + if (mosaicIsPresentOnFlex() == true) // Note: this changes the COM1 baud from 115200 to 460800 + { + systemPrintln("Auto-detected GNSS receiver: mosaic-X5"); + settings.detectedGnssReceiver = GNSS_RECEIVER_MOSAIC_X5; + recordSystemSettings(); // Record the detected GNSS receiver and avoid this test in the future + break; + } +#else // COMPILE_MOSAICX5 + systemPrintln("<<<<<<<<<< !!!!!!!!!! MOSAICX5 NOT COMPILED !!!!!!!!!! >>>>>>>>>>"); +#endif // COMPILE_MOSAICX5 + } while (0); + } + + // Start the detected receiver + if (settings.detectedGnssReceiver == GNSS_RECEIVER_LG290P) + { +#ifdef COMPILE_LG290P + gnss = (GNSS *)new GNSS_LG290P(); + + present.gnss_lg290p = true; + present.minCno = true; + present.minElevation = true; + present.needsExternalPpl = true; // Uses the PointPerfect Library + +#endif // COMPILE_LGP290P + } + else if (settings.detectedGnssReceiver == GNSS_RECEIVER_MOSAIC_X5) + { +#ifdef COMPILE_MOSAICX5 + gnss = (GNSS *)new GNSS_MOSAIC(); + + present.gnss_mosaicX5 = true; + present.minCno = true; + present.minElevation = true; + present.dynamicModel = true; + present.mosaicMicroSd = true; + // present.needsExternalPpl = true; // Nope. No L-Band support... + +#endif // COMPILE_MOSAICX5 + } + + // Auto ID failed, mark everything as unknown + else if (settings.detectedGnssReceiver == GNSS_RECEIVER_UNKNOWN) + { + gnss = (GNSS *)new GNSS_None(); + } +} + +// Based on the platform, put the GNSS receiver into run mode +void gnssBoot() +{ + if (productVariant == RTK_TORCH) + { + digitalWrite(pin_GNSS_DR_Reset, HIGH); // Tell UM980 and DR to boot + } + else if (productVariant == RTK_TORCH_X2) + { + digitalWrite(pin_GNSS_DR_Reset, HIGH); // Tell LG290P to boot + } + else if (productVariant == RTK_FLEX) + { + gpioExpanderGnssBoot(); // Drive the GNSS reset pin high + } + else if (productVariant == RTK_POSTCARD) + { + digitalWrite(pin_GNSS_Reset, HIGH); // Tell LG290P to boot + } +} + +// Based on the platform, put the GNSS receiver into reset +void gnssReset() +{ + if (productVariant == RTK_TORCH) + { + digitalWrite(pin_GNSS_DR_Reset, LOW); // Tell UM980 and DR to reset + } + else if (productVariant == RTK_TORCH_X2) + { + digitalWrite(pin_GNSS_Reset, LOW); // Tell LG290P to reset + } + else if (productVariant == RTK_FLEX) + { + gpioExpanderGnssReset(); // Drive the GNSS reset pin low + } + else if (productVariant == RTK_POSTCARD) + { + digitalWrite(pin_GNSS_Reset, LOW); // Tell LG290P to reset + } +} + +//---------------------------------------- +// Force UART connection to GNSS for firmware update on the next boot by special file in +// LittleFS +//---------------------------------------- +bool createGNSSPassthrough() +{ + return createPassthrough("/updateGnssFirmware.txt"); +} +bool createPassthrough(const char *filename) +{ + if (online.fs == false) + return false; + + if (LittleFS.exists(filename)) + { + if (settings.debugGnss) + systemPrintf("LittleFS %s already exists\r\n", filename); + return true; + } + + File updateUm980Firmware = LittleFS.open(filename, FILE_WRITE); + updateUm980Firmware.close(); + + if (LittleFS.exists(filename)) + return true; + + if (settings.debugGnss) + systemPrintf("Unable to create %s on LittleFS\r\n", filename); + return false; +} + +//---------------------------------------- +void gnssFirmwareBeginUpdate() +{ + // Note: UM980 needs its own dedicated update function, due to the T@ and bootloader trigger + + // Note: gnssFirmwareBeginUpdate is called during setup, after identify board. I2C, gpio expanders, buttons + // and display have all been initialized. But, importantly, the UARTs have not yet been started. + // This makes our job much easier... + + // NOTE: QGNSS firmware update fails on LG290P due, I think, to QGNSS doing some kind of autobaud + // detection at the start of the update. I think the delays introduced by serialGNSS->write(Serial.read()) + // and Serial.write(serialGNSS->read()) cause the failure, but I'm not sure. + // It seems that LG290P needs a dedicated hardware link from USB to GNSS UART for a successful update. + // This will be added in the next rev of the Flex motherboard. + + // NOTE: X20P will expect a baud rate change during the update, unless we force 9600 baud. + // The dedicated hardware link will make X20P firmware updates easy. + + // Flag that we are in direct connect mode. Button task will gnssFirmwareRemoveUpdate and exit + inDirectConnectMode = true; + + // Note: we can't call gnssFirmwareRemoveUpdate() here as closing Tera Term will reset the ESP32, + // returning the firmware to normal operation... + + // Paint GNSS Update + paintGnssUpdate(); + + // Stop all UART tasks. Redundant + tasksStopGnssUart(); + + uint32_t serialBaud = 115200; + + forceGnssCommunicationRate(serialBaud); // On Flex, must be called after gnssDetectReceiverType + + systemPrintln(); + systemPrintf("Entering GNSS direct connect for firmware update and configuration. Disconnect this terminal " + "connection. Use the GNSS manufacturer software " + "to update the firmware. Baudrate: %dbps. Press the %s button to return " + "to normal operation.\r\n", + serialBaud, present.button_mode ? "mode" : "power"); + systemFlush(); + + Serial.end(); // We must end before we begin otherwise the UART settings are corrupted + Serial.begin(serialBaud); + + if (serialGNSS == nullptr) + serialGNSS = new HardwareSerial(2); // Use UART2 on the ESP32 for communication with the GNSS module + + serialGNSS->setRxBufferSize(settings.uartReceiveBufferSize); + serialGNSS->setTimeout(settings.serialTimeoutGNSS); // Requires serial traffic on the UART pins for detection + + // This is OK for Flex too. We're using the main GNSS pins. + serialGNSS->begin(serialBaud, SERIAL_8N1, pin_GnssUart_RX, pin_GnssUart_TX); + + // Echo everything to/from GNSS + task.endDirectConnectMode = false; + while (!task.endDirectConnectMode) + { + static unsigned long lastSerial = millis(); // Temporary fix for buttonless Flex + + if (Serial.available()) // Note: use if, not while + { + serialGNSS->write(Serial.read()); + lastSerial = millis(); + } + + if (serialGNSS->available()) // Note: use if, not while + Serial.write(serialGNSS->read()); + + // Button task will set task.endDirectConnectMode true + + // Temporary fix for buttonless Flex. TODO - remove + if ((productVariant == RTK_FLEX) && ((millis() - lastSerial) > 30000)) + { + // Beep to indicate exit + beepOn(); + delay(300); + beepOff(); + delay(100); + beepOn(); + delay(300); + beepOff(); + + gnssFirmwareRemoveUpdate(); + + systemPrintln("Exiting direct connection (passthrough) mode"); + systemFlush(); // Complete prints + + ESP.restart(); } } -#endif // COMPILE_NETWORK + + // Remove all the special file. See #763 . Do the file removal in the loop + gnssFirmwareRemoveUpdate(); + + systemFlush(); // Complete prints + + ESP.restart(); } + +//---------------------------------------- +// Check if direct connection file exists +//---------------------------------------- +bool gnssFirmwareCheckUpdate() +{ + return gnssFirmwareCheckUpdateFile("/updateGnssFirmware.txt"); +} +bool gnssFirmwareCheckUpdateFile(const char *filename) +{ + if (online.fs == false) + return false; + + if (LittleFS.exists(filename)) + { + if (settings.debugGnss) + systemPrintf("LittleFS %s exists\r\n", filename); + + // We do not remove the file here. See removeupdateUm980Firmware(). + + return true; + } + + return false; +} + +//---------------------------------------- +// Remove direct connection file +//---------------------------------------- +void gnssFirmwareRemoveUpdate() +{ + return gnssFirmwareRemoveUpdateFile("/updateGnssFirmware.txt"); +} +void gnssFirmwareRemoveUpdateFile(const char *filename) +{ + if (online.fs == false) + return; + + if (LittleFS.exists(filename)) + { + if (settings.debugGnss) + systemPrintf("Removing %s\r\n", filename); + + LittleFS.remove(filename); + } +} + +//---------------------------------------- +// Update the constellations following a set command +//---------------------------------------- +bool gnssCmdUpdateConstellations(int commandIndex) +{ + if (gnss == nullptr) + return false; + + //return gnss->setConstellations(); + // setConstellations() can take multiple seconds. Avoid calling during WebConfig + // as this can lead to >10 seconds required for parsing of the incoming settings blob + return true; +} + +//---------------------------------------- +// Update the message rates following a set command +//---------------------------------------- +bool gnssCmdUpdateMessageRates(int commandIndex) +{ + if (gnss == nullptr) + return false; + + //return gnss->setMessages(MAX_SET_MESSAGES_RETRIES); + return true; +} + +//---------------------------------------- diff --git a/Firmware/RTK_Everywhere/GNSS_LG290P.h b/Firmware/RTK_Everywhere/GNSS_LG290P.h index f7e3417d3..541f1435b 100644 --- a/Firmware/RTK_Everywhere/GNSS_LG290P.h +++ b/Firmware/RTK_Everywhere/GNSS_LG290P.h @@ -14,7 +14,12 @@ GNSS_LG290P.h // Constellations monitored/used for fix // Available constellations: GPS, BDS, GLO, GAL, QZSS, NavIC const char *lg290pConstellationNames[] = { - "GPS", "GLONASS", "Galileo", "BeiDou", "QZSS", "NavIC", + "GPS", + "GLONASS", + "Galileo", + "BeiDou", + "QZSS", + "NavIC", }; #define MAX_LG290P_CONSTELLATIONS (6) @@ -23,22 +28,31 @@ const char *lg290pConstellationNames[] = { // Each message will have the serial command and its default value typedef struct { - const char msgTextName[11]; - const float msgDefaultRate; - const uint8_t firmwareVersionSupported; // The minimum version this message is supported. - // 0 = all versions. - // 9999 = Not supported + const char msgTextName[11]; + const float msgDefaultRate; + const uint8_t firmwareVersionSupported; // The minimum version this message is supported. + // 0 = all versions. + // 9999 = Not supported } lg290pMsg; // Static array containing all the compatible messages // Rate = Output once every N position fix(es). const lg290pMsg lgMessagesNMEA[] = { - {"RMC", 1, 0}, {"GGA", 1, 0}, {"GSV", 1, 0}, {"GSA", 1, 0}, {"VTG", 1, 0}, - {"GLL", 1, 0}, {"GBS", 0, 4}, {"GNS", 0, 4}, {"GST", 1, 4}, {"ZDA", 0, 4}, + {"RMC", 1, 0}, + {"GGA", 1, 0}, + {"GSV", 1, 0}, + {"GSA", 1, 0}, + {"VTG", 1, 0}, + {"GLL", 1, 0}, + {"GBS", 0, 4}, + {"GNS", 0, 4}, + {"GST", 1, 4}, + {"ZDA", 0, 4}, }; const lg290pMsg lgMessagesRTCM[] = { - {"RTCM3-1005", 1, 0}, {"RTCM3-1006", 0, 0}, + {"RTCM3-1005", 1, 0}, + {"RTCM3-1006", 0, 0}, {"RTCM3-1019", 0, 0}, @@ -46,10 +60,17 @@ const lg290pMsg lgMessagesRTCM[] = { {"RTCM3-1033", 0, 4}, // v4 and above - {"RTCM3-1041", 0, 0}, {"RTCM3-1042", 0, 0}, {"RTCM3-1044", 0, 0}, {"RTCM3-1046", 0, 0}, - - {"RTCM3-107X", 1, 0}, {"RTCM3-108X", 1, 0}, {"RTCM3-109X", 1, 0}, {"RTCM3-111X", 1, 0}, - {"RTCM3-112X", 1, 0}, {"RTCM3-113X", 1, 0}, + {"RTCM3-1041", 0, 0}, + {"RTCM3-1042", 0, 0}, + {"RTCM3-1044", 0, 0}, + {"RTCM3-1046", 0, 0}, + + {"RTCM3-107X", 1, 0}, + {"RTCM3-108X", 1, 0}, + {"RTCM3-109X", 1, 0}, + {"RTCM3-111X", 1, 0}, + {"RTCM3-112X", 1, 0}, + {"RTCM3-113X", 1, 0}, }; // Quectel Proprietary messages @@ -64,52 +85,64 @@ const lg290pMsg lgMessagesPQTM[] = { enum lg290p_Models { - // LG290P does not have models - LG290P_DYN_MODEL_SURVEY = 0, - LG290P_DYN_MODEL_UAV, - LG290P_DYN_MODEL_AUTOMOTIVE, + // LG290P does not have models + LG290P_DYN_MODEL_SURVEY = 0, + LG290P_DYN_MODEL_UAV, + LG290P_DYN_MODEL_AUTOMOTIVE, }; class GNSS_LG290P : GNSS { - private: - LG290P *_lg290p; // Library class instance +private: + LG290P *_lg290p; // Library class instance + +protected: + bool configureOnce(); + + // Setup the general configuration of the GNSS + // Not Rover or Base specific (ie, baud rates) + // Outputs: + // Returns true if successfully configured and false upon failure + bool configureGNSS(); + + // Turn on all the enabled NMEA messages on COM3 + bool enableNMEA(); - protected: - bool configureOnce(); + // Turn on all the enabled RTCM Rover messages on COM3 + bool enableRTCMRover(); - // Setup the general configuration of the GNSS - // Not Rover or Base specific (ie, baud rates) - // Outputs: - // Returns true if successfully configured and false upon failure - bool configureGNSS(); + // Turn on all the enabled RTCM Base messages on COM3 + bool enableRTCMBase(); - // Turn on all the enabled NMEA messages on COM3 - bool enableNMEA(); + uint8_t getActiveNmeaMessageCount(); - // Turn on all the enabled RTCM Rover messages on COM3 - bool enableRTCMRover(); + // Given the name of an NMEA message, return the array number + uint8_t getNmeaMessageNumberByName(const char *msgName); - // Turn on all the enabled RTCM Base messages on COM3 - bool enableRTCMBase(); + // Given the name of an RTCM message, return the array number + uint8_t getRtcmMessageNumberByName(const char *msgName); - uint8_t getActiveNmeaMessageCount(); + // Return true if the GPGGA message is active + bool isGgaActive(); - // Given the name of an NMEA message, return the array number - uint8_t getNmeaMessageNumberByName(const char *msgName); + // Given a sub type (ie "RTCM", "NMEA") present menu showing messages with this subtype + // Controls the messages that get broadcast over Bluetooth and logged (if enabled) + void menuMessagesSubtype(int *localMessageRate, const char *messageType); - // Given the name of an RTCM message, return the array number - uint8_t getRtcmMessageNumberByName(const char *msgName); + // Set the minimum satellite signal level for navigation. + bool setMinCnoRadio(uint8_t cnoValue); - // Return true if the GPGGA message is active - bool isGgaActive(); + // Set all NMEA message report rates to one value + void setNmeaMessageRates(uint8_t msgRate); - // Given a sub type (ie "RTCM", "NMEA") present menu showing messages with this subtype - // Controls the messages that get broadcast over Bluetooth and logged (if enabled) - void menuMessagesSubtype(int *localMessageRate, const char *messageType); + // Given the name of a message, find it, and set the rate + bool setNmeaMessageRateByName(const char *msgName, uint8_t msgRate); - // Set the minimum satellite signal level for navigation. - bool setMinCnoRadio(uint8_t cnoValue); + // Set all RTCM Rover message report rates to one value + void setRtcmRoverMessageRates(uint8_t msgRate); + + // Given the name of a message, find it, and set the rate + bool setRtcmRoverMessageRateByName(const char *msgName, uint8_t msgRate); public: // Constructor @@ -117,353 +150,353 @@ class GNSS_LG290P : GNSS { } - // If we have decryption keys, configure module - // Note: don't check online.lband_neo here. We could be using ip corrections - void applyPointPerfectKeys(); + // If we have decryption keys, configure module + // Note: don't check online.lband_neo here. We could be using ip corrections + void applyPointPerfectKeys(); + + // Set RTCM for base mode to defaults (1005/1074/1084/1094/1124 1Hz & 1230 0.1Hz) + void baseRtcmDefault(); + + // Reset to Low Bandwidth Link (1074/1084/1094/1124 0.5Hz & 1005/1230 0.1Hz) + void baseRtcmLowDataRate(); + + // Check if a given baud rate is supported by this module + bool baudIsAllowed(uint32_t baudRate); + uint32_t baudGetMinimum(); + uint32_t baudGetMaximum(); - // Set RTCM for base mode to defaults (1005/1074/1084/1094/1124 1Hz & 1230 0.1Hz) - void baseRtcmDefault(); + // Connect to GNSS and identify particulars + void begin(); - // Reset to Low Bandwidth Link (1074/1084/1094/1124 0.5Hz & 1005/1230 0.1Hz) - void baseRtcmLowDataRate(); + // Setup TM2 time stamp input as need + // Outputs: + // Returns true when an external event occurs and false if no event + bool beginExternalEvent(); - // Check if a given baud rate is supported by this module - bool baudIsAllowed(uint32_t baudRate); - uint32_t baudGetMinimum(); - uint32_t baudGetMaximum(); + // Setup the timepulse output on the PPS pin for external triggering + // Outputs + // Returns true if the pin was successfully setup and false upon + // failure + bool beginPPS(); - // Connect to GNSS and identify particulars - void begin(); + bool checkNMEARates(); - // Setup TM2 time stamp input as need - // Outputs: - // Returns true when an external event occurs and false if no event - bool beginExternalEvent(); + bool checkPPPRates(); - // Setup the timepulse output on the PPS pin for external triggering - // Outputs - // Returns true if the pin was successfully setup and false upon - // failure - bool beginPPS(); + // Configure the Base + // Outputs: + // Returns true if successfully configured and false upon failure + bool configureBase(); - bool checkNMEARates(); + // Configure specific aspects of the receiver for NTP mode + bool configureNtpMode(); - bool checkPPPRates(); + // Configure the Rover + // Outputs: + // Returns true if successfully configured and false upon failure + bool configureRover(); - // Configure the Base - // Outputs: - // Returns true if successfully configured and false upon failure - bool configureBase(); + // Responds with the messages supported on this platform + // Inputs: + // returnText: String to receive message names + // Returns message names in the returnText string + void createMessageList(String &returnText); - // Configure specific aspects of the receiver for NTP mode - bool configureNtpMode(); + // Responds with the RTCM/Base messages supported on this platform + // Inputs: + // returnText: String to receive message names + // Returns message names in the returnText string + void createMessageListBase(String &returnText); - // Configure the Rover - // Outputs: - // Returns true if successfully configured and false upon failure - bool configureRover(); + void debuggingDisable(); - // Responds with the messages supported on this platform - // Inputs: - // returnText: String to receive message names - // Returns message names in the returnText string - void createMessageList(String &returnText); + void debuggingEnable(); - // Responds with the RTCM/Base messages supported on this platform - // Inputs: - // returnText: String to receive message names - // Returns message names in the returnText string - void createMessageListBase(String &returnText); + bool disableSurveyIn(bool saveAndReset); - void debuggingDisable(); + void enableGgaForNtrip(); - void debuggingEnable(); + // Enable RTCM 1230. This is the GLONASS bias sentence and is transmitted + // even if there is no GPS fix. We use it to test serial output. + // Outputs: + // Returns true if successfully started and false upon failure + bool enableRTCMTest(); - bool disableSurveyIn(bool saveAndReset); + bool enterConfigMode(unsigned long waitForSemaphoreTimeout_millis); - void enableGgaForNtrip(); + bool exitConfigMode(); - // Enable RTCM 1230. This is the GLONASS bias sentence and is transmitted - // even if there is no GPS fix. We use it to test serial output. - // Outputs: - // Returns true if successfully started and false upon failure - bool enableRTCMTest(); + // Restore the GNSS to the factory settings + void factoryReset(); - bool enterConfigMode(unsigned long waitForSemaphoreTimeout_millis); + uint16_t fileBufferAvailable(); - bool exitConfigMode(); + uint16_t fileBufferExtractData(uint8_t *fileBuffer, int fileBytesToRead); - // Restore the GNSS to the factory settings - void factoryReset(); + // Start the base using fixed coordinates + // Outputs: + // Returns true if successfully started and false upon failure + bool fixedBaseStart(); - uint16_t fileBufferAvailable(); + // Return the number of active/enabled messages + uint8_t getActiveMessageCount(); - uint16_t fileBufferExtractData(uint8_t *fileBuffer, int fileBytesToRead); + // Return the number of active/enabled RTCM messages + uint8_t getActiveRtcmMessageCount(); - // Start the base using fixed coordinates - // Outputs: - // Returns true if successfully started and false upon failure - bool fixedBaseStart(); + // Get the altitude + // Outputs: + // Returns the altitude in meters or zero if the GNSS is offline + double getAltitude(); - // Return the number of active/enabled messages - uint8_t getActiveMessageCount(); + uint32_t getBaudRate(uint8_t uartNumber); - // Return the number of active/enabled RTCM messages - uint8_t getActiveRtcmMessageCount(); + // Returns the carrier solution or zero if not online + uint8_t getCarrierSolution(); - // Get the altitude - // Outputs: - // Returns the altitude in meters or zero if the GNSS is offline - double getAltitude(); + uint32_t getCommBaudRate(); - // Returns the carrier solution or zero if not online - uint8_t getCarrierSolution(); + uint32_t getDataBaudRate(); - uint32_t getDataBaudRate(); + // Returns the day number or zero if not online + uint8_t getDay(); - // Returns the day number or zero if not online - uint8_t getDay(); + // Return the number of milliseconds since GNSS data was last updated + uint16_t getFixAgeMilliseconds(); - // Return the number of milliseconds since GNSS data was last updated - uint16_t getFixAgeMilliseconds(); + // Returns the fix type or zero if not online + uint8_t getFixType(); - // Returns the fix type or zero if not online - uint8_t getFixType(); + // Returns the hours of 24 hour clock or zero if not online + uint8_t getHour(); - // Returns the hours of 24 hour clock or zero if not online - uint8_t getHour(); + // Get the horizontal position accuracy + // Outputs: + // Returns the horizontal position accuracy or zero if offline + float getHorizontalAccuracy(); - // Get the horizontal position accuracy - // Outputs: - // Returns the horizontal position accuracy or zero if offline - float getHorizontalAccuracy(); + const char *getId(); - const char *getId(); + // Get the latitude value + // Outputs: + // Returns the latitude value or zero if not online + double getLatitude(); - // Get the latitude value - // Outputs: - // Returns the latitude value or zero if not online - double getLatitude(); + // Query GNSS for current leap seconds + uint8_t getLeapSeconds(); - // Query GNSS for current leap seconds - uint8_t getLeapSeconds(); + // Return the type of logging that matches the enabled messages - drives the logging icon + uint8_t getLoggingType(); - // Return the type of logging that matches the enabled messages - drives the logging icon - uint8_t getLoggingType(); + // Get the longitude value + // Outputs: + // Returns the longitude value or zero if not online + double getLongitude(); - // Get the longitude value - // Outputs: - // Returns the longitude value or zero if not online - double getLongitude(); + // Returns two digits of milliseconds or zero if not online + uint8_t getMillisecond(); - // Returns two digits of milliseconds or zero if not online - uint8_t getMillisecond(); + // Get the minimum satellite signal level for navigation. + uint8_t getMinCno(); - // Get the minimum satellite signal level for navigation. - uint8_t getMinCno(); + // Returns minutes or zero if not online + uint8_t getMinute(); - // Returns minutes or zero if not online - uint8_t getMinute(); + // Returns 0 - Unknown, 1 - Rover, 2 - Base + uint8_t getMode(); - // Returns 0 - Unknown, 1 - Rover, 2 - Base - uint8_t getMode(); + // Returns month number or zero if not online + uint8_t getMonth(); - // Returns month number or zero if not online - uint8_t getMonth(); + // Returns nanoseconds or zero if not online + uint32_t getNanosecond(); - // Returns nanoseconds or zero if not online - uint32_t getNanosecond(); + uint32_t getRadioBaudRate(); - uint32_t getRadioBaudRate(); + // Returns the seconds between solutions + double getRateS(); - // Returns the seconds between solutions - double getRateS(); + const char *getRtcmDefaultString(); - const char *getRtcmDefaultString(); + const char *getRtcmLowDataRateString(); - const char *getRtcmLowDataRateString(); + // Returns the number of satellites in view or zero if offline + uint8_t getSatellitesInView(); - // Returns the number of satellites in view or zero if offline - uint8_t getSatellitesInView(); + // Returns seconds or zero if not online + uint8_t getSecond(); - // Returns seconds or zero if not online - uint8_t getSecond(); + // Get the survey-in mean accuracy + // Outputs: + // Returns the mean accuracy or zero (0) + float getSurveyInMeanAccuracy(); - // Get the survey-in mean accuracy - // Outputs: - // Returns the mean accuracy or zero (0) - float getSurveyInMeanAccuracy(); + uint8_t getSurveyInMode(); - uint8_t getSurveyInMode(); + // Return the number of seconds the survey-in process has been running + int getSurveyInObservationTime(); - // Return the number of seconds the survey-in process has been running - int getSurveyInObservationTime(); + float getSurveyInStartingAccuracy(); - float getSurveyInStartingAccuracy(); + // Returns timing accuracy or zero if not online + uint32_t getTimeAccuracy(); - // Returns timing accuracy or zero if not online - uint32_t getTimeAccuracy(); + // Returns full year, ie 2023, not 23. + uint16_t getYear(); - // Returns full year, ie 2023, not 23. - uint16_t getYear(); + // Returns true if the device is in Rover mode + // Currently the only two modes are Rover or Base + bool inRoverMode(); - // Returns true if the device is in Rover mode - // Currently the only two modes are Rover or Base - bool inRoverMode(); + bool isBlocking(); - bool isBlocking(); + // Date is confirmed once we have GNSS fix + bool isConfirmedDate(); - // Date is confirmed once we have GNSS fix - bool isConfirmedDate(); + // Date is confirmed once we have GNSS fix + bool isConfirmedTime(); - // Date is confirmed once we have GNSS fix - bool isConfirmedTime(); + // Returns true if data is arriving on the Radio Ext port + bool isCorrRadioExtPortActive(); - // Returns true if data is arriving on the Radio Ext port - bool isCorrRadioExtPortActive(); + // Return true if GNSS receiver has a higher quality DGPS fix than 3D + bool isDgpsFixed(); - // Return true if GNSS receiver has a higher quality DGPS fix than 3D - bool isDgpsFixed(); + // Some functions (L-Band area frequency determination) merely need + // to know if we have a valid fix, not what type of fix + // This function checks to see if the given platform has reached + // sufficient fix type to be considered valid + bool isFixed(); - // Some functions (L-Band area frequency determination) merely need - // to know if we have a valid fix, not what type of fix - // This function checks to see if the given platform has reached - // sufficient fix type to be considered valid - bool isFixed(); + // Used in tpISR() for time pulse synchronization + bool isFullyResolved(); - // Used in tpISR() for time pulse synchronization - bool isFullyResolved(); + bool isPppConverged(); - bool isPppConverged(); + bool isPppConverging(); - bool isPppConverging(); + // Some functions (L-Band area frequency determination) merely need + // to know if we have an RTK Fix. This function checks to see if the + // given platform has reached sufficient fix type to be considered valid + bool isRTKFix(); - // Some functions (L-Band area frequency determination) merely need - // to know if we have an RTK Fix. This function checks to see if the - // given platform has reached sufficient fix type to be considered valid - bool isRTKFix(); + // Some functions (L-Band area frequency determination) merely need + // to know if we have an RTK Float. This function checks to see if + // the given platform has reached sufficient fix type to be considered + // valid + bool isRTKFloat(); - // Some functions (L-Band area frequency determination) merely need - // to know if we have an RTK Float. This function checks to see if - // the given platform has reached sufficient fix type to be considered - // valid - bool isRTKFloat(); + // Determine if the survey-in operation is complete + // Outputs: + // Returns true if the survey-in operation is complete and false + // if the operation is still running + bool isSurveyInComplete(); - // Determine if the survey-in operation is complete - // Outputs: - // Returns true if the survey-in operation is complete and false - // if the operation is still running - bool isSurveyInComplete(); + // Date will be valid if the RTC is reporting (regardless of GNSS fix) + bool isValidDate(); - // Date will be valid if the RTC is reporting (regardless of GNSS fix) - bool isValidDate(); + // Time will be valid if the RTC is reporting (regardless of GNSS fix) + bool isValidTime(); - // Time will be valid if the RTC is reporting (regardless of GNSS fix) - bool isValidTime(); + // Controls the constellations that are used to generate a fix and logged + void menuConstellations(); - // Controls the constellations that are used to generate a fix and logged - void menuConstellations(); + void menuMessageBaseRtcm(); - void menuMessageBaseRtcm(); + // Control the messages that get broadcast over Bluetooth and logged (if enabled) + void menuMessages(); - // Control the messages that get broadcast over Bluetooth and logged (if enabled) - void menuMessages(); + // Print the module type and firmware version + void printModuleInfo(); - // Print the module type and firmware version - void printModuleInfo(); + // Send correction data to the GNSS + // Inputs: + // dataToSend: Address of a buffer containing the data + // dataLength: The number of valid data bytes in the buffer + // Outputs: + // Returns the number of correction data bytes written + int pushRawData(uint8_t *dataToSend, int dataLength); - // Send correction data to the GNSS - // Inputs: - // dataToSend: Address of a buffer containing the data - // dataLength: The number of valid data bytes in the buffer - // Outputs: - // Returns the number of correction data bytes written - int pushRawData(uint8_t *dataToSend, int dataLength); + uint16_t rtcmBufferAvailable(); - uint16_t rtcmBufferAvailable(); + // If LBand is being used, ignore any RTCM that may come in from the GNSS + void rtcmOnGnssDisable(); - // If LBand is being used, ignore any RTCM that may come in from the GNSS - void rtcmOnGnssDisable(); + // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver + void rtcmOnGnssEnable(); - // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver - void rtcmOnGnssEnable(); + uint16_t rtcmRead(uint8_t *rtcmBuffer, int rtcmBytesToRead); - uint16_t rtcmRead(uint8_t *rtcmBuffer, int rtcmBytesToRead); + // Save the current configuration + // Outputs: + // Returns true when the configuration was saved and false upon failure + bool saveConfiguration(); - // Save the current configuration - // Outputs: - // Returns true when the configuration was saved and false upon failure - bool saveConfiguration(); + bool setBaudRate(uint8_t uartNumber, uint32_t baudRate); - // Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS - // This just sets the GNSS side - // Used during Bluetooth testing - // Inputs: - // baudRate: The desired baudrate - bool setBaudrate(uint32_t baudRate); + bool setCommBaudrate(uint32_t baud); - // Enable all the valid constellations and bands for this platform - bool setConstellations(); + // Enable all the valid constellations and bands for this platform + bool setConstellations(); - // Enable / disable corrections protocol(s) on the Radio External port - // Always update if force is true. Otherwise, only update if enable has changed state - bool setCorrRadioExtPort(bool enable, bool force); + // Enable / disable corrections protocol(s) on the Radio External port + // Always update if force is true. Otherwise, only update if enable has changed state + bool setCorrRadioExtPort(bool enable, bool force); - bool setDataBaudRate(uint32_t baud); + bool setDataBaudRate(uint32_t baud); - // Set the elevation in degrees - // Inputs: - // elevationDegrees: The elevation value in degrees - bool setElevation(uint8_t elevationDegrees); + // Set the elevation in degrees + // Inputs: + // elevationDegrees: The elevation value in degrees + bool setElevation(uint8_t elevationDegrees); - // Enable all the valid messages for this platform - bool setMessages(int maxRetries); + bool setHighAccuracyService(bool enableGalileoHas, const char *configurePPP); - // Enable all the valid messages for this platform over the USB port - bool setMessagesUsb(int maxRetries); + // Enable all the valid messages for this platform + bool setMessages(int maxRetries); - // Set the dynamic model to use for RTK - // Inputs: - // modelNumber: Number of the model to use, provided by radio library - bool setModel(uint8_t modelNumber); + // Enable all the valid messages for this platform over the USB port + bool setMessagesUsb(int maxRetries); - bool setRadioBaudRate(uint32_t baud); + // Set the dynamic model to use for RTK + // Inputs: + // modelNumber: Number of the model to use, provided by radio library + bool setModel(uint8_t modelNumber); - // Specify the interval between solutions - // Inputs: - // secondsBetweenSolutions: Number of seconds between solutions - // Outputs: - // Returns true if the rate was successfully set and false upon - // failure - bool setRate(double secondsBetweenSolutions); + bool setRadioBaudRate(uint32_t baud); - bool setTalkerGNGGA(); + // Specify the interval between solutions + // Inputs: + // secondsBetweenSolutions: Number of seconds between solutions + // Outputs: + // Returns true if the rate was successfully set and false upon + // failure + bool setRate(double secondsBetweenSolutions); - // Hotstart GNSS to try to get RTK lock - bool softwareReset(); + bool setTalkerGNGGA(); - bool standby(); + // Hotstart GNSS to try to get RTK lock + bool softwareReset(); - // Reset the survey-in operation - // Outputs: - // Returns true if the survey-in operation was reset successfully - // and false upon failure - bool surveyInReset(); + bool standby(); - // Start the survey-in operation - // Outputs: - // Return true if successful and false upon failure - bool surveyInStart(); + // Reset the survey-in operation + // Outputs: + // Returns true if the survey-in operation was reset successfully + // and false upon failure + bool surveyInReset(); - // If we have received serial data from the LG290P outside of the library (ie, from processUart1Message task) - // we can pass data back into the LG290P library to allow it to update its own variables - void lg290pUpdate(uint8_t *incomingBuffer, int bufferLength); + // Start the survey-in operation + // Outputs: + // Return true if successful and false upon failure + bool surveyInStart(); - // Return the baud rate of UART2, connected to the ESP32 UART1 - uint32_t getCommBaudRate(); + // If we have received serial data from the LG290P outside of the library (ie, from processUart1Message task) + // we can pass data back into the LG290P library to allow it to update its own variables + void lg290pUpdate(uint8_t *incomingBuffer, int bufferLength); - // Poll routine to update the GNSS state - void update(); + // Poll routine to update the GNSS state + void update(); }; #endif // COMPILE_LG290P diff --git a/Firmware/RTK_Everywhere/GNSS_LG290P.ino b/Firmware/RTK_Everywhere/GNSS_LG290P.ino index f52cd5d2a..4c44e68ae 100644 --- a/Firmware/RTK_Everywhere/GNSS_LG290P.ino +++ b/Firmware/RTK_Everywhere/GNSS_LG290P.ino @@ -85,13 +85,13 @@ void GNSS_LG290P::begin() if (_lg290p->begin(*serialGNSS) == false) // Give the serial port over to the library { if (settings.debugGnss) - systemPrintln("GNSS Failed to begin. Trying again."); + systemPrintln("GNSS LG290P failed to begin. Trying again."); // Try again with power on delay delay(1000); if (_lg290p->begin(*serialGNSS) == false) { - systemPrintln("GNSS offline"); + systemPrintln("GNSS LG290P offline"); displayGNSSFail(1000); return; } @@ -114,6 +114,15 @@ void GNSS_LG290P::begin() "update the " "firmware on your LG290P to allow for these features. Please see https://bit.ly/sfe-rtk-lg290p-update\r\n", lg290pFirmwareVersion, gnssFirmwareVersion); + + // Determine if the "LG290P03AANR01A03S_PPP_TEMP0812 2025/08/12" firmware is present + // Or "LG290P03AANR01A06S_PPP_TEMP0829 2025/08/29 17:08:39" + // The 03S_PPP_TEMP version has support for testing out E6/HAS PPP, but confusingly was released after v05. + if (strstr(gnssFirmwareVersion, "PPP_TEMP") != nullptr) + { + present.galileoHasCapable = true; + systemPrintln("PPP trial firmware detected. HAS settings will now be available."); + } } if (lg290pFirmwareVersion < 5) { @@ -132,6 +141,22 @@ void GNSS_LG290P::begin() present.minCno = true; } + // Determine if PPP temp firmware is detected. + // "LG290P03AANR01A03S_PPP_TEMP0812" + // "LG290P03AANR01A06S_PPP_TEMP0829" + // There is also a v06 firmware that does not have PPP support. + // v07 is reportedly the first version to formally support PPP + if (strstr(gnssFirmwareVersion, "PPP_TEMP") != nullptr) + { + present.galileoHasCapable = true; + systemPrintln("PPP trial firmware detected. HAS settings will now be available."); + } + + if (lg290pFirmwareVersion >= 7) + { + present.galileoHasCapable = true; + } + printModuleInfo(); snprintf(gnssUniqueId, sizeof(gnssUniqueId), "%s", getId()); @@ -192,9 +217,9 @@ bool GNSS_LG290P::configureGNSS() // If we fail, reset LG290P systemPrintln("Resetting LG290P to complete configuration"); - lg290pReset(); + gnssReset(); delay(500); - lg290pBoot(); + gnssBoot(); } systemPrintln("LG290P failed to configure"); @@ -255,15 +280,12 @@ bool GNSS_LG290P::configureOnce() // Set the baud rate for the three UARTs if (response == true) { - if (getDataBaudRate() != settings.dataPortBaud) - response &= setDataBaudRate(settings.dataPortBaud); // LG290P UART1 is connected to CH342 (Port B) + response &= setDataBaudRate(settings.dataPortBaud); // If available, set baud of DATA port - if (getCommBaudRate() != (115200 * 4)) - response &= setBaudrate(115200 * 4); // LG290P UART2 is connected to the ESP32 UART1 + // The following setCommBaudrate() is redundant because to get this far, the comm interface must already be + // working response &= setCommBaudrate(115200 * 4); // Set baud for main comm channel - if (getRadioBaudRate() != settings.radioPortBaud) - response &= - setRadioBaudRate(settings.radioPortBaud); // LG290P UART3 is connected to the locking JST connector + response &= setRadioBaudRate(settings.radioPortBaud); // If available, set baud of RADIO port if (response == false && settings.debugGnss) systemPrintln("configureOnce: setBauds failed."); @@ -360,11 +382,38 @@ bool GNSS_LG290P::configureRover() response &= setMinCnoRadio(settings.minCNO); + // If we are on a platform that supports tilt + if (present.tiltPossible == true) + { + // And tilt is present and enabled + if (present.imu_im19 == true && settings.enableTiltCompensation == true) + { + // Configure GNSS to support the tilt sensor + + // Tilt sensor requires 5Hz at a minimum + if (settings.measurementRateMs > 200) + { + systemPrintln("Increasing GNSS measurement rate to 5Hz for tilt support"); + settings.measurementRateMs = 200; + } + + // On the LG290P Flex module, UART 3 of the GNSS is connected to the IMU UART 1 + response &= setBaudRate(3, 115200); + + if (response == false && settings.debugGnss) + systemPrintln("configureRover: setBaud failed."); + + // Enable of GGA, RMC, GST for tilt sensor is done in enableNMEA() + } + } + // Set the fix rate. Default on LG290P is 10Hz so set accordingly. response &= setRate(settings.measurementRateMs / 1000.0); // May require save/reset if (settings.debugGnss && response == false) systemPrintln("configureRover: Set rate failed"); + response &= setHighAccuracyService(settings.enableGalileoHas, (const char *)settings.configurePPP); + response &= enableRTCMRover(); if (settings.debugGnss && response == false) systemPrintln("configureRover: Enable RTCM failed"); @@ -479,6 +528,8 @@ bool GNSS_LG290P::configureBase() response &= setMinCnoRadio(settings.minCNO); + response &= setHighAccuracyService(settings.enableGalileoHas, (const char *)settings.configurePPP); + response &= enableRTCMBase(); // Set RTCM messages if (settings.debugGnss && response == false) systemPrintln("configureBase: Enable RTCM failed"); @@ -521,6 +572,25 @@ bool GNSS_LG290P::configureBase() //---------------------------------------- void GNSS_LG290P::createMessageList(String &returnText) { + for (int messageNumber = 0; messageNumber < MAX_LG290P_NMEA_MSG; messageNumber++) + { + // Strictly, this should be bool true/false as only 0/1 values are allowed + // and a checkbox should be used to select. BUT other platforms permit + // rates higher than 1. It's way cleaner if we just use 0/1 here + returnText += "messageRateNMEA_" + String(lgMessagesNMEA[messageNumber].msgTextName) + "," + + String(settings.lg290pMessageRatesNMEA[messageNumber]) + ","; + } + for (int messageNumber = 0; messageNumber < MAX_LG290P_RTCM_MSG; messageNumber++) + { + returnText += "messageRateRTCMRover_" + String(lgMessagesRTCM[messageNumber].msgTextName) + "," + + String(settings.lg290pMessageRatesRTCMRover[messageNumber]) + ","; + } + for (int messageNumber = 0; messageNumber < MAX_LG290P_PQTM_MSG; messageNumber++) + { + // messageRatePQTM is unique to the LG290P. So we can use true/false and a checkbox + returnText += "messageRatePQTM_" + String(lgMessagesPQTM[messageNumber].msgTextName) + "," + + String(settings.lg290pMessageRatesPQTM[messageNumber] ? "true" : "false") + ","; + } } //---------------------------------------- @@ -531,6 +601,14 @@ void GNSS_LG290P::createMessageList(String &returnText) //---------------------------------------- void GNSS_LG290P::createMessageListBase(String &returnText) { + for (int messageNumber = 0; messageNumber < MAX_LG290P_RTCM_MSG; messageNumber++) + { + // Strictly, this should be bool true/false as only 0/1 values are allowed + // and a checkbox should be used to select. BUT other platforms permit + // rates higher than 1. It's way cleaner if we just use 0/1 here + returnText += "messageRateRTCMBase_" + String(lgMessagesRTCM[messageNumber].msgTextName) + "," + + String(settings.lg290pMessageRatesRTCMBase[messageNumber]) + ","; + } } //---------------------------------------- @@ -564,11 +642,16 @@ bool GNSS_LG290P::enterConfigMode(unsigned long waitForSemaphoreTimeout_millis) do { // Wait for up to waitForSemaphoreTimeout for library to stop blocking isBlocking = _lg290p->isBlocking(); - } while (isBlocking && (millis() < (start + waitForSemaphoreTimeout_millis))); + } while (isBlocking && ((millis() - start) < waitForSemaphoreTimeout_millis)); // This will fail if the library is still blocking, but it is worth a punt... - return (_lg290p->sendOkCommand("$PQTMCFGPROT", - ",W,1,2,00000000,00000000")); // Disable NMEA and RTCM on the LG290P UART2 + + if (lg290pFirmwareVersion >= 6) // See #747 + // Disable NMEA and RTCM on the LG290P UART2, but leave the undocumented Bit 1 enabled + return (_lg290p->sendOkCommand("$PQTMCFGPROT", ",W,1,2,00000007,00000002")); + + // Disable NMEA and RTCM on the LG290P UART2 + return (_lg290p->sendOkCommand("$PQTMCFGPROT", ",W,1,2,00000000,00000000")); } return (false); } @@ -579,8 +662,14 @@ bool GNSS_LG290P::enterConfigMode(unsigned long waitForSemaphoreTimeout_millis) bool GNSS_LG290P::exitConfigMode() { if (online.gnss) - return (_lg290p->sendOkCommand("$PQTMCFGPROT", - ",W,1,2,00000005,00000005")); // Enable NMEA and RTCM on the LG290P UART2 + { + if (lg290pFirmwareVersion >= 6) // See #747 + // Enable NMEA and RTCM on the LG290P UART2, plus the undocumented Bit 1 + return (_lg290p->sendOkCommand("$PQTMCFGPROT", ",W,1,2,00000007,00000007")); + + // Enable NMEA and RTCM on the LG290P UART2 + return (_lg290p->sendOkCommand("$PQTMCFGPROT", ",W,1,2,00000005,00000005")); + } return (false); } @@ -640,7 +729,6 @@ bool GNSS_LG290P::enableNMEA() { bool response = true; bool gpggaEnabled = false; - bool gpzdaEnabled = false; int portNumber = 1; @@ -670,17 +758,13 @@ bool GNSS_LG290P::enableNMEA() // If we are using IP based corrections, we need to send local data to the PPL // The PPL requires being fed GPGGA/ZDA, and RTCM1019/1020/1042/1046 - if (pointPerfectIsEnabled()) + if (pointPerfectServiceUsesKeys()) { // Mark PPL required messages as enabled if rate > 0 if (settings.lg290pMessageRatesNMEA[messageNumber] > 0) { if (strcmp(lgMessagesNMEA[messageNumber].msgTextName, "GGA") == 0) gpggaEnabled = true; - - // ZDA not supported on LG290P - // if (strcmp(lgMessagesNMEA[messageNumber].msgTextName, "ZDA") == 0) - // gpzdaEnabled = true; } } } @@ -693,30 +777,53 @@ bool GNSS_LG290P::enableNMEA() break; // Don't step through portNumbers } - if (pointPerfectIsEnabled()) + if (pointPerfectServiceUsesKeys()) { // Force on any messages that are needed for PPL // If firmware is 4 or higher, use setMessageRateOnPort, otherwise setMessageRate if (lg290pFirmwareVersion >= 4) { - // Enable GGA / ZDA on port 2 (ESP32) only + // Enable GGA on UART 2 (connected to ESP32) only if (gpggaEnabled == false) response &= _lg290p->setMessageRateOnPort("GGA", 1, 2); - - // if (gpggaEnabled == false) - // response &= _lg290p->setMessageRateOnPort("GGA", 1, 1); } else { - // Enable GGA / ZDA on all ports. It's the best we can do. + // Enable GGA on all UARTs. It's the best we can do. if (gpggaEnabled == false) response &= _lg290p->setMessageRate("GGA", 1); - - // if (gpzdaEnabled == false) - // response &= _lg290p->setMessageRate("ZDA", 1); } } + // If this is Flex, we may need to enable NMEA for Tilt IMU + if (present.tiltPossible == true) + { + if (present.imu_im19 == true && settings.enableTiltCompensation == true) + { + // Regardless of user settings, enable GGA, RMC, GST on UART3 + // If firmware is 4 or higher, use setMessageRateOnPort, otherwise setMessageRate + if (lg290pFirmwareVersion >= 4) + { + // Enable GGA/RMS/GST on UART 3 (connected to the IMU) only + response &= _lg290p->setMessageRateOnPort("GGA", 1, 3); + response &= _lg290p->setMessageRateOnPort("RMC", 1, 3); + response &= _lg290p->setMessageRateOnPort("GST", 1, 3); + } + else + { + // GST not supported below 4 + systemPrintf( + "Current LG290P firmware: v%d (full form: %s). Tilt compensation requires GST on firmware v4 " + "or newer. Please " + "update the " + "firmware on your LG290P to allow for these features. Please see " + "https://bit.ly/sfe-rtk-lg290p-update\r\n Marking tilt compensation offline.", + lg290pFirmwareVersion, gnssFirmwareVersion); + + present.imu_im19 = false; + } + } + } return (response); } @@ -726,10 +833,12 @@ bool GNSS_LG290P::enableNMEA() bool GNSS_LG290P::enableRTCMBase() { bool response = true; - bool enableMSM = false; // Goes true if we need to enable MSM output reporting + bool enableRTCM = false; // Goes true if we need to enable RTCM output reporting int portNumber = 1; + int minimumRtcmRate = 1000; + while (portNumber < 4) { for (int messageNumber = 0; messageNumber < MAX_LG290P_RTCM_MSG; messageNumber++) @@ -778,9 +887,14 @@ bool GNSS_LG290P::enableRTCMBase() lgMessagesRTCM[messageNumber].msgTextName); } - // If any message is enabled, enable MSM output + // If any message is enabled, enable RTCM output if (settings.lg290pMessageRatesRTCMBase[messageNumber] > 0) - enableMSM = true; + { + enableRTCM = true; + // Capture the message with the lowest rate + if (settings.lg290pMessageRatesRTCMBase[messageNumber] < minimumRtcmRate) + minimumRtcmRate = settings.lg290pMessageRatesRTCMBase[messageNumber]; + } } } @@ -791,14 +905,17 @@ bool GNSS_LG290P::enableRTCMBase() break; // Don't step through portNumbers } - if (enableMSM == true) + if (enableRTCM == true) { if (settings.debugGnss) - systemPrintln("Enabling Base RTCM MSM output"); + systemPrintf("Enabling Base RTCM MSM%c output with rate of %d\r\n", settings.useMSM7 ? '7' : '4', + minimumRtcmRate); // PQTMCFGRTCM fails to respond with OK over UART2 of LG290P, so don't look for it - _lg290p->sendOkCommand( - "PQTMCFGRTCM,W,7,0,-90,07,06,2,1"); // Enable MSM7, output regular intervals, interval (seconds) + char cfgRtcm[40]; + snprintf(cfgRtcm, sizeof(cfgRtcm), "PQTMCFGRTCM,W,%c,0,%d,07,06,2,%d", settings.useMSM7 ? '7' : '4', + settings.rtcmMinElev, minimumRtcmRate); + _lg290p->sendOkCommand(cfgRtcm); // Enable MSM4/7, output regular intervals, interval (seconds) } return (response); @@ -814,14 +931,30 @@ bool GNSS_LG290P::enableRTCMRover() bool rtcm1020Enabled = false; bool rtcm1042Enabled = false; bool rtcm1046Enabled = false; - bool enableMSM = false; // Goes true if we need to enable MSM output reporting + bool enableRTCM = false; // Goes true if we need to enable RTCM output reporting int portNumber = 1; + int minimumRtcmRate = 1000; + while (portNumber < 4) { for (int messageNumber = 0; messageNumber < MAX_LG290P_RTCM_MSG; messageNumber++) { + // 1019 to 1046 can only be set to 1 fix per report + // 107x to 112x can be set to 1-1200 fixes between reports + // So we set all RTCM to 1, and set PQTMCFGRTCM to the lowest value found + + // Capture the message with the lowest rate + if (settings.lg290pMessageRatesRTCMRover[messageNumber] > 0 && + settings.lg290pMessageRatesRTCMRover[messageNumber] < minimumRtcmRate) + minimumRtcmRate = settings.lg290pMessageRatesRTCMRover[messageNumber]; + + // Force all RTCM messages to 1 or 0. See above for reasoning. + int rate = settings.lg290pMessageRatesRTCMRover[messageNumber]; + if (rate > 1) + rate = 1; + // Check if this RTCM message is supported by the current LG290P firmware if (lg290pFirmwareVersion >= lgMessagesRTCM[messageNumber].firmwareVersionSupported) { @@ -835,13 +968,11 @@ bool GNSS_LG290P::enableRTCMRover() if (lg290pFirmwareVersion >= 4) { // If any one of the commands fails, report failure overall - response &= _lg290p->setMessageRateOnPort(lgMessagesRTCM[messageNumber].msgTextName, - settings.lg290pMessageRatesRTCMRover[messageNumber], - portNumber); + response &= + _lg290p->setMessageRateOnPort(lgMessagesRTCM[messageNumber].msgTextName, rate, portNumber); } else - response &= _lg290p->setMessageRate(lgMessagesRTCM[messageNumber].msgTextName, - settings.lg290pMessageRatesRTCMRover[messageNumber]); + response &= _lg290p->setMessageRate(lgMessagesRTCM[messageNumber].msgTextName, rate); if (response == false && settings.debugGnss) systemPrintf("Enable RTCM failed at messageNumber %d %s\r\n", messageNumber, @@ -851,6 +982,8 @@ bool GNSS_LG290P::enableRTCMRover() { // X found. This is RTCM-1??X message. Assign 'offset' of 0 + // The rate of these type of messages can be 1 to 1200, so we allow the full rate + // If firmware is 4 or higher, use setMessageRateOnPort, otherwise setMessageRate if (lg290pFirmwareVersion >= 4) { @@ -867,13 +1000,13 @@ bool GNSS_LG290P::enableRTCMRover() lgMessagesRTCM[messageNumber].msgTextName); } - // If any message is enabled, enable MSM output + // If any message is enabled, enable RTCM output if (settings.lg290pMessageRatesRTCMRover[messageNumber] > 0) - enableMSM = true; + enableRTCM = true; // If we are using IP based corrections, we need to send local data to the PPL // The PPL requires being fed GPGGA/ZDA, and RTCM1019/1020/1042/1046 - if (pointPerfectIsEnabled()) + if (pointPerfectServiceUsesKeys()) { // Mark PPL required messages as enabled if rate > 0 if (settings.lg290pMessageRatesRTCMRover[messageNumber] > 0) @@ -898,9 +1031,9 @@ bool GNSS_LG290P::enableRTCMRover() break; // Don't step through portNumbers } - if (pointPerfectIsEnabled()) + if (pointPerfectServiceUsesKeys()) { - enableMSM = true; // Force enable MSM output + enableRTCM = true; // Force enable RTCM output // Force on any messages that are needed for PPL if (rtcm1019Enabled == false) @@ -931,14 +1064,23 @@ bool GNSS_LG290P::enableRTCMRover() } } - if (enableMSM == true) + // If any RTCM message is enabled, send CFGRTCM + if (enableRTCM == true) { if (settings.debugCorrections) - systemPrintln("Enabling Rover RTCM MSM output"); + systemPrintf("Enabling Rover RTCM MSM%c output with rate of %d\r\n", settings.useMSM7 ? '7' : '4', + minimumRtcmRate); + + // Enable MSM4/7 (for faster PPP CSRS results), output at a rate equal to the minimum RTCM rate (EPH Mode = 2) + // PQTMCFGRTCM, W, , , , , , , + // Set MSM_ElevThd to 15 degrees from rftop suggestion + + char msmCommand[40] = {0}; + snprintf(msmCommand, sizeof(msmCommand), "PQTMCFGRTCM,W,%c,0,%d,07,06,2,%d", settings.useMSM7 ? '7' : '4', + settings.rtcmMinElev, minimumRtcmRate); // PQTMCFGRTCM fails to respond with OK over UART2 of LG290P, so don't look for it - _lg290p->sendOkCommand( - "PQTMCFGRTCM,W,7,0,-90,07,06,2,1"); // Enable MSM7, output regular intervals, interval (seconds) + _lg290p->sendOkCommand(msmCommand); } return (response); @@ -1078,7 +1220,7 @@ uint8_t GNSS_LG290P::getActiveRtcmMessageCount() } //---------------------------------------- -// Returns the altitude in meters or zero if the GNSS is offline +// Returns the altitude in meters or zero if the GNSS is offline //---------------------------------------- double GNSS_LG290P::getAltitude() { @@ -1114,55 +1256,162 @@ uint8_t GNSS_LG290P::getCarrierSolution() } //---------------------------------------- -// UART1 of the LG290P is connected to USB CH342 (Port B) -// This is nicknamed the DATA port -// Return the baud rate of UART1 +// Return the baud rate of a given UART //---------------------------------------- -uint32_t GNSS_LG290P::getDataBaudRate() +uint32_t GNSS_LG290P::getBaudRate(uint8_t uartNumber) { + if (uartNumber < 1 || uartNumber > 3) + { + systemPrintln("getBaudRate error: out of range"); + return (0); + } + uint32_t baud = 0; if (online.gnss) { uint8_t dataBits, parity, stop, flowControl; - _lg290p->getPortInfo(1, baud, dataBits, parity, stop, flowControl, 250); + _lg290p->getPortInfo(uartNumber, baud, dataBits, parity, stop, flowControl, 250); } return (baud); } //---------------------------------------- -// UART1 of the LG290P is connected to USB CH342 (Port B) -// This is nicknamed the DATA port -// Return the baud rate of UART1 +// Set the baud rate of a given UART +//---------------------------------------- +bool GNSS_LG290P::setBaudRate(uint8_t uartNumber, uint32_t baudRate) +{ + if (uartNumber < 1 || uartNumber > 3) + { + systemPrintln("setBaudRate error: out of range"); + return (false); + } + + return (_lg290p->setPortBaudrate(uartNumber, baudRate, 250)); +} + +//---------------------------------------- +// Return the baud rate of port nicknamed DATA +//---------------------------------------- +uint32_t GNSS_LG290P::getDataBaudRate() +{ + uint8_t dataUart = 0; + if (productVariant == RTK_POSTCARD) + { + // UART1 of the LG290P is connected to USB CH342 (Port B) + // This is nicknamed the DATA port + dataUart = 1; + } + else if (productVariant == RTK_TORCH_X2) + { + // UART3 of the LG290P is connected to USB CH342 (Port A) + // This is nicknamed the DATA port + dataUart = 3; + } + else + { + systemPrintln("getDataBaudRate: Uncaught platform"); + } + return (getBaudRate(dataUart)); +} + +//---------------------------------------- +// Set the baud rate of port nicknamed DATA //---------------------------------------- bool GNSS_LG290P::setDataBaudRate(uint32_t baud) { if (online.gnss) { - return (_lg290p->setPortBaudrate(1, baud, 250)); + if (getDataBaudRate() == baud) + { + return (true); // Baud is set! + } + else + { + if (productVariant == RTK_POSTCARD) + { + // UART1 of the LG290P is connected to USB CH342 (Port B) + // This is nicknamed the DATA port + return (setBaudRate(1, baud)); + } + else if (productVariant == RTK_TORCH_X2) + { + if (getDataBaudRate() != baud) + { + // UART3 of the LG290P is connected to USB CH342 (Port A) + // This is nicknamed the DATA port + return (setBaudRate(3, baud)); + } + } + else + { + // On products that don't have a DATA port (Flex), act as if we have set the baud successfully + return (true); + } + } } - return (0); + return (false); } -// Return the baud rate of UART3, connected to the locking JST connector +//---------------------------------------- +// Return the baud rate of interface where a radio is connected //---------------------------------------- uint32_t GNSS_LG290P::getRadioBaudRate() { - uint32_t baud = 0; - if (online.gnss) + uint8_t radioUart = 0; + if (productVariant == RTK_POSTCARD) { - uint8_t dataBits, parity, stop, flowControl; - - _lg290p->getPortInfo(3, baud, dataBits, parity, stop, flowControl, 250); + // UART3 of the LG290P is connected to the locking JST connector labled RADIO + radioUart = 3; } - return (baud); + else if (productVariant == RTK_FLEX) + { + // UART2 of the LG290P is connected to SW4, which is connected to LoRa UART0 + radioUart = 2; + } + else if (productVariant == RTK_TORCH_X2) + { + // UART1 of the LG290P is connected to SW, which is connected to ESP32 UART0 + // Not really used at this time but available for configuration + radioUart = 1; + } + return (getBaudRate(radioUart)); } -// Set the baud rate for UART3, connected to the locking JST connector +//---------------------------------------- +// Set the baud rate for the Radio connection //---------------------------------------- bool GNSS_LG290P::setRadioBaudRate(uint32_t baud) { - return (_lg290p->setPortBaudrate(3, baud, 250)); + if (online.gnss) + { + if (getRadioBaudRate() == baud) + { + return (true); // Baud is set! + } + else + { + uint8_t radioUart = 0; + if (productVariant == RTK_POSTCARD) + { + // UART3 of the LG290P is connected to the locking JST connector labled RADIO + radioUart = 3; + } + else if (productVariant == RTK_FLEX) + { + // UART2 of the LG290P is connected to SW4, which is connected to LoRa UART0 + radioUart = 2; + } + else if (productVariant == RTK_TORCH_X2) + { + // UART1 of the LG290P is connected to SW, which is connected to ESP32 UART0 + // Not really used at this time but available for configuration + radioUart = 1; + } + return (setBaudRate(radioUart, baud)); + } + } + return (false); } //---------------------------------------- @@ -1222,6 +1471,8 @@ uint8_t GNSS_LG290P::getHour() return 0; } +//---------------------------------------- +// Return the serial number of the LG290P //---------------------------------------- const char *GNSS_LG290P::getId() { @@ -1267,16 +1518,18 @@ uint8_t GNSS_LG290P::getLoggingType() // GST is not available/default if (getActiveNmeaMessageCount() == 6 && getActiveRtcmMessageCount() == 0) logType = LOGGING_STANDARD; + else if (getActiveNmeaMessageCount() == 6 && getActiveRtcmMessageCount() == 4) + logType = LOGGING_PPP; } else { // GST *is* available/default if (getActiveNmeaMessageCount() == 7 && getActiveRtcmMessageCount() == 0) logType = LOGGING_STANDARD; + else if (getActiveNmeaMessageCount() == 7 && getActiveRtcmMessageCount() == 4) + logType = LOGGING_PPP; } - // What RTCM messages need to be logged to reach LOGGING_PPP? - return ((uint8_t)logType); } @@ -1655,6 +1908,15 @@ void GNSS_LG290P::menuConstellations() systemPrintln(); } + if (present.galileoHasCapable) + { + systemPrintf("%d) Galileo E6 Corrections: %s\r\n", MAX_LG290P_CONSTELLATIONS + 1, + settings.enableGalileoHas ? "Enabled" : "Disabled"); + if (settings.enableGalileoHas) + systemPrintf("%d) PPP Configuration: \"%s\"\r\n", MAX_LG290P_CONSTELLATIONS + 2, + settings.configurePPP); + } + systemPrintln("x) Exit"); int incoming = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long @@ -1665,6 +1927,35 @@ void GNSS_LG290P::menuConstellations() settings.lg290pConstellations[incoming] ^= 1; } + else if ((incoming == MAX_LG290P_CONSTELLATIONS + 1) && present.galileoHasCapable) + { + settings.enableGalileoHas ^= 1; + } + else if ((incoming == MAX_LG290P_CONSTELLATIONS + 2) && present.galileoHasCapable && settings.enableGalileoHas) + { + systemPrintln("Enter the PPP configuration separated by spaces, not commas:"); + char newConfig[sizeof(settings.configurePPP)]; + getUserInputString(newConfig, sizeof(newConfig)); + bool isValid = true; + int spacesSeen = 0; + for (size_t i = 0; i < strlen(newConfig); i++) + { + if ((isValid) && (newConfig[i] == ',')) // Check for no commas + { + systemPrintln("Comma detected. Please try again"); + isValid = false; + } + if (newConfig[i] == ' ') + spacesSeen++; + } + if ((isValid) && (spacesSeen < 4)) // Check for at least 4 spaces + { + systemPrintln("Configuration should contain at least 4 spaces"); + isValid = false; + } + if (isValid) + snprintf(settings.configurePPP, sizeof(settings.configurePPP), "%s", newConfig); + } else if (incoming == INPUT_RESPONSE_GETNUMBER_EXIT) break; else if (incoming == INPUT_RESPONSE_GETNUMBER_TIMEOUT) @@ -1676,6 +1967,8 @@ void GNSS_LG290P::menuConstellations() // Apply current settings to module gnss->setConstellations(); + setHighAccuracyService(settings.enableGalileoHas, (const char *)settings.configurePPP); + clearBuffer(); // Empty buffer of any newline chars } @@ -1703,6 +1996,13 @@ void GNSS_LG290P::menuMessages() systemPrintln("4) Set PQTM Messages"); systemPrintln("10) Reset to Defaults"); + systemPrintln("11) Reset to PPP Logging (NMEAx7 / RTCMx4 - 30 second decimation)"); + systemPrintln("12) Reset to High-rate PPP Logging (NMEAx7 / RTCMx4 - 1Hz)"); + + if (namedSettingAvailableOnPlatform("useMSM7")) // Redundant - but good practice for code reuse + systemPrintf("13) MSM Selection: MSM%c\r\n", settings.useMSM7 ? '7' : '4'); + if (namedSettingAvailableOnPlatform("rtcmMinElev")) // Redundant - but good practice for code reuse + systemPrintf("14) Minimum Elevation for RTCM: %d\r\n", settings.rtcmMinElev); systemPrintln("x) Exit"); @@ -1736,6 +2036,61 @@ void GNSS_LG290P::menuMessages() systemPrintln("Reset to Defaults"); } + else if (incoming == 11 || incoming == 12) + { + // setMessageRate() on the LG290P sets the output of a message + // 'Output once every N position fixes' + // Slowest update rate of LG290P is an update per second, (0.5Hz not allowed) + + int rtcmReportRate = 1; + if (incoming == 11) + rtcmReportRate = 30; + + // Reset NMEA rates to defaults + for (int x = 0; x < MAX_LG290P_NMEA_MSG; x++) + settings.lg290pMessageRatesNMEA[x] = lgMessagesNMEA[x].msgDefaultRate; + + setRtcmRoverMessageRates(0); // Turn off all RTCM messages + setRtcmRoverMessageRateByName("RTCM3-1019", rtcmReportRate); + // setRtcmRoverMessageRateByName("RTCM3-1020", rtcmReportRate); //Not needed when MSM7 is used + // setRtcmRoverMessageRateByName("RTCM3-1042", rtcmReportRate); //BeiDou not used by CSRS-PPP + // setRtcmRoverMessageRateByName("RTCM3-1046", rtcmReportRate); //Not needed when MSM7 is used + setRtcmRoverMessageRateByName("RTCM3-107X", rtcmReportRate); + setRtcmRoverMessageRateByName("RTCM3-108X", rtcmReportRate); + setRtcmRoverMessageRateByName("RTCM3-109X", rtcmReportRate); + // setRtcmRoverMessageRateByName("RTCM3-112X", rtcmReportRate); //BeiDou not used by CSRS-PPP + + // MSM7 is set during enableRTCMRover() + + // Override settings for PPP logging + setElevation(15); + setMinCnoRadio(30); + + setRate(1); // Go to 1 Hz + + if (incoming == 12) + { + systemPrintln("Reset to High-rate PPP Logging Defaults (NMEAx7 / RTCMx4 - 1Hz)"); + } + else + { + systemPrintln("Reset to PPP Logging Defaults (NMEAx7 / RTCMx4 - 30 second decimation)"); + } + } + else if ((incoming == 13) && + (namedSettingAvailableOnPlatform("useMSM7"))) // Redundant - but good practice for code reuse) + settings.useMSM7 ^= 1; + else if ((incoming == 14) && (namedSettingAvailableOnPlatform("rtcmMinElev"))) + { + systemPrintf("Enter minimum elevation for RTCM: "); + + int elevation = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long + + if (elevation >= -90 && elevation <= 90) + { + settings.rtcmMinElev = elevation; + } + } else if (incoming == INPUT_RESPONSE_GETNUMBER_EXIT) break; @@ -1752,6 +2107,8 @@ void GNSS_LG290P::menuMessages() restartRover = true; else restartBase = true; + + setLoggingType(); // Determine if we are standard, PPP, or custom. Changes logging icon accordingly. } //---------------------------------------- @@ -1942,7 +2299,7 @@ void GNSS_LG290P::rtcmOnGnssDisable() } //---------------------------------------- -// If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver +// If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver //---------------------------------------- void GNSS_LG290P::rtcmOnGnssEnable() { @@ -1972,27 +2329,50 @@ bool GNSS_LG290P::saveConfiguration() // Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS // This just sets the GNSS side //---------------------------------------- -bool GNSS_LG290P::setBaudrate(uint32_t baud) +bool GNSS_LG290P::setCommBaudrate(uint32_t baud) { if (online.gnss) - // Set the baud rate on UART2 of the LG290P - return (_lg290p->setPortBaudrate(2, baud, 250)); - return false; + { + if (getCommBaudRate() == baud) + { + return (true); // Baud is set! + } + else + { + uint8_t commUart = 0; + if (productVariant == RTK_POSTCARD) + { + // UART2 of the LG290P is connected to the ESP32 for the main config/comm + commUart = 2; + } + else if (productVariant == RTK_FLEX) + { + // UART1 of the LG290P is connected to the ESP32 for the main config/comm + commUart = 1; + } + return (setBaudRate(commUart, baud)); + } + } + return (false); } //---------------------------------------- -// Return the baud rate of UART2, connected to the ESP32 UART1 +// Return the baud rate of the UART connected to the ESP32 UART1 //---------------------------------------- uint32_t GNSS_LG290P::getCommBaudRate() { - uint32_t baud = 0; - if (online.gnss) + uint8_t commUart = 0; + if (productVariant == RTK_POSTCARD) { - uint8_t dataBits, parity, stop, flowControl; - - _lg290p->getPortInfo(2, baud, dataBits, parity, stop, flowControl, 250); + // On the Postcard, the ESP32 UART1 is connected to LG290P UART2 + commUart = 2; } - return (baud); + else if (productVariant == RTK_FLEX) + { + // On the Flex, the ESP32 UART1 is connected to LG290P UART1 + commUart = 1; + } + return (getBaudRate(commUart)); } //---------------------------------------- @@ -2062,6 +2442,51 @@ bool GNSS_LG290P::setElevation(uint8_t elevationDegrees) return true; } +//---------------------------------------- +bool GNSS_LG290P::setHighAccuracyService(bool enableGalileoHas, const char *configurePPP) +{ + bool result = true; + + // E6 reception requires version v03/v06 with 'PPP_TEMP' in firmware title + // Present is set during LG290P begin() + if (present.galileoHasCapable == false) + return (result); // We are unable to set this setting to report success + + // Enable E6 and PPP if enabled + if (settings.enableGalileoHas) + { + // $PQTMCFGPPP,W,2,1,120,0.10,0.15*68 + // Enable E6 HAS, WGS84, 120 timeout, 0.10m Horizontal convergence accuracy threshold, 0.15m Vertical threshold + char paramConfigurePPP[sizeof(settings.configurePPP) + 4]; + snprintf(paramConfigurePPP, sizeof(paramConfigurePPP), ",W,%s", configPppSpacesToCommas(configurePPP)); + if (_lg290p->sendOkCommand("$PQTMCFGPPP", paramConfigurePPP) == true) + { + systemPrintln("Galileo E6 HAS service enabled"); + } + else + { + systemPrintln("Galileo E6 HAS service failed to enable"); + result = false; + } + } + else + { + // Turn off HAS/E6 + // $PQTMCFGPPP,W,0* + if (_lg290p->sendOkCommand("$PQTMCFGPPP", ",W,0") == true) + { + systemPrintln("Galileo E6 HAS service disabled"); + } + else + { + systemPrintln("Galileo E6 HAS service failed to disable"); + result = false; + } + } + + return (result); +} + //---------------------------------------- // Enable all the valid messages for this platform // There are many messages so split into batches. VALSET is limited to 64 max per batch @@ -2328,17 +2753,52 @@ uint32_t GNSS_LG290P::baudGetMaximum() return (lg290pAllowedRates[lg290pAllowedRatesCount - 1]); } -//---------------------------------------- -void lg290pBoot() +// Set all NMEA message report rates to one value +void GNSS_LG290P::setNmeaMessageRates(uint8_t msgRate) +{ + for (int x = 0; x < MAX_LG290P_NMEA_MSG; x++) + settings.lg290pMessageRatesNMEA[x] = msgRate; +} + +// Set all RTCM Rover message report rates to one value +void GNSS_LG290P::setRtcmRoverMessageRates(uint8_t msgRate) +{ + for (int x = 0; x < MAX_LG290P_RTCM_MSG; x++) + settings.lg290pMessageRatesRTCMRover[x] = msgRate; +} + +// Given the name of a message, find it, and set the rate +bool GNSS_LG290P::setNmeaMessageRateByName(const char *msgName, uint8_t msgRate) { - digitalWrite(pin_GNSS_Reset, HIGH); // Tell LG290P to boot + for (int x = 0; x < MAX_LG290P_NMEA_MSG; x++) + { + if (strcmp(lgMessagesNMEA[x].msgTextName, msgName) == 0) + { + settings.lg290pMessageRatesNMEA[x] = msgRate; + return (true); + } + } + systemPrintf("setNmeaMessageRateByName: %s not found\r\n", msgName); + return (false); } -void lg290pReset() +// Given the name of a message, find it, and set the rate +bool GNSS_LG290P::setRtcmRoverMessageRateByName(const char *msgName, uint8_t msgRate) { - digitalWrite(pin_GNSS_Reset, LOW); + for (int x = 0; x < MAX_LG290P_RTCM_MSG; x++) + { + if (strcmp(lgMessagesRTCM[x].msgTextName, msgName) == 0) + { + settings.lg290pMessageRatesRTCMRover[x] = msgRate; + return (true); + } + } + systemPrintf("setRtcmRoverMessageRateByName: %s not found\r\n", msgName); + return (false); } +//---------------------------------------- + // Given a NMEA or PQTM sentence, determine if it is enabled in settings // This is used to signal to the processUart1Message() task to remove messages that are needed // by the library to function (ie, PQTMEPE, PQTMPVT, GNGSV) but should not be logged or passed to other consumers @@ -2392,4 +2852,39 @@ bool lg290pMessageEnabled(char *nmeaSentence, int sentenceLength) return (true); } +// Return true if we detect this receiver type +bool lg290pIsPresent() +{ + // Locally instantiate the hardware and library so it will release on exit + + HardwareSerial serialTestGNSS(2); + + // LG290P communicates at 460800bps. + uint32_t platformGnssCommunicationRate = 115200 * 4; + + serialTestGNSS.begin(platformGnssCommunicationRate, SERIAL_8N1, pin_GnssUart_RX, pin_GnssUart_TX); + + LG290P lg290p; + + if (settings.debugGnss) + { + lg290p.enableDebugging(); // Print all debug to Serial + lg290p.enablePrintRxMessages(); // Print incoming processed messages from SEMP + } + + if (lg290p.begin(serialTestGNSS) == true) // Give the serial port over to the library + { + if (settings.debugGnss) + systemPrintln("LG290P detected"); + serialTestGNSS.end(); + return true; + } + + if (settings.debugGnss) + systemPrintln("LG290P not detected. Moving on."); + + serialTestGNSS.end(); + return false; +} + #endif // COMPILE_LG290P diff --git a/Firmware/RTK_Everywhere/GNSS_Mosaic.h b/Firmware/RTK_Everywhere/GNSS_Mosaic.h index b73c662ac..a2cace644 100644 --- a/Firmware/RTK_Everywhere/GNSS_Mosaic.h +++ b/Firmware/RTK_Everywhere/GNSS_Mosaic.h @@ -559,6 +559,8 @@ class GNSS_MOSAIC : GNSS // and add a private library class instance here. protected: + // Flag which indicates GNSS is blocking (needs exclusive access to the UART) + bool _isBlocking = false; // These globals are updated regularly via the SBF parser double _clkBias_ms; // PVTGeodetic RxClkBias (will be sawtooth unless clock steering is enabled) @@ -594,8 +596,34 @@ class GNSS_MOSAIC : GNSS float _lonStdDev; bool _receiverSetupSeen; bool _diskStatusSeen; - std::vector svInTracking; - //std::vector svInPVT; + struct svTracking_t + { + uint8_t SVID; + unsigned long lastSeen; + }; + std::vector svInTracking; + // Find sv in the vector of svTracking_t + // https://stackoverflow.com/a/590005 + struct find_sv + { + uint8_t findThisSv; + find_sv(uint8_t sv) : findThisSv(sv) {} + bool operator () (const svTracking_t& m) const + { + return m.SVID == findThisSv; + } + }; + // Check if SV is stale based on its lastSeen + struct find_stale_sv + { + const unsigned long expireAfter_millis = 2000; + unsigned long millisNow; + find_stale_sv(unsigned long now) : millisNow(now) {} + bool operator () (const svTracking_t& m) const + { + return (millisNow > (m.lastSeen + expireAfter_millis)); + } + }; // Constructor GNSS_MOSAIC() : _determiningFixedPosition(true), _clkBias_ms(0), @@ -604,8 +632,7 @@ class GNSS_MOSAIC : GNSS _antennaIsOpen(false), _antennaIsShorted(false), GNSS() { - svInTracking.clear(); - //svInPVT.clear(); + svInTracking.clear(); } // If we have decryption keys, configure module @@ -858,6 +885,11 @@ class GNSS_MOSAIC : GNSS bool isPppConverging(); + // Send commands out the UART to see if a mosaic module is present + bool isPresent(); + bool isPresentOnSerial(HardwareSerial *serialPort, const char *command, const char *response, const char *console, int retryLimit = 20); + bool mosaicIsPresentOnFlex(); + // Some functions (L-Band area frequency determination) merely need // to know if we have an RTK Fix. This function checks to see if the // given platform has reached sufficient fix type to be considered valid @@ -909,7 +941,7 @@ class GNSS_MOSAIC : GNSS // If LBand is being used, ignore any RTCM that may come in from the GNSS void rtcmOnGnssDisable(); - // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver + // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver void rtcmOnGnssEnable(); uint16_t rtcmRead(uint8_t *rtcmBuffer, int rtcmBytesToRead); @@ -940,6 +972,14 @@ class GNSS_MOSAIC : GNSS char *response = nullptr, size_t responseSize = 0, bool debug = true); + bool sendAndWaitForIdle(HardwareSerial *serialPort, + const char *message, + const char *reply, + unsigned long timeout = 1000, + unsigned long idle = 25, + char *response = nullptr, + size_t responseSize = 0, + bool debug = true); // Send message. Wait for up to timeout millis for reply to arrive // If the reply is received, keep reading bytes until the serial port has @@ -982,6 +1022,13 @@ class GNSS_MOSAIC : GNSS unsigned long wait = 25, char *response = nullptr, size_t responseSize = 0); + bool sendWithResponse(HardwareSerial *serialPort, + const char *message, + const char *reply, + unsigned long timeout = 1000, + unsigned long wait = 25, + char *response = nullptr, + size_t responseSize = 0); // Send message. Wait for up to timeout millis for reply to arrive // If the reply has started to be received when timeout is reached, wait for a further wait millis @@ -1003,13 +1050,6 @@ class GNSS_MOSAIC : GNSS char *response = nullptr, size_t responseSize = 0); - // Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS - // This just sets the GNSS side - // Used during Bluetooth testing - // Inputs: - // baudRate: The desired baudrate - bool setBaudrate(uint32_t baudRate); - // Set the baud rate of mosaic-X5 COM1 // This is used during the Bluetooth test // Inputs: @@ -1017,7 +1057,8 @@ class GNSS_MOSAIC : GNSS // baudRate: New baud rate for the COM port // Outputs: // Returns true if the baud rate was set and false upon failure - bool setBaudRateCOM(uint8_t port, uint32_t baudRate); + bool setBaudRate(uint8_t uartNumber, uint32_t baudRate); // From the super class + bool setBaudRateCOM(uint8_t port, uint32_t baudRate); // Original X5 implementation // Enable all the valid constellations and bands for this platform bool setConstellations(); @@ -1098,7 +1139,7 @@ class GNSS_MOSAIC : GNSS void updateSD(); - void waitSBFReceiverSetup(unsigned long timeout); + void waitSBFReceiverSetup(HardwareSerial *serialPort, unsigned long timeout); }; #endif // __GNSS_MOSAIC_H__ diff --git a/Firmware/RTK_Everywhere/GNSS_Mosaic.ino b/Firmware/RTK_Everywhere/GNSS_Mosaic.ino index 6bfbab784..063b0cbf3 100644 --- a/Firmware/RTK_Everywhere/GNSS_Mosaic.ino +++ b/Firmware/RTK_Everywhere/GNSS_Mosaic.ino @@ -26,30 +26,46 @@ GNSS_Mosaic.ino // File type "1" is NMEA //============================================================================== -//---------------------------------------- -// Control the messages that get logged to SD -//---------------------------------------- -void menuLogMosaic() +void printMosaicCardSpace() { - bool applyChanges = false; - - while (1) + // mosaicSdCardSize and mosaicSdFreeSpace are updated via the SBF 4059 (storeBlock4059) + if (present.mosaicMicroSd) { - systemPrintln(); - systemPrintln("Menu: Logging"); - char sdCardSizeChar[20]; String cardSize; - stringHumanReadableSize(cardSize, sdCardSize); + stringHumanReadableSize(cardSize, mosaicSdCardSize); cardSize.toCharArray(sdCardSizeChar, sizeof(sdCardSizeChar)); char sdFreeSpaceChar[20]; String freeSpace; - stringHumanReadableSize(freeSpace, sdFreeSpace); + stringHumanReadableSize(freeSpace, mosaicSdFreeSpace); freeSpace.toCharArray(sdFreeSpaceChar, sizeof(sdFreeSpaceChar)); + // On Facet mosaic, the SD is connected directly to the X5 and is accessible + // On Flex mosaic-X5, the internal mosaic SD card is not accessible char myString[70]; snprintf(myString, sizeof(myString), "SD card size: %s / Free space: %s", sdCardSizeChar, sdFreeSpaceChar); systemPrintln(myString); + } +} + +//---------------------------------------- +// Control the messages that get logged to SD +//---------------------------------------- +void menuLogMosaic() +{ + if (!present.mosaicMicroSd) // This may be needed for the G5 P3 ? + return; + + bool applyChanges = false; + + while (1) + { + systemPrintln(); + systemPrintln("Menu: Mosaic Logging"); + systemPrintln(); + + printMosaicCardSpace(); + systemPrintln(); systemPrint("1) Log NMEA to microSD: "); if (settings.enableLogging == true) @@ -205,95 +221,130 @@ void GNSS_MOSAIC::baseRtcmLowDataRate() //---------------------------------------- void GNSS_MOSAIC::begin() { - if (serial2GNSS == nullptr) - { - systemPrintln("GNSS UART 2 not started"); - return; - } - - // Mosaic could still be starting up, so allow many retries - int retries = 0; - int retryLimit = 20; - - // Set COM4 to: CMD input (only), SBF output (only) - while (!sendWithResponse("sdio,COM4,CMD,SBF\n\r", "DataInOut")) - { - if (retries == retryLimit) - break; - retries++; - sendWithResponse("SSSSSSSSSSSSSSSSSSSS\n\r", "COM4>"); // Send escape sequence - } - - if (retries == retryLimit) - { - systemPrintln("Could not communicate with mosaic-X5! Attempting a soft reset..."); + // On Facet mosaic: + // COM1 is connected to the ESP32 for: Encapsulated RTCMv3 + SBF + NMEA, plus L-Band + // COM2 is connected to the RADIO port + // COM3 is connected to the DATA port + // COM4 is connected to the ESP32 for config + // (The comments on the schematic are out of date) + + // On Flex (with Ethernet): + // COM1 is connected to the ESP32 UART1 for: Encapsulated RTCMv3 + SBF + NMEA + // COM2 is connected to LoRa or 4-pin JST (switched by SW4) + // COM3 can be connected to ESP32 UART2 (switched by SW3) + // COM4 can be connected to ESP32 UART0 (switched by SW2) + // We need to do everything through COM1: configure, transfer RTCM, receive NMEA + // We need to Encapsulate RTCMv3 and NMEA in SBF format. Both SBF and NMEA messages start with "$". + // The alternative would be to add a 'hybrid' parser to the SEMP which can disambiguate SBF and NMEA + + // On Flex (with IMU): + // COM1 is connected to the ESP32 UART1 for: Encapsulated RTCMv3 + SBF + NMEA + // COM2 is connected to LoRa or 4-pin JST (switched by SW4) + // COM3 is N/C (ESP32 UART2 is connected to the IMU) + // COM4 TX provides data to the IMU - TODO + + if (productVariant != RTK_FLEX) // productVariant == RTK_FACET_MOSAIC + { + if (serial2GNSS == nullptr) + { + systemPrintln("GNSS UART 2 not started"); + return; + } - sendWithResponse("erst,soft,none\n\r", "ResetReceiver"); + if(isPresent() == false) //Detect if the module is present + return; - retries = 0; + int retries = 0; + int retryLimit = 3; - // Set COM4 to: CMD input (only), SBF output (only) - while (!sendWithResponse("sdio,COM4,CMD,SBF\n\r", "DataInOut")) + // Set COM1 baud rate. X5 defaults to 115200. Settings default to 230400bps + while (!setBaudRateCOM(1, settings.dataPortBaud)) { if (retries == retryLimit) break; retries++; - sendWithResponse("SSSSSSSSSSSSSSSSSSSS\n\r", "COM4>"); // Send escape sequence + sendWithResponse(serial2GNSS, "SSSSSSSSSSSSSSSSSSSS\n\r", "COM4>"); // Send escape sequence } if (retries == retryLimit) { - systemPrintln("Could not communicate with mosaic-X5!"); + systemPrintln("Could not set mosaic-X5 COM1 baud!"); return; } - } - retries = 0; - retryLimit = 3; + // Set COM2 (Radio) and COM3 (Data) baud rates + setRadioBaudRate(settings.radioPortBaud); + setDataBaudRate(settings.dataPortBaud); - // Set COM1 baud rate - while (!setBaudRateCOM(1, settings.dataPortBaud)) - { - if (retries == retryLimit) - break; - retries++; - sendWithResponse("SSSSSSSSSSSSSSSSSSSS\n\r", "COM4>"); // Send escape sequence - } + // Set COM2 (Radio) protocol(s) + setCorrRadioExtPort(settings.enableExtCorrRadio, true); // Force the setting - if (retries == retryLimit) - { - systemPrintln("Could not set mosaic-X5 COM1 baud!"); - return; + updateSD(); // Check card size and free space + + _receiverSetupSeen = false; + + // Request the ReceiverSetup SBF block using a esoc (exeSBFOnce) command on COM4 + String request = "esoc,COM4,ReceiverSetup\n\r"; + serial2GNSS->write(request.c_str(), request.length()); + + // Wait for up to 5 seconds for the Receiver Setup + waitSBFReceiverSetup(serial2GNSS, 5000); + + if (_receiverSetupSeen) // Check 5902 ReceiverSetup was seen + { + systemPrintln("GNSS mosaic-X5 online"); + + // Check firmware version and print info + printModuleInfo(); + online.gnss = true; + } + else + systemPrintln("GNSS mosaic-X5 offline!"); } + else // productVariant == RTK_FLEX + { + if (serialGNSS == nullptr) + { + systemPrintln("GNSS UART not started"); + return; + } + + if(isPresent() == false) //Detect if the module is present + return; - // Set COM2 (Radio) and COM3 (Data) baud rates - setRadioBaudRate(settings.radioPortBaud); - setDataBaudRate(settings.dataPortBaud); + // Set COM2 (Radio) and COM3 (Data) baud rates + setRadioBaudRate(settings.radioPortBaud); + setDataBaudRate(settings.dataPortBaud); // Probably redundant - // Set COM2 (Radio) protocol(s) - setCorrRadioExtPort(settings.enableExtCorrRadio, true); // Force the setting + // Set COM2 (Radio) protocol(s) + setCorrRadioExtPort(settings.enableExtCorrRadio, true); // Force the setting - updateSD(); // Check card size and free space + updateSD(); // Check card size and free space - _receiverSetupSeen = false; + _receiverSetupSeen = false; - // Request the ReceiverSetup SBF block using a esoc (exeSBFOnce) command on COM4 - String request = "esoc,COM4,ReceiverSetup\n\r"; - serial2GNSS->write(request.c_str(), request.length()); + _isBlocking = true; // Suspend the GNSS read task - // Wait for up to 5 seconds for the Receiver Setup - waitSBFReceiverSetup(5000); + // Request the ReceiverSetup SBF block using a esoc (exeSBFOnce) command on COM1 + String request = "esoc,COM1,ReceiverSetup\n\r"; + serialGNSS->write(request.c_str(), request.length()); - if (_receiverSetupSeen) // Check 5902 ReceiverSetup was seen - { - systemPrintln("GNSS mosaic-X5 online"); + // Wait for up to 5 seconds for the Receiver Setup + waitSBFReceiverSetup(serialGNSS, 5000); + + _isBlocking = false; - // Check firmware version and print info - printModuleInfo(); - online.gnss = true; + if (_receiverSetupSeen) // Check 5902 ReceiverSetup was seen + { + systemPrintln("GNSS mosaic-X5 online"); + + // Check firmware version and print info + printModuleInfo(); + online.gnss = true; + } + else + systemPrintln("GNSS mosaic-X5 offline!"); } - else - systemPrintln("GNSS mosaic-X5 offline!"); } //---------------------------------------- @@ -528,13 +579,11 @@ bool GNSS_MOSAIC::configureLBand(bool enableLBand, uint32_t LBandFreq) // US SPARTN 1.8 service is on 1556290000 Hz // EU SPARTN 1.8 service is on 1545260000 Hz - result &= - sendWithResponse(String("slbb,User1," + String(storedLBandFreq) + ",baud2400,PPerfect,EU,Enabled\n\r"), - "LBandBeams"); // Set Freq, baud rate - result &= - sendWithResponse("slcs,5555,6959\n\r", "LBandCustomServiceID"); // 21845 = 0x5555; 26969 = 0x6959 + result &= sendWithResponse(String("slbb,User1," + String(storedLBandFreq) + ",baud2400,PPerfect,EU,Enabled\n\r"), + "LBandBeams"); // Set Freq, baud rate + result &= sendWithResponse("slcs,5555,6959\n\r", "LBandCustomServiceID"); // 21845 = 0x5555; 26969 = 0x6959 result &= sendWithResponse("slsm,manual,Inmarsat,User1,\n\r", - "LBandSelectMode"); // Set L-Band demodulator to manual + "LBandSelectMode"); // Set L-Band demodulator to manual return result; } @@ -565,7 +614,7 @@ bool GNSS_MOSAIC::configureOnce() bool response = true; // Configure COM1. NMEA and RTCMv3 will be encapsulated in SBF format - response &= configureGNSSCOM(pointPerfectIsEnabled()); + response &= configureGNSSCOM(pointPerfectLbandNeeded()); // COM2 is configured by setCorrRadioExtPort @@ -575,7 +624,8 @@ bool GNSS_MOSAIC::configureOnce() // Output SBF PVTGeodetic and ReceiverTime on their own stream - on COM1 only // TODO : make the interval adjustable // TODO : do we need to enable SBF LBandTrackerStatus so we can get CN0 ? - String setting = String("sso,Stream" + String(MOSAIC_SBF_PVT_STREAM) + ",COM1,PVTGeodetic+ReceiverTime,msec500\n\r"); + String setting = + String("sso,Stream" + String(MOSAIC_SBF_PVT_STREAM) + ",COM1,PVTGeodetic+ReceiverTime,msec500\n\r"); response &= sendWithResponse(setting, "SBFOutput"); // Output SBF InputLink on its own stream - at 1Hz - on COM1 only @@ -585,7 +635,8 @@ bool GNSS_MOSAIC::configureOnce() // Output SBF ChannelStatus, ReceiverStatus and DiskStatus on their own stream - at 0.5Hz - on COM1 only // For ChannelStatus: OnChange is too often. The message is typically 1000 bytes in size. // For DiskStatus: DiskUsage is slow to update. 0.5Hz is plenty fast enough. - setting = String("sso,Stream" + String(MOSAIC_SBF_STATUS_STREAM) + ",COM1,ChannelStatus+ReceiverStatus+DiskStatus,sec2\n\r"); + setting = String("sso,Stream" + String(MOSAIC_SBF_STATUS_STREAM) + + ",COM1,ChannelStatus+ReceiverStatus+DiskStatus,sec2\n\r"); response &= sendWithResponse(setting, "SBFOutput"); // Mark L5 as healthy @@ -712,8 +763,8 @@ void GNSS_MOSAIC::createMessageList(String &returnText) } for (int messageNumber = 0; messageNumber < MAX_MOSAIC_RTCM_V3_INTERVAL_GROUPS; messageNumber++) { - returnText += "messageIntervalRTCMRover_" + String(mosaicRTCMv3MsgIntervalGroups[messageNumber].name) + - "," + String(settings.mosaicMessageIntervalsRTCMv3Rover[messageNumber]) + ","; + returnText += "messageIntervalRTCMRover_" + String(mosaicRTCMv3MsgIntervalGroups[messageNumber].name) + "," + + String(settings.mosaicMessageIntervalsRTCMv3Rover[messageNumber]) + ","; } for (int messageNumber = 0; messageNumber < MAX_MOSAIC_RTCM_V3_MSG; messageNumber++) { @@ -787,7 +838,7 @@ bool GNSS_MOSAIC::enableNMEA() // The PPL requires being fed GPGGA/ZDA, and RTCM1019/1020/1042/1046 if (strstr(settings.pointPerfectKeyDistributionTopic, "/ip") != nullptr) { - // Mark PPL requied messages as enabled if stream > 0 + // Mark PPL required messages as enabled if stream > 0 if (strcmp(mosaicMessagesNMEA[messageNumber].msgTextName, "GGA") == 0) gpggaEnabled = true; if (strcmp(mosaicMessagesNMEA[messageNumber].msgTextName, "ZDA") == 0) @@ -855,7 +906,7 @@ bool GNSS_MOSAIC::enableNMEA() if (settings.enableNmeaOnRadio) setting = String("sno,Stream" + String(stream + MOSAIC_NUM_NMEA_STREAMS + 1) + ",COM2," + streams[stream] + - "," + String(mosaicMsgRates[settings.mosaicStreamIntervalsNMEA[stream]].name) + "\n\r"); + "," + String(mosaicMsgRates[settings.mosaicStreamIntervalsNMEA[stream]].name) + "\n\r"); else setting = String("sno,Stream" + String(stream + MOSAIC_NUM_NMEA_STREAMS + 1) + ",COM2,none,off\n\r"); response &= sendWithResponse(setting, "NMEAOutput"); @@ -1052,7 +1103,7 @@ bool GNSS_MOSAIC::enableRTCMTest() if (retries == retryLimit) break; retries++; - sendWithResponse("SSSSSSSSSSSSSSSSSSSS\n\r", "COM2>"); // Send escape sequence + sendWithResponse("SSSSSSSSSSSSSSSSSSSS\n\r", "COM"); // Send escape sequence } if (retries == retryLimit) @@ -1073,12 +1124,14 @@ void GNSS_MOSAIC::factoryReset() unsigned long start = millis(); bool result = sendWithResponse("eccf,RxDefault,Boot\n\r", "CopyConfigFile", 5000); if (settings.debugGnss) - systemPrintf("factoryReset: sendWithResponse eccf,RxDefault,Boot returned %s after %d ms\r\n", result ? "true" : "false", millis() - start); + systemPrintf("factoryReset: sendWithResponse eccf,RxDefault,Boot returned %s after %d ms\r\n", + result ? "true" : "false", millis() - start); start = millis(); result = sendWithResponse("eccf,RxDefault,Current\n\r", "CopyConfigFile", 5000); if (settings.debugGnss) - systemPrintf("factoryReset: sendWithResponse eccf,RxDefault,Current returned %s after %d ms\r\n", result ? "true" : "false", millis() - start); + systemPrintf("factoryReset: sendWithResponse eccf,RxDefault,Current returned %s after %d ms\r\n", + result ? "true" : "false", millis() - start); } //---------------------------------------- @@ -1533,7 +1586,9 @@ bool GNSS_MOSAIC::isAntennaOpen() //---------------------------------------- bool GNSS_MOSAIC::isBlocking() { - return false; + // Facet mosaic is non-blocking. It has exclusive access to COM4 + // Flex (mosaic) is blocking. Suspend the GNSS read task only if needed + return _isBlocking && (productVariant == RTK_FLEX); } //---------------------------------------- @@ -1700,7 +1755,8 @@ void GNSS_MOSAIC::menuConstellations() for (int x = 0; x < MAX_MOSAIC_CONSTELLATIONS; x++) { - systemPrintf("%d) Constellation %s: ", x + 1, mosaicSignalConstellations[x].name); + const char *ptr = mosaicSignalConstellations[x].configName; + systemPrintf("%d) Constellation %s: ", x + 1, ptr); if (settings.mosaicConstellations[x] > 0) systemPrint("Enabled"); else @@ -1995,7 +2051,7 @@ void GNSS_MOSAIC::rtcmOnGnssDisable() } //---------------------------------------- -// If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver +// If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver //---------------------------------------- void GNSS_MOSAIC::rtcmOnGnssEnable() { @@ -2019,7 +2075,8 @@ bool GNSS_MOSAIC::saveConfiguration() unsigned long start = millis(); bool result = sendWithResponse("eccf,Current,Boot\n\r", "CopyConfigFile", 5000); if (settings.debugGnss) - systemPrintf("saveConfiguration: sendWithResponse returned %s after %d ms\r\n", result ? "true" : "false", millis() - start); + systemPrintf("saveConfiguration: sendWithResponse returned %s after %d ms\r\n", result ? "true" : "false", + millis() - start); return result; } @@ -2039,28 +2096,38 @@ bool GNSS_MOSAIC::saveConfiguration() // Outputs: // Returns true if the response was received and false upon failure //---------------------------------------- -bool GNSS_MOSAIC::sendAndWaitForIdle(const char *message, const char *reply, unsigned long timeout, unsigned long idle, +bool GNSS_MOSAIC::sendAndWaitForIdle(const char *message, const char *reply, unsigned long timeout, unsigned long wait, + char *response, size_t responseSize, bool debug) +{ + if (productVariant == RTK_FACET_MOSAIC) + return sendAndWaitForIdle(serial2GNSS, message, reply, timeout, wait, response, responseSize, debug); + else + return sendAndWaitForIdle(serialGNSS, message, reply, timeout, wait, response, responseSize, debug); +} +bool GNSS_MOSAIC::sendAndWaitForIdle(HardwareSerial *serialPort, const char *message, const char *reply, unsigned long timeout, unsigned long idle, char *response, size_t responseSize, bool debug) { if (strlen(reply) == 0) // Reply can't be zero-length return false; + _isBlocking = true; // Suspend the GNSS read task + if (debug && (settings.debugGnss == true) && (!inMainMenu)) systemPrintf("sendAndWaitForIdle: sending %s\r\n", message); if (strlen(message) > 0) - serial2GNSS->write(message, strlen(message)); // Send the message + serialPort->write(message, strlen(message)); // Send the message unsigned long startTime = millis(); size_t replySeen = 0; - while ((millis() < (startTime + timeout)) && (replySeen < strlen(reply))) // While not timed out and reply not seen + while (((millis() - startTime) < timeout) && (replySeen < strlen(reply))) // While not timed out and reply not seen { - if (serial2GNSS->available()) // If a char is available + if (serialPort->available()) // If a char is available { - uint8_t c = serial2GNSS->read(); // Read it - if (debug && (settings.debugGnss == true) && (!inMainMenu)) - systemPrintf("%c", (char)c); + uint8_t c = serialPort->read(); // Read it + //if (debug && (settings.debugGnss == true) && (!inMainMenu)) + // systemPrintf("%c", (char)c); if (c == *(reply + replySeen)) // Is it a char from reply? { if (response && (replySeen < (responseSize - 1))) @@ -2078,13 +2145,13 @@ bool GNSS_MOSAIC::sendAndWaitForIdle(const char *message, const char *reply, uns if (replySeen == strlen(reply)) // If the reply was seen { startTime = millis(); - while (millis() < (startTime + idle)) + while ((millis() - startTime) < idle) { - if (serial2GNSS->available()) + if (serialPort->available()) { - uint8_t c = serial2GNSS->read(); - if (debug && (settings.debugGnss == true) && (!inMainMenu)) - systemPrintf("%c", (char)c); + uint8_t c = serialPort->read(); + //if (debug && (settings.debugGnss == true) && (!inMainMenu)) + // systemPrintf("%c", (char)c); if (response && (replySeen < (responseSize - 1))) { *(response + replySeen) = c; @@ -2095,9 +2162,13 @@ bool GNSS_MOSAIC::sendAndWaitForIdle(const char *message, const char *reply, uns } } + _isBlocking = false; + return true; } + _isBlocking = false; + return false; } @@ -2140,15 +2211,25 @@ bool GNSS_MOSAIC::sendAndWaitForIdle(String message, const char *reply, unsigned //---------------------------------------- bool GNSS_MOSAIC::sendWithResponse(const char *message, const char *reply, unsigned long timeout, unsigned long wait, char *response, size_t responseSize) +{ + if (productVariant == RTK_FACET_MOSAIC) + return sendWithResponse(serial2GNSS, message, reply, timeout, wait, response, responseSize); + else + return sendWithResponse(serialGNSS, message, reply, timeout, wait, response, responseSize); +} +bool GNSS_MOSAIC::sendWithResponse(HardwareSerial *serialPort, const char *message, const char *reply, unsigned long timeout, unsigned long wait, + char *response, size_t responseSize) { if (strlen(reply) == 0) // Reply can't be zero-length return false; + _isBlocking = true; // Suspend the GNSS read task + if ((settings.debugGnss == true) && (!inMainMenu)) systemPrintf("sendWithResponse: sending %s\r\n", message); if (strlen(message) > 0) - serial2GNSS->write(message, strlen(message)); // Send the message + serialPort->write(message, strlen(message)); // Send the message unsigned long startTime = millis(); size_t replySeen = 0; @@ -2156,11 +2237,11 @@ bool GNSS_MOSAIC::sendWithResponse(const char *message, const char *reply, unsig while ((keepGoing) && (replySeen < strlen(reply))) // While not timed out and reply not seen { - if (serial2GNSS->available()) // If a char is available + if (serialPort->available()) // If a char is available { - uint8_t c = serial2GNSS->read(); // Read it - if ((settings.debugGnss == true) && (!inMainMenu)) - systemPrintf("%c", (char)c); + uint8_t c = serialPort->read(); // Read it + //if ((settings.debugGnss == true) && (!inMainMenu)) + // systemPrintf("%c", (char)c); if (c == *(reply + replySeen)) // Is it a char from reply? { if (response && (replySeen < (responseSize - 1))) @@ -2175,24 +2256,24 @@ bool GNSS_MOSAIC::sendWithResponse(const char *message, const char *reply, unsig } // If the reply has started to arrive at the timeout, allow extra time - if (millis() > (startTime + timeout)) // Have we timed out? + if ((millis() - startTime) > timeout) // Have we timed out? if (replySeen == 0) // If replySeen is zero, don't keepGoing keepGoing = false; - if (millis() > (startTime + timeout + wait)) // Have we really timed out? + if ((millis() - startTime) > (timeout + wait)) // Have we really timed out? keepGoing = false; // Don't keepGoing } if (replySeen == strlen(reply)) // If the reply was seen { startTime = millis(); - while (millis() < (startTime + wait)) + while ((millis() - startTime) < wait) { - if (serial2GNSS->available()) + if (serialPort->available()) { - uint8_t c = serial2GNSS->read(); - if ((settings.debugGnss == true) && (!inMainMenu)) - systemPrintf("%c", (char)c); + uint8_t c = serialPort->read(); + //if ((settings.debugGnss == true) && (!inMainMenu)) + // systemPrintf("%c", (char)c); if (response && (replySeen < (responseSize - 1))) { *(response + replySeen) = c; @@ -2202,9 +2283,13 @@ bool GNSS_MOSAIC::sendWithResponse(const char *message, const char *reply, unsig } } + _isBlocking = false; + return true; } + _isBlocking = false; + return false; } @@ -2230,15 +2315,22 @@ bool GNSS_MOSAIC::sendWithResponse(String message, const char *reply, unsigned l } //---------------------------------------- -// Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS -// This just sets the GNSS side -// Used during Bluetooth testing +// Set the baud rate of mosaic-X5 COMn - from the super class // Inputs: -// baudRate: The desired baudrate +// port: COM port number +// baudRate: New baud rate for the COM port +// Outputs: +// Returns true if the baud rate was set and false upon failure //---------------------------------------- -bool GNSS_MOSAIC::setBaudrate(uint32_t baudRate) +bool GNSS_MOSAIC::setBaudRate(uint8_t port, uint32_t baudRate) { - return setBaudRateCOM(1, baudRate); + if (port < 1 || port > 4) + { + systemPrintln("setBaudRate error: out of range"); + return (false); + } + + return setBaudRateCOM(port, baudRate); } //---------------------------------------- @@ -2341,6 +2433,8 @@ bool GNSS_MOSAIC::setDataBaudRate(uint32_t baud) // Set the elevation in degrees // Inputs: // elevationDegrees: The elevation value in degrees +// Notes: +// mosaic supports negative elevations, but our firmware only support 0-90 //---------------------------------------- bool GNSS_MOSAIC::setElevation(uint8_t elevationDegrees) { @@ -2460,7 +2554,7 @@ void GNSS_MOSAIC::storeBlock4007(SEMP_PARSE_STATE *parse) // NrSV is the total number of satellites used in the PVT computation. //_satellitesInView = sempSbfGetU1(parse, 74); - //if (_satellitesInView == 255) // 255 indicates "Do-Not-Use" + // if (_satellitesInView == 255) // 255 indicates "Do-Not-Use" // _satellitesInView = 0; _fixType = sempSbfGetU1(parse, 14) & 0x0F; @@ -2500,62 +2594,44 @@ void GNSS_MOSAIC::storeBlock4013(SEMP_PARSE_STATE *parse) if (Tracking) { - // SV is being tracked. If it is not in svInTracking, add it - std::vector::iterator pos = - std::find(svInTracking.begin(), svInTracking.end(), SVID); - if (pos == svInTracking.end()) - svInTracking.push_back(SVID); + // SV is being tracked + std::vector::iterator pos = std::find_if(svInTracking.begin(), svInTracking.end(), find_sv(SVID)); + if (pos == svInTracking.end()) // If it is not in svInTracking, add it + svInTracking.push_back({SVID, millis()}); + else // Update lastSeen + { + svTracking_t sv = *pos; + sv.lastSeen = millis(); + *pos = sv; + } } else { // SV is not being tracked. If it is in svInTracking, remove it - std::vector::iterator pos = - std::find(svInTracking.begin(), svInTracking.end(), SVID); + std::vector::iterator pos = std::find_if(svInTracking.begin(), svInTracking.end(), find_sv(SVID)); if (pos != svInTracking.end()) svInTracking.erase(pos); } - - // uint16_t PVTStatus = sempSbfGetU2(parse, 20 + ChannelInfoBytes + SB1Length + (j * SB2Length) + 4); - - // bool Used = false; - // for (uint16_t shift = 0; shift < 16; shift += 2) // Step through each 2-bit status field - // { - // if ((PVTStatus & (0x0003 << shift)) == (0x0002 << shift)) // 2 : Used - // { - // Used = true; - // } - // } - - // if (Used) - // { - // // SV is being used for PVT. If it is not in svInPVT, add it - // std::vector::iterator pos = - // std::find(svInPVT.begin(), svInPVT.end(), SVID); - // if (pos == svInPVT.end()) - // svInPVT.push_back(SVID); - // } - // else - // { - // // SV is not being used for PVT. If it is in svInPVT, remove it - // std::vector::iterator pos = - // std::find(svInPVT.begin(), svInPVT.end(), SVID); - // if (pos != svInPVT.end()) - // svInPVT.erase(pos); - // } - } ChannelInfoBytes += SB1Length + (N2 * SB2Length); } + // Erase stale SVs + bool keepGoing = true; + while (keepGoing) + { + std::vector::iterator pos = std::find_if(svInTracking.begin(), svInTracking.end(), find_stale_sv(millis())); + if (pos != svInTracking.end()) + svInTracking.erase(pos); + else + keepGoing = false; + } + _satellitesInView = (uint8_t)std::distance(svInTracking.begin(), svInTracking.end()); // if (settings.debugGnss && !inMainMenu) - // { - // uint8_t _inPVT = (uint8_t)std::distance(svInPVT.begin(), svInPVT.end()); - // systemPrintf("ChannelStatus: InTracking %d, InPVT %d\r\n", _satellitesInView, _inPVT); - // } - + // systemPrintf("ChannelStatus: InTracking %d\r\n", _satellitesInView); } //---------------------------------------- @@ -2579,6 +2655,9 @@ void GNSS_MOSAIC::storeBlock4014(SEMP_PARSE_STATE *parse) //---------------------------------------- void GNSS_MOSAIC::storeBlock4059(SEMP_PARSE_STATE *parse) { + if (!present.mosaicMicroSd) + return; + if (sempSbfGetU1(parse, 14) < 1) // Check N is at least 1 return; @@ -2598,9 +2677,15 @@ void GNSS_MOSAIC::storeBlock4059(SEMP_PARSE_STATE *parse) uint64_t diskUsage = (diskUsageMSB * 4294967296) + diskUsageLSB; - sdCardSize = diskSizeMB * 1048576; // Convert to bytes + mosaicSdCardSize = diskSizeMB * 1048576; // Convert to bytes - sdFreeSpace = sdCardSize - diskUsage; + mosaicSdFreeSpace = mosaicSdCardSize - diskUsage; + + if (!present.microSd) // Overwrite - if this is the only SD card + { + sdCardSize = mosaicSdCardSize; + sdFreeSpace = mosaicSdFreeSpace; + } _diskStatusSeen = true; } @@ -2712,7 +2797,7 @@ void GNSS_MOSAIC::update() const unsigned long sdCardSizeCheckInterval = 5000; // Matches the interval in logUpdate static unsigned long sdCardLastFreeChange = millis(); // X5 is slow to update free. Seems to be about every ~20s? static uint64_t previousFreeSpace = 0; - if (millis() > (sdCardSizeLastCheck + sdCardSizeCheckInterval)) + if ((millis() - sdCardSizeLastCheck) > sdCardSizeCheckInterval) { updateSD(); // Check if the card has been removed / inserted @@ -2734,7 +2819,7 @@ void GNSS_MOSAIC::update() // The free space has not changed // X5 is slow to update free. Seems to be about every ~20s? // So only set logIncreasing to false after 30s - if (millis() > (sdCardLastFreeChange + 30000)) + if ((millis() - sdCardLastFreeChange) > 30000) logIncreasing = false; } else // if (sdFreeSpace > previousFreeSpace) @@ -2751,12 +2836,12 @@ void GNSS_MOSAIC::update() } sdCardSizeLastCheck = millis(); // Update the timer - _diskStatusSeen = false; // Clear the flag + _diskStatusSeen = false; // Clear the flag } // Update spartnCorrectionsReceived // Does this need if(online.lband_gnss) ? Not sure... TODO - if (millis() > (lastSpartnReception + (settings.correctionsSourcesLifetime_s * 1000))) // Timeout + if ((millis() - lastSpartnReception) > (settings.correctionsSourcesLifetime_s * 1000)) // Timeout { if (spartnCorrectionsReceived) // If corrections were being received { @@ -2794,13 +2879,16 @@ void GNSS_MOSAIC::updateSD() if (!previousCardPresent) retryLimit = 40; - // Set COM4 to: CMD input (only), SBF output (only) - while (!sendWithResponse("sdio,COM4,CMD,SBF\n\r", "DataInOut")) + // Set COM4 to: CMD input (only), SBF output (only) on Facet mosaic + if (productVariant == RTK_FACET_MOSAIC) { - if (retries == retryLimit) - break; - retries++; - sendWithResponse("SSSSSSSSSSSSSSSSSSSS\n\r", "COM4>"); // Send escape sequence + while (!sendWithResponse("sdio,COM4,CMD,SBF\n\r", "DataInOut")) + { + if (retries == retryLimit) + break; + retries++; + sendWithResponse("SSSSSSSSSSSSSSSSSSSS\n\r", "COM4>"); // Send escape sequence + } } if (retries == retryLimit) @@ -2811,8 +2899,10 @@ void GNSS_MOSAIC::updateSD() } //---------------------------------------- -void GNSS_MOSAIC::waitSBFReceiverSetup(unsigned long timeout) +void GNSS_MOSAIC::waitSBFReceiverSetup(HardwareSerial *serialPort, unsigned long timeout) { + // Note: _isBlocking should be set externally - if needed + SEMP_PARSE_ROUTINE const sbfParserTable[] = {sempSbfPreamble}; const int sbfParserCount = sizeof(sbfParserTable) / sizeof(sbfParserTable[0]); const char *const sbfParserNames[] = { @@ -2832,12 +2922,12 @@ void GNSS_MOSAIC::waitSBFReceiverSetup(unsigned long timeout) reportFatalError("Failed to initialize the SBF parser"); unsigned long startTime = millis(); - while ((millis() < (startTime + timeout)) && (_receiverSetupSeen == false)) + while (((millis() - startTime) < timeout) && (_receiverSetupSeen == false)) { - if (serial2GNSS->available()) + if (serialPort->available()) { // Update the parser state based on the incoming byte - sempParseNextByte(sbfParse, serial2GNSS->read()); + sempParseNextByte(sbfParse, serialPort->read()); } } @@ -2850,7 +2940,8 @@ void GNSS_MOSAIC::waitSBFReceiverSetup(unsigned long timeout) bool GNSS_MOSAIC::baudIsAllowed(uint32_t baudRate) { for (int x = 0; x < MAX_MOSAIC_COM_RATES; x++) - if (mosaicComRates[x].rate == baudRate) return (true); + if (mosaicComRates[x].rate == baudRate) + return (true); return (false); } @@ -2864,6 +2955,64 @@ uint32_t GNSS_MOSAIC::baudGetMaximum() return (mosaicComRates[MAX_MOSAIC_COM_RATES - 1].rate); } +//Return true if the receiver is detected +bool GNSS_MOSAIC::isPresent() +{ + if (productVariant != RTK_FLEX) // productVariant == RTK_FACET_MOSAIC + { + // Set COM4 to: CMD input (only), SBF output (only) + // Mosaic could still be starting up, so allow many retries + return isPresentOnSerial(serial2GNSS, "sdio,COM4,CMD,SBF\n\r", "DataInOut", "COM4>", 20); + } + else // productVariant == RTK_FLEX + { + // Set COM1 to: auto input, RTCMv3+SBF+NMEA+Encapsulate output + // Mosaic could still be starting up, so allow many retries + return isPresentOnSerial(serialGNSS, "sdio,COM1,auto,RTCMv3+SBF+NMEA+Encapsulate\n\r", "DataInOut", "COM1>", 20); + } +} + +//Return true if the receiver is detected +bool GNSS_MOSAIC::isPresentOnSerial(HardwareSerial *serialPort, const char *command, const char *response, const char *console, int retryLimit) +{ + // Mosaic could still be starting up, so allow many retries + int retries = 0; + + while (!sendWithResponse(serialPort, command, response)) + { + if (retries == retryLimit) + break; + retries++; + sendWithResponse(serialPort, "SSSSSSSSSSSSSSSSSSSS\n\r", console); // Send escape sequence + } + + if (retries == retryLimit) + { + systemPrintln("Could not communicate with mosaic-X5 at selected baud rate. Attempting a soft reset..."); + + sendWithResponse(serialPort, "erst,soft,none\n\r", "ResetReceiver"); + + retries = 0; + + while (!sendWithResponse(serialPort, command, response)) + { + if (retries == retryLimit) + break; + retries++; + sendWithResponse(serialPort, "SSSSSSSSSSSSSSSSSSSS\n\r", console); // Send escape sequence + } + + if (retries == retryLimit) + { + systemPrintln("Could not communicate with mosaic-X5 at selected baud rate"); + return(false); + } + } + + // Module responded correctly! + return (true); +} + //========================================================================== // Parser support routines //========================================================================== @@ -3076,7 +3225,7 @@ void mosaicX5flushRX(unsigned long timeout) if (timeout > 0) { unsigned long startTime = millis(); - while (millis() < (startTime + timeout)) + while ((millis() - startTime) < timeout) { if (serial2GNSS->available()) { @@ -3100,7 +3249,7 @@ void mosaicX5flushRX(unsigned long timeout) bool mosaicX5waitCR(unsigned long timeout) { unsigned long startTime = millis(); - while (millis() < (startTime + timeout)) + while ((millis() - startTime) < timeout) { if (serial2GNSS->available()) { @@ -3116,3 +3265,52 @@ bool mosaicX5waitCR(unsigned long timeout) */ #endif // COMPILE_MOSAICX5 + +// Test for mosaic on UART1 of the ESP32 on Flex +bool mosaicIsPresentOnFlex() +{ + // Locally instantiate the hardware and library so it will release on exit + HardwareSerial serialTestGNSS(2); + GNSS_MOSAIC mosaic; + + // Check with 115200 initially. If that succeeds, increase to 460800 + serialTestGNSS.begin(115200, SERIAL_8N1, pin_GnssUart_RX, pin_GnssUart_TX); + + // Only try 3 times. LG290P detection will have been done first. X5 should have booted. Baud rate could be wrong. + if (mosaic.isPresentOnSerial(&serialTestGNSS, "sdio,COM1,auto,RTCMv3+SBF+NMEA+Encapsulate\n\r", "DataInOut", "COM1>", 3) == true) + { + if (settings.debugGnss) + systemPrintln("mosaic-X5 detected at 115200 baud"); + } + else + { + if (settings.debugGnss) + systemPrintln("mosaic-X5 not detected at 115200 baud. Trying 460800"); + } + + // Now increase the baud rate to 460800 + // The baud rate change is immediate. The response is returned at the new baud rate + serialTestGNSS.write("scs,COM1,baud460800,bits8,No,bit1,none\n\r"); + + delay(1000); + serialTestGNSS.end(); + serialTestGNSS.begin(460800, SERIAL_8N1, pin_GnssUart_RX, pin_GnssUart_TX); + + // Only try 3 times, so we fail and pass on to the next Facet GNSS detection + if (mosaic.isPresentOnSerial(&serialTestGNSS, "sdio,COM1,auto,RTCMv3+SBF+NMEA+Encapsulate\n\r", "DataInOut", "COM1>", 3) == true) + { + // serialGNSS and serial2GNSS have not yet been begun. We need to saveConfiguration manually + unsigned long start = millis(); + bool result = mosaic.sendWithResponse(&serialTestGNSS, "eccf,Current,Boot\n\r", "CopyConfigFile", 5000); + if (settings.debugGnss) + systemPrintf("saveConfiguration: sendWithResponse returned %s after %d ms\r\n", result ? "true" : "false", + millis() - start); + if (settings.debugGnss) + systemPrintf("mosaic-X5 baud rate %supdated\r\n", result ? "" : "NOT "); + serialTestGNSS.end(); + return result; + } + + serialTestGNSS.end(); + return false; +} \ No newline at end of file diff --git a/Firmware/RTK_Everywhere/GNSS_None.h b/Firmware/RTK_Everywhere/GNSS_None.h index 8afb402b1..879804b6e 100644 --- a/Firmware/RTK_Everywhere/GNSS_None.h +++ b/Firmware/RTK_Everywhere/GNSS_None.h @@ -9,7 +9,7 @@ GNSS_None.h class GNSS_None : public GNSS { - protected: +protected: // Setup the general configuration of the GNSS // Not Rover or Base specific (ie, baud rates) // Outputs: @@ -25,7 +25,7 @@ class GNSS_None : public GNSS return false; } - public: +public: // Constructor GNSS_None() : GNSS() { @@ -48,13 +48,16 @@ class GNSS_None : public GNSS } // Check if a given baud rate is supported by this module - bool baudIsAllowed(uint32_t baudRate) { + bool baudIsAllowed(uint32_t baudRate) + { return false; } - uint32_t baudGetMinimum() { + uint32_t baudGetMinimum() + { return 0; } - uint32_t baudGetMaximum() { + uint32_t baudGetMaximum() + { return 0; } @@ -118,7 +121,6 @@ class GNSS_None : public GNSS // Returns message names in the returnText string void createMessageList(String &returnText) { - } // Responds with the RTCM/Base messages supported on this platform @@ -127,7 +129,6 @@ class GNSS_None : public GNSS // Returns message names in the returnText string void createMessageListBase(String &returnText) { - } // Responds with the messages supported on this platform @@ -510,7 +511,7 @@ class GNSS_None : public GNSS { } - // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver + // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver void rtcmOnGnssEnable() { } @@ -528,14 +529,9 @@ class GNSS_None : public GNSS return false; } - // Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS - // This just sets the GNSS side - // Used during Bluetooth testing - // Inputs: - // baudRate: The desired baudrate - bool setBaudrate(uint32_t baudRate) + bool setBaudRate(uint8_t uartNumber, uint32_t baudRate) { - return true; + return false; } // Enable all the valid constellations and bands for this platform diff --git a/Firmware/RTK_Everywhere/GNSS_UM980.h b/Firmware/RTK_Everywhere/GNSS_UM980.h index 4ad8bb408..588f228c1 100644 --- a/Firmware/RTK_Everywhere/GNSS_UM980.h +++ b/Firmware/RTK_Everywhere/GNSS_UM980.h @@ -143,6 +143,8 @@ class GNSS_UM980 : GNSS // Controls the messages that get broadcast over Bluetooth and logged (if enabled) void menuMessagesSubtype(float *localMessageRate, const char *messageType); + bool setBaudRate(uint8_t uartNumber, uint32_t baudRate); // From the super class + // Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS // Inputs: // baudRate: The desired baudrate @@ -421,7 +423,7 @@ class GNSS_UM980 : GNSS // If LBand is being used, ignore any RTCM that may come in from the GNSS void rtcmOnGnssDisable(); - // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver + // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver void rtcmOnGnssEnable(); uint16_t rtcmRead(uint8_t *rtcmBuffer, int rtcmBytesToRead); @@ -431,13 +433,6 @@ class GNSS_UM980 : GNSS // Returns true when the configuration was saved and false upon failure bool saveConfiguration(); - // Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS - // This just sets the GNSS side - // Used during Bluetooth testing - // Inputs: - // baudRate: The desired baudrate - bool setBaudrate(uint32_t baudRate); - // Enable all the valid constellations and bands for this platform bool setConstellations(); @@ -465,6 +460,18 @@ class GNSS_UM980 : GNSS // modelNumber: Number of the model to use, provided by radio library bool setModel(uint8_t modelNumber); + // Set all NMEA message report rates to one value + void setNmeaMessageRates(uint8_t msgRate); + + // Given the name of a message, find it, and set the rate + bool setNmeaMessageRateByName(const char *msgName, uint8_t msgRate); + + // Set all RTCM Rover message report rates to one value + void setRtcmRoverMessageRates(uint8_t msgRate); + + // Given the name of a message, find it, and set the rate + bool setRtcmRoverMessageRateByName(const char *msgName, uint8_t msgRate); + bool setRadioBaudRate(uint32_t baud); // Specify the interval between solutions diff --git a/Firmware/RTK_Everywhere/GNSS_UM980.ino b/Firmware/RTK_Everywhere/GNSS_UM980.ino index f8717452d..9a67c9757 100644 --- a/Firmware/RTK_Everywhere/GNSS_UM980.ino +++ b/Firmware/RTK_Everywhere/GNSS_UM980.ino @@ -69,10 +69,6 @@ void GNSS_UM980::begin() // Instantiate the library _um980 = new UM980(); - // Turn on/off debug messages - if (settings.debugGnss) - debuggingEnable(); - // In order to reduce UM980 configuration time, the UM980 library blocks the start of BESTNAV and RECTIME until 3D // fix is achieved However, if all NMEA messages are disabled, the UM980 will never detect a 3D fix. if (isGgaActive()) @@ -86,19 +82,25 @@ void GNSS_UM980::begin() if (_um980->begin(*serialGNSS) == false) // Give the serial port over to the library { if (settings.debugGnss) - systemPrintln("GNSS Failed to begin. Trying again."); + systemPrintln("GNSS UM980 failed to begin. Trying again."); // Try again with power on delay delay(1000); if (_um980->begin(*serialGNSS) == false) { - systemPrintln("GNSS offline"); + systemPrintln("GNSS UM980 offline"); displayGNSSFail(1000); return; } } + + online.gnss = true; + systemPrintln("GNSS UM980 online"); + if (settings.debugGnss) + debuggingEnable(); // Print all debug to Serial + // Check firmware version and print info printModuleInfo(); @@ -119,8 +121,6 @@ void GNSS_UM980::begin() gnssFirmwareVersionInt = 99; snprintf(gnssUniqueId, sizeof(gnssUniqueId), "%s", _um980->getID()); - - online.gnss = true; } //---------------------------------------- @@ -252,8 +252,8 @@ bool GNSS_UM980::configureOnce() response &= _um980->setPortBaudrate("COM2", 115200); // COM2 is connected to the IMU response &= _um980->setPortBaudrate("COM3", 115200); // COM3 is connected to the switch, then ESP32 - // For now, let's not change the baud rate of the interface. We'll be using the default 115200 for now. - response &= setBaudRateCOM3(settings.dataPortBaud); // COM3 is connected to ESP UART2 + // // For now, let's not change the baud rate of the interface. We'll be using the default 115200 for now. + // response &= setBaudRateCOM3(settings.dataPortBaud); // COM3 is connected to ESP UART2 // Enable PPS signal with a width of 200ms, and a period of 1 second response &= _um980->enablePPS(200000, 1000); // widthMicroseconds, periodMilliseconds @@ -324,9 +324,9 @@ bool GNSS_UM980::configureGNSS() // If we fail, reset UM980 systemPrintln("Resetting UM980 to complete configuration"); - um980Reset(); + gnssReset(); delay(500); - um980Boot(); + gnssBoot(); delay(500); } @@ -475,8 +475,10 @@ void GNSS_UM980::disableAllOutput() response &= _um980->disableOutputPort("COM2"); response &= _um980->disableOutputPort("COM3"); if (response) - break; + return; } + + systemPrintln("UM980 failed to disable output"); } //---------------------------------------- @@ -519,7 +521,7 @@ bool GNSS_UM980::enableNMEA() // If we are using IP based corrections, we need to send local data to the PPL // The PPL requires being fed GPGGA/ZDA, and RTCM1019/1020/1042/1046 - if (pointPerfectIsEnabled()) + if (pointPerfectServiceUsesKeys()) { // Mark PPL required messages as enabled if rate > 0 if (settings.um980MessageRatesNMEA[messageNumber] > 0) @@ -533,7 +535,7 @@ bool GNSS_UM980::enableNMEA() } } - if (pointPerfectIsEnabled()) + if (pointPerfectServiceUsesKeys()) { // Force on any messages that are needed for PPL if (gpggaEnabled == false) @@ -599,7 +601,7 @@ bool GNSS_UM980::enableRTCMRover() // If we are using IP based corrections, we need to send local data to the PPL // The PPL requires being fed GPGGA/ZDA, and RTCM1019/1020/1042/1046 - if (pointPerfectIsEnabled()) + if (pointPerfectServiceUsesKeys()) { // Mark PPL required messages as enabled if rate > 0 if (settings.um980MessageRatesRTCMRover[messageNumber] > 0) @@ -617,7 +619,7 @@ bool GNSS_UM980::enableRTCMRover() } } - if (pointPerfectIsEnabled()) + if (pointPerfectServiceUsesKeys()) { // Force on any messages that are needed for PPL if (rtcm1019Enabled == false) @@ -1331,6 +1333,8 @@ void GNSS_UM980::menuMessages() systemPrintln("3) Set Base RTCM Messages"); systemPrintln("10) Reset to Defaults"); + systemPrintln("11) Reset to PPP Logging (NMEAx5 / RTCMx4 - 30 second decimation)"); + systemPrintln("12) Reset to High-rate PPP Logging (NMEAx5 / RTCMx4 - 1Hz)"); systemPrintln("x) Exit"); @@ -1358,6 +1362,40 @@ void GNSS_UM980::menuMessages() systemPrintln("Reset to Defaults"); } + else if (incoming == 11 || incoming == 12) + { + // setMessageRate() on the UM980 sets the seconds between reported messages + // 1, 0.5, 0.2, 0.1 corresponds to 1Hz, 2Hz, 5Hz, 10Hz respectively. + // Ex: RTCM1005 0.5 <- 2 times per second + + int reportRate = 30; // Default to 30 seconds between reports + if (incoming == 12) + reportRate = 1; + + // Reset NMEA rates to defaults + for (int x = 0; x < MAX_UM980_NMEA_MSG; x++) + settings.um980MessageRatesNMEA[x] = umMessagesNMEA[x].msgDefaultRate; + setNmeaMessageRateByName("GPGSV", 5); // Limit GSV updates to 1 every 5 seconds + + setRtcmRoverMessageRates(0); // Turn off all RTCM messages + setRtcmRoverMessageRateByName("RTCM1019", reportRate); + // setRtcmRoverMessageRateByName("RTCM1020", reportRate); //Not needed when MSM7 is used + // setRtcmRoverMessageRateByName("RTCM1042", reportRate); //BeiDou not used by CSRS-PPP + // setRtcmRoverMessageRateByName("RTCM1046", reportRate); //Not needed when MSM7 is used + setRtcmRoverMessageRateByName("RTCM1077", reportRate); + setRtcmRoverMessageRateByName("RTCM1087", reportRate); + setRtcmRoverMessageRateByName("RTCM1097", reportRate); + // setRtcmRoverMessageRateByName("RTCM1124", reportRate); //BeiDou not used by CSRS-PPP + + if (incoming == 12) + { + systemPrintln("Reset to High-rate PPP Logging (NMEAx5 / RTCMx4 - 1Hz)"); + } + else + { + systemPrintln("Reset to PPP Logging (NMEAx5 / RTCMx4 - 30 second decimation)"); + } + } else if (incoming == INPUT_RESPONSE_GETNUMBER_EXIT) break; @@ -1534,7 +1572,7 @@ void GNSS_UM980::rtcmOnGnssDisable() } //---------------------------------------- -// If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver +// If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver //---------------------------------------- void GNSS_UM980::rtcmOnGnssEnable() { @@ -1560,16 +1598,17 @@ bool GNSS_UM980::saveConfiguration() } //---------------------------------------- -// Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS -// This just sets the GNSS side -// Used during Bluetooth testing +// Set the baud rate on the designated port - from the super class //---------------------------------------- -bool GNSS_UM980::setBaudrate(uint32_t baudRate) +bool GNSS_UM980::setBaudRate(uint8_t uartNumber, uint32_t baudRate) { - if (online.gnss) - // Set the baud rate on COM3 of the UM980 - return setBaudRateCOM3(baudRate); - return false; + if (uartNumber != 3) + { + systemPrintln("setBaudRate error: out of range"); + return (false); + } + + return setBaudRateCOM3(baudRate); } //---------------------------------------- @@ -1649,10 +1688,10 @@ bool GNSS_UM980::setHighAccuracyService(bool enableGalileoHas) if (_um980->isConfigurationPresent("CONFIG PPP ENABLE E6-HAS") == false) { if (_um980->sendCommand("CONFIG PPP ENABLE E6-HAS")) - systemPrintln("Galileo E6 service enabled"); + systemPrintln("Galileo E6 HAS service enabled"); else { - systemPrintln("Galileo E6 service failed to enable"); + systemPrintln("Galileo E6 HAS service failed to enable"); result = false; } @@ -1680,10 +1719,10 @@ bool GNSS_UM980::setHighAccuracyService(bool enableGalileoHas) if (_um980->isConfigurationPresent("CONFIG PPP ENABLE E6-HAS")) { if (_um980->sendCommand("CONFIG PPP DISABLE")) - systemPrintln("Galileo E6 service disabled"); + systemPrintln("Galileo E6 HAS service disabled"); else { - systemPrintln("Galileo E6 service failed to disable"); + systemPrintln("Galileo E6 HAS service failed to disable"); result = false; } } @@ -1927,7 +1966,6 @@ uint32_t GNSS_UM980::baudGetMaximum() return (um980AllowedRates[um980AllowedRatesCount - 1]); } - //---------------------------------------- // If we have received serial data from the UM980 outside of the Unicore library (ie, from processUart1Message task) // we can pass data back into the Unicore library to allow it to update its own variables @@ -1955,39 +1993,61 @@ void GNSS_UM980::update() // We don't check serial data here; the gnssReadTask takes care of serial consumption } -#endif // COMPILE_UM980 +// Set all NMEA message report rates to one value +void GNSS_UM980::setNmeaMessageRates(uint8_t msgRate) +{ + for (int x = 0; x < MAX_UM980_NMEA_MSG; x++) + settings.um980MessageRatesNMEA[x] = msgRate; +} -//---------------------------------------- -void um980Boot() +// Set all RTCM Rover message report rates to one value +void GNSS_UM980::setRtcmRoverMessageRates(uint8_t msgRate) { - digitalWrite(pin_GNSS_DR_Reset, HIGH); // Tell UM980 and DR to boot + for (int x = 0; x < MAX_UM980_RTCM_MSG; x++) + settings.um980MessageRatesRTCMRover[x] = msgRate; } -//---------------------------------------- -// Force UART connection to UM980 for firmware update on the next boot by creating updateUm980Firmware.txt in -// LittleFS -//---------------------------------------- -bool createUm980Passthrough() +// Given the name of a message, find it, and set the rate +bool GNSS_UM980::setNmeaMessageRateByName(const char *msgName, uint8_t msgRate) { - if (online.fs == false) - return false; + for (int x = 0; x < MAX_UM980_NMEA_MSG; x++) + { + if (strcmp(umMessagesNMEA[x].msgTextName, msgName) == 0) + { + settings.um980MessageRatesNMEA[x] = msgRate; + return (true); + } + } + systemPrintf("setNmeaMessageRateByName: %s not found\r\n", msgName); + return (false); +} - if (LittleFS.exists("/updateUm980Firmware.txt")) +// Given the name of a message, find it, and set the rate +bool GNSS_UM980::setRtcmRoverMessageRateByName(const char *msgName, uint8_t msgRate) +{ + for (int x = 0; x < MAX_UM980_RTCM_MSG; x++) { - if (settings.debugGnss) - systemPrintln("LittleFS updateUm980Firmware.txt already exists"); - return true; + if (strcmp(umMessagesRTCM[x].msgTextName, msgName) == 0) + { + settings.um980MessageRatesRTCMRover[x] = msgRate; + return (true); + } } + systemPrintf("setRtcmRoverMessageRateByName: %s not found\r\n", msgName); + return (false); +} - File updateUm980Firmware = LittleFS.open("/updateUm980Firmware.txt", FILE_WRITE); - updateUm980Firmware.close(); +#endif // COMPILE_UM980 - if (LittleFS.exists("/updateUm980Firmware.txt")) - return true; +//---------------------------------------- - if (settings.debugGnss) - systemPrintln("Unable to create updateUm980Firmware.txt on LittleFS"); - return false; +//---------------------------------------- +// Force UART connection to GNSS for firmware update on the next boot by special file in +// LittleFS +//---------------------------------------- +bool createUm980Passthrough() +{ + return createPassthrough("/updateUm980Firmware.txt"); } //---------------------------------------- @@ -2000,22 +2060,42 @@ void um980FirmwareBeginUpdate() // then reconfigures the UM980 to 115200bps, then resets, but autobaud detection in the UM980 library is // not yet supported. - // Stop all UART tasks + // Note: UM980 needs its own dedicated update function, due to the T@ and bootloader trigger + + // Note: UM980 is cuurrently only available on Torch. + // But um980FirmwareBeginUpdate has been reworked so it will work on Facet too. + + // Note: um980FirmwareBeginUpdate is called during setup, after identify board. I2C, gpio expanders, buttons + // and display have all been initialized. But, importantly, the UARTs have not yet been started. + // This makes our job much easier... + + // Flag that we are in direct connect mode. Button task will um980FirmwareRemoveUpdate and exit + inDirectConnectMode = true; + + // Paint GNSS Update + paintGnssUpdate(); + + // Stop all UART tasks. Redundant tasksStopGnssUart(); systemPrintln(); - systemPrintln("Entering UM980 direct connect for firmware update and configuration. Disconnect this terminal " - "connection. Use " - "UPrecise to update the firmware. Baudrate: 115200bps. Press the power button to return " - "to normal operation."); + systemPrintf("Entering UM980 direct connect for firmware update and configuration. Disconnect this terminal " + "connection. Use " + "UPrecise to update the firmware. Baudrate: 115200bps. Press the %s button to return " + "to normal operation.\r\n", + present.button_mode ? "mode" : "power"); systemFlush(); - // Make sure ESP-UART1 is connected to UM980 + // Make sure ESP-UART is connected to UM980 muxSelectUm980(); if (serialGNSS == nullptr) serialGNSS = new HardwareSerial(2); // Use UART2 on the ESP32 for communication with the GNSS module + serialGNSS->setRxBufferSize(settings.uartReceiveBufferSize); + serialGNSS->setTimeout(settings.serialTimeoutGNSS); // Requires serial traffic on the UART pins for detection + + // This is OK for Flex too. We're using the main GNSS pins. serialGNSS->begin(115200, SERIAL_8N1, pin_GnssUart_RX, pin_GnssUart_TX); // UPrecise needs to query the device before entering bootload mode @@ -2023,14 +2103,15 @@ void um980FirmwareBeginUpdate() bool inBootMode = false; // Echo everything to/from UM980 - while (1) + task.endDirectConnectMode = false; + while (!task.endDirectConnectMode) { // Data coming from UM980 to external USB - if (serialGNSS->available()) + if (serialGNSS->available()) // Note: use if, not while Serial.write(serialGNSS->read()); // Data coming from external USB to UM980 - if (Serial.available()) + if (Serial.available()) // Note: use if, not while { byte incoming = Serial.read(); serialGNSS->write(incoming); @@ -2042,80 +2123,40 @@ void um980FirmwareBeginUpdate() if (nextIncoming == '@') { // Reset UM980 - um980Reset(); + gnssReset(); delay(25); - um980Boot(); + gnssBoot(); inBootMode = true; } } } - if (readAnalogPinAsDigital(pin_powerButton) == HIGH) - { - while (readAnalogPinAsDigital(pin_powerButton) == HIGH) - delay(100); - - // Remove file and reset to exit pass-through mode - um980FirmwareRemoveUpdate(); - - // Beep to indicate exit - beepOn(); - delay(300); - beepOff(); - delay(100); - beepOn(); - delay(300); - beepOff(); - - systemPrintln("Exiting UM980 passthrough mode"); - systemFlush(); // Complete prints - - ESP.restart(); - } + // Button task will set task.endDirectConnectMode true } + // Remove the special file. See #763 . Do the file removal in the loop + um980FirmwareRemoveUpdate(); + systemFlush(); // Complete prints + + ESP.restart(); } //---------------------------------------- -// Check if updateUm980Firmware.txt exists +// Check if direct connection file exists //---------------------------------------- bool um980FirmwareCheckUpdate() { - if (online.fs == false) - return false; - - if (LittleFS.exists("/updateUm980Firmware.txt")) - { - if (settings.debugGnss) - systemPrintln("LittleFS updateUm980Firmware.txt exists"); - - // We do not remove the file here. See removeupdateUm980Firmware(). - - return true; - } - - return false; + return gnssFirmwareCheckUpdateFile("/updateUm980Firmware.txt"); } +//---------------------------------------- +// Remove direct connection file //---------------------------------------- void um980FirmwareRemoveUpdate() { - if (online.fs == false) - return; - - if (LittleFS.exists("/updateUm980Firmware.txt")) - { - if (settings.debugGnss) - systemPrintln("Removing updateUm980Firmware.txt "); - - LittleFS.remove("/updateUm980Firmware.txt"); - } + gnssFirmwareRemoveUpdateFile("/updateUm980Firmware.txt"); } //---------------------------------------- -void um980Reset() -{ - digitalWrite(pin_GNSS_DR_Reset, LOW); // Tell UM980 and DR to reset -} diff --git a/Firmware/RTK_Everywhere/GNSS_ZED.h b/Firmware/RTK_Everywhere/GNSS_ZED.h index 20f2cc443..5da4d942f 100644 --- a/Firmware/RTK_Everywhere/GNSS_ZED.h +++ b/Firmware/RTK_Everywhere/GNSS_ZED.h @@ -526,6 +526,8 @@ class GNSS_ZED : GNSS // Given the name of a message, return the array number uint8_t getMessageNumberByName(const char *msgName); + uint8_t getMessageNumberByNameSkipChecks(const char *msgName); + uint8_t getMessageNumberByName(const char *msgName, bool skipPlatformChecks); // Given the name of a message, find it, and return the rate uint8_t getMessageRateByName(const char *msgName); @@ -662,7 +664,7 @@ class GNSS_ZED : GNSS uint16_t rtcmBufferAvailable(); - // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver + // If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver void rtcmOnGnssDisable(); // If LBand is being used, ignore any RTCM that may come in from the GNSS @@ -675,12 +677,8 @@ class GNSS_ZED : GNSS // Returns true when the configuration was saved and false upon failure bool saveConfiguration(); - // Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS - // This just sets the GNSS side - // Used during Bluetooth testing - // Inputs: - // baudRate: The desired baudrate - bool setBaudrate(uint32_t baudRate); + // Set the baud rate on the designated port + bool setBaudRate(uint8_t uartNumber, uint32_t baudRate); // From the super class // Enable all the valid constellations and bands for this platform bool setConstellations(); diff --git a/Firmware/RTK_Everywhere/GNSS_ZED.ino b/Firmware/RTK_Everywhere/GNSS_ZED.ino index 4f1533373..089d6b377 100644 --- a/Firmware/RTK_Everywhere/GNSS_ZED.ino +++ b/Firmware/RTK_Everywhere/GNSS_ZED.ino @@ -137,7 +137,7 @@ void GNSS_ZED::begin() if (_zed->begin(*i2c_0) == false) { - systemPrintln("GNSS Failed to begin. Trying again."); + systemPrintln("GNSS ZED failed to begin. Trying again."); // Try again with power on delay delay(1000); // Wait for ZED-F9P to power up before it can respond to ACK @@ -406,7 +406,9 @@ bool GNSS_ZED::configureBase() settings.ubxMessageRatesBase[x]); // UBLOX_CFG UART1 + 2 = USB } - response &= _zed->addCfgValset(UBLOX_CFG_NAVSPG_INFIL_MINELEV, settings.minElev); // Set minimum elevation + // Set minimum elevation + // Note: ZED supports negative elevations, but our firmware only allows 0-90 + response &= _zed->addCfgValset(UBLOX_CFG_NAVSPG_INFIL_MINELEV, settings.minElev); response &= _zed->sendCfgValset(); // Closing value @@ -542,10 +544,6 @@ bool GNSS_ZED::configureGNSS() _zed->setAutoPVTcallbackPtr(&storePVTdata, VAL_LAYER_ALL); // Enable automatic NAV PVT messages with callback to storePVTdata response &= _zed->setAutoHPPOSLLHcallbackPtr( &storeHPdata, VAL_LAYER_ALL); // Enable automatic NAV HPPOSLLH messages with callback to storeHPdata - _zed->setRTCM1005InputcallbackPtr( - &storeRTCM1005data); // Configure a callback for RTCM 1005 - parsed from pushRawData - _zed->setRTCM1006InputcallbackPtr( - &storeRTCM1006data); // Configure a callback for RTCM 1006 - parsed from pushRawData if (present.timePulseInterrupt) response &= _zed->setAutoTIMTPcallbackPtr( @@ -1232,7 +1230,15 @@ double GNSS_ZED::getLongitude() //---------------------------------------- uint8_t GNSS_ZED::getMessageNumberByName(const char *msgName) { - if (present.gnss_zedf9p) + return getMessageNumberByName(msgName, false); +} +uint8_t GNSS_ZED::getMessageNumberByNameSkipChecks(const char *msgName) +{ + return getMessageNumberByName(msgName, true); +} +uint8_t GNSS_ZED::getMessageNumberByName(const char *msgName, bool skipPlatformChecks) +{ + if (skipPlatformChecks || present.gnss_zedf9p) { for (int x = 0; x < MAX_UBX_MSG; x++) { @@ -1379,7 +1385,7 @@ float GNSS_ZED::getSurveyInMeanAccuracy() // Use a local static so we don't have to request these values multiple times (ZED takes many ms to respond // to this command) - if (millis() - lastCheck > 1000) + if ((millis() - lastCheck) > 1000) { lastCheck = millis(); svinMeanAccuracy = _zed->getSurveyInMeanAccuracy(50); @@ -1400,7 +1406,7 @@ int GNSS_ZED::getSurveyInObservationTime() // Use a local static so we don't have to request these values multiple times (ZED takes many ms to respond // to this command) - if (millis() - lastCheck > 1000) + if ((millis() - lastCheck) > 1000) { lastCheck = millis(); svinObservationTime = _zed->getSurveyInObservationTime(50); @@ -1995,7 +2001,7 @@ void GNSS_ZED::rtcmOnGnssDisable() } //---------------------------------------- -// If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-Now) to GNSS receiver +// If L-Band is available, but encrypted, allow RTCM through other sources (radio, ESP-NOW) to GNSS receiver //---------------------------------------- void GNSS_ZED::rtcmOnGnssEnable() { @@ -2011,6 +2017,28 @@ uint16_t GNSS_ZED::rtcmRead(uint8_t *rtcmBuffer, int rtcmBytesToRead) return (0); } +//---------------------------------------- +// Set the baud rate of mosaic-X5 COMn - from the super class +// Inputs: +// port: COM port number +// baudRate: New baud rate for the COM port +// Outputs: +// Returns true if the baud rate was set and false upon failure +//---------------------------------------- +bool GNSS_ZED::setBaudRate(uint8_t port, uint32_t baudRate) +{ + if (port < 1 || port > 2) + { + systemPrintln("setBaudRate error: out of range"); + return (false); + } + + if (port == 1) + return setDataBaudRate(baudRate); + else + return setRadioBaudRate(baudRate); +} + //---------------------------------------- // Save the current configuration // Returns true when the configuration was saved and false upon failure @@ -2024,19 +2052,6 @@ bool GNSS_ZED::saveConfiguration() return true; } -//---------------------------------------- -// Set the baud rate on the GNSS port that interfaces between the ESP32 and the GNSS -// This just sets the GNSS side -// Used during Bluetooth testing -//---------------------------------------- -bool GNSS_ZED::setBaudrate(uint32_t baudRate) -{ - if (online.gnss) - return _zed->setVal32(UBLOX_CFG_UART1_BAUDRATE, - (115200 * 2), VAL_LAYER_ALL); // Defaults to 230400 to maximize message output support - return false; -} - //---------------------------------------- // Enable all the valid constellations and bands for this platform // Band support varies between platforms and firmware versions @@ -2598,30 +2613,6 @@ void GNSS_ZED::storeMONCOMMSdataRadio(UBX_MON_COMMS_data_t *ubxDataStruct) } } -//---------------------------------------- -// Callback to save ARPECEF* -//---------------------------------------- -void storeRTCM1005data(RTCM_1005_data_t *rtcmData1005) -{ - ARPECEFX = rtcmData1005->AntennaReferencePointECEFX; - ARPECEFY = rtcmData1005->AntennaReferencePointECEFY; - ARPECEFZ = rtcmData1005->AntennaReferencePointECEFZ; - ARPECEFH = 0; - newARPAvailable = true; -} - -//---------------------------------------- -// Callback to save ARPECEF* -//---------------------------------------- -void storeRTCM1006data(RTCM_1006_data_t *rtcmData1006) -{ - ARPECEFX = rtcmData1006->AntennaReferencePointECEFX; - ARPECEFY = rtcmData1006->AntennaReferencePointECEFY; - ARPECEFZ = rtcmData1006->AntennaReferencePointECEFZ; - ARPECEFH = rtcmData1006->AntennaHeight; - newARPAvailable = true; -} - //---------------------------------------- void storeTIMTPdata(UBX_TIM_TP_data_t *ubxDataStruct) { @@ -2687,7 +2678,7 @@ bool GNSS_ZED::surveyInReset() while (_zed->getSurveyInActive(100) || _zed->getSurveyInValid(100)) { delay(100); - if (millis() - startTime > maxTime) + if ((millis() - startTime) > maxTime) return (false); // Reset of survey failed } @@ -2751,7 +2742,7 @@ bool GNSS_ZED::surveyInStart() while (_zed->getSurveyInActive(100) == false) { delay(100); - if (millis() - startTime > maxTime) + if ((millis() - startTime) > maxTime) return (false); // Reset of survey failed } @@ -2994,7 +2985,7 @@ void inputMessageRate(uint8_t &localMessageRate, uint8_t messageNumber) if (rate == INPUT_RESPONSE_GETNUMBER_TIMEOUT || rate == INPUT_RESPONSE_GETNUMBER_EXIT) return; - while (rate < 0 || rate > 255) // 8 bit limit + while (rate < 0 || rate > 250) // 8 bit limit. Avoid 254! { systemPrintln("Error: Message rate out of range"); systemPrintf("Enter %s message rate (0 to disable): ", ubxMessages[messageNumber].msgTextName); diff --git a/Firmware/RTK_Everywhere/HTTP_Client.ino b/Firmware/RTK_Everywhere/HTTP_Client.ino index 55194e4d9..03bb8a7b5 100644 --- a/Firmware/RTK_Everywhere/HTTP_Client.ino +++ b/Firmware/RTK_Everywhere/HTTP_Client.ino @@ -11,7 +11,7 @@ HTTP_Client.ino ------------------------------------------------------------------------------*/ ZtpResponse ztpResponse = - ZTP_NOT_STARTED; // Used in menuPP. This is the overall result of the ZTP process of testing multiple tokens + ZTP_NOT_STARTED; // Used in menuPointPerfect(). This is the overall result of the ZTP process of testing multiple tokens #ifdef COMPILE_HTTP_CLIENT @@ -372,6 +372,17 @@ void httpClientUpdate() if (!httpSecureClient->connect(THINGSTREAM_SERVER, HTTPS_PORT)) { // Failed to connect to the server + int length = 1024; + char * errMessage = (char *)rtkMalloc(length, "HTTP error message"); + if (errMessage) + { + memset(errMessage, 0, length); + httpSecureClient->lastError(errMessage, length - 1); + systemPrintf("Get %s failed, %s\r\n", THINGSTREAM_SERVER, errMessage); + rtkFree(errMessage, "HTTP error message"); + } + else + systemPrintf("Get %s failed!\r\n", THINGSTREAM_SERVER); systemPrintln("ERROR: Failed to connect to the Thingstream server!"); httpClientRestart(); // I _think_ we want to restart here - i.e. retry after the timeout? break; @@ -682,7 +693,7 @@ void httpClientUpdate() } // Periodically display the HTTP client state - if (PERIODIC_DISPLAY(PD_HTTP_CLIENT_STATE)) + if (PERIODIC_DISPLAY(PD_HTTP_CLIENT_STATE) && !inMainMenu) { const char *line = ""; httpClientEnabled(&line); diff --git a/Firmware/RTK_Everywhere/LoRa.ino b/Firmware/RTK_Everywhere/LoRa.ino index 7901fc3a7..63bc0d6cc 100644 --- a/Firmware/RTK_Everywhere/LoRa.ino +++ b/Firmware/RTK_Everywhere/LoRa.ino @@ -1,35 +1,46 @@ /*------------------------------------------------------------------------------ LoRa.ino - This module implements the interface to the LoRa radio in the Torch. + This module implements the interface to the LoRa radio in the Torch and Flex. - ESP32 (UART1) <-> Switch U12 B0 <-> UM980 (UART3) - ESP32 (UART1) <-> Switch U12 B1 <-> STM32 LoRa(UART0) + Torch: + ESP32 (UART1) <-> Switch U12 B0 <-> UM980 (UART3) + ESP32 (UART1) <-> Switch U12 B1 <-> STM32 LoRa(UART0) - UART0 on the STM32 is used for debug messages and bootloading new firmware. + UART0 on the STM32 is used for debug messages and bootloading new firmware. - ESP32 (UART0) <-> Switch U18 B0 <-> USB to Serial - ESP32 (UART0) <-> Switch U18 B1 <-> Switch U11 + ESP32 (UART0) <-> Switch U18 B0 <-> USB to Serial + ESP32 (UART0) <-> Switch U18 B1 <-> Switch U11 - Switch U11 B0 <-> STM32 LoRa(UART2) - Switch U11 B1 <-> UM980 (UART1) - Not generally used + Switch U11 B0 <-> STM32 LoRa(UART2) + Switch U11 B1 <-> UM980 (UART1) - Not generally used - UART2 on the STM32 is used for configuration and pushing data across the link. - This poses a bit of a problem: we have to disconnect from USB serial (no prints) - while configuration or data is being passed. + UART2 on the STM32 is used for configuration and pushing data across the link. + This poses a bit of a problem: we have to disconnect from USB serial (no prints) + while configuration or data is being passed. - If we are in Base mode, listen from RTCM. Once received, disconnect from USB, send to - LoRa radio, then re-connect to USB. + If we are in Base mode, listen from RTCM. Once received, disconnect from USB, send to + LoRa radio, then re-connect to USB. - If we are in Rover mode, and LoRa is enabled, then we are connected permanently to the LoRa - radio to listen for incoming serial data. If no USB cable is attached, immediately - go into dedicated listening mode. If a USB cable is detected, then the dedicated listening mode is exited - for X seconds before re-entering the dedicated listening mode. Any serial traffic from USB during this time - resets the timeout. + If we are in Rover mode, and LoRa is enabled, then we are connected permanently to the LoRa + radio to listen for incoming serial data. If no USB cable is attached, immediately + go into dedicated listening mode. If a USB cable is detected, then the dedicated listening mode is exited + for X seconds before re-entering the dedicated listening mode. Any serial traffic from USB during this time + resets the timeout. + + Flex: + Flex GNSS (UART2) <-> Switch 4 B0 <-> 4-Pin Serial TTL on 1mm JST under microSD + Flex GNSS (UART2) <-> Switch 4 B1 <-> STM32 LoRa (UART0) + + ESP32 (UART2) <-> Switch 3 B0 <-> Flex GNSS Tilt (UART3) + ESP32 (UART2) <-> Switch 3 B1 <-> STM32 LoRa (UART2) + + UART0 on the STM32 is used for pushing data across the link. + UART2 on the STM32 is used for configuration. Printing: - Use systemPrint() to output serial to the USB serial interface - Use Serial.print() along with to output + On Torch, Serial must be used to send and receive data from the radio. At times, this requires disconnecting from the USB interface. + On Flex, SerialForLoRa is used on UART2 to configure and TX/RX data from the radio. If active, SerialForTilt must be ended first. Updating the STM32 LoRa Firmware: Bootloading the STM32 requires a connection to the USB serial. Because it is @@ -65,6 +76,8 @@ static volatile uint8_t loraState = LORA_OFF; char loraFirmwareVersion[25] = {'\0'}; int loraBytesSent = 0; +HardwareSerial *SerialForLoRa; // Don't instantiate until we know the platform. May compete with SerialForTilt + // Called from main loop // Control incoming/outgoing RTCM data from STM32 based LoRa radio (if supported by platform) void updateLora() @@ -105,7 +118,7 @@ void updateLora() loraSetupReceive(); systemFlush(); // Complete prints - muxSelectLoRa(); // Disconnect from USB + muxSelectLoRaCommunication(); // Disconnect from USB loraState = LORA_RX_DEDICATED; } else // USB cable attached, share the ESP32 UART0 connection between USB and LoRa @@ -147,7 +160,7 @@ void updateLora() if (settings.debugLora == true) { static unsigned long lastReport = 0; - if (millis() - lastReport > 3000) + if ((millis() - lastReport) > 3000) { lastReport = millis(); systemPrintf("LoRa transmitted %d RTCM bytes\r\n", loraBytesSent); @@ -162,7 +175,7 @@ void updateLora() break; case (LORA_RX_DEDICATED): - if (Serial.available()) + if (loraAvailable()) { uint8_t rtcmData[512]; int rtcmCount = 0; @@ -183,7 +196,7 @@ void updateLora() systemPrintf("LoRa received %d RTCM bytes, pushed to GNSS\r\n", rtcmCount); systemFlush(); // Allow print to complete - muxSelectLoRa(); // Disconnect from USB + muxSelectLoRaCommunication(); // Disconnect from USB } } else @@ -196,7 +209,7 @@ void updateLora() systemPrintf("LoRa received %d RTCM bytes, NOT pushed due to priority\r\n", rtcmCount); systemFlush(); // Allow print to complete - muxSelectLoRa(); // Disconnect from USB + muxSelectLoRaCommunication(); // Disconnect from USB } } } @@ -220,11 +233,11 @@ void updateLora() break; case (LORA_RX_SHARED): - if ((millis() - loraLastIncomingSerial) / 1000 > settings.loraSerialInteractionTimeout_s) + if (((millis() - loraLastIncomingSerial) / 1000) > settings.loraSerialInteractionTimeout_s) { systemPrintln("LoRa shared port timeout expired. Moving to dedicated LoRa receive with no USB output."); - systemFlush(); // Complete prints - muxSelectLoRa(); // Disconnect from USB + systemFlush(); // Complete prints + muxSelectLoRaCommunication(); // Disconnect from USB loraState = LORA_RX_DEDICATED_USB; } @@ -241,7 +254,7 @@ void updateLora() // USB cable is present. loraSerialInteractionTimeout_s has occurred. Be dedicated until USB is // disconnected. - if (Serial.available()) + if (loraAvailable()) { uint8_t rtcmData[512]; int rtcmCount = 0; @@ -262,7 +275,7 @@ void updateLora() systemPrintf("LoRa received %d RTCM bytes, pushed to GNSS\r\n", rtcmCount); systemFlush(); // Allow print to complete - muxSelectLoRa(); // Disconnect from USB + muxSelectLoRaCommunication(); // Disconnect from USB } } else @@ -275,7 +288,7 @@ void updateLora() systemPrintf("LoRa received %d RTCM bytes, NOT pushed due to priority\r\n", rtcmCount); systemFlush(); // Allow print to complete - muxSelectLoRa(); // Disconnect from USB + muxSelectLoRaCommunication(); // Disconnect from USB } } } @@ -320,65 +333,111 @@ void loraStop() void muxSelectUm980() { - digitalWrite(pin_muxA, LOW); // Connect ESP UART1 to UM980 -} - -// Used during firmware updates -void muxSelectLoRaUart0() -{ - digitalWrite(pin_muxA, HIGH); // Connect ESP UART1 to LoRa UART0 + // On a possible Flex UM980 variant, UM980 UART1 will be hardwired to ESP32 UART0. No muxes to change + if (productVariant == RTK_TORCH) + digitalWrite(pin_muxA, LOW); // Connect ESP UART1 to UM980 } void muxSelectUsb() { - pinMode(pin_muxB, OUTPUT); // Make really sure we can control this pin - digitalWrite(pin_muxB, LOW); // Connect ESP UART0 to CH340 Serial + if (productVariant == RTK_TORCH) + { + pinMode(pin_muxB, OUTPUT); // Make really sure we can control this pin + digitalWrite(pin_muxB, LOW); // Connect ESP UART0 to CH340 Serial - usbSerialIsSelected = true; // Let other print operations know we are connected to the CH34x + usbSerialIsSelected = true; // Let other print operations know we are connected to the CH34x + } } -void muxSelectLoRa() +// Connect ESP32 to LoRa for regular transmissions +void muxSelectLoRaCommunication() { - pinMode(pin_muxB, OUTPUT); // Make really sure we can control this pin - digitalWrite(pin_muxA, LOW); // Connect ESP UART1 to UM980 - digitalWrite(pin_muxB, HIGH); // Connect ESP UART0 to U11 + if (productVariant == RTK_TORCH) + { + pinMode(pin_muxB, OUTPUT); // Make really sure we can control this pin + digitalWrite(pin_muxA, LOW); // Connect ESP UART1 to UM980 + digitalWrite(pin_muxB, HIGH); // Connect ESP UART0 to U11 + + usbSerialIsSelected = false; // Let other print operations know we are not connected to the CH34x + } + else if (productVariant == RTK_FLEX) + { + gpioExpanderSelectLoraCommunication(); + } +} - usbSerialIsSelected = false; // Let other print operations know we are not connected to the CH34x +// Connect ESP32 to LoRa for configuration and bootloading +void muxSelectLoRaConfigure() +{ + if (productVariant == RTK_TORCH) + digitalWrite(pin_muxA, HIGH); // Connect ESP UART1 to LoRa UART0 + else if (productVariant == RTK_FLEX) + gpioExpanderSelectLoraConfigure(); // Connect ESP32 UART2 to LoRa UART2 } void loraEnterBootloader() { - digitalWrite(pin_loraRadio_boot, HIGH); // Enter bootload mode + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) + digitalWrite(pin_loraRadio_boot, HIGH); // Enter bootload mode + else if (productVariant == RTK_FLEX) + gpioExpanderLoraBootEnable(); + loraReset(); } void loraExitBootloader() { - digitalWrite(pin_loraRadio_boot, LOW); // Exit bootload mode + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) + digitalWrite(pin_loraRadio_boot, LOW); // Exit bootload mode + else if (productVariant == RTK_FLEX) + gpioExpanderLoraBootDisable(); + loraReset(); } void loraReset() { - digitalWrite(pin_loraRadio_reset, LOW); // Reset STM32/radio - delay(15); - digitalWrite(pin_loraRadio_reset, HIGH); // Run STM32/radio - delay(15); + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) + { + digitalWrite(pin_loraRadio_reset, LOW); // Reset STM32/radio + delay(15); + digitalWrite(pin_loraRadio_reset, HIGH); // Run STM32/radio + delay(15); + } + else if (productVariant == RTK_FLEX) + { + gpioExpanderLoraDisable(); + delay(15); + gpioExpanderLoraEnable(); + delay(15); + } } void loraPowerOn() { - digitalWrite(pin_loraRadio_power, HIGH); // Power STM32/radio + if (productVariant == RTK_TORCH) + digitalWrite(pin_loraRadio_power, HIGH); // Power STM32/radio + else if (productVariant == RTK_FLEX) + gpioExpanderLoraEnable(); } void loraPowerOff() { - digitalWrite(pin_loraRadio_power, LOW); // Power off STM32/radio + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) + digitalWrite(pin_loraRadio_power, LOW); // Power off STM32/radio + else if (productVariant == RTK_FLEX) + gpioExpanderLoraDisable(); } bool loraIsOn() { - if (digitalRead(pin_loraRadio_power) == HIGH) - return (true); + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) + { + if (digitalRead(pin_loraRadio_power) == HIGH) + return (true); + return (false); + } + else if (productVariant == RTK_FLEX) + return (gpioExpanderLoraIsOn()); return (false); } @@ -442,6 +501,19 @@ bool createLoRaPassthrough() void beginLoraFirmwareUpdate() { + // NOTE: this currently fails on Flex due to the way LoRa_EN and LoRa_NRST are interconnected. + // This will be resolved with the next Flex motherboard rev. + // TODO: delete this comment once new hardware is available. + + // Flag that we are in direct connect mode. Button task will removeUpdateLoraFirmware and exit + inDirectConnectMode = true; + + // Paint GNSS Update + paintLoRaUpdate(); + + // Stop all UART tasks. Redundant + tasksStopGnssUart(); + systemPrintln(); systemPrintln("Entering STM32 direct connect for firmware update. Disconnect this terminal connection. Use " "'STM32CubeProgrammer' to update the " @@ -458,12 +530,20 @@ void beginLoraFirmwareUpdate() Serial.begin(57600); // Keep this at slower rate if (serialGNSS == nullptr) - serialGNSS = new HardwareSerial(2); // Use UART2 on the ESP32 for communication with the GNSS module + serialGNSS = new HardwareSerial(2); // Use UART2 on the ESP32 for communication with the LoRa radio - serialGNSS->begin(115200, SERIAL_8N1, pin_GnssUart_RX, pin_GnssUart_TX); // Keep this at 115200 + serialGNSS->setRxBufferSize(settings.uartReceiveBufferSize); + serialGNSS->setTimeout(settings.serialTimeoutGNSS); // Requires serial traffic on the UART pins for detection + + if (productVariant == RTK_TORCH) + serialGNSS->begin(115200, SERIAL_8N1, pin_GnssUart_RX, pin_GnssUart_TX); // Keep this at 115200 + else if (productVariant == RTK_FLEX) + serialGNSS->begin(115200, SERIAL_8N1, pin_IMU_RX, pin_IMU_TX); // Keep this at 115200 + else + systemPrintln("ERROR: productVariant does not support LoRa"); - // Make sure ESP-UART1 is connected to LoRA STM32 UART0 - muxSelectLoRaUart0(); + // Make sure ESP-UART1 is connected to LoRa STM32 UART0 + muxSelectLoRaConfigure(); loraEnterBootloader(); // Push boot pin high and reset STM32 @@ -472,39 +552,51 @@ void beginLoraFirmwareUpdate() while (Serial.available()) Serial.read(); - // Push any incoming ESP32 UART0 to UART1 and vice versa + // Push any incoming ESP32 UART0 to UART1 or UART2 and vice versa // Infinite loop until button is pressed - while (1) + task.endDirectConnectMode = false; + while (!task.endDirectConnectMode) { - while (Serial.available()) + static unsigned long lastSerial = millis(); // Temporary fix for buttonless Flex + + if (Serial.available()) // Note: use if, not while + { serialGNSS->write(Serial.read()); + lastSerial = millis(); + } - while (serialGNSS->available()) + if (serialGNSS->available()) // Note: use if, not while Serial.write(serialGNSS->read()); - if (readAnalogPinAsDigital(pin_powerButton) == HIGH) + // Button task will set task.endDirectConnectMode true + + // Temporary fix for buttonless Flex. TODO - remove + if ((productVariant == RTK_FLEX) && ((millis() - lastSerial) > 30000)) { - while (readAnalogPinAsDigital(pin_powerButton) == HIGH) + // Beep to indicate exit + beepOn(); + delay(300); + beepOff(); delay(100); + beepOn(); + delay(300); + beepOff(); - // Remove file and reset to exit LoRa update pass-through mode - removeUpdateLoraFirmware(); + removeUpdateLoraFirmware(); - // Beep to indicate exit - beepOn(); - delay(300); - beepOff(); - delay(100); - beepOn(); - delay(300); - beepOff(); + systemPrintln("Exiting direct connection (passthrough) mode"); + systemFlush(); // Complete prints - systemPrintln("Exiting LoRa Firmware update mode"); - systemFlush(); // Complete prints - - ESP.restart(); + ESP.restart(); } } + + // Remove the special file. See #763 . Do the file removal in the loop + removeUpdateLoraFirmware(); + + systemFlush(); // Complete prints + + ESP.restart(); } void loraSetupTransmit() @@ -573,10 +665,10 @@ bool loraSendCommand(const char *command, char *response, int *responseSize) systemFlush(); // Complete prints - muxSelectLoRa(); // Disconnect from USB + muxSelectLoRaCommunication(); // Disconnect from USB - Serial.printf("%s\r\n", command); - while (Serial.available() == 0) + loraPrintf("%s\r\n", command); + while (loraAvailable() == 0) { delay(1); responseTime++; @@ -588,9 +680,9 @@ bool loraSendCommand(const char *command, char *response, int *responseSize) } delay(10); // Allow all serial to arrive - while (Serial.available()) + while (loraAvailable()) { - response[responseSpot++] = Serial.read(); + response[responseSpot++] = loraRead(); if (responseSpot == *responseSize) { responseSpot--; @@ -607,7 +699,8 @@ bool loraSendCommand(const char *command, char *response, int *responseSize) return (false); } -// Disconnects from USB +// On the Torch, USB and LoRa radio are shared, so disconnects from USB are required +// On the Flex, LoRa UART2 is on ESP32 UART2 // Sends AT+V?, if response, we are already in command mode -> Reconnects to USB, Return // Sends +++ (but there is no response) // Sends AT+V?, if response, we are in command mode -> Reconnects to USB, Return @@ -622,14 +715,14 @@ bool loraEnterCommandMode() systemFlush(); // Complete prints - muxSelectLoRa(); // Disconnect from USB + muxSelectLoRaCommunication(); // Connect the LoRa radio to ESP32 UART0 (shared with USB) delay(50); // Wait for incoming serial to complete while (Serial.available()) Serial.read(); // Read any incoming and trash // Send version query. Wait up to 2000ms for a response - Serial.print("AT+V?\r\n"); + loraPrint("AT+V?\r\n"); for (int x = 0; x < 2000; x++) { if (Serial.available()) @@ -648,11 +741,11 @@ bool loraEnterCommandMode() } // No response so send +++ - Serial.print("+++\r\n"); + loraPrint("+++\r\n"); delay(100); // Allow STM32 time to enter command mode // Send version query. Wait up to 2000ms for a response - Serial.print("AT+V?\r\n"); + loraPrint("AT+V?\r\n"); for (int x = 0; x < 2000; x++) { if (Serial.available()) @@ -723,16 +816,79 @@ void loraProcessRTCM(uint8_t *rtcmData, uint16_t dataLength) { if (loraState == LORA_TX) { - // Send this data to the LoRa radio + // Only needed for Torch. Flex has GNSS tied directly to LoRa. + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) + { + // Send this data to the LoRa radio - systemFlush(); // Complete prints - muxSelectLoRa(); // Disconnect from USB + systemFlush(); // Complete prints + muxSelectLoRaCommunication(); // Connect to STM32 for regular TX/RX of corrections - Serial.write(rtcmData, dataLength); + loraWrite(rtcmData, dataLength); - systemFlush(); // Complete prints - muxSelectUsb(); // Connect USB + systemFlush(); // Complete prints + muxSelectUsb(); // Connect USB + } loraBytesSent += dataLength; } } + +// Write data to the LoRa radio, depends on platform +void loraWrite(uint8_t *data, uint16_t dataLength) +{ + if (productVariant == RTK_TORCH) + Serial.write(data, dataLength); + else if (productVariant == RTK_FLEX) + SerialForLoRa->write(data, dataLength); +} + +void loraPrint(const char *data) +{ + if (productVariant == RTK_TORCH) + Serial.print(data); + else if (productVariant == RTK_FLEX) + SerialForLoRa->print(data); +} + +void loraPrintf(const char *format, ...) +{ + va_list args; + va_start(args, format); + + va_list args2; + va_copy(args2, args); + char buf[vsnprintf(nullptr, 0, format, args) + 1]; + + vsnprintf(buf, sizeof buf, format, args2); + + if (productVariant == RTK_TORCH) + Serial.printf(buf); + else if (productVariant == RTK_FLEX) + SerialForLoRa->printf(buf); + + va_end(args); + va_end(args2); +} + +uint16_t loraAvailable() +{ + if (productVariant == RTK_TORCH) + return (Serial.available()); + else if (productVariant == RTK_FLEX) + return (SerialForLoRa->available()); + + systemPrintln("loraAvailable - invalid ProductVariant"); + return 0; +} + +uint16_t loraRead() +{ + if (productVariant == RTK_TORCH) + return (Serial.read()); + else if (productVariant == RTK_FLEX) + return (SerialForLoRa->read()); + + systemPrintln("loraRead - invalid ProductVariant"); + return 0; +} \ No newline at end of file diff --git a/Firmware/RTK_Everywhere/MQTT_Client.ino b/Firmware/RTK_Everywhere/MQTT_Client.ino index b5a6e905d..63bdf2352 100644 --- a/Firmware/RTK_Everywhere/MQTT_Client.ino +++ b/Firmware/RTK_Everywhere/MQTT_Client.ino @@ -75,7 +75,7 @@ MQTT_Client.ino // When the dict is received, we subscribe to the nearest localized topic and unsubscribe from the continental topic // When the AssistNow MGA data arrives, we unsubscribe and subscribe to AssistNow updates -String localizedDistributionDictTopic = ""; // Used in menuPP +String localizedDistributionDictTopic = ""; // Used in menuPointPerfect() String localizedDistributionTileTopic = ""; #ifdef COMPILE_MQTT_CLIENT @@ -514,6 +514,7 @@ int mqttClientProcessZedMessage(uint8_t *mqttData, uint16_t mqttCount, int bytes zed->updateCorrectionsSource(0); // Set SOURCE to 0 (IP) if needed gnss->pushRawData(mqttData, mqttCount); + // Corrections are SPARTN. No point in pushing them to rtcmParse bytesPushed += mqttCount; mqttClientDataReceived = true; @@ -542,6 +543,7 @@ int mqttClientProcessZedMessage(uint8_t *mqttData, uint16_t mqttCount, int bytes } gnss->pushRawData(mqttData, mqttCount); + // No point in pushing keys / MGA to rtcmParse bytesPushed += mqttCount; } #endif // COMPILE_ZED @@ -952,6 +954,16 @@ void mqttClientUpdate() // Attempt connection to the MQTT broker if (!mqttClient->connect(settings.pointPerfectBrokerHost, 8883)) { + // Failed to connect to the server + int length = 1024; + char * errMessage = (char *)rtkMalloc(length, "HTTP error message"); + if (errMessage) + { + memset(errMessage, 0, length); + mqttSecureClient->lastError(errMessage, length - 1); + systemPrintf("MQTT Error: %s\r\n", errMessage); + rtkFree(errMessage, "HTTP error message"); + } systemPrintf("Failed to connect to MQTT broker %s\r\n", settings.pointPerfectBrokerHost); mqttClientRestart(); break; @@ -1013,7 +1025,7 @@ void mqttClientUpdate() mqttClient->poll(); // Determine if a data timeout has occurred - if (millis() - mqttClientLastDataReceived >= MQTT_CLIENT_DATA_TIMEOUT) + if ((millis() - mqttClientLastDataReceived) >= MQTT_CLIENT_DATA_TIMEOUT) { systemPrintln("MQTT client data timeout. Disconnecting..."); mqttClientRestart(); @@ -1157,7 +1169,7 @@ void mqttClientUpdate() } // Periodically display the MQTT client state - if (PERIODIC_DISPLAY(PD_MQTT_CLIENT_STATE)) + if (PERIODIC_DISPLAY(PD_MQTT_CLIENT_STATE) && !inMainMenu) { const char *line = ""; mqttClientEnabled(&line); diff --git a/Firmware/RTK_Everywhere/NTP.ino b/Firmware/RTK_Everywhere/NTP.ino index e525a3df7..8a8c1878d 100644 --- a/Firmware/RTK_Everywhere/NTP.ino +++ b/Firmware/RTK_Everywhere/NTP.ino @@ -609,7 +609,7 @@ bool ntpProcessOneRequest(bool process, const timeval *recTv, const timeval *syn if (ntpDiag != nullptr) { char tmpbuf[128]; - snprintf(tmpbuf, sizeof(tmpbuf), "Originate Timestamp (Client Transmit): %u.%06u\r\n", + snprintf(tmpbuf, sizeof(tmpbuf), "Originate Timestamp (Client Transmit): %lu.%06lu\r\n", packet.transmitTimestampSeconds, packet.convertFractionToMicros(packet.transmitTimestampFraction)); strlcat(ntpDiag, tmpbuf, ntpDiagSize); @@ -631,7 +631,7 @@ bool ntpProcessOneRequest(bool process, const timeval *recTv, const timeval *syn if (ntpDiag != nullptr) { char tmpbuf[128]; - snprintf(tmpbuf, sizeof(tmpbuf), "Received Timestamp: %u.%06u\r\n", + snprintf(tmpbuf, sizeof(tmpbuf), "Received Timestamp: %lu.%06lu\r\n", packet.receiveTimestampSeconds, packet.convertFractionToMicros(packet.receiveTimestampFraction)); strlcat(ntpDiag, tmpbuf, ntpDiagSize); @@ -649,7 +649,7 @@ bool ntpProcessOneRequest(bool process, const timeval *recTv, const timeval *syn if (ntpDiag != nullptr) { char tmpbuf[128]; - snprintf(tmpbuf, sizeof(tmpbuf), "Reference Timestamp (Last Sync): %u.%06u\r\n", + snprintf(tmpbuf, sizeof(tmpbuf), "Reference Timestamp (Last Sync): %lu.%06lu\r\n", packet.referenceTimestampSeconds, packet.convertFractionToMicros(packet.referenceTimestampFraction)); strlcat(ntpDiag, tmpbuf, ntpDiagSize); @@ -677,7 +677,7 @@ bool ntpProcessOneRequest(bool process, const timeval *recTv, const timeval *syn if (ntpDiag != nullptr) { char tmpbuf[128]; - snprintf(tmpbuf, sizeof(tmpbuf), "Transmit Timestamp: %u.%06u\r\n", + snprintf(tmpbuf, sizeof(tmpbuf), "Transmit Timestamp: %lu.%06lu\r\n", packet.transmitTimestampSeconds, packet.convertFractionToMicros(packet.transmitTimestampFraction)); strlcat(ntpDiag, tmpbuf, ntpDiagSize); @@ -957,13 +957,13 @@ void ntpServerUpdate() } } - if (millis() > (lastLoggedNTPRequest + 5000)) + if ((millis() - lastLoggedNTPRequest) > 5000) ntpLogIncreasing = false; break; } // Periodically display the NTP server state - if (PERIODIC_DISPLAY(PD_NTP_SERVER_STATE)) + if (PERIODIC_DISPLAY(PD_NTP_SERVER_STATE) && !inMainMenu) { const char * line = ""; if (NEQ_RTK_MODE(ntpServerMode)) diff --git a/Firmware/RTK_Everywhere/NVM.ino b/Firmware/RTK_Everywhere/NVM.ino index 007b5189f..ed0fdf70e 100644 --- a/Firmware/RTK_Everywhere/NVM.ino +++ b/Firmware/RTK_Everywhere/NVM.ino @@ -227,8 +227,21 @@ void recordSystemSettingsToFile(File *settingsFile) for (int i = 0; i < numRtkSettingsEntries; i++) { // Do not record this setting if it is not supported by the current platform - if (settingAvailableOnPlatform(i) == false) - continue; + // But oh what a tangled web we weave... + // Thanks to Flex, initially we should be saving all possible settings. + // Later, once we know what Flex GNSS is present, we save only the available + // settings for that platform. Passing usePossibleSettings in as a parameter + // would be messy. So, we'll use a global flag which is updated by commandIndexFill + if (savePossibleSettings) + { + if (settingPossibleOnPlatform(i) == false) + continue; + } + else + { + if (settingAvailableOnPlatform(i) == false) + continue; + } switch (rtkSettingsEntries[i].type) { @@ -266,7 +279,7 @@ void recordSystemSettingsToFile(File *settingsFile) break; case _uint32_t: { uint32_t *ptr = (uint32_t *)rtkSettingsEntries[i].var; - settingsFile->printf("%s=%d\r\n", rtkSettingsEntries[i].name, *ptr); + settingsFile->printf("%s=%lu\r\n", rtkSettingsEntries[i].name, *ptr); } break; case _uint64_t: { @@ -326,8 +339,17 @@ void recordSystemSettingsToFile(File *settingsFile) } break; + case tCmnCnst: + break; // Nothing to do here. Let each GNSS add its settings + case tCmnRtNm: + break; // Nothing to do here. Let each GNSS add its settings + case tCnRtRtB: + break; // Nothing to do here. Let each GNSS add its settings + case tCnRtRtR: + break; // Nothing to do here. Let each GNSS add its settings + case tEspNowPr: { - // Record ESP-Now peer MAC addresses + // Record ESP-NOW peer MAC addresses for (int x = 0; x < rtkSettingsEntries[i].qualifier; x++) { char tempString[50]; // espnowPeer_1=B4:C1:33:42:DE:01, @@ -647,6 +669,12 @@ void recordSystemSettingsToFile(File *settingsFile) } break; #endif // COMPILE_LG290P + + case tGnssReceiver: { + gnssReceiverType_e *ptr = (gnssReceiverType_e *)rtkSettingsEntries[i].var; + settingsFile->printf("%s=%d\r\n", rtkSettingsEntries[i].name, (int)*ptr); + } + break; } } @@ -962,8 +990,16 @@ bool parseLine(char *str) { char *ptr; + // A health warning about strtok: + // strtok will convert any delimiters it finds ("=" in our case) into NULL characters. + // Also, be very careful that you do not use strtok within an strtok while loop. + // The next call of strtok(NULL, ...) in the outer loop will use the pointer saved from the inner loop! + // The same is true for tasks! + // The solution is to use strtok_r - the reentrant version of strtok + // Set strtok start of line. - str = strtok(str, "="); + char *preservedPointer; + str = strtok_r(str, "=", &preservedPointer); if (!str) { log_d("Fail"); @@ -978,7 +1014,7 @@ bool parseLine(char *str) char settingString[100] = ""; // Move pointer to end of line - str = strtok(nullptr, "\n"); + str = strtok_r(nullptr, "\n", &preservedPointer); if (!str) { // This line does not contain a \n or the settingString is zero length @@ -1066,12 +1102,11 @@ bool parseLine(char *str) else { const char *table[] = { - "gnssFirmwareVersion", "gnssUniqueId", "neoFirmwareVersion", - "rtkFirmwareVersion", "rtkIdentifier", + "gnssFirmwareVersion", "gnssUniqueId", "neoFirmwareVersion", "rtkFirmwareVersion", "rtkIdentifier", }; const int tableEntries = sizeof(table) / sizeof(table[0]); - knownSetting = commandCheckForUnknownVariable(settingName, table, tableEntries); + knownSetting = commandCheckListForVariable(settingName, table, tableEntries); } if (knownSetting == false) @@ -1084,8 +1119,6 @@ bool parseLine(char *str) RTK_Settings_Types type; void *var; - double settingValue; - // Loop through the valid command entries i = commandLookupSettingName(false, settingName, truncatedName, sizeof(truncatedName), suffix, sizeof(suffix)); @@ -1210,9 +1243,21 @@ bool parseLine(char *str) } break; + case tCmnCnst: { +#ifdef COMPILE_MOSAICX5 + for (int x = 0; x < MAX_MOSAIC_CONSTELLATIONS; x++) + { + if ((suffix[0] == mosaicSignalConstellations[x].configName[0]) && + (strcmp(suffix, mosaicSignalConstellations[x].configName) == 0)) + { + settings.mosaicConstellations[x] = d; + knownSetting = true; + break; + } + } +#endif // COMPILE_MOSAICX5 #ifdef COMPILE_ZED - case tUbxConst: { - for (int x = 0; x < qualifier; x++) + for (int x = 0; x < MAX_UBX_CONSTELLATIONS; x++) { if ((suffix[0] == settings.ubxConstellations[x].textName[0]) && (strcmp(suffix, settings.ubxConstellations[x].textName) == 0)) @@ -1222,6 +1267,118 @@ bool parseLine(char *str) break; } } +#endif // COMPILE_ZED +#ifdef COMPILE_UM980 + for (int x = 0; x < MAX_UM980_CONSTELLATIONS; x++) + { + if ((suffix[0] == um980ConstellationCommands[x].textName[0]) && + (strcmp(suffix, um980ConstellationCommands[x].textName) == 0)) + { + settings.um980Constellations[x] = d; + knownSetting = true; + break; + } + } +#endif // COMPILE_UM980 +#ifdef COMPILE_LG290P + for (int x = 0; x < MAX_LG290P_CONSTELLATIONS; x++) + { + if ((suffix[0] == lg290pConstellationNames[x][0]) && + (strcmp(suffix, lg290pConstellationNames[x]) == 0)) + { + settings.lg290pConstellations[x] = d; + knownSetting = true; + break; + } + } +#endif // COMPILE_LG290P + } + break; + case tCmnRtNm: { +#ifdef COMPILE_UM980 + for (int x = 0; x < MAX_UM980_NMEA_MSG; x++) + { + if ((suffix[0] == umMessagesNMEA[x].msgTextName[0]) && + (strcmp(suffix, umMessagesNMEA[x].msgTextName) == 0)) + { + settings.um980MessageRatesNMEA[x] = d; + knownSetting = true; + break; + } + } +#endif +#ifdef COMPILE_LG290P + for (int x = 0; x < MAX_LG290P_NMEA_MSG; x++) + { + if ((suffix[0] == lgMessagesNMEA[x].msgTextName[0]) && + (strcmp(suffix, lgMessagesNMEA[x].msgTextName) == 0)) + { + settings.lg290pMessageRatesNMEA[x] = d; + knownSetting = true; + break; + } + } +#endif // COMPILE_LG290P + } + break; + case tCnRtRtB: { +#ifdef COMPILE_UM980 + for (int x = 0; x < MAX_UM980_RTCM_MSG; x++) + { + if ((suffix[0] == umMessagesRTCM[x].msgTextName[0]) && + (strcmp(suffix, umMessagesRTCM[x].msgTextName) == 0)) + { + settings.um980MessageRatesRTCMBase[x] = d; + knownSetting = true; + break; + } + } +#endif +#ifdef COMPILE_LG290P + for (int x = 0; x < MAX_LG290P_RTCM_MSG; x++) + { + if ((suffix[0] == lgMessagesRTCM[x].msgTextName[0]) && + (strcmp(suffix, lgMessagesRTCM[x].msgTextName) == 0)) + { + settings.lg290pMessageRatesRTCMBase[x] = d; + knownSetting = true; + break; + } + } +#endif // COMPILE_LG290P + } + break; + case tCnRtRtR: { +#ifdef COMPILE_UM980 + for (int x = 0; x < MAX_UM980_RTCM_MSG; x++) + { + if ((suffix[0] == umMessagesRTCM[x].msgTextName[0]) && + (strcmp(suffix, umMessagesRTCM[x].msgTextName) == 0)) + { + settings.um980MessageRatesRTCMRover[x] = d; + knownSetting = true; + break; + } + } +#endif +#ifdef COMPILE_LG290P + for (int x = 0; x < MAX_LG290P_RTCM_MSG; x++) + { + if ((suffix[0] == lgMessagesRTCM[x].msgTextName[0]) && + (strcmp(suffix, lgMessagesRTCM[x].msgTextName) == 0)) + { + settings.lg290pMessageRatesRTCMRover[x] = d; + knownSetting = true; + break; + } + } +#endif // COMPILE_LG290P + } + break; + +#ifdef COMPILE_ZED + case tUbxConst: { + // Covered by ttCmnCnst } break; case tUbxMsgRt: { @@ -1356,55 +1513,19 @@ bool parseLine(char *str) #ifdef COMPILE_UM980 case tUmMRNmea: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == umMessagesNMEA[x].msgTextName[0]) && - (strcmp(suffix, umMessagesNMEA[x].msgTextName) == 0)) - { - settings.um980MessageRatesNMEA[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCmnRtNm } break; case tUmMRRvRT: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == umMessagesRTCM[x].msgTextName[0]) && - (strcmp(suffix, umMessagesRTCM[x].msgTextName) == 0)) - { - settings.um980MessageRatesRTCMRover[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCnRtRtR } break; case tUmMRBaRT: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == umMessagesRTCM[x].msgTextName[0]) && - (strcmp(suffix, umMessagesRTCM[x].msgTextName) == 0)) - { - settings.um980MessageRatesRTCMBase[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCnRtRtB } break; case tUmConst: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == um980ConstellationCommands[x].textName[0]) && - (strcmp(suffix, um980ConstellationCommands[x].textName) == 0)) - { - settings.um980Constellations[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCmnCnst } break; #endif // COMPILE_UM980 @@ -1434,16 +1555,7 @@ bool parseLine(char *str) #ifdef COMPILE_MOSAICX5 case tMosaicConst: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == mosaicSignalConstellations[x].configName[0]) && - (strcmp(suffix, mosaicSignalConstellations[x].configName) == 0)) - { - settings.mosaicConstellations[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCmnCnst } break; case tMosaicMSNmea: { @@ -1525,42 +1637,15 @@ bool parseLine(char *str) #ifdef COMPILE_LG290P case tLgMRNmea: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == lgMessagesNMEA[x].msgTextName[0]) && - (strcmp(suffix, lgMessagesNMEA[x].msgTextName) == 0)) - { - settings.lg290pMessageRatesNMEA[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCmnRtNm } break; case tLgMRRvRT: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == lgMessagesRTCM[x].msgTextName[0]) && - (strcmp(suffix, lgMessagesRTCM[x].msgTextName) == 0)) - { - settings.lg290pMessageRatesRTCMRover[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCnRtRtR } break; case tLgMRBaRT: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == lgMessagesRTCM[x].msgTextName[0]) && - (strcmp(suffix, lgMessagesRTCM[x].msgTextName) == 0)) - { - settings.lg290pMessageRatesRTCMBase[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCnRtRtB } break; case tLgMRPqtm: { @@ -1577,19 +1662,17 @@ bool parseLine(char *str) } break; case tLgConst: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == lg290pConstellationNames[x][0]) && - (strcmp(suffix, lg290pConstellationNames[x]) == 0)) - { - settings.lg290pConstellations[x] = d; - knownSetting = true; - break; - } - } + // Covered by tCmnCnst } break; #endif // COMPILE_LG290P + + case tGnssReceiver: { + gnssReceiverType_e *ptr = (gnssReceiverType_e *)var; + *ptr = (gnssReceiverType_e)d; + knownSetting = true; + } + break; } } } @@ -1613,7 +1696,7 @@ bool parseLine(char *str) // Last catch if (knownSetting == false) { - log_d("Unknown setting %s", settingName); + log_d("Unknown / unwanted setting %s", settingName); } return (true); diff --git a/Firmware/RTK_Everywhere/Network.ino b/Firmware/RTK_Everywhere/Network.ino index 7d8b5f17d..7a8a531c6 100644 --- a/Firmware/RTK_Everywhere/Network.ino +++ b/Firmware/RTK_Everywhere/Network.ino @@ -226,8 +226,11 @@ void menuTcpUdp() if (settings.mdnsEnable) systemPrintf("n) MDNS host name: %s\r\n", settings.mdnsHostName); - systemPrint("a) Broadcast TCP/UDP Server packets over local WiFi or act as Access Point: "); - systemPrintf("%s\r\n", settings.tcpUdpOverWiFiStation ? "WiFi" : "AP"); + systemPrint("t) Broadcast TCP/UDP Server packets over local WiFi or act as Access Point: "); + systemPrintf("%s\r\n", settings.tcpOverWiFiStation ? "WiFi" : "AP"); + + systemPrint("u) Broadcast UDP Server packets over local WiFi or act as Access Point: "); + systemPrintf("%s\r\n", settings.udpOverWiFiStation ? "WiFi" : "AP"); //------------------------------ // Finish the menu and get the input @@ -259,10 +262,11 @@ void menuTcpUdp() // Remove any http:// or https:// prefix from host name // strtok modifies string to be parsed so we create a copy strncpy(hostname, settings.tcpClientHost, sizeof(hostname) - 1); - char *token = strtok(hostname, "//"); + char *preservedPointer; + char *token = strtok_r(hostname, "//", &preservedPointer); if (token != nullptr) { - token = strtok(nullptr, "//"); // Advance to data after // + token = strtok_r(nullptr, "//", &preservedPointer); // Advance to data after // if (token != nullptr) strcpy(settings.tcpClientHost, token); } @@ -323,11 +327,18 @@ void menuTcpUdp() getUserInputString((char *)&settings.mdnsHostName, sizeof(settings.mdnsHostName)); } - else if (incoming == 'a') + else if (incoming == 't') + { + settings.tcpOverWiFiStation ^= 1; + wifiUpdateSettings(); + } + + else if (incoming == 'u') { - settings.tcpUdpOverWiFiStation ^= 1; + settings.udpOverWiFiStation ^= 1; wifiUpdateSettings(); } + //------------------------------ // Handle exit and invalid input //------------------------------ @@ -2442,10 +2453,12 @@ void networkUpdate() // Update the WiFi state wifiStationUpdate(); + // Update Ethernet + ethernetUpdate(); + // Update the network services // Start or stop mDNS - if (networkMdnsRequests != networkMdnsRunning) - networkMulticastDNSUpdate(); + networkMulticastDNSUpdate(); // Update the network services DMW_c("mqttClientUpdate"); @@ -2578,7 +2591,12 @@ void networkUserAdd(NETCONSUMER_t consumer, const char *fileName, uint32_t lineN // Display the user if (settings.debugNetworkLayer) - systemPrintf("%s adding user %s\r\n", networkInterfaceTable[index].name, networkConsumerTable[consumer]); + { + if (index < NETWORK_OFFLINE) + systemPrintf("%s adding user %s\r\n", networkInterfaceTable[index].name, networkConsumerTable[consumer]); + else + systemPrintf("NETWORK_ANY adding user %s\r\n", networkConsumerTable[consumer]); + } // Remember this network interface networkConsumerIndexLast[consumer] = index; diff --git a/Firmware/RTK_Everywhere/NtripClient.ino b/Firmware/RTK_Everywhere/NtripClient.ino index a686367d6..0019f8614 100644 --- a/Firmware/RTK_Everywhere/NtripClient.ino +++ b/Firmware/RTK_Everywhere/NtripClient.ino @@ -138,7 +138,7 @@ static const uint32_t NTRIP_CLIENT_RESPONSE_TIMEOUT = 10 * 1000; // Milliseconds static const uint32_t NTRIP_CLIENT_RECEIVE_DATA_TIMEOUT = 30 * 1000; // Milliseconds // Most incoming data is around 500 bytes but may be larger -static const int RTCM_DATA_SIZE = 512 * 4; +static const size_t RTCM_DATA_SIZE = 512 * 4; // NTRIP client server request buffer size static const int SERVER_BUFFER_SIZE = CREDENTIALS_BUFFER_SIZE + 3; @@ -216,10 +216,11 @@ bool ntripClientConnect() char hostname[51]; strncpy(hostname, settings.ntripClient_CasterHost, sizeof(hostname) - 1); // strtok modifies string to be parsed so we create a copy - char *token = strtok(hostname, "//"); + char *preservedPointer; + char *token = strtok_r(hostname, "//", &preservedPointer); if (token != nullptr) { - token = strtok(nullptr, "//"); // Advance to data after // + token = strtok_r(nullptr, "//", &preservedPointer); // Advance to data after // if (token != nullptr) strcpy(settings.ntripClient_CasterHost, token); } @@ -228,7 +229,7 @@ bool ntripClientConnect() systemPrintf("NTRIP Client connecting to %s:%d\r\n", settings.ntripClient_CasterHost, settings.ntripClient_CasterPort); - int connectResponse = ntripClient->connect(settings.ntripClient_CasterHost, settings.ntripClient_CasterPort); + int connectResponse = ntripClient->connect(settings.ntripClient_CasterHost, settings.ntripClient_CasterPort, NTRIP_CLIENT_RESPONSE_TIMEOUT); if (connectResponse < 1) { @@ -248,7 +249,7 @@ bool ntripClientConnect() length = strlen(serverRequest); serverRequest[length++] = '\r'; serverRequest[length++] = '\n'; - serverRequest[length++] = 0; + serverRequest[length] = 0; // Set up the credentials char credentials[CREDENTIALS_BUFFER_SIZE]; @@ -657,7 +658,8 @@ void ntripClientUpdate() { // Allocate the ntripClient structure networkUseDefaultInterface(); - ntripClient = new NetworkClient(); + if (!ntripClient) + ntripClient = new NetworkClient(); if (!ntripClient) { // Failed to allocate the ntripClient structure @@ -717,7 +719,7 @@ void ntripClientUpdate() if (ntripClientReceiveDataAvailable() < strlen("ICY 200 OK")) // Wait until at least a few bytes have arrived { // Check for response timeout - if (millis() - ntripClientTimer > NTRIP_CLIENT_RESPONSE_TIMEOUT) + if ((millis() - ntripClientTimer) > NTRIP_CLIENT_RESPONSE_TIMEOUT) { // NTRIP web service did not respond if (ntripClientConnectLimitReached()) // Updates ntripClientConnectionAttemptTimeout @@ -759,6 +761,7 @@ void ntripClientUpdate() { systemPrintf("Caster may not have mountpoint %s. Caster responded with problem: %s\r\n", settings.ntripClient_MountPoint, response); + systemPrintln("ntripClient shutdown. Please update the mountpoint and reconnect"); // Stop NTRIP client operations ntripClientForceShutdown(); @@ -803,6 +806,7 @@ void ntripClientUpdate() // We don't use a task because we use I2C hardware (and don't have a semaphore). online.ntripClient = true; ntripClientStartTime = millis(); + ntripClient->setConnectionTimeout(NTRIP_CLIENT_RECEIVE_DATA_TIMEOUT); ntripClientSetState(NTRIP_CLIENT_CONNECTED); } } @@ -919,9 +923,10 @@ void ntripClientUpdate() { // Push RTCM to GNSS module over I2C / SPI gnss->pushRawData(rtcmData, rtcmCount); + sempParseNextBytes(rtcmParse, rtcmData, rtcmCount); // Parse the data for RTCM1005/1006 if ((settings.debugCorrections || settings.debugNtripClientRtcm || - PERIODIC_DISPLAY(PD_NTRIP_CLIENT_DATA)) && + PERIODIC_DISPLAY(PD_NTRIP_CLIENT_DATA)) && (!inMainMenu)) { PERIODIC_CLEAR(PD_NTRIP_CLIENT_DATA); @@ -931,7 +936,7 @@ void ntripClientUpdate() else { if ((settings.debugCorrections || settings.debugNtripClientRtcm || - PERIODIC_DISPLAY(PD_NTRIP_CLIENT_DATA)) && + PERIODIC_DISPLAY(PD_NTRIP_CLIENT_DATA)) && (!inMainMenu)) { PERIODIC_CLEAR(PD_NTRIP_CLIENT_DATA); @@ -943,12 +948,15 @@ void ntripClientUpdate() } } } + + // Now that the ntripClient->read is complete, write GPGGA if needed and available. See #695 + pushGPGGA(nullptr); } break; } // Periodically display the NTRIP client state - if (PERIODIC_DISPLAY(PD_NTRIP_CLIENT_STATE)) + if (PERIODIC_DISPLAY(PD_NTRIP_CLIENT_STATE) && !inMainMenu) { systemPrintf("NTRIP Client state: %s%s\r\n", ntripClientStateName[ntripClientState], line); PERIODIC_CLEAR(PD_NTRIP_CLIENT_STATE); diff --git a/Firmware/RTK_Everywhere/NtripServer.ino b/Firmware/RTK_Everywhere/NtripServer.ino index 85a5417e5..1353783ac 100644 --- a/Firmware/RTK_Everywhere/NtripServer.ino +++ b/Firmware/RTK_Everywhere/NtripServer.ino @@ -192,10 +192,11 @@ bool ntripServerConnectCaster(int serverIndex) char hostname[51]; strncpy(hostname, settings.ntripServer_CasterHost[serverIndex], sizeof(hostname) - 1); // strtok modifies string to be parsed so we create a copy - char *token = strtok(hostname, "//"); + char *preservedPointer; + char *token = strtok_r(hostname, "//", &preservedPointer); if (token != nullptr) { - token = strtok(nullptr, "//"); // Advance to data after // + token = strtok_r(nullptr, "//", &preservedPointer); // Advance to data after // if (token != nullptr) strcpy(settings.ntripServer_CasterHost[serverIndex], token); } @@ -249,8 +250,8 @@ bool ntripServerConnectLimitReached(int serverIndex) // Shutdown the NTRIP server ntripServerStop(serverIndex, limitReached || (!ntripServerEnabled(serverIndex, nullptr))); - ntripServer->connectionAttempts++; - ntripServer->connectionAttemptsTotal++; + ntripServer->connectionAttempts = ntripServer->connectionAttempts + 1; + ntripServer->connectionAttemptsTotal = ntripServer->connectionAttemptsTotal + 1; if (settings.debugNtripServerState) ntripServerPrintStatus(serverIndex); @@ -311,9 +312,9 @@ bool ntripServerEnabled(int serverIndex, const char ** line) { if (line) { - if (settings.ntripServer_CasterHost[0] == 0) + if (settings.ntripServer_CasterHost[serverIndex][0] == 0) *line = ", Caster host not specified!"; - else if (settings.ntripServer_CasterPort == 0) + else if (settings.ntripServer_CasterPort[serverIndex] == 0) *line = ", Caster port not specified!"; else *line = ", Mount point not specified!"; @@ -379,7 +380,7 @@ void ntripServerPrintStatus(int serverIndex) if (ntripServer->state == NTRIP_SERVER_CASTING) // Use ntripServer->timer since it gets reset after each successful data // reception from the NTRIP caster - milliseconds = ntripServer->timer - ntripServer->startTime; + milliseconds = ntripServer->getUptime(); else { milliseconds = ntripServer->startTime; @@ -425,14 +426,7 @@ void ntripServerProcessRTCM(int serverIndex, uint8_t incoming) (!settings.enableRtcmMessageChecking) && (!inMainMenu) && ntripServer->bytesSent) { PERIODIC_CLEAR(PD_NTRIP_SERVER_DATA); - printTimeStamp(); - // 1 2 3 - // 123456789012345678901234567890 - // YYYY-mm-dd HH:MM:SS.xxxrn0 - struct tm timeinfo = rtc.getTimeStruct(); - char timestamp[30]; - strftime(timestamp, sizeof(timestamp), "%Y-%m-%d %H:%M:%S", &timeinfo); - systemPrintf(" Tx%d RTCM: %s.%03ld, %d bytes sent\r\n", serverIndex, timestamp, rtc.getMillis(), + systemPrintf(" Tx%d RTCM: %s, %d bytes sent\r\n", serverIndex, getTimeStamp(), ntripServer->rtcmBytesSent); ntripServer->rtcmBytesSent = 0; } @@ -440,22 +434,27 @@ void ntripServerProcessRTCM(int serverIndex, uint8_t incoming) } // If we have not gotten new RTCM bytes for a period of time, assume end of frame - if (((millis() - ntripServer->timer) > 100) && (ntripServer->bytesSent > 0)) - { - if ((!inMainMenu) && settings.debugNtripServerRtcm) - systemPrintf("NTRIP Server %d transmitted %d RTCM bytes to Caster\r\n", serverIndex, - ntripServer->bytesSent); - - ntripServer->bytesSent = 0; - } + if (ntripServer->checkBytesSentAndReset(100) && (!inMainMenu) && settings.debugNtripServerRtcm) + systemPrintf("NTRIP Server %d transmitted %d RTCM bytes to Caster\r\n", serverIndex, + ntripServer->bytesSent); if (ntripServer->networkClient && ntripServer->networkClient->connected()) { - ntripServer->networkClient->write(incoming); // Send this byte to socket - ntripServer->bytesSent++; - ntripServer->rtcmBytesSent++; - ntripServer->timer = millis(); - netOutgoingRTCM = true; + if (ntripServer->networkClient->write(incoming) == 1) // Send this byte to socket + { + ntripServer->updateTimerAndBytesSent(); + netOutgoingRTCM = true; + while (ntripServer->networkClient->available()) + ntripServer->networkClient->read(); // Absorb any unwanted incoming traffic + } + // Failed to write the data + else + { + // Done with this client connection + if (settings.debugNtripServerRtcm && (!inMainMenu)) + systemPrintf("NTRIP Server %d broken connection to %s\r\n", serverIndex, + settings.ntripServer_CasterHost[serverIndex]); + } } } @@ -494,7 +493,7 @@ void ntripServerRestart(int serverIndex) // Save the previous uptime value if (ntripServer->state == NTRIP_SERVER_CASTING) - ntripServer->startTime = ntripServer->timer - ntripServer->startTime; + ntripServer->startTime = ntripServer->getUptime(); ntripServerConnectLimitReached(serverIndex); } @@ -572,7 +571,7 @@ void ntripServerStop(int serverIndex, bool shutdown) // Increase timeouts if we started the network if (ntripServer->state > NTRIP_SERVER_OFF) // Mark the Server stop so that we don't immediately attempt re-connect to Caster - ntripServer->timer = millis(); + ntripServer->setTimerToMillis(); // Determine the next NTRIP server state online.ntripServer[serverIndex] = false; @@ -684,8 +683,7 @@ void ntripServerUpdate(int serverIndex) // Failed to connect to to the network, attempt to restart the network ntripServerRestart(serverIndex); - else if (settings.enableNtripServer && - (millis() - ntripServer->lastConnectionAttempt > ntripServer->connectionAttemptTimeout)) + else if (settings.enableNtripServer) { // No RTCM correction data sent yet rtcmPacketsSent = 0; @@ -703,7 +701,7 @@ void ntripServerUpdate(int serverIndex) // Initiate the connection to the NTRIP caster case NTRIP_SERVER_CONNECTING: // Delay before opening the NTRIP server connection - if ((millis() - ntripServer->timer) >= ntripServer->connectionAttemptTimeout) + if (ntripServer->checkConnectionAttemptTimeout()) { // Attempt a connection to the NTRIP caster if (!ntripServerConnectCaster(serverIndex)) @@ -717,7 +715,7 @@ void ntripServerUpdate(int serverIndex) else { // Connection open to NTRIP caster, wait for the authorization response - ntripServer->timer = millis(); + ntripServer->setTimerToMillis(); ntripServerSetState(serverIndex, NTRIP_SERVER_AUTHORIZATION); } } @@ -730,7 +728,7 @@ void ntripServerUpdate(int serverIndex) strlen("ICY 200 OK")) // Wait until at least a few bytes have arrived { // Check for response timeout - if (millis() - ntripServer->timer > 10000) + if (ntripServer->millisSinceTimer() > 10000) { if (ntripServerConnectLimitReached(serverIndex)) systemPrintf( @@ -777,7 +775,7 @@ void ntripServerUpdate(int serverIndex) settings.ntripServer_MountPoint[serverIndex]); // Connection is now open, start the RTCM correction data timer - ntripServer->timer = millis(); + ntripServer->setTimerToMillis(); // We don't use a task because we use I2C hardware (and don't have a semaphore). online.ntripServer[serverIndex] = true; @@ -822,7 +820,7 @@ void ntripServerUpdate(int serverIndex) settings.ntripServer_CasterHost[serverIndex]); ntripServerRestart(serverIndex); } - else if ((millis() - ntripServer->timer) > (10 * 1000)) + else if (ntripServer->millisSinceTimer() > (10 * 1000)) { // GNSS stopped sending RTCM correction data systemPrintf("NTRIP Server %d breaking connection to %s due to lack of RTCM data!\r\n", serverIndex, @@ -837,7 +835,7 @@ void ntripServerUpdate(int serverIndex) // connection. However increasing backoff delays should be // added when the NTRIP caster fails after a short connection // interval. - if (((millis() - ntripServer->startTime) > NTRIP_SERVER_CONNECTION_TIME) && + if ((ntripServer->millisSinceStartTime() > NTRIP_SERVER_CONNECTION_TIME) && (ntripServer->connectionAttempts || ntripServer->connectionAttemptTimeout)) { // After a long connection period, reset the attempt counter @@ -852,7 +850,7 @@ void ntripServerUpdate(int serverIndex) } // Periodically display the state - if (PERIODIC_DISPLAY(PD_NTRIP_SERVER_STATE)) + if (PERIODIC_DISPLAY(PD_NTRIP_SERVER_STATE) && !inMainMenu) { systemPrintf("NTRIP Server %d state: %s%s\r\n", serverIndex, ntripServerStateName[ntripServer->state], line); diff --git a/Firmware/RTK_Everywhere/Patch/libbt.a b/Firmware/RTK_Everywhere/Patch/libbt.a new file mode 100644 index 000000000..f56a28f7f Binary files /dev/null and b/Firmware/RTK_Everywhere/Patch/libbt.a differ diff --git a/Firmware/RTK_Everywhere/PointPerfectLibrary.ino b/Firmware/RTK_Everywhere/PointPerfectLibrary.ino index 1116dd4ca..ee8bbdf1e 100644 --- a/Firmware/RTK_Everywhere/PointPerfectLibrary.ino +++ b/Firmware/RTK_Everywhere/PointPerfectLibrary.ino @@ -13,7 +13,7 @@ void updatePplTask(void *e) while (task.updatePplTaskStopRequest == false) { // Display an alive message - if (PERIODIC_DISPLAY(PD_TASK_UPDATE_PPL)) + if (PERIODIC_DISPLAY(PD_TASK_UPDATE_PPL) && !inMainMenu) { PERIODIC_CLEAR(PD_TASK_UPDATE_PPL); systemPrintln("UpdatePplTask running"); @@ -48,6 +48,7 @@ void updatePplTask(void *e) } gnss->pushRawData(pplRtcmBuffer, rtcmLength); + sempParseNextBytes(rtcmParse, pplRtcmBuffer, rtcmLength); // Parse the data for RTCM1005/1006 if (settings.debugCorrections == true && !inMainMenu) systemPrintf("Received %d RTCM bytes from PPL. Pushed to the GNSS.\r\n", rtcmLength); @@ -71,7 +72,8 @@ void updatePplTask(void *e) } // Check to see if our key has expired - if (millis() > pplKeyExpirationMs) + // https://stackoverflow.com/a/3097744 - see issue #742 + if (!((long)(pplKeyExpirationMs - millis()) > 0)) { if (settings.debugCorrections == true) systemPrintln("Key has expired. Going to new key."); @@ -251,7 +253,7 @@ void updatePPL() if (settings.debugCorrections == true) { - if (millis() - pplReport > 5000) + if ((millis() - pplReport) > 5000) { pplReport = millis(); @@ -307,7 +309,7 @@ void updatePPL() if (rtkTimeToFixMs == 0) rtkTimeToFixMs = millis(); - if (millis() - pplReport > 5000) + if ((millis() - pplReport) > 5000) { pplReport = millis(); @@ -369,6 +371,15 @@ bool getUsablePplKey(char *keyBuffer, int keyBufferSize) if (daysRemainingCurrent >= 0) // Use the current key { + // Notes: + // pplKeyExpirationMs is unsigned long (32-bit unsigned) + // settings.pointPerfectCurrentKeyStart is uint64_t (64-bit unsigned) + // settings.pointPerfectCurrentKeyDuration is uint64_t (64-bit unsigned) + // secondsFrom Epoch returns long (32-bit signed) + // PP keys are valid for (typically) 4 weeks so key end (start + duration) + // could be up to ~28 days away. I.e. well within the 2^32 millis (49.7 day) + // wrap-around. + pplKeyExpirationMs = secondsFromEpoch(settings.pointPerfectCurrentKeyStart + settings.pointPerfectCurrentKeyDuration) * 1000; diff --git a/Firmware/RTK_Everywhere/RTK_Everywhere.ino b/Firmware/RTK_Everywhere/RTK_Everywhere.ino index 1064d296b..f97109fd4 100644 --- a/Firmware/RTK_Everywhere/RTK_Everywhere.ino +++ b/Firmware/RTK_Everywhere/RTK_Everywhere.ino @@ -78,6 +78,10 @@ */ +// While we wait for the next hardware revisions, Flex and Torch can be manually enabled: +//#define FLEX_OVERRIDE // Uncomment to force support for Flex +//#define TORCH_X2_OVERRIDE // Uncomment to force support for Torch X2 + // To reduce compile times, various parts of the firmware can be disabled/removed if they are not // needed during development #define COMPILE_BT // Comment out to remove Bluetooth functionality @@ -85,9 +89,13 @@ #define COMPILE_ETHERNET // Comment out to remove Ethernet (W5500) support #define COMPILE_CELLULAR // Comment out to remove cellular modem support +#ifdef COMPILE_BT +#define COMPILE_AUTHENTICATION // Comment out to disable MFi authentication +#endif + #ifdef COMPILE_WIFI #define COMPILE_AP // Requires WiFi. Comment out to remove Access Point functionality -#define COMPILE_ESPNOW // Requires WiFi. Comment out to remove ESP-Now functionality. +#define COMPILE_ESPNOW // Requires WiFi. Comment out to remove ESP-NOW functionality. #endif // COMPILE_WIFI #define COMPILE_LG290P // Comment out to remove LG290P functionality @@ -202,6 +210,10 @@ int pin_gnssStatusLED = PIN_UNDEFINED; // LED on Torch int pin_muxA = PIN_UNDEFINED; int pin_muxB = PIN_UNDEFINED; +int pin_mux1 = PIN_UNDEFINED; +int pin_mux2 = PIN_UNDEFINED; +int pin_mux3 = PIN_UNDEFINED; +int pin_mux4 = PIN_UNDEFINED; int pin_powerSenseAndControl = PIN_UNDEFINED; // Power button and power down I/O on Facet int pin_modeButton = PIN_UNDEFINED; // Mode button on EVK int pin_powerButton = PIN_UNDEFINED; // Power and general purpose button on Torch @@ -273,6 +285,17 @@ int gpioExpander_right = 2; int gpioExpander_left = 3; int gpioExpander_center = 4; int gpioExpander_cardDetect = 5; + +const int gpioExpanderSwitch_S1 = 0; // Controls U16 switch 1: connect ESP UART0 to CH342 or SW2 +const int gpioExpanderSwitch_S2 = 1; // Controls U17 switch 2: connect SW1 to RS232 Output or GNSS UART4 +const int gpioExpanderSwitch_S3 = 2; // Controls U18 switch 3: connect ESP UART2 to GNSS UART3 or LoRa UART2 +const int gpioExpanderSwitch_S4 = 3; // Controls U19 switch 4: connect GNSS UART2 to 4-pin JST TTL Serial or LoRa UART0 +const int gpioExpanderSwitch_LoraEnable = 4; // LoRa_EN +const int gpioExpanderSwitch_GNSS_Reset = 5; // RST_GNSS +const int gpioExpanderSwitch_LoraBoot = 6; // LoRa_BOOT0 - Used for bootloading the STM32 radio IC +const int gpioExpanderSwitch_PowerFastOff = 7; // PWRKILL +const int gpioExpanderNumSwitches = 8; + //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= // I2C for GNSS, battery gauge, display @@ -283,6 +306,7 @@ int gpioExpander_cardDetect = 5; TwoWire *i2c_0 = nullptr; TwoWire *i2c_1 = nullptr; TwoWire *i2cDisplay = nullptr; +TwoWire *i2cAuthCoPro = nullptr; //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- // LittleFS for storing settings for different user profiles @@ -307,6 +331,7 @@ const int COMMON_COORDINATES_MAX_STATIONS = 50; // Record up to 50 ECEF and Geod #include //http://librarymanager/All#ESP32Time by FBiego ESP32Time rtc; unsigned long syncRTCInterval = 1000; // To begin, sync RTC every second. Interval can be increased once sync'd. +void printTimeStamp(bool always = false); // Header //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- // microSD Interface @@ -315,6 +340,8 @@ unsigned long syncRTCInterval = 1000; // To begin, sync RTC every second. Interv void beginSPI(bool force = false); // Header +// Important note: the firmware currently requires SdFat v2.1.1 +// sd->begin will crash second time around with ~v2.2.3 #include "SdFat.h" //http://librarymanager/All#sdfat_exfat by Bill Greiman. SdFat *sd; @@ -322,20 +349,29 @@ SdFat *sd; SdFile *logFile; // File that all GNSS messages sentences are written to unsigned long lastUBXLogSyncTime; // Used to record to SD every half second -int startLogTime_minutes; // Mark when we start any logging so we can stop logging after maxLogTime_minutes -int startCurrentLogTime_minutes; -// Mark when we start this specific log file so we can close it after x minutes and start a new one +int startLogTime_minutes; // Mark when we (re)start any logging so we can stop logging after maxLogTime_minutes +unsigned long nextLogTime_ms; // Open the next log file at this many millis() // System crashes if two tasks access a file at the same time // So we use a semaphore to see if the file system is available -SemaphoreHandle_t sdCardSemaphore; +// https://github.com/espressif/arduino-esp32/blob/master/libraries/ESP32/examples/FreeRTOS/Mutex/Mutex.ino#L11 +SemaphoreHandle_t sdCardSemaphore = NULL; TickType_t loggingSemaphoreWait_ms = 10 / portTICK_PERIOD_MS; const TickType_t fatSemaphore_shortWait_ms = 10 / portTICK_PERIOD_MS; const TickType_t fatSemaphore_longWait_ms = 200 / portTICK_PERIOD_MS; +const TickType_t ringBuffer_shortWait_ms = 20 / portTICK_PERIOD_MS; +const TickType_t ringBuffer_longWait_ms = 300 / portTICK_PERIOD_MS; + +// ringBuffer semaphore - prevent processUart1Message (gnssReadTask) and handleGnssDataTask +// from gatecrashing each other. +SemaphoreHandle_t ringBufferSemaphore = NULL; +const char *ringBufferSemaphoreHolder = "None"; // Display used/free space in menu and config page uint64_t sdCardSize; uint64_t sdFreeSpace; +uint64_t mosaicSdCardSize; +uint64_t mosaicSdFreeSpace; bool outOfSDSpace; const uint32_t sdMinAvailableSpace = 10000000; // Minimum available bytes before SD is marked as out of space @@ -358,6 +394,9 @@ const int sdSizeCheckStackSize = 3000; bool sdSizeCheckTaskComplete; char logFileName[sizeof("SFE_Reference_Station_230101_120101.ubx_plusExtraSpace")] = {0}; + +bool savePossibleSettings = true; // Save possible vs. available settings. See recordSystemSettingsToFile for details + //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- // WiFi support @@ -369,12 +408,12 @@ RTK_WIFI wifi(false); // WiFi Globals - For other module direct access WIFI_CHANNEL_t wifiChannel; // Current WiFi channel number -bool wifiEspNowOnline; // ESP-Now started successfully +bool wifiEspNowOnline; // ESP-NOW started successfully bool wifiEspNowRunning; // False: stopped, True: starting, running, stopping uint32_t wifiReconnectionTimer; // Delay before reconnection, timer running when non-zero bool wifiSoftApOnline; // WiFi soft AP started successfully bool wifiSoftApRunning; // False: stopped, True: starting, running, stopping -bool wifiSoftApConnected; // False: no client connected, True: client connected +bool wifiSoftApConnected; // False: no client connected, True: client connected bool wifiStationOnline; // WiFi station started successfully bool wifiStationRunning; // False: stopped, True: starting, running, stopping @@ -429,6 +468,7 @@ bool otaRequestFirmwareUpdate = false; bool enableRCFirmware; // Goes true from AP config page bool currentlyParsingData; // Goes true when we hit 750ms timeout with new data +bool tcpServerInCasterMode;// True when TCP server is running in caster mode // Give up connecting after this number of attempts // Connection attempts are throttled to increase the time between attempts @@ -460,7 +500,7 @@ uint32_t timTpEpoch; uint32_t timTpMicros; unsigned long lastARPLog; // Time of the last ARP log event -bool newARPAvailable; +bool newARPAvailable = false; int64_t ARPECEFX; // ARP ECEF is 38-bit signed int64_t ARPECEFY; int64_t ARPECEFZ; @@ -472,6 +512,7 @@ unsigned long rtcmLastPacketReceived; // Time stamp of RTCM coming in (from BT, bool usbSerialIncomingRtcm; // Incoming RTCM over the USB serial port #define RTCM_CORRECTION_INPUT_TIMEOUT (2 * 1000) + //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= // Extensible Message Parser @@ -480,13 +521,13 @@ bool usbSerialIncomingRtcm; // Incoming RTCM over the USB serial port SEMP_PARSE_STATE *rtkParse = nullptr; SEMP_PARSE_STATE *sbfParse = nullptr; // mosaic-X5 SEMP_PARSE_STATE *spartnParse = nullptr; // mosaic-X5 +SEMP_PARSE_STATE *rtcmParse = nullptr; // Parse incoming corrections for RTCM1005 / 1006 base locations //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= // Share GNSS variables //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= -// Note: GnssPlatform gnssPlatform has been replaced by present.gnss_zedf9p etc. -char gnssFirmwareVersion[21]; // mosaic-X5 could be 20 digits +char gnssFirmwareVersion[32]; // mosaic-X5 could be 20 digits. LG290P could be 31 characters. int gnssFirmwareVersionInt; char gnssUniqueId[21]; // um980 ID is 16 digits. mosaic-X5 could be 20 digits //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= @@ -548,6 +589,8 @@ volatile bool forwardGnssDataToUsbSerial; HardwareSerial *serialGNSS = nullptr; // Don't instantiate until we know what gnssPlatform we're on HardwareSerial *serial2GNSS = nullptr; // Don't instantiate until we know what gnssPlatform we're on +volatile bool inDirectConnectMode = false; // Global state to indicate if GNSS/LoRa has direct connection for update + #define SERIAL_SIZE_TX 512 uint8_t wBuffer[SERIAL_SIZE_TX]; // Buffer for writing from incoming SPP to F9P const int btReadTaskStackSize = 4000; @@ -564,7 +607,7 @@ uint8_t *ringBuffer; // Buffer for reading from GNSS receiver. At 230400bps, 230 const int gnssReadTaskStackSize = 8000; const size_t sempGnssReadBufferSize = 8000; // Make the SEMP buffer size the ~same -const int handleGnssDataTaskStackSize = 3000; +const int handleGnssDataTaskStackSize = 4000; TaskHandle_t pinBluetoothTaskHandle; // Dummy task to start hardware on an assigned core volatile bool bluetoothPinned; // This variable is touched by core 0 but checked by core 1. Must be volatile. @@ -576,9 +619,6 @@ int bufferOverruns; // Running count of possible data lo bool zedUartPassed; // Goes true during testing if ESP can communicate with ZED over UART const uint8_t btEscapeCharacter = '+'; const uint8_t btMaxEscapeCharacters = 3; // Number of characters needed to enter remote command mode over Bluetooth -const uint8_t btAppCommandCharacter = '-'; -const uint8_t btMaxAppCommandCharacters = 10; // Number of characters needed to enter app command mode over Bluetooth -bool runCommandMode; // Goes true when user or remote app enters ---------- command mode sequence //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= @@ -640,6 +680,7 @@ char *incomingSettings; int incomingSettingsSpot; unsigned long timeSinceLastIncomingSetting; unsigned long lastDynamicDataUpdate; +bool websocketConnected = false; #ifdef COMPILE_WIFI #ifdef COMPILE_AP @@ -649,8 +690,6 @@ unsigned long lastDynamicDataUpdate; #include // Port 80 #include // Needed for web sockets only - on port 81 -bool websocketConnected = false; - #endif // COMPILE_AP #endif // COMPILE_WIFI @@ -698,6 +737,7 @@ IPAddress ethernetSubnetMask; // }; volatile struct timeval ethernetNtpTv; // This will hold the time the Ethernet NTP packet arrived bool ntpLogIncreasing; +bool ethernetRestartRequested = false; // Perform ETH.end() to disconnect TCP resources #endif // COMPILE_ETHERNET unsigned long lastEthernetCheck; // Prevents cable checking from continually happening @@ -758,6 +798,37 @@ uint8_t gpioExpander_lastReleased = 255; #define GPIO_EXPANDER_CARD_INSERTED 1 #define GPIO_EXPANDER_CARD_REMOVED 0 +SFE_PCA95XX *gpioExpanderSwitches = nullptr; + +//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= + +// MFi Authentication Coprocessor +//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= +#ifdef COMPILE_AUTHENTICATION + +#include // Click here to get the library: http://librarymanager/All#SparkFun_Apple_Accessory_Arduino_Library + +SparkFunAppleAccessoryDriver *appleAccessory; // Instantiated by beginAuthCoPro + +const char *sdp_service_name = "iAP2"; + +// UUID : Big-Endian +//static const uint8_t UUID_IAP2[] = {0x00, 0x00, 0x00, 0x00, 0xDE, 0xCA, 0xFA, 0xDE, 0xDE, 0xCA, 0xDE, 0xAF, 0xDE, 0xCA, 0xCA, 0xFF}; +// UUID : Little-Endian +static const uint8_t UUID_IAP2[] = {0xFF, 0xCA, 0xCA, 0xDE, 0xAF, 0xDE, 0xCA, 0xDE, 0xDE, 0xFA, 0xCA, 0xDE, 0x00, 0x00, 0x00, 0x00}; + +#endif + +// Storage for the latest NMEA GPGGA/GPRMC/GPGST - to be passed to the MFi Apple device +// We should optimse this with a Lee table... TODO +const size_t latestNmeaMaxLen = 100; +char *latestGPGGA; +char *latestGPRMC; +char *latestGPGST; +char *latestGPVTG; +const size_t latestEASessionDataMaxLen = 4001; // 1000 * 4 plus NULL +char *latestEASessionData; + //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= // Global variables @@ -765,13 +836,16 @@ uint8_t gpioExpander_lastReleased = 255; uint8_t wifiMACAddress[6]; // Display this address in the system menu uint8_t btMACAddress[6]; // Display this address when Bluetooth is enabled, otherwise display wifiMACAddress uint8_t ethernetMACAddress[6]; // Display this address when Ethernet is enabled, otherwise display wifiMACAddress -char deviceName[70]; // The serial string that is broadcast. Ex: 'EVK Base-BC61' +char deviceName[40]; // The serial string that is broadcast. E.g.: 'SparkFun Postcard-ABCD' +char serialNumber[5]; // The serial number for MFi. Ex: 'BC61' +char deviceFirmware[9]; // The firmware version for MFi. Ex: 'v2.2' const uint16_t menuTimeout = 60 * 10; // Menus will exit/timeout after this number of seconds int systemTime_minutes; // Used to test if logging is less than max minutes uint32_t powerPressedStartTime; // Times how long the user has been holding the power button, used for power down bool inMainMenu; // Set true when in the serial config menu system. bool btPrintEcho; // Set true when in the serial config menu system via Bluetooth. bool btPrintEchoExit; // When true, exit all config menus. +bool sendAccessoryHandshakeOnBtConnect = false; // Send accessory handshake on BT connect bool forceDisplayUpdate = true; // Goes true when setup is pressed, causes the display to refresh in real-time uint32_t lastSystemStateUpdate; @@ -798,7 +872,42 @@ uint32_t rtcmLastPacketSent; // Time stamp of RTCM going out (to NTRIP Server, E uint32_t maxSurveyInWait_s = 60L * 15L; // Re-start survey-in after X seconds -uint32_t lastSetupMenuChange; // Limits how much time is spent in the setup menu +typedef struct { + volatile unsigned long timer; + + SemaphoreHandle_t updateSemaphore = NULL; + + void setTimerToMillis() + { + if (updateSemaphore == NULL) + updateSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(updateSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + timer = millis(); + xSemaphoreGive(updateSemaphore); + } + } + + unsigned long millisSinceUpdate() + { + unsigned long retVal = 0; + if (updateSemaphore == NULL) + updateSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(updateSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + // The semaphore prevents the race condition where timer is updated after + // millis() is read but before the subtraction. It prevents retVal from underflowing + retVal = millis() - timer; + xSemaphoreGive(updateSemaphore); + } + return retVal; + } +} semaphoreProtectedTimer; +// Needs a mutex because the timer is updated by the button task +// but read by stateUpdate the loop. Prevents a race condition +// and the occasional glitching seen in the button menu +semaphoreProtectedTimer lastSetupMenuChange; // Limits how much time is spent in the setup menu + uint32_t lastTestMenuChange; // Avoids exiting the test menu for at least 1 second uint8_t setupSelectedButton = 0; // In Display Setup, start displaying at this button. This is the selected (highlighted) button. @@ -806,7 +915,7 @@ std::vector setupButtons; // A vector (linked list) of the setup 'b bool firstRoverStart; // Used to detect if the user is toggling the power button at POR to enter the test menu -bool newEventToRecord; // Goes true when INT pin goes high +bool newEventToRecord; // Goes true when INT pin goes high. Currently this is ZED-specific. uint32_t triggerCount; // Global copy - TM2 event counter uint32_t triggerTowMsR; // Global copy - Time Of Week of rising edge (ms) uint32_t triggerTowSubMsR; // Global copy - Millisecond fraction of Time Of Week of rising edge in nanoseconds @@ -837,7 +946,7 @@ uint32_t max_idle_count = MAX_IDLE_TIME_COUNT; bool bluetoothIncomingRTCM; bool bluetoothOutgoingRTCM; bool netIncomingRTCM; -bool netOutgoingRTCM; +volatile bool netOutgoingRTCM; volatile bool mqttClientDataReceived; // Flag for display uint16_t failedParserMessages_UBX; @@ -876,7 +985,7 @@ unsigned long loraLastIncomingSerial; // Last time a user sent a serial command. // Display boot times //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- -#define MAX_BOOT_TIME_ENTRIES 42 +#define MAX_BOOT_TIME_ENTRIES 50 uint8_t bootTimeIndex; uint32_t bootTime[MAX_BOOT_TIME_ENTRIES]; const char *bootTimeString[MAX_BOOT_TIME_ENTRIES]; @@ -1173,8 +1282,8 @@ void setup() DMW_b("identifyBoard"); identifyBoard(); // Determine what hardware platform we are running on. - DMW_b("commandIndexFill"); - if (!commandIndexFill()) // Initialize the command table index + DMW_b("commandIndexFillPossible"); + if (!commandIndexFillPossible()) // Initialize the command table index using possible settings reportFatalError("Failed to allocate and fill the commandIndex!"); DMW_b("beginBoard"); @@ -1193,20 +1302,12 @@ void setup() DMW_b("tickerBegin"); tickerBegin(); // Start ticker tasks for LEDs and beeper - DMW_b("checkUpdateLoraFirmware"); - if (checkUpdateLoraFirmware() == true) // Check if updateLoraFirmware.txt exists - beginLoraFirmwareUpdate(); - - DMW_b("um980FirmwareCheckUpdate"); - if (um980FirmwareCheckUpdate() == true) // Check if updateUm980Firmware.txt exists - um980FirmwareBeginUpdate(); - DMW_b("beginPsram"); beginPsram(); // Initialize PSRAM (if available). Needs to occur before beginGnssUart and other malloc users. DMW_b("beginMux"); - beginMux(); // Must come before I2C activity to avoid external devices from corrupting the bus. See issue #474: - // https://github.com/sparkfun/SparkFun_RTK_Firmware/issues/474 + beginMux(); // Must come before I2C activity to avoid external devices from corrupting the bus. See issue 474 + // https://github.com/sparkfun/SparkFun_RTK_Firmware/issues/474 DMW_b("peripheralsOn"); peripheralsOn(); // Enable power for the display, SD, etc @@ -1214,14 +1315,55 @@ void setup() DMW_b("beginI2C"); beginI2C(); // Requires settings and peripheral power (if applicable). + DMW_b("beginGpioExpanderSwitches"); + beginGpioExpanderSwitches(); // Start the GPIO expander for switch control + DMW_b("beginDisplay"); beginDisplay(i2cDisplay); // Start display to be able to display any errors + DMW_b("beginAuthCoPro"); + beginAuthCoPro(i2cAuthCoPro); // Discover and start authentication coprocessor + DMW_b("verifyTables"); verifyTables(); // Verify the consistency of the internal tables + DMW_b("beginVersion"); beginVersion(); // Assemble platform name. Requires settings/LFS. + if ((settings.haltOnPanic) && (esp_reset_reason() == ESP_RST_PANIC)) // Halt on PANIC - to trap rare crashes + reportFatalError("ESP_RST_PANIC"); + + DMW_b("displaySplash"); + displaySplash(); // Display the RTK product name and firmware version + + DMW_b("beginButtons"); + beginButtons(); // Start task for button monitoring. Needed for beginSD (gpioExpander) + + DMW_b("beginSD"); + beginSD(); // Requires settings. Test if SD is present + + DMW_b("loadSettings"); + loadSettings(); // Attempt to load settings after SD is started so we can read the settings file if available + + DMW_b("gnssDetectReceiverType"); + gnssDetectReceiverType(); // If we don't know the receiver from the platform, auto-detect it. Uses settings. + + DMW_b("checkUpdateLoraFirmware"); + if (checkUpdateLoraFirmware() == true) // Check if updateLoraFirmware.txt exists + beginLoraFirmwareUpdate(); // Needs I2C, GPIO Expander Switches, display, buttons, etc. + + DMW_b("um980FirmwareCheckUpdate"); + if (um980FirmwareCheckUpdate() == true) // UM980 needs special treatment + um980FirmwareBeginUpdate(); // Needs Flex GNSS, I2C, GPIO Expander Switches, display, buttons, etc. + + DMW_b("gnssFirmwareCheckUpdate"); + if (gnssFirmwareCheckUpdate() == true) // Check if updateGnssFirmware.txt exists + gnssFirmwareBeginUpdate(); // Needs Flex GNSS, I2C, GPIO Expander Switches, display, buttons, etc. + + DMW_b("commandIndexFillActual"); + commandIndexFillActual(); // Shrink the commandIndex table now we're certain what GNSS we have + recordSystemSettings(); // Save the reduced settings now we're certain what GNSS we have + DMW_b("beginGnssUart"); beginGnssUart(); // Requires settings. Start the UART connected to the GNSS receiver on core 0. Start before // gnssBegin in case it is needed (Torch). @@ -1229,17 +1371,14 @@ void setup() DMW_b("beginGnssUart2"); beginGnssUart2(); - DMW_b("displaySplash"); - displaySplash(); // Display the RTK product name and firmware version - DMW_b("gnss->begin"); gnss->begin(); // Requires settings. Connect to GNSS to get module type - DMW_b("beginSD"); - beginSD(); // Requires settings. Test if SD is present + DMW_b("beginRtcmParse"); + beginRtcmParse(); - DMW_b("loadSettings"); - loadSettings(); // Attempt to load settings after SD is started so we can read the settings file if available + DMW_b("tiltDetect"); + tiltDetect(); // If we don't know if there is a tilt compensation sensor, auto-detect it. Uses settings. // DEBUG_NEARLY_EVERYTHING // Debug nearly all the things // DEBUG_THE_ESSENTIALS // Debug the essentials - handy for measuring the boot time after a factory reset @@ -1279,14 +1418,12 @@ void setup() DMW_b("beginInterrupts"); beginInterrupts(); // Begin the TP interrupts - DMW_b("beginButtons"); - beginButtons(); // Start task for button monitoring. - DMW_b("beginSystemState"); beginSystemState(); // Determine initial system state. DMW_b("rtcUpdate"); - rtcUpdate(); // The GNSS likely has a time/date. Update ESP32 RTC to match. Needed for PointPerfect key expiration. + rtcUpdate(); // The GNSS likely has a time/date. Update ESP32 RTC to match. Needed for PointPerfect key + // expiration. systemFlush(); // Complete any previous prints @@ -1396,6 +1533,9 @@ void loop() DMW_c("networkUpdate"); networkUpdate(); // Maintain the network connections + DMW_c("updateAuthCoPro"); + updateAuthCoPro(); // Update the Apple Accessory + DMW_c("updateLBand"); updateLBand(); // Update L-Band @@ -1437,6 +1577,27 @@ void loopDelay() delay(10); } +bool logTimeExceeded() // Limit total logging time to maxLogTime_minutes +{ + if (settings.maxLogTime_minutes == 0) // No limit if maxLogTime_minutes is zero + return false; + + return ((systemTime_minutes - startLogTime_minutes) >= settings.maxLogTime_minutes); +} + +bool logLengthExceeded() // Limit individual files to maxLogLength_minutes +{ + if (settings.maxLogLength_minutes == 0) // No limit if maxLogLength_minutes is zero + return false; + + if (nextLogTime_ms == 0) // Keep logging if nextLogTime_ms has not been set + return false; + + // Note: this will roll over every 49.71 days... + // Solution: https://stackoverflow.com/a/3097744 - see issue #742 + return (!((long)(nextLogTime_ms - millis()) > 0)); +} + // Create or close files as needed (startup or as the user changes settings) // Push new data to log as needed void logUpdate() @@ -1458,11 +1619,12 @@ void logUpdate() if (outOfSDSpace == true) return; // We can't log if we are out of SD space - if (online.logging == false && settings.enableLogging == true && blockLogging == false) + if (online.logging == false && settings.enableLogging == true && blockLogging == false && !logTimeExceeded()) { if (beginLogging() == false) { // Failed to create file, block future logging attempts + systemPrintln("beginLogging failed. Blocking further attempts"); blockLogging = true; return; } @@ -1474,93 +1636,26 @@ void logUpdate() // Close down file endSD(false, true); } - else if (online.logging == true && settings.enableLogging == true && - (systemTime_minutes - startCurrentLogTime_minutes) >= settings.maxLogLength_minutes) + else if (online.logging == true && settings.enableLogging == true && (logLengthExceeded() || logTimeExceeded())) { - endSD(false, true); // Close down file. A new one will be created at the next calling of updateLogs(). - } - - if (online.logging == true) - { - // Record any pending trigger events - if (newEventToRecord == true) + if (logTimeExceeded()) { - systemPrintln("Recording event"); - - // Record trigger count with Time Of Week of rising edge (ms), Millisecond fraction of Time Of Week of - // rising edge (ns), and accuracy estimate (ns) - char eventData[82]; // Max NMEA sentence length is 82 - snprintf(eventData, sizeof(eventData), "%d,%d,%d,%d", triggerCount, triggerTowMsR, triggerTowSubMsR, - triggerAccEst); - - char nmeaMessage[82]; // Max NMEA sentence length is 82 - createNMEASentence(CUSTOM_NMEA_TYPE_EVENT, nmeaMessage, sizeof(nmeaMessage), - eventData); // textID, buffer, sizeOfBuffer, text - - if (xSemaphoreTake(sdCardSemaphore, fatSemaphore_shortWait_ms) == pdPASS) - { - markSemaphore(FUNCTION_EVENT); - - logFile->println(nmeaMessage); - - xSemaphoreGive(sdCardSemaphore); - newEventToRecord = false; - } - else - { - char semaphoreHolder[50]; - getSemaphoreFunction(semaphoreHolder); - - // While a retry does occur during the next loop, it is possible to lose - // trigger events if they occur too rapidly or if the log file is closed - // before the trigger event is written! - log_w("sdCardSemaphore failed to yield, held by %s, RTK_Everywhere.ino line %d", semaphoreHolder, - __LINE__); - } + if (!inMainMenu) + systemPrintln("Log file: maximum logging time reached"); + endSD(false, true); // Close down SD. } - - // Record the Antenna Reference Position - if available - if (newARPAvailable == true && settings.enableARPLogging && - ((millis() - lastARPLog) > (settings.ARPLoggingInterval_s * 1000))) + else { - systemPrintln("Recording Antenna Reference Position"); - - lastARPLog = millis(); - newARPAvailable = false; - - double x = ARPECEFX; - x /= 10000.0; // Convert to m - double y = ARPECEFY; - y /= 10000.0; // Convert to m - double z = ARPECEFZ; - z /= 10000.0; // Convert to m - double h = ARPECEFH; - h /= 10000.0; // Convert to m - char ARPData[82]; // Max NMEA sentence length is 82 - snprintf(ARPData, sizeof(ARPData), "%.4f,%.4f,%.4f,%.4f", x, y, z, h); - - char nmeaMessage[82]; // Max NMEA sentence length is 82 - createNMEASentence(CUSTOM_NMEA_TYPE_ARP_ECEF_XYZH, nmeaMessage, sizeof(nmeaMessage), - ARPData); // textID, buffer, sizeOfBuffer, text - - if (xSemaphoreTake(sdCardSemaphore, fatSemaphore_shortWait_ms) == pdPASS) - { - markSemaphore(FUNCTION_EVENT); - - logFile->println(nmeaMessage); - - xSemaphoreGive(sdCardSemaphore); - newEventToRecord = false; - } - else - { - char semaphoreHolder[50]; - getSemaphoreFunction(semaphoreHolder); - log_w("sdCardSemaphore failed to yield, held by %s, RTK_Everywhere.ino line %d", semaphoreHolder, - __LINE__); - } + if (!inMainMenu) + systemPrintln("Log file: log length reached"); + endLogging(false, true); //(gotSemaphore, releaseSemaphore) Close file. Reset parser stats. + beginLogging(); // Create new file based on current RTC. + setLoggingType(); // Determine if we are standard, PPP, or custom. Changes logging icon accordingly. } + } + if (online.logging == true) + { // Report file sizes to show recording is working if ((millis() - lastFileReport) > 5000) { @@ -1568,15 +1663,15 @@ void logUpdate() { lastFileReport = millis(); - if (settings.enablePrintLogFileStatus) + if ((settings.enablePrintLogFileStatus) && (!inMainMenu)) { systemPrintf("Log file size: %lld", logFileSize); - if ((systemTime_minutes - startLogTime_minutes) < settings.maxLogTime_minutes) + if (!logTimeExceeded()) { // Calculate generation and write speeds every 5 seconds uint64_t fileSizeDelta = logFileSize - lastLogSize; - systemPrintf(" - Generation rate: %0.1fkB/s", ((float)fileSizeDelta) / 5.0 / 1000.0); + systemPrintf(" - Generation rate: %0.1fkB/s", ((double)fileSizeDelta) / 5.0 / 1000.0); } else { @@ -1593,7 +1688,8 @@ void logUpdate() } else { - log_d("No increase in file size"); + if ((settings.enablePrintLogFileStatus) && (!inMainMenu)) + systemPrintf("No increase in file size: %llu -> %llu\r\n", lastLogSize, logFileSize); logIncreasing = false; endSD(false, true); // alreadyHaveSemaphore, releaseSemaphore @@ -1611,7 +1707,7 @@ void rtcUpdate() { if (online.gnss == true) // Only do this if the GNSS is online { - if (millis() - lastRTCAttempt > syncRTCInterval) // Only attempt this once per second + if ((millis() - lastRTCAttempt) > syncRTCInterval) // Only attempt this once per second { lastRTCAttempt = millis(); @@ -1807,5 +1903,8 @@ void getSemaphoreFunction(char *functionName) case FUNCTION_NTPEVENT: strcpy(functionName, "NTP Event"); break; + case FUNCTION_ARPWRITE: + strcpy(functionName, "ARP Write"); + break; } } diff --git a/Firmware/RTK_Everywhere/SD.ino b/Firmware/RTK_Everywhere/SD.ino index 2cf8e48c7..5bfc2fbc0 100644 --- a/Firmware/RTK_Everywhere/SD.ino +++ b/Firmware/RTK_Everywhere/SD.ino @@ -27,7 +27,7 @@ void sdUpdate() } else if (sdCardPresent() == true) // Poll card to see if a card is inserted { - systemPrintln("SD inserted"); + systemPrintf("SD inserted @ %s\r\n", getTimeStamp()); beginSD(); // Attempt to start SD } } @@ -35,7 +35,7 @@ void sdUpdate() if (online.logging == true && sdCardSize > 0 && sdFreeSpace < sdMinAvailableSpace) // Stop logging if we are below the min { - log_d("Logging stopped. SD full."); + systemPrintf("Logging stopped. SD full @ %s\r\n", getTimeStamp()); outOfSDSpace = true; endSD(false, true); //(alreadyHaveSemaphore, releaseSemaphore) Close down file. return; @@ -48,8 +48,11 @@ void sdUpdate() deleteSDSizeCheckTask(); // Check if SD card is still present - if (sdCardPresent() == false) + if (sdCardPresent() == false && online.microSD == true) + { + systemPrintf("SD removed @ %s\r\n", getTimeStamp()); endSD(false, true); //(alreadyHaveSemaphore, releaseSemaphore) Close down SD. + } } /* @@ -74,12 +77,21 @@ void sdUpdate() #define SD_READ_OCR (0x40 + 58) // read OCR #define SD_ADV_INIT (0xc0 + 41) // ACMD41, for SDHC cards - advanced start initialization -// Begin initialization by sending CMD0 and waiting until SD card -// responds with In Idle Mode (0x01). If the response is not 0x01 -// within a reasonable amount of time, there is no SD card on the bus. -// Returns false if not card is detected -// Returns true if a card responds -// This test takes approximately 13ms to complete +// How this works: +// Some variants have the SD socket card detect pin connected directly to GPIO +// Of those, some are low when the card is present, some are high +// On some variants the card detection is performed via a GPIO expander +// On Postcard: on the Portability Shield, SD DET (SD_CD) is connected to +// IO5 of a PCA9554 I2C GPIO expander (address 0x20) +// IO5 is high when the card is present +// On Flex: SD_#CD is connected to ESP32 GPIO39 +// Torch: has no SD card +// On Facet mosaic: the SD card is connected directly to the X5 but +// SD_!DET is connected to ESP32 GPIO15 +// +// More generally: +// The GPIO expander on Postcard is known as gpioExpanderButtons (0x20) +// Flex also has a GPIO expander, known as gpioExpanderSwitches (0x21) bool sdCardPresent(void) { if (present.microSdCardDetectLow == true) @@ -94,44 +106,113 @@ bool sdCardPresent(void) return (true); // Card detect high = SD in place return (false); // Card detect low = No SD } - else if (present.microSdCardDetectGpioExpanderHigh == true && online.gpioExpander == true) + else if (present.microSdCardDetectGpioExpanderHigh == true) { - if (io.digitalRead(gpioExpander_cardDetect) == GPIO_EXPANDER_CARD_INSERTED) - return (true); // Card detect high = SD in place - return (false); // Card detect low = No SD + if (online.gpioExpanderButtons == true) + { + static uint32_t lastExpanderCheck = 0; + static bool lastPresenceResult = false; + + // Avoid constantly checking I2C bus for SD presence + // Update status every 1000ms + if (millis() - lastExpanderCheck > 1000) + { + lastExpanderCheck = millis(); + + if (io.digitalRead(gpioExpander_cardDetect) == GPIO_EXPANDER_CARD_INSERTED) + { + lastPresenceResult = true; + return (true); // Card detect high = SD in place + } + + // If the SD card was online but it is now detected offline, re-check after debounce + if (online.microSD == true) + { + delay(25); // Debounce + + if (io.digitalRead(gpioExpander_cardDetect) == GPIO_EXPANDER_CARD_INSERTED) + { + lastPresenceResult = true; + return (true); // Card detect high = SD in place + } + } + lastPresenceResult = false; + return (false); // Card detect low = No SD + } + else + { + // Between allowed checks, if asked, return what we found during last check + return (lastPresenceResult); + } + } + else + { + // reportFatalError("sdCardPresent: gpioExpander not online."); + return (false); + } } // else - no card detect pin. Use software detect - // Use software to detect a card - DMW_if systemPrintf("pin_microSD_CS: %d\r\n", pin_microSD_CS); - if (pin_microSD_CS == -1) - reportFatalError("Illegal SD CS pin assignment."); + // Begin initialization by sending CMD0 and waiting until SD card + // responds with In Idle Mode (0x01). If the response is not 0x01 + // within a reasonable amount of time, there is no SD card on the bus. + // Returns false if not card is detected + // Returns true if a card responds + // This test takes approximately 13ms to complete + + // Note: even though this is protected by the semaphore, + // this will probably cause issues / corruption if + // a SdFile is open for writing...? + + static bool previousCardPresentBySW = false; + + if (xSemaphoreTake(sdCardSemaphore, fatSemaphore_longWait_ms) == pdPASS) + { + markSemaphore(FUNCTION_RECORDSETTINGS); + + // Use software to detect a card + DMW_if systemPrintf("pin_microSD_CS: %d\r\n", pin_microSD_CS); + if (pin_microSD_CS == -1) + reportFatalError("Illegal SD CS pin assignment."); + + byte response = 0; - byte response = 0; + beginSPI(false); + SPI.setClockDivider(SPI_CLOCK_DIV2); + SPI.setDataMode(SPI_MODE0); + SPI.setBitOrder(MSBFIRST); + pinMode(pin_microSD_CS, OUTPUT); - beginSPI(false); - SPI.setClockDivider(SPI_CLOCK_DIV2); - SPI.setDataMode(SPI_MODE0); - SPI.setBitOrder(MSBFIRST); - pinMode(pin_microSD_CS, OUTPUT); + // Sending clocks while card power stabilizes... + sdDeselectCard(); // always make sure + for (byte i = 0; i < 30; i++) // send several clocks while card power stabilizes + xchg(0xff); + + // Sending CMD0 - GO IDLE... + for (byte i = 0; i < 0x10; i++) // Attempt to go idle + { + response = sdSendCommand(SD_GO_IDLE, 0); // send CMD0 - go to idle state + if (response == 1) + break; + } - // Sending clocks while card power stabilizes... - sdDeselectCard(); // always make sure - for (byte i = 0; i < 30; i++) // send several clocks while card power stabilizes - xchg(0xff); + xSemaphoreGive(sdCardSemaphore); - // Sending CMD0 - GO IDLE... - for (byte i = 0; i < 0x10; i++) // Attempt to go idle + if (response != 1) + { + previousCardPresentBySW = false; + return (false); // Card failed to respond to idle + } + + previousCardPresentBySW = true; + return (true); // Card detected + } + else { - response = sdSendCommand(SD_GO_IDLE, 0); // send CMD0 - go to idle state - if (response == 1) - break; + // Could not get semaphore. Return previous state + return previousCardPresentBySW; } - if (response != 1) - return (false); // Card failed to respond to idle - - return (true); // Card detected } /* diff --git a/Firmware/RTK_Everywhere/States.ino b/Firmware/RTK_Everywhere/States.ino index 3154afb01..b66a06661 100644 --- a/Firmware/RTK_Everywhere/States.ino +++ b/Firmware/RTK_Everywhere/States.ino @@ -11,7 +11,7 @@ static uint32_t lastStateTime = 0; // A user pressing the mode button (change between rover/base) is handled by buttonCheckTask() void stateUpdate() { - if (millis() - lastSystemStateUpdate > 500 || forceSystemStateUpdate == true) + if (((millis() - lastSystemStateUpdate) > 500) || (forceSystemStateUpdate == true)) { lastSystemStateUpdate = millis(); forceSystemStateUpdate = false; @@ -101,7 +101,7 @@ void stateUpdate() if (gnss->configureRover() == false) { settings.gnssConfiguredRover = false; // On the next boot, reapply all settings - recordSystemSettings(); // Record this state for next POR + recordSystemSettings(); // Record this state for next POR systemPrintln("Rover config failed"); displayRoverFail(1000); @@ -110,12 +110,12 @@ void stateUpdate() setMuxport(settings.dataPortChannel); // Return mux to original channel - bluetoothStart(); // Turn on Bluetooth with 'Rover' name + bluetoothStart(); // Start Bluetooth if it is not already started webServerStop(); // Stop the web config server baseCasterDisableOverride(); // Disable casting overrides - // Start the UART connected to the GNSS receiver for NMEA and UBX data (enables logging) + // Start the UART connected to the GNSS receiver for NMEA data (enables logging) if (tasksStartGnssUart() == false) displayRoverFail(1000); else @@ -208,7 +208,6 @@ void stateUpdate() case (STATE_BASE_CASTER_NOT_STARTED): { baseCasterEnableOverride(); - wifiSoftApSsid = "RTK Caster"; changeState(STATE_BASE_NOT_STARTED); } break; @@ -224,18 +223,17 @@ void stateUpdate() displayBaseStart(0); // Show 'Base' - bluetoothStop(); - bluetoothStart(); // Restart Bluetooth with 'Base' identifier + bluetoothStart(); // Start Bluetooth if it is not already started webServerStop(); // Stop the web config server - // Start the UART connected to the GNSS receiver for NMEA and UBX data (enables logging) + // Start the UART connected to the GNSS receiver for NMEA data (enables logging) if (tasksStartGnssUart() && gnss->configureBase()) { // settings.gnssConfiguredBase is set by gnss->configureBase() - settings.gnssConfiguredRover = false; // When the mode changes, reapply all settings + settings.gnssConfiguredRover = false; // When the mode changes, reapply all settings settings.lastState = STATE_BASE_NOT_STARTED; // Record this state for next POR - recordSystemSettings(); // Record this state for next POR + recordSystemSettings(); // Record this state for next POR displayBaseSuccess(500); // Show 'Base Started' @@ -247,7 +245,7 @@ void stateUpdate() else { settings.gnssConfiguredBase = false; // On the next boot, reapply all settings - recordSystemSettings(); // Record this state for next POR + recordSystemSettings(); // Record this state for next POR displayBaseFail(1000); } @@ -257,7 +255,7 @@ void stateUpdate() // Wait for horz acc of 5m or less before starting survey in case (STATE_BASE_TEMP_SETTLE): { // Blink base LED slowly while we wait for first fix - if (millis() - lastBaseLEDupdate > 1000) + if ((millis() - lastBaseLEDupdate) > 1000) { lastBaseLEDupdate = millis(); @@ -297,7 +295,7 @@ void stateUpdate() // Check survey status until it completes or 15 minutes elapses and we go back to rover case (STATE_BASE_TEMP_SURVEY_STARTED): { // Blink base LED quickly during survey in - if (millis() - lastBaseLEDupdate > 500) + if ((millis() - lastBaseLEDupdate) > 500) { lastBaseLEDupdate = millis(); @@ -401,7 +399,7 @@ void stateUpdate() break; case (STATE_DISPLAY_SETUP): { - if (millis() - lastSetupMenuChange > 10000) // Exit Setup after 10s + if (lastSetupMenuChange.millisSinceUpdate() > 10000) // Exit Setup after 10s { firstButtonThrownOut = false; changeState(lastSystemState); // Return to the last system state @@ -431,7 +429,6 @@ void stateUpdate() for (int serverIndex = 0; serverIndex < NTRIP_SERVER_MAX; serverIndex++) ntripServerStop(serverIndex, true); // Do not allocate new wifiClient - wifiSoftApSsid = "RTK Config"; webServerStart(); // Start the webserver state machine for web config RTK_MODE(RTK_MODE_WEB_CONFIG); @@ -442,25 +439,28 @@ void stateUpdate() case (STATE_WEB_CONFIG): { if (incomingSettingsSpot > 0) { - // Allow for 750ms before we parse buffer for all data to arrive - if (millis() - timeSinceLastIncomingSetting > 750) + // Allow for 250ms before we parse buffer for all data to arrive + if ((millis() - timeSinceLastIncomingSetting) > 250) { - bool changed; + // Confirm receipt so the web interface stops sending the config blob + if (settings.debugWebServer == true) + systemPrintln("Sending receipt confirmation of settings"); + sendStringToWebsocket("confirmDataReceipt,1,"); - currentlyParsingData = - true; // Disallow new data to flow from websocket while we are parsing the current data + // Disallow new data to flow from websocket while we are parsing the current data + currentlyParsingData = true; systemPrint("Parsing: "); for (int x = 0; x < incomingSettingsSpot; x++) systemWrite(incomingSettings[x]); systemPrintln(); - //Create temporary copy of Settings, so that we can check if they change while parsing - //Useful for detecting when we need to change WiFi station settings + // Create temporary copy of Settings, so that we can check if they change while parsing + // Useful for detecting when we need to change WiFi station settings wifiSettingsClone(); - + parseIncomingSettings(); - + settings.gnssConfiguredOnce = false; // On the next boot, reapply all settings settings.gnssConfiguredBase = false; settings.gnssConfiguredRover = false; @@ -480,7 +480,7 @@ void stateUpdate() if (websocketConnected == true) { // Update the coordinates on the AP page - if (millis() - lastDynamicDataUpdate > 1000) + if ((millis() - lastDynamicDataUpdate) > 1000) { lastDynamicDataUpdate = millis(); createDynamicDataString(settingsCSV); @@ -510,7 +510,7 @@ void stateUpdate() // Setup device for testing case (STATE_TEST): { // Debounce entry into test menu - if (millis() - lastTestMenuChange > 500) + if ((millis() - lastTestMenuChange) > 500) { tasksStopGnssUart(); // Stop absoring GNSS serial via task zedUartPassed = false; @@ -542,10 +542,11 @@ void stateUpdate() case (STATE_ESPNOW_PAIRING_NOT_STARTED): { #ifdef COMPILE_ESPNOW + paintEspNowPairing(); - // Start ESP-Now if needed, put ESP-Now into broadcast state - espNowBeginPairing(); + // Let the ESP-NOW state machine know we want to start pairing + espnowRequestPair = true; changeState(STATE_ESPNOW_PAIRING); #else // COMPILE_ESPNOW @@ -555,15 +556,11 @@ void stateUpdate() break; case (STATE_ESPNOW_PAIRING): { - if (espNowProcessRxPairedMessage() == true) - { - paintEspNowPaired(); - + // The ESP-NOW state machine handles the pairing process + // Once it exits the pairing process, return to last system state + if (espNowIsPairing) // Return to the previous state changeState(lastSystemState); - } - else - espNowSendPairMessage(espNowBroadcastAddr); // Send unit's MAC address over broadcast, no ack, no encryption } break; @@ -577,11 +574,11 @@ void stateUpdate() displayNtpStart(500); // Show 'NTP' - // Start UART connected to the GNSS receiver for NMEA and UBX data (enables logging) + // Start UART connected to the GNSS receiver for NMEA data (enables logging) if (tasksStartGnssUart() && ntpConfigureUbloxModule()) { settings.lastState = STATE_NTPSERVER_NOT_STARTED; // Record this state for next POR - settings.gnssConfiguredBase = false; // On the next boot, reapply all settings + settings.gnssConfiguredBase = false; // On the next boot, reapply all settings settings.gnssConfiguredRover = false; recordSystemSettings(); @@ -689,6 +686,7 @@ const char *getState(SystemState state, char *buffer) return "STATE_DISPLAY_SETUP"; case (STATE_WEB_CONFIG_NOT_STARTED): return "STATE_WEB_CONFIG_NOT_STARTED"; + case (STATE_WEB_CONFIG_WAIT_FOR_NETWORK): case (STATE_WEB_CONFIG): return "STATE_WEB_CONFIG"; case (STATE_TEST): @@ -764,16 +762,8 @@ void changeState(SystemState newState) if (!online.rtc) systemPrintf("%s%s%s%s\r\n", asterisk, initialState, arrow, endingState); else - { // Timestamp the state change - // 1 2 - // 12345678901234567890123456 - // YYYY-mm-dd HH:MM:SS.xxxrn0 - struct tm timeinfo = rtc.getTimeStruct(); - char s[30]; - strftime(s, sizeof(s), "%Y-%m-%d %H:%M:%S", &timeinfo); - systemPrintf("%s%s%s%s, %s.%03ld\r\n", asterisk, initialState, arrow, endingState, s, rtc.getMillis()); - } + systemPrintf("%s%s%s%s, %s\r\n", asterisk, initialState, arrow, endingState, getTimeStamp()); } } @@ -785,13 +775,15 @@ typedef struct _RTK_MODE_ENTRY SystemState last; } RTK_MODE_ENTRY; -const RTK_MODE_ENTRY stateModeTable[] = {{"Rover", STATE_ROVER_NOT_STARTED, STATE_ROVER_RTK_FIX}, - {"Base", STATE_BASE_NOT_STARTED, STATE_BASE_FIXED_TRANSMITTING}, - {"Setup", STATE_DISPLAY_SETUP, STATE_PROFILE}, - {"ESPNOW Pairing", STATE_ESPNOW_PAIRING_NOT_STARTED, STATE_ESPNOW_PAIRING}, - {"Provisioning", STATE_KEYS_REQUESTED, STATE_KEYS_REQUESTED}, - {"NTP", STATE_NTPSERVER_NOT_STARTED, STATE_NTPSERVER_SYNC}, - {"Shutdown", STATE_SHUTDOWN, STATE_SHUTDOWN}}; +const RTK_MODE_ENTRY stateModeTable[] = { + {"Rover", STATE_ROVER_NOT_STARTED, STATE_ROVER_RTK_FIX}, + {"Base Caster", STATE_BASE_CASTER_NOT_STARTED, STATE_BASE_CASTER_NOT_STARTED}, + {"Base", STATE_BASE_NOT_STARTED, STATE_BASE_FIXED_TRANSMITTING}, + {"Setup", STATE_DISPLAY_SETUP, STATE_PROFILE}, // Covers SETUP, WEB_CONFIG, TEST + {"Provisioning", STATE_KEYS_REQUESTED, STATE_KEYS_REQUESTED}, + {"ESPNOW Pairing", STATE_ESPNOW_PAIRING_NOT_STARTED, STATE_ESPNOW_PAIRING}, + {"NTP", STATE_NTPSERVER_NOT_STARTED, STATE_NTPSERVER_SYNC}, + {"Shutdown", STATE_SHUTDOWN, STATE_SHUTDOWN}}; const int stateModeTableEntries = sizeof(stateModeTable) / sizeof(stateModeTable[0]); const char *stateToRtkMode(SystemState state) diff --git a/Firmware/RTK_Everywhere/System.ino b/Firmware/RTK_Everywhere/System.ino index b48fbc647..5a94befe1 100644 --- a/Firmware/RTK_Everywhere/System.ino +++ b/Firmware/RTK_Everywhere/System.ino @@ -112,14 +112,24 @@ void beepOn() { // Disallow beeper if setting is turned off if ((pin_beeper != PIN_UNDEFINED) && (settings.enableBeeper == true)) - digitalWrite(pin_beeper, HIGH); + { + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) + digitalWrite(pin_beeper, HIGH); + else if (productVariant == RTK_FLEX) + tone(pin_beeper, 523); // NOTE_C5 + } } void beepOff() { // Disallow beeper if setting is turned off if ((pin_beeper != PIN_UNDEFINED) && (settings.enableBeeper == true)) - digitalWrite(pin_beeper, LOW); + { + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) + digitalWrite(pin_beeper, LOW); + else if (productVariant == RTK_FLEX) + noTone(pin_beeper); + } } // Only useful for pin_chargerLED on Facet mosaic @@ -140,12 +150,14 @@ void updateBattery() if (online.batteryFuelGauge == true) { static unsigned long lastBatteryFuelGaugeUpdate = 0; - if (millis() - lastBatteryFuelGaugeUpdate > 5000) + if ((millis() - lastBatteryFuelGaugeUpdate) > 5000) { lastBatteryFuelGaugeUpdate = millis(); checkBatteryLevels(); + bluetoothSendBatteryPercent(batteryLevelPercent); // Send over dedicated BLE service + // Display the battery data if (settings.enablePrintBatteryMessages) { @@ -187,7 +199,7 @@ void updateBattery() if (online.batteryCharger_mp2762a == true) { static unsigned long lastBatteryChargerUpdate = 0; - if (millis() - lastBatteryChargerUpdate > 5000) + if ((millis() - lastBatteryChargerUpdate) > 5000) { lastBatteryChargerUpdate = millis(); @@ -314,7 +326,7 @@ void reportHeap() { if (settings.enableHeapReport == true) { - if (millis() - lastHeapReport > 1000) + if ((millis() - lastHeapReport) > 1000) { reportHeapNow(false); } @@ -391,11 +403,27 @@ void settingsToDefaults() { static const Settings defaultSettings; settings = defaultSettings; + + checkArrayDefaults(); // This does not call recordSystemSettings + checkGNSSArrayDefaults(); // This calls recordSystemSettings if any GNSS defaults are applied } // Periodically print information if enabled void printReports() { + if (bluetoothCommandIsConnected() == true) + return; + + if (inMainMenu) + return; + + // Periodically display the firmware mode + if (PERIODIC_DISPLAY(PD_FIRMWARE_MODE)) + { + PERIODIC_CLEAR(PD_FIRMWARE_MODE); + systemPrintf("Firmware mode: %s\r\n", stateToRtkMode(systemState)); + } + // Periodically print the position if (settings.enablePrintPosition && ((millis() - lastPrintPosition) > 15000)) { @@ -403,7 +431,7 @@ void printReports() lastPrintPosition = millis(); } - if (settings.enablePrintRoverAccuracy && (millis() - lastPrintRoverAccuracy > 2000)) + if (settings.enablePrintRoverAccuracy && ((millis() - lastPrintRoverAccuracy) > 2000)) { lastPrintRoverAccuracy = millis(); if (online.gnss) @@ -557,10 +585,11 @@ CoordinateInputType coordinateIdentifyInputType(const char *userEntryOriginal, d { coordinateInputType = COORDINATE_INPUT_TYPE_DD_MM_DASH; - char *token = strtok(userEntry, "-"); // Modifies the given array + char *preservedPointer; + char *token = strtok_r(userEntry, "-", &preservedPointer); // Modifies the given array // We trust that token points at something because the dashCount is > 0 int decimal = atoi(token); // Get DD - token = strtok(nullptr, "-"); + token = strtok_r(nullptr, "-", &preservedPointer); double minutes = atof(token); // Get MM.mmmmmmm *coordinate = decimal + (minutes / 60.0); if (negativeSign) @@ -570,12 +599,13 @@ CoordinateInputType coordinateIdentifyInputType(const char *userEntryOriginal, d { coordinateInputType = COORDINATE_INPUT_TYPE_DD_MM_SS_DASH; - char *token = strtok(userEntry, "-"); // Modifies the given array + char *preservedPointer; + char *token = strtok_r(userEntry, "-", &preservedPointer); // Modifies the given array // We trust that token points at something because the spaceCount is > 0 int decimal = atoi(token); // Get DD - token = strtok(nullptr, "-"); + token = strtok_r(nullptr, "-", &preservedPointer); int minutes = atoi(token); // Get MM - token = strtok(nullptr, "-"); + token = strtok_r(nullptr, "-", &preservedPointer); // Find '.' char *decimalPtr = strchr(token, '.'); @@ -598,10 +628,11 @@ CoordinateInputType coordinateIdentifyInputType(const char *userEntryOriginal, d { coordinateInputType = COORDINATE_INPUT_TYPE_DD_MM; - char *token = strtok(userEntry, " "); // Modifies the given array + char *preservedPointer; + char *token = strtok_r(userEntry, " ", &preservedPointer); // Modifies the given array // We trust that token points at something because the spaceCount is > 0 int decimal = atoi(token); // Get DD - token = strtok(nullptr, " "); + token = strtok_r(nullptr, " ", &preservedPointer); double minutes = atof(token); // Get MM.mmmmmmm *coordinate = decimal + (minutes / 60.0); if (negativeSign) @@ -611,12 +642,13 @@ CoordinateInputType coordinateIdentifyInputType(const char *userEntryOriginal, d { coordinateInputType = COORDINATE_INPUT_TYPE_DD_MM_SS; - char *token = strtok(userEntry, " "); // Modifies the given array + char *preservedPointer; + char *token = strtok_r(userEntry, " ", &preservedPointer); // Modifies the given array // We trust that token points at something because the spaceCount is > 0 int decimal = atoi(token); // Get DD - token = strtok(nullptr, " "); + token = strtok_r(nullptr, " ", &preservedPointer); int minutes = atoi(token); // Get MM - token = strtok(nullptr, " "); + token = strtok_r(nullptr, " ", &preservedPointer); // Find '.' char *decimalPtr = strchr(token, '.'); @@ -871,4 +903,121 @@ void getMacAddresses(uint8_t *macAddress, const char *name, esp_mac_type_t type, if (debug) systemPrintf("%02X:%02X:%02X:%02X:%02X:%02X - %s\r\n", macAddress[0], macAddress[1], macAddress[2], macAddress[3], macAddress[4], macAddress[5], name); -}; +} + +// Start the I2C GPIO expander responsible for switches (generally the RTK Flex) +void beginGpioExpanderSwitches() +{ + if (present.gpioExpanderSwitches) + { + if (gpioExpanderSwitches == nullptr) + gpioExpanderSwitches = new SFE_PCA95XX(PCA95XX_PCA9534); + + // In Flex, the GPIO Expander has been assigned address 0x21 + if (gpioExpanderSwitches->begin(0x21, *i2c_0) == false) + { + systemPrintln("GPIO expander for switches not detected"); + delete gpioExpanderSwitches; + gpioExpanderSwitches = nullptr; + return; + } + + // SW1 is on pin 0. Driving it high will disconnect the ESP32 from USB + // GNSS_RST is on pin 5. Driving it low when an LG290P is connected will kill the I2C bus. + // PWRKILL is on pin 7. Driving it low will turn off the system + for (int i = 0; i < gpioExpanderNumSwitches; i++) + { + // Set all pins to low except GNSS RESET and PWRKILL + if (i == gpioExpanderSwitch_GNSS_Reset || i == gpioExpanderSwitch_PowerFastOff) + gpioExpanderSwitches->digitalWrite(i, HIGH); + else + gpioExpanderSwitches->digitalWrite(i, LOW); + + gpioExpanderSwitches->pinMode(i, OUTPUT); + } + + online.gpioExpanderSwitches = true; + + systemPrintln("GPIO Expander for switches configuration complete"); + } +} + +// Drive GPIO pin high to bring GNSS out of reset +void gpioExpanderGnssBoot() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_GNSS_Reset, HIGH); +} + +void gpioExpanderGnssReset() +{ + if (online.gpioExpanderSwitches == true) + { + if (settings.detectedGnssReceiver != GNSS_RECEIVER_LG290P) + { + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_GNSS_Reset, LOW); + } + else + systemPrintln("Skipped disable of LG290P"); // Disabling an LG290P when it's connected to an I2C bus will + // bring down the I2C bus + } +} + +// The IMU is on UART3 of the Flex module connected to switch 3 +void gpioExpanderSelectImu() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_S3, LOW); +} + +// Connect ESP32 UART2 to LoRa UART2 for configuration and bootloading/firmware updates +void gpioExpanderSelectLoraConfigure() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_S3, HIGH); +} + +// Connect Flex GNSS UART2 to LoRa UART0 for normal TX/RX of corrections and data +void gpioExpanderSelectLoraCommunication() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_S4, HIGH); +} + +// Connect Flex GNSS UART2 to 4-pin JST RADIO port +void gpioExpanderSelectRadioPort() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_S4, LOW); +} + +// Drive GPIO pin high to enable LoRa Radio +void gpioExpanderLoraEnable() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_LoraEnable, HIGH); +} +void gpioExpanderLoraDisable() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_LoraEnable, LOW); +} +bool gpioExpanderLoraIsOn() +{ + if (online.gpioExpanderSwitches == true) + { + if (gpioExpanderSwitches->digitalRead(gpioExpanderSwitch_LoraEnable) == HIGH) + return (true); + } + return (false); +} +void gpioExpanderLoraBootEnable() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_LoraBoot, HIGH); +} +void gpioExpanderLoraBootDisable() +{ + if (online.gpioExpanderSwitches == true) + gpioExpanderSwitches->digitalWrite(gpioExpanderSwitch_LoraBoot, LOW); +} \ No newline at end of file diff --git a/Firmware/RTK_Everywhere/Tasks.ino b/Firmware/RTK_Everywhere/Tasks.ino index bbdeebbdf..c651537bd 100644 --- a/Firmware/RTK_Everywhere/Tasks.ino +++ b/Firmware/RTK_Everywhere/Tasks.ino @@ -38,11 +38,11 @@ Tasks.ino // Macros //---------------------------------------- -#define WRAP_OFFSET(offset, increment, arraySize) \ - { \ - offset += increment; \ - if (offset >= arraySize) \ - offset -= arraySize; \ +#define WRAP_OFFSET(offset, increment, arraySize) \ + { \ + offset += increment; \ + if (offset >= arraySize) \ + offset -= arraySize; \ } //---------------------------------------- @@ -62,7 +62,12 @@ enum RingBufferConsumers }; const char *const ringBufferConsumer[] = { - "Bluetooth", "TCP Client", "TCP Server", "SD Card", "UDP Server", "USB Serial", + "Bluetooth", + "TCP Client", + "TCP Server", + "SD Card", + "UDP Server", + "USB Serial", }; const int ringBufferConsumerEntries = sizeof(ringBufferConsumer) / sizeof(ringBufferConsumer[0]); @@ -76,13 +81,21 @@ const int ringBufferConsumerEntries = sizeof(ringBufferConsumer) / sizeof(ringBu // List the parsers to be included SEMP_PARSE_ROUTINE const parserTable[] = { - sempNmeaPreamble, sempUnicoreHashPreamble, sempRtcmPreamble, sempUbloxPreamble, sempUnicoreBinaryPreamble, + sempNmeaPreamble, + sempUnicoreHashPreamble, + sempRtcmPreamble, + sempUbloxPreamble, + sempUnicoreBinaryPreamble, }; const int parserCount = sizeof(parserTable) / sizeof(parserTable[0]); // List the names of the parsers const char *const parserNames[] = { - "NMEA", "Unicore Hash_(#)", "RTCM", "u-Blox", "Unicore Binary", + "NMEA", + "Unicore Hash_(#)", + "RTCM", + "u-Blox", + "Unicore Binary", }; const int parserNameCount = sizeof(parserNames) / sizeof(parserNames[0]); @@ -94,6 +107,7 @@ const char *const sbfParserNames[] = { "SBF", }; const int sbfParserNameCount = sizeof(sbfParserNames) / sizeof(sbfParserNames[0]); + SEMP_PARSE_ROUTINE const spartnParserTable[] = {sempSpartnPreamble}; const int spartnParserCount = sizeof(spartnParserTable) / sizeof(spartnParserTable[0]); const char *const spartnParserNames[] = { @@ -101,6 +115,11 @@ const char *const spartnParserNames[] = { }; const int spartnParserNameCount = sizeof(spartnParserNames) / sizeof(spartnParserNames[0]); +SEMP_PARSE_ROUTINE const rtcmParserTable[] = { sempRtcmPreamble }; +const int rtcmParserCount = sizeof(rtcmParserTable) / sizeof(rtcmParserTable[0]); +const char *const rtcmParserNames[] = { "RTCM" }; +const int rtcmParserNameCount = sizeof(rtcmParserNames) / sizeof(rtcmParserNames[0]); + //---------------------------------------- // Locals //---------------------------------------- @@ -134,11 +153,9 @@ void btReadTask(void *e) unsigned long btLastByteReceived = 0; // Track when the last BT transmission was received. const long btMinEscapeTime = - 2000; // Bluetooth serial traffic must stop this amount before an escape char is recognized + 2000; // Bluetooth serial traffic must stop this amount before an escape char is recognized uint8_t btEscapeCharsReceived = 0; // Used to enter remote command mode - uint8_t btAppCommandCharsReceived = 0; // Used to enter app command mode - // Start notification task.btReadTaskRunning = true; if (settings.printTaskStartStop) @@ -149,7 +166,7 @@ void btReadTask(void *e) while (task.btReadTaskStopRequest == false) { // Display an alive message - if (PERIODIC_DISPLAY(PD_TASK_BLUETOOTH_READ)) + if (PERIODIC_DISPLAY(PD_TASK_BLUETOOTH_READ) && !inMainMenu) { PERIODIC_CLEAR(PD_TASK_BLUETOOTH_READ); systemPrintln("btReadTask running"); @@ -169,7 +186,7 @@ void btReadTask(void *e) { // Ignore escape characters received within 2 seconds of serial traffic // Allow escape characters received within the first 2 seconds of power on - if (millis() - btLastByteReceived > btMinEscapeTime || millis() < btMinEscapeTime) + if (((millis() - btLastByteReceived) > btMinEscapeTime) || (millis() < btMinEscapeTime)) { btEscapeCharsReceived++; if (btEscapeCharsReceived == btMaxEscapeCharacters) @@ -188,25 +205,7 @@ void btReadTask(void *e) addToGnssBuffer(btEscapeCharacter); } } - else if (incoming == btAppCommandCharacter) - { - btAppCommandCharsReceived++; - if (btAppCommandCharsReceived == btMaxAppCommandCharacters) - { - sendGnssBuffer(); // Finish sending whatever is left in the buffer - // Discard any bluetooth data in the circular buffer - btRingBufferTail = dataHead; - - systemPrintln("Device has entered config mode over Bluetooth"); - printEndpoint = PRINT_ENDPOINT_ALL; - btPrintEcho = true; - runCommandMode = true; - - btAppCommandCharsReceived = 0; - btLastByteReceived = millis(); - } - } else // This character is not a command character, pass along to GNSS { @@ -215,10 +214,6 @@ void btReadTask(void *e) { addToGnssBuffer(btEscapeCharacter); } - while (btAppCommandCharsReceived-- > 0) - { - addToGnssBuffer(btAppCommandCharacter); - } // Pass byte to GNSS receiver or to system // TODO - control if this RTCM source should be listened to or not @@ -231,8 +226,6 @@ void btReadTask(void *e) btLastByteReceived = millis(); btEscapeCharsReceived = 0; // Update timeout check for escape char and partial frame - btAppCommandCharsReceived = 0; - bluetoothIncomingRTCM = true; // Record the arrival of RTCM from the Bluetooth connection (a phone or tablet is providing the RTCM @@ -243,7 +236,7 @@ void btReadTask(void *e) } // End btPrintEcho == false && bluetoothRxDataAvailable() - if (PERIODIC_DISPLAY(PD_BLUETOOTH_DATA_RX)) + if (PERIODIC_DISPLAY(PD_BLUETOOTH_DATA_RX) && !inMainMenu) { PERIODIC_CLEAR(PD_BLUETOOTH_DATA_RX); systemPrintf("Bluetooth received %d bytes\r\n", rxBytes); @@ -287,6 +280,7 @@ void sendGnssBuffer() { if (correctionLastSeen(CORR_BLUETOOTH)) { + sempParseNextBytes(rtcmParse, bluetoothOutgoingToGnss, bluetoothOutgoingToGnssHead); // Parse the data for RTCM1005/1006 if (gnss->pushRawData(bluetoothOutgoingToGnss, bluetoothOutgoingToGnssHead)) { if ((settings.debugCorrections || PERIODIC_DISPLAY(PD_GNSS_DATA_TX)) && !inMainMenu) @@ -378,7 +372,10 @@ void gnssReadTask(void *e) if (settings.debugGnss) sempEnableDebugOutput(rtkParse); - if (present.gnss_mosaicX5) + bool sbfParserNeeded = present.gnss_mosaicX5; + bool spartnParserNeeded = present.gnss_mosaicX5 && (productVariant != RTK_FLEX); + + if (sbfParserNeeded) { // Initialize the SBF parser for the mosaic-X5 sbfParse = sempBeginParser(sbfParserTable, sbfParserCount, sbfParserNames, sbfParserNameCount, @@ -389,25 +386,28 @@ void gnssReadTask(void *e) if (!sbfParse) reportFatalError("Failed to initialize the SBF parser"); - // Any data which is not SBF will be passed to the SPARTN parser via the invalid data callback - sempSbfSetInvalidDataCallback(sbfParse, processNonSBFData); - // Uncomment the next line to enable SBF parser debug // But be careful - you get a lot of "SEMP: Sbf SBF, 0x0002 (2) bytes, invalid preamble2" // if (settings.debugGnss) sempEnableDebugOutput(sbfParse); - // Initialize the SPARTN parser for the mosaic-X5 - spartnParse = sempBeginParser(spartnParserTable, spartnParserCount, spartnParserNames, spartnParserNameCount, - 0, // Scratchpad bytes - 1200, // Buffer length - SPARTN payload is 1024 bytes max - processUart1SPARTN, // eom Call Back - in mosaic.ino - "spartnParse"); // Parser Name - if (!spartnParse) - reportFatalError("Failed to initialize the SPARTN parser"); - - // Uncomment the next line to enable SPARTN parser debug - // But be careful - you get a lot of "SEMP: Spartn SPARTN 0 0, 0x00f4 (244) bytes, bad CRC" - // if (settings.debugGnss) sempEnableDebugOutput(spartnParse); + if (spartnParserNeeded) + { + // Any data which is not SBF will be passed to the SPARTN parser via the invalid data callback + sempSbfSetInvalidDataCallback(sbfParse, processNonSBFData); + + // Initialize the SPARTN parser for the mosaic-X5 + spartnParse = sempBeginParser(spartnParserTable, spartnParserCount, spartnParserNames, spartnParserNameCount, + 0, // Scratchpad bytes + 1200, // Buffer length - SPARTN payload is 1024 bytes max + processUart1SPARTN, // eom Call Back - in mosaic.ino + "spartnParse"); // Parser Name + if (!spartnParse) + reportFatalError("Failed to initialize the SPARTN parser"); + + // Uncomment the next line to enable SPARTN parser debug + // But be careful - you get a lot of "SEMP: Spartn SPARTN 0 0, 0x00f4 (244) bytes, bad CRC" + // if (settings.debugGnss) sempEnableDebugOutput(spartnParse); + } } // Run task until a request is raised @@ -415,7 +415,7 @@ void gnssReadTask(void *e) while (task.gnssReadTaskStopRequest == false) { // Display an alive message - if (PERIODIC_DISPLAY(PD_TASK_GNSS_READ)) + if (PERIODIC_DISPLAY(PD_TASK_GNSS_READ) && !inMainMenu) { PERIODIC_CLEAR(PD_TASK_GNSS_READ); systemPrintln("gnssReadTask running"); @@ -426,7 +426,7 @@ void gnssReadTask(void *e) // Display the RX byte count static uint32_t totalRxByteCount = 0; - if (PERIODIC_DISPLAY(PD_GNSS_DATA_RX_BYTE_COUNT)) + if (PERIODIC_DISPLAY(PD_GNSS_DATA_RX_BYTE_COUNT) && !inMainMenu) { PERIODIC_CLEAR(PD_GNSS_DATA_RX_BYTE_COUNT); systemPrintf("gnssReadTask total byte count: %d\r\n", totalRxByteCount); @@ -437,7 +437,7 @@ void gnssReadTask(void *e) // device) To allow the Unicore library to send/receive serial commands, we need to block the gnssReadTask // If the Unicore library does not need lone access, then read from serial port - // For the mosaic-X5, things are different. The mosaic-X5 outputs a raw stream of L-Band bytes, + // For the Facet mosaic-X5, things are different. The mosaic-X5 outputs a raw stream of L-Band bytes, // interspersed with periodic SBF blocks. The SBF blocks can contain encapsulated NMEA and RTCMv3. // We need to pass each incoming byte to a SBF parser first, so it can pick out any SBF blocks. // The SBF parser needs to 'give up' (return) any bytes which are not SBF. We do that using the @@ -453,6 +453,8 @@ void gnssReadTask(void *e) // from being parsed from valid SBF blocks and causes the NTRIP server connection to break. We need // to add extra checks, above and beyond the invalidDataCallback, to make sure that doesn't happen. // Here we check that the SBF ID and length are expected / valid too. + // + // For Flex mosaic, we need the SBF parser but not the SPARTN parser if (gnss->isBlocking() == false) { @@ -468,11 +470,11 @@ void gnssReadTask(void *e) { // Update the parser state based on the incoming byte // On mosaic-X5, pass the byte to sbfParse. On all other platforms, pass it straight to rtkParse - sempParseNextByte(present.gnss_mosaicX5 ? sbfParse : rtkParse, incomingData[x]); + sempParseNextByte(sbfParserNeeded ? sbfParse : rtkParse, incomingData[x]); // See notes above. On the mosaic-X5, check that the incoming SBF blocks have expected IDs and // lengths to help prevent raw L-Band data being misidentified as SBF - if (present.gnss_mosaicX5) + if (sbfParserNeeded) { SEMP_SCRATCH_PAD *scratchPad = (SEMP_SCRATCH_PAD *)sbfParse->scratchPad; @@ -497,7 +499,8 @@ void gnssReadTask(void *e) if (!expected) // SBF is not expected so restart the parsers { sbfParse->state = sempFirstByte; - spartnParse->state = sempFirstByte; + if (spartnParserNeeded) + spartnParse->state = sempFirstByte; if (settings.debugGnss) systemPrintf("Unexpected SBF block %d - rejected on ID or length\r\n", scratchPad->sbf.sbfID); @@ -537,7 +540,8 @@ void gnssReadTask(void *e) if (!expected) // SBF is not expected so restart the parsers { sbfParse->state = sempFirstByte; - spartnParse->state = sempFirstByte; + if (spartnParserNeeded) + spartnParse->state = sempFirstByte; if (settings.debugGnss) systemPrintf("Unexpected EncapsulatedOutput block - rejected\r\n"); // We could pass the rejected bytes to the SPARTN parser but this is ~risky @@ -569,6 +573,121 @@ void gnssReadTask(void *e) vTaskDelete(NULL); } +// Force the NMEA Talker ID - if needed +void forceTalkerId(const char *Id, char *msg, size_t maxLen) +{ + if (msg[2] == *Id) + return; // Nothing to do + + char oldTalker = msg[2]; + msg[2] = *Id; // Force the Talker ID + + // Update the checksum: XOR chars between '$' and '*' + size_t len = 1; + uint8_t csum = 0; + while ((len < maxLen) && (msg[len] != '*')) + csum = csum ^ msg[len++]; + + if (len >= (maxLen - 3)) + { + // Something went horribly wrong. Restore the Talker ID + msg[2] = oldTalker; + return; + } + + len++; // Point at the checksum and update it + sprintf(&msg[len], "%02X", csum); +} + +// Force the RMC COG entry - if needed +void forceRmcCog(char *msg, size_t maxLen) +{ + const char *noCog = "0.0"; + + if (strstr(msg, "RMC") == nullptr) + return; // Nothing to do + + if (maxLen < (strlen(msg) + strlen(noCog))) + return; // No room for the COG! + + // Find the start of COG ("Track made good") - after the 8th comma + int numCommas = 0; + size_t len = 0; + while ((numCommas < 8) && (len < maxLen)) + { + if (msg[len++] == ',') + numCommas++; + } + + if (len >= maxLen) // Something went horribly wrong + return; + + // If the next char is not a ',' - there's nothing to do + if (msg[len] != ',') + return; + + // If the next char is a ',' - add "0.0" manually + // Start by creating space for the "0.0" + for (size_t i = strlen(msg); i > len; i--) // Work backwards from the NULL + msg[i + strlen(noCog)] = msg[i]; + + // Now insert the "0.0" + memcpy(&msg[len], noCog, strlen(noCog)); + + // Update the checksum: XOR chars between '$' and '*' + len = 1; + uint8_t csum = 0; + while ((len < maxLen) && (msg[len] != '*')) + csum = csum ^ msg[len++]; + len++; // Point at the checksum and update it + sprintf(&msg[len], "%02X", csum); +} + +// Remove the RMC Navigational Status field - if needed +void removeRmcNavStat(char *msg, size_t maxLen) +{ + if (strstr(msg, "RMC") == nullptr) + return; // Nothing to do + + // Find the start of Nav Stat - at the 13th comma + int numCommas = 0; + size_t len = 0; + while ((numCommas < 13) && (msg[len] != '*') && (len < maxLen)) + { + if (msg[len++] == ',') + numCommas++; + } + + if (len >= (maxLen - 3)) // Something went horribly wrong + return; + + // If the next char is '*' - there's nothing to do + if ((msg[len] == '*') || (numCommas < 13)) + return; + + // Find the asterix. (NavStatus should be a single char) + size_t asterix = len; + len--; + + while ((msg[asterix] != '*') && (asterix < maxLen)) + asterix++; + + if (msg[asterix] != '*') // Something went horribly wrong + return; + + // Delete the NavStat + for (size_t i = 0; i < (strlen(msg) + 1 - asterix); i++) // Copy the * CSUM NULL + msg[len + i] = msg[asterix + i]; + + // Update the checksum: XOR chars between '$' and '*' + len = 1; + uint8_t csum = 0; + while ((len < maxLen) && (msg[len] != '*')) + csum = csum ^ msg[len++]; + len++; // Point at the checksum and update it + sprintf(&msg[len], "%02X", csum); +} + // Call back from within parser, for end of message // Process a complete message incoming from parser // If we get a complete NMEA/UBX/RTCM message, pass on to SD/BT/TCP/UDP interfaces @@ -623,6 +742,105 @@ void processUart1Message(SEMP_PARSE_STATE *parse, uint16_t type) } } + // Save GGA / RMC / GST for the Apple device + // We should optimse this with a Lee table... TODO + if ((online.authenticationCoPro) && (type == RTK_NMEA_PARSER_INDEX)) + { + if (strstr(sempNmeaGetSentenceName(parse), "GGA") != nullptr) + { + if (parse->length < latestNmeaMaxLen) + { + memcpy(latestGPGGA, parse->buffer, parse->length); + latestGPGGA[parse->length] = 0; // NULL terminate + if ((strlen(latestGPGGA) > 10) && (latestGPGGA[strlen(latestGPGGA) - 2] == '\r')) + latestGPGGA[strlen(latestGPGGA) - 2] = 0; // Truncate the \r\n + forceTalkerId("P",latestGPGGA,latestNmeaMaxLen); + } + else + systemPrintf("Increase latestNmeaMaxLen to > %d\r\n", parse->length); + } + else if (strstr(sempNmeaGetSentenceName(parse), "RMC") != nullptr) + { + if (parse->length < latestNmeaMaxLen) + { + memcpy(latestGPRMC, parse->buffer, parse->length); + latestGPRMC[parse->length] = 0; // NULL terminate + if ((strlen(latestGPRMC) > 10) && (latestGPRMC[strlen(latestGPRMC) - 2] == '\r')) + latestGPRMC[strlen(latestGPRMC) - 2] = 0; // Truncate the \r\n + forceTalkerId("P",latestGPRMC,latestNmeaMaxLen); + forceRmcCog(latestGPRMC,latestNmeaMaxLen); + removeRmcNavStat(latestGPRMC,latestNmeaMaxLen); + } + else + systemPrintf("Increase latestNmeaMaxLen to > %d\r\n", parse->length); + } + else if (strstr(sempNmeaGetSentenceName(parse), "GST") != nullptr) + { + if (parse->length < latestNmeaMaxLen) + { + memcpy(latestGPGST, parse->buffer, parse->length); + latestGPGST[parse->length] = 0; // NULL terminate + if ((strlen(latestGPGST) > 10) && (latestGPGST[strlen(latestGPGST) - 2] == '\r')) + latestGPGST[strlen(latestGPGST) - 2] = 0; // Truncate the \r\n + forceTalkerId("P",latestGPGST,latestNmeaMaxLen); + } + else + systemPrintf("Increase latestNmeaMaxLen to > %d\r\n", parse->length); + } + else if (strstr(sempNmeaGetSentenceName(parse), "VTG") != nullptr) + { + if (parse->length < latestNmeaMaxLen) + { + memcpy(latestGPVTG, parse->buffer, parse->length); + latestGPVTG[parse->length] = 0; // NULL terminate + if ((strlen(latestGPVTG) > 10) && (latestGPVTG[strlen(latestGPVTG) - 2] == '\r')) + latestGPVTG[strlen(latestGPVTG) - 2] = 0; // Truncate the \r\n + forceTalkerId("P",latestGPVTG,latestNmeaMaxLen); + } + else + systemPrintf("Increase latestNmeaMaxLen to > %d\r\n", parse->length); + } + else if ((strstr(sempNmeaGetSentenceName(parse), "GSA") != nullptr) + || (strstr(sempNmeaGetSentenceName(parse), "GSV") != nullptr)) + { + // If the Apple Accessory is sending the data to the EA Session, + // discard this GSA / GSV. Bad things would happen if we were to + // manipulate latestEASessionData while appleAccessory is using it. +#ifdef COMPILE_AUTHENTICATION + if (appleAccessory->latestEASessionDataIsBlocking() == false) + { + size_t spaceAvailable = latestEASessionDataMaxLen - strlen(latestEASessionData); + if (spaceAvailable >= 3) + spaceAvailable -= 3; // Leave room for the CR, LF and NULL + while (spaceAvailable < parse->length) // If the buffer is full, delete the oldest message(s) + { + const char *lfPtr = strstr(latestEASessionData, "\n"); // Find the first LF + if (lfPtr == nullptr) + break; // Something has gone badly wrong... + lfPtr++; // Point at the byte after the LF + size_t oldLen = lfPtr - latestEASessionData; // This much data is old + size_t newLen = strlen(latestEASessionData) - oldLen; // This much is new (not old) + for (size_t i = 0; i <= newLen; i++) // Move the new data over the old. Include the NULL + latestEASessionData[i] = latestEASessionData[oldLen + i]; + spaceAvailable += oldLen; + } + size_t dataLen = strlen(latestEASessionData); + memcpy(&latestEASessionData[dataLen], parse->buffer, parse->length); // Add the new NMEA data + dataLen += parse->length; + latestEASessionData[dataLen] = 0; // NULL terminate + if (latestEASessionData[dataLen - 1] != '\n') + { + latestEASessionData[dataLen] = '\r'; // Add CR + latestEASessionData[dataLen + 1] = '\n'; // Add LF + latestEASessionData[dataLen + 2] = 0; // NULL terminate + } + } + else if (settings.debugNetworkLayer) + systemPrintf("Discarding %d GSA/GSV bytes - latestEASessionDataIsBlocking\r\n", parse->length); +#endif //COMPILE_AUTHENTICATION + } + } + // Determine if this message should be processed by the Unicore library // Pass NMEA to um980 before applying compensation if (present.gnss_um980) @@ -681,7 +899,7 @@ void processUart1Message(SEMP_PARSE_STATE *parse, uint16_t type) if ((present.gnss_lg290p) && (pointPerfectIsEnabled()) && (mqttClientIsConnected() == true)) usingPPL = true; // mosaic-X5 : Determine if we want to use corrections - if ((present.gnss_mosaicX5) && (pointPerfectIsEnabled())) + if ((present.gnss_mosaicX5) && (pointPerfectLbandNeeded())) usingPPL = true; if (usingPPL) @@ -747,7 +965,7 @@ void processUart1Message(SEMP_PARSE_STATE *parse, uint16_t type) // If BaseCasterOverride is enabled, remove everything but RTCM from the circular buffer // to avoid saturating the downstream radio link that is consuming over a TCP (NTRIP Caster) connection // Remove NMEA, etc after passing to the GNSS receiver library so that we still have SIV and other stats available - if (settings.baseCasterOverride == true) + if (tcpServerInCasterMode) { if (type != RTK_RTCM_PARSER_INDEX) { @@ -779,222 +997,271 @@ void processUart1Message(SEMP_PARSE_STATE *parse, uint16_t type) parse->length = 0; } - // Determine if this message will fit into the ring buffer - bytesToCopy = parse->length; - space = availableHandlerSpace; - use = settings.gnssHandlerBufferSize - space; - consumer = (char *)slowConsumer; - if ((bytesToCopy > space) && (!inMainMenu)) + // If parse->length is zero, we should exit now. + // Previously, the code would continue past here and fill rbOffsetArray with 'empty' entries. + // E.g. RTCM1019/1042/1046 suppressed above + if (parse->length == 0) + return; + + // Use a semaphore to prevent handleGnssDataTask from gatecrashing + if (ringBufferSemaphore == NULL) + ringBufferSemaphore = xSemaphoreCreateMutex(); // Create the mutex + + // Take the semaphore. Long wait. handleGnssDataTask could block + // Enable printing of the ring buffer offsets (s d 10) and the SD buffer sizes (s h 7) + // to see this in action. No more gatecrashing! + if (xSemaphoreTake(ringBufferSemaphore, ringBuffer_longWait_ms) == pdPASS) { - int32_t bufferedData; - int32_t bytesToDiscard; - int32_t discardedBytes; - int32_t listEnd; - int32_t messageLength; - int32_t previousTail; - int32_t rbOffsetTail; - - // Determine the tail of the ring buffer - previousTail = dataHead + space + 1; - if (previousTail >= settings.gnssHandlerBufferSize) - previousTail -= settings.gnssHandlerBufferSize; - - /* The rbOffsetArray holds the offsets into the ring buffer of the - * start of each of the parsed messages. A head (rbOffsetHead) and - * tail (rbOffsetTail) offsets are used for this array to insert and - * remove entries. Typically this task only manipulates the head as - * new messages are placed into the ring buffer. The handleGnssDataTask - * normally manipulates the tail as data is removed from the buffer. - * However this task will manipulate the tail under two conditions: - * - * 1. The ring buffer gets full and data must be discarded - * - * 2. The rbOffsetArray is too small to hold all of the message - * offsets for the data in the ring buffer. The array is full - * when (Head + 1) == Tail - * - * Notes: - * The rbOffsetArray is allocated along with the ring buffer in - * Begin.ino - * - * The first entry rbOffsetArray[0] is initialized to zero (0) - * in Begin.ino - * - * The array always has one entry in it containing the head offset - * which contains a valid offset into the ringBuffer, handled below - * - * The empty condition is Tail == Head - * - * The amount of data described by the rbOffsetArray is - * rbOffsetArray[Head] - rbOffsetArray[Tail] - * - * rbOffsetArray ringBuffer - * .-----------------. .-----------------. - * | | | | - * +-----------------+ | | - * Tail --> | Msg 1 Offset |---------->+-----------------+ <-- Tail n - * +-----------------+ | Msg 1 | - * | Msg 2 Offset |--------. | | - * +-----------------+ | | | - * | Msg 3 Offset |------. '->+-----------------+ - * +-----------------+ | | Msg 2 | - * Head --> | Head Offset |--. | | | - * +-----------------+ | | | | - * | | | | | | - * +-----------------+ | | | | - * | | | '--->+-----------------+ - * +-----------------+ | | Msg 3 | - * | | | | | - * +-----------------+ '------->+-----------------+ <-- dataHead - * | | | | - */ - - // Determine the index for the end of the circular ring buffer - // offset list - listEnd = rbOffsetHead; - WRAP_OFFSET(listEnd, 1, rbOffsetEntries); - - // Update the tail, walk newest message to oldest message - rbOffsetTail = rbOffsetHead; - bufferedData = 0; - messageLength = 0; - while ((rbOffsetTail != listEnd) && (bufferedData < use)) + ringBufferSemaphoreHolder = "processUart1Message"; + + // Determine if this message will fit into the ring buffer + int32_t discardedBytes = 0; + bytesToCopy = parse->length; + space = availableHandlerSpace; // Take a copy of availableHandlerSpace here + use = settings.gnssHandlerBufferSize - space; + consumer = (char *)slowConsumer; + if (bytesToCopy > space) // Paul removed the && (!inMainMenu)) check 7-25-25 { - // Determine the amount of data in the ring buffer up until - // either the tail or the end of the rbOffsetArray + int32_t bufferedData; + int32_t bytesToDiscard; + int32_t listEnd; + int32_t messageLength; + int32_t previousTail; + int32_t rbOffsetTail; + + // Determine the tail of the ring buffer + previousTail = dataHead + space + 1; + if (previousTail >= settings.gnssHandlerBufferSize) + previousTail -= settings.gnssHandlerBufferSize; + + /* The rbOffsetArray holds the offsets into the ring buffer of the + * start of each of the parsed messages. A head (rbOffsetHead) and + * tail (rbOffsetTail) offsets are used for this array to insert and + * remove entries. Typically this task only manipulates the head as + * new messages are placed into the ring buffer. The handleGnssDataTask + * normally manipulates the tail as data is removed from the buffer. + * However this task will manipulate the tail under two conditions: + * + * 1. The ring buffer gets full and data must be discarded + * + * 2. The rbOffsetArray is too small to hold all of the message + * offsets for the data in the ring buffer. The array is full + * when (Head + 1) == Tail + * + * Notes: + * The rbOffsetArray is allocated along with the ring buffer in + * Begin.ino + * + * The first entry rbOffsetArray[0] is initialized to zero (0) + * in Begin.ino + * + * The array always has one entry in it containing the head offset + * which contains a valid offset into the ringBuffer, handled below + * + * The empty condition is Tail == Head + * + * The amount of data described by the rbOffsetArray is + * rbOffsetArray[Head] - rbOffsetArray[Tail] + * + * rbOffsetArray ringBuffer + * .-----------------. .-----------------. + * | | | | + * +-----------------+ | | + * Tail --> | Msg 1 Offset |---------->+-----------------+ <-- Tail n + * +-----------------+ | Msg 1 | + * | Msg 2 Offset |--------. | | + * +-----------------+ | | | + * | Msg 3 Offset |------. '->+-----------------+ + * +-----------------+ | | Msg 2 | + * Head --> | Head Offset |--. | | | + * +-----------------+ | | | | + * | | | | | | + * +-----------------+ | | | | + * | | | '--->+-----------------+ + * +-----------------+ | | Msg 3 | + * | | | | | + * +-----------------+ '------->+-----------------+ <-- dataHead + * | | | | + */ + + // Determine the index for the end of the circular ring buffer + // offset list + listEnd = rbOffsetHead; + WRAP_OFFSET(listEnd, 1, rbOffsetEntries); + + // Update the tail, walk newest message to oldest message + rbOffsetTail = rbOffsetHead; + bufferedData = 0; + messageLength = 0; + while ((rbOffsetTail != listEnd) && (bufferedData < use)) + { + // Determine the amount of data in the ring buffer up until + // either the tail or the end of the rbOffsetArray + // + // | | + // | | Valid, still in ring buffer + // | Newest | + // +-----------+ <-- rbOffsetHead + // | | + // | | free space + // | | + // rbOffsetTail --> +-----------+ <-- bufferedData + // | ring | + // | buffer | <-- used + // | data | + // +-----------+ Valid, still in ring buffer + // | | + // + messageLength = rbOffsetArray[rbOffsetTail]; + WRAP_OFFSET(rbOffsetTail, rbOffsetEntries - 1, rbOffsetEntries); + messageLength -= rbOffsetArray[rbOffsetTail]; + if (messageLength < 0) + messageLength += settings.gnssHandlerBufferSize; + bufferedData += messageLength; + } + + // Account for any data in the ring buffer not described by the array // // | | - // | | Valid, still in ring buffer + // +-----------+ + // | Oldest | + // | | + // | ring | + // | buffer | <-- used + // | data | + // +-----------+ Valid, still in ring buffer + // | | + // rbOffsetTail --> +-----------+ <-- bufferedData + // | | // | Newest | // +-----------+ <-- rbOffsetHead // | | - // | | free space + // + if (bufferedData < use) + discardedBytes = use - bufferedData; + + // Writing to the SD card, the network or Bluetooth, a partial + // message may be written leaving the tail pointer mid-message + // + // | | + // rbOffsetTail --> +-----------+ + // | Oldest | // | | - // rbOffsetTail --> +-----------+ <-- bufferedData // | ring | // | buffer | <-- used - // | data | - // +-----------+ Valid, still in ring buffer + // | data | Valid, still in ring buffer + // +-----------+ <-- + // | | + // +-----------+ + // | | + // | Newest | + // +-----------+ <-- rbOffsetHead // | | // - messageLength = rbOffsetArray[rbOffsetTail]; - WRAP_OFFSET(rbOffsetTail, rbOffsetEntries - 1, rbOffsetEntries); - messageLength -= rbOffsetArray[rbOffsetTail]; - if (messageLength < 0) - messageLength += settings.gnssHandlerBufferSize; - bufferedData += messageLength; - } + else if (bufferedData > use) + { + // Remove the remaining portion of the oldest entry in the array + discardedBytes = messageLength + use - bufferedData; + WRAP_OFFSET(rbOffsetTail, 1, rbOffsetEntries); + } - // Account for any data in the ring buffer not described by the array - // - // | | - // +-----------+ - // | Oldest | - // | | - // | ring | - // | buffer | <-- used - // | data | - // +-----------+ Valid, still in ring buffer - // | | - // rbOffsetTail --> +-----------+ <-- bufferedData - // | | - // | Newest | - // +-----------+ <-- rbOffsetHead - // | | - // - discardedBytes = 0; - if (bufferedData < use) - discardedBytes = use - bufferedData; + // rbOffsetTail now points to the beginning of a message in the + // ring buffer + // Determine the amount of data to discard + bytesToDiscard = discardedBytes; + if (bytesToDiscard < bytesToCopy) + bytesToDiscard = bytesToCopy; + if (bytesToDiscard < AMOUNT_OF_RING_BUFFER_DATA_TO_DISCARD) + bytesToDiscard = AMOUNT_OF_RING_BUFFER_DATA_TO_DISCARD; + + // Walk the ring buffer messages from oldest to newest + while ((discardedBytes < bytesToDiscard) && (rbOffsetTail != rbOffsetHead)) + { + // Determine the length of the oldest message + WRAP_OFFSET(rbOffsetTail, 1, rbOffsetEntries); + discardedBytes = rbOffsetArray[rbOffsetTail] - previousTail; + if (discardedBytes < 0) + discardedBytes += settings.gnssHandlerBufferSize; + } - // Writing to the SD card, the network or Bluetooth, a partial - // message may be written leaving the tail pointer mid-message - // - // | | - // rbOffsetTail --> +-----------+ - // | Oldest | - // | | - // | ring | - // | buffer | <-- used - // | data | Valid, still in ring buffer - // +-----------+ <-- - // | | - // +-----------+ - // | | - // | Newest | - // +-----------+ <-- rbOffsetHead - // | | - // - else if (bufferedData > use) - { - // Remove the remaining portion of the oldest entry in the array - discardedBytes = messageLength + use - bufferedData; - WRAP_OFFSET(rbOffsetTail, 1, rbOffsetEntries); + // Discard the oldest data from the ring buffer + // Printing the slow consumer is not that useful as any consumer will be + // considered 'slow' if its data wraps over the end of the buffer and + // needs a second write to clear... + if (!inMainMenu) + { + if (consumer) + systemPrintf("Ring buffer full: discarding %d bytes, %s could be slow\r\n", discardedBytes, consumer); + else + systemPrintf("Ring buffer full: discarding %d bytes\r\n", discardedBytes); + Serial.flush(); // TODO - delete me! + } + + // Update the tails. This needs semaphore protection + updateRingBufferTails(previousTail, rbOffsetArray[rbOffsetTail]); } - // rbOffsetTail now points to the beginning of a message in the - // ring buffer - // Determine the amount of data to discard - bytesToDiscard = discardedBytes; - if (bytesToDiscard < bytesToCopy) - bytesToDiscard = bytesToCopy; - if (bytesToDiscard < AMOUNT_OF_RING_BUFFER_DATA_TO_DISCARD) - bytesToDiscard = AMOUNT_OF_RING_BUFFER_DATA_TO_DISCARD; - - // Walk the ring buffer messages from oldest to newest - while ((discardedBytes < bytesToDiscard) && (rbOffsetTail != rbOffsetHead)) + if (bytesToCopy > (space + discardedBytes - 1)) // Sanity check { - // Determine the length of the oldest message - WRAP_OFFSET(rbOffsetTail, 1, rbOffsetEntries); - discardedBytes = rbOffsetArray[rbOffsetTail] - previousTail; - if (discardedBytes < 0) - discardedBytes += settings.gnssHandlerBufferSize; + systemPrintf("Ring buffer update error %s: bytesToCopy (%d) is > space (%d) + discardedBytes (%d) - 1\r\n", + getTimeStamp(), bytesToCopy, space, discardedBytes); + Serial.flush(); // Flush Serial - the code is about to go bang...! + } + + // Add another message to the ring buffer + // Account for this message + // Diagnostic prints are provided by settings.enablePrintSDBuffers and the handleGnssDataTask + // The semaphore prevents badness here. Previously availableHandlerSpace may have been updated + // by handleGnssDataTask + availableHandlerSpace = availableHandlerSpace + discardedBytes - bytesToCopy; + + // Copy dataHead so we can update with a single write - redundant with the semaphore + RING_BUFFER_OFFSET newDataHead = dataHead; + + // Fill the buffer to the end and then start at the beginning + if ((newDataHead + bytesToCopy) > settings.gnssHandlerBufferSize) + bytesToCopy = settings.gnssHandlerBufferSize - newDataHead; + + // Display the dataHead offset + if (settings.enablePrintRingBufferOffsets && (!inMainMenu)) + systemPrintf("DH: %4d --> ", newDataHead); + + // Copy the data into the ring buffer + memcpy(&ringBuffer[newDataHead], parse->buffer, bytesToCopy); + newDataHead = newDataHead + bytesToCopy; + if (newDataHead >= settings.gnssHandlerBufferSize) + newDataHead = newDataHead - settings.gnssHandlerBufferSize; + + // Determine the remaining bytes + remainingBytes = parse->length - bytesToCopy; + if (remainingBytes) + { + // Copy the remaining bytes into the beginning of the ring buffer + memcpy(ringBuffer, &parse->buffer[bytesToCopy], remainingBytes); + newDataHead = newDataHead + remainingBytes; + if (newDataHead >= settings.gnssHandlerBufferSize) + newDataHead = newDataHead - settings.gnssHandlerBufferSize; } - // Discard the oldest data from the ring buffer - if (consumer) - systemPrintf("Ring buffer full: discarding %d bytes, %s is slow\r\n", discardedBytes, consumer); - else - systemPrintf("Ring buffer full: discarding %d bytes\r\n", discardedBytes); - updateRingBufferTails(previousTail, rbOffsetArray[rbOffsetTail]); - availableHandlerSpace = availableHandlerSpace + discardedBytes; - } - - // Add another message to the ring buffer - // Account for this message - availableHandlerSpace = availableHandlerSpace - bytesToCopy; - - // Fill the buffer to the end and then start at the beginning - if ((dataHead + bytesToCopy) > settings.gnssHandlerBufferSize) - bytesToCopy = settings.gnssHandlerBufferSize - dataHead; + // Add the head offset to the offset array + WRAP_OFFSET(rbOffsetHead, 1, rbOffsetEntries); + rbOffsetArray[rbOffsetHead] = newDataHead; - // Display the dataHead offset - if (settings.enablePrintRingBufferOffsets && (!inMainMenu)) - systemPrintf("DH: %4d --> ", dataHead); + // Display the dataHead offset + if (settings.enablePrintRingBufferOffsets && (!inMainMenu)) + systemPrintf("%4d @ %s\r\n", newDataHead, getTimeStamp()); - // Copy the data into the ring buffer - memcpy(&ringBuffer[dataHead], parse->buffer, bytesToCopy); - dataHead = dataHead + bytesToCopy; - if (dataHead >= settings.gnssHandlerBufferSize) - dataHead = dataHead - settings.gnssHandlerBufferSize; + // Update dataHead in a single write - redundant with the semaphore + // handleGnssDataTask will use it as soon as it updates + dataHead = newDataHead; - // Determine the remaining bytes - remainingBytes = parse->length - bytesToCopy; - if (remainingBytes) + // handleGnssDataTask will be chomping at the bit. Let it fly! + xSemaphoreGive(ringBufferSemaphore); + } + else { - // Copy the remaining bytes into the beginning of the ring buffer - memcpy(ringBuffer, &parse->buffer[bytesToCopy], remainingBytes); - dataHead = dataHead + remainingBytes; - if (dataHead >= settings.gnssHandlerBufferSize) - dataHead = dataHead - settings.gnssHandlerBufferSize; + systemPrintf("processUart1Message could not get ringBuffer semaphore - held by %s\r\n", ringBufferSemaphoreHolder); } - - // Add the head offset to the offset array - WRAP_OFFSET(rbOffsetHead, 1, rbOffsetEntries); - rbOffsetArray[rbOffsetHead] = dataHead; - - // Display the dataHead offset - if (settings.enablePrintRingBufferOffsets && (!inMainMenu)) - systemPrintf("%4d\r\n", dataHead); } // Remove previous messages from the ring buffer @@ -1002,10 +1269,11 @@ void updateRingBufferTails(RING_BUFFER_OFFSET previousTail, RING_BUFFER_OFFSET n { // Trim any long or medium tails discardRingBufferBytes(&btRingBufferTail, previousTail, newTail); - discardRingBufferBytes(&sdRingBufferTail, previousTail, newTail); tcpClientDiscardBytes(previousTail, newTail); tcpServerDiscardBytes(previousTail, newTail); udpServerDiscardBytes(previousTail, newTail); + discardRingBufferBytes(&sdRingBufferTail, previousTail, newTail); + discardRingBufferBytes(&usbRingBufferTail, previousTail, newTail); } // Remove previous messages from the ring buffer @@ -1056,7 +1324,7 @@ void handleGnssDataTask(void *e) uint32_t deltaMillis; int32_t freeSpace; static uint32_t maxMillis[RBC_MAX]; - uint32_t startMillis; + unsigned long startMillis; int32_t usedSpace; // Start notification @@ -1070,13 +1338,14 @@ void handleGnssDataTask(void *e) tcpServerZeroTail(); udpServerZeroTail(); sdRingBufferTail = 0; + usbRingBufferTail = 0; // Run task until a request is raised task.handleGnssDataTaskStopRequest = false; while (task.handleGnssDataTaskStopRequest == false) { // Display an alive message - if (PERIODIC_DISPLAY(PD_TASK_HANDLE_GNSS_DATA)) + if (PERIODIC_DISPLAY(PD_TASK_HANDLE_GNSS_DATA) && !inMainMenu) { PERIODIC_CLEAR(PD_TASK_HANDLE_GNSS_DATA); systemPrintln("handleGnssDataTask running"); @@ -1084,337 +1353,448 @@ void handleGnssDataTask(void *e) usedSpace = 0; - //---------------------------------------------------------------------- - // Send data over Bluetooth - //---------------------------------------------------------------------- + // Use a semaphore to prevent handleGnssDataTask from gatecrashing + if (ringBufferSemaphore == NULL) + ringBufferSemaphore = xSemaphoreCreateMutex(); // Create the mutex + + // Take the semaphore. Short wait. processUart1Message shouldn't block for long + if (xSemaphoreTake(ringBufferSemaphore, ringBuffer_shortWait_ms) == pdPASS) + { + ringBufferSemaphoreHolder = "handleGnssDataTask"; - startMillis = millis(); + //---------------------------------------------------------------------- + // Send data over Bluetooth + //---------------------------------------------------------------------- - // Determine BT connection state - bool connected = (bluetoothGetState() == BT_CONNECTED); + startMillis = millis(); - if (!connected) - // Discard the data - btRingBufferTail = dataHead; - else - { - // Determine the amount of Bluetooth data in the buffer - bytesToSend = dataHead - btRingBufferTail; - if (bytesToSend < 0) - bytesToSend += settings.gnssHandlerBufferSize; - if (bytesToSend > 0) - { - // Reduce bytes to send if we have more to send then the end of - // the buffer, we'll wrap next loop - if ((btRingBufferTail + bytesToSend) > settings.gnssHandlerBufferSize) - bytesToSend = settings.gnssHandlerBufferSize - btRingBufferTail; + // Determine BT connection state. Discard the data if in BLUETOOTH_RADIO_SPP_ACCESSORY_MODE + bool connected = false; + if (settings.bluetoothRadioType != BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + connected = (bluetoothGetState() == BT_CONNECTED); - // If we are in the config menu, suppress data flowing from GNSS to cell phone - if (btPrintEcho == false) - { - // Push new data over Bluetooth - bytesToSend = bluetoothWrite(&ringBuffer[btRingBufferTail], bytesToSend); - } - - // Account for the data that was sent + if (!connected) + // Discard the data + btRingBufferTail = dataHead; + else + { + // Determine the amount of Bluetooth data in the buffer + bytesToSend = dataHead - btRingBufferTail; + if (bytesToSend < 0) + bytesToSend += settings.gnssHandlerBufferSize; if (bytesToSend > 0) { - // If we are in base mode, assume part of the outgoing data is RTCM - if (inBaseMode() == true) - bluetoothOutgoingRTCM = true; - - // Account for the sent or dropped data - btRingBufferTail += bytesToSend; - if (btRingBufferTail >= settings.gnssHandlerBufferSize) - btRingBufferTail -= settings.gnssHandlerBufferSize; - - // Remember the maximum transfer time - deltaMillis = millis() - startMillis; - if (maxMillis[RBC_BLUETOOTH] < deltaMillis) - maxMillis[RBC_BLUETOOTH] = deltaMillis; - - // Display the data movement - if (PERIODIC_DISPLAY(PD_BLUETOOTH_DATA_TX)) + // Reduce bytes to send if we have more to send then the end of + // the buffer, we'll wrap next loop + if ((btRingBufferTail + bytesToSend) > settings.gnssHandlerBufferSize) + bytesToSend = settings.gnssHandlerBufferSize - btRingBufferTail; + + // If we are in the config menu, suppress data flowing from GNSS to cell phone + if (btPrintEcho == false) + { + // Push new data over Bluetooth + bytesToSend = bluetoothWrite(&ringBuffer[btRingBufferTail], bytesToSend); + } + + // Account for the data that was sent + if (bytesToSend > 0) + { + // If we are in base mode, assume part of the outgoing data is RTCM + if (inBaseMode() == true) + bluetoothOutgoingRTCM = true; + + // Account for the sent or dropped data + btRingBufferTail += bytesToSend; + if (btRingBufferTail >= settings.gnssHandlerBufferSize) + btRingBufferTail -= settings.gnssHandlerBufferSize; + + // Remember the maximum transfer time + deltaMillis = millis() - startMillis; + if (maxMillis[RBC_BLUETOOTH] < deltaMillis) + maxMillis[RBC_BLUETOOTH] = deltaMillis; + + // Display the data movement + if (PERIODIC_DISPLAY(PD_BLUETOOTH_DATA_TX) && !inMainMenu) + { + PERIODIC_CLEAR(PD_BLUETOOTH_DATA_TX); + systemPrintf("Bluetooth: %d bytes written\r\n", bytesToSend); + } + } + else + log_w("BT failed to send"); + + // Determine the amount of data that remains in the buffer + bytesToSend = dataHead - btRingBufferTail; + if (bytesToSend < 0) + bytesToSend += settings.gnssHandlerBufferSize; + if (usedSpace < bytesToSend) { - PERIODIC_CLEAR(PD_BLUETOOTH_DATA_TX); - systemPrintf("Bluetooth: %d bytes written\r\n", bytesToSend); + usedSpace = bytesToSend; + slowConsumer = "Bluetooth"; } } - else - log_w("BT failed to send"); + } - // Determine the amount of data that remains in the buffer - bytesToSend = dataHead - btRingBufferTail; + //---------------------------------------------------------------------- + // Send data over USB serial + //---------------------------------------------------------------------- + + startMillis = millis(); + + // Determine USB serial connection state + if (!forwardGnssDataToUsbSerial) + // Discard the data + usbRingBufferTail = dataHead; + else + { + // Determine the amount of USB serial data in the buffer + bytesToSend = dataHead - usbRingBufferTail; if (bytesToSend < 0) bytesToSend += settings.gnssHandlerBufferSize; - if (usedSpace < bytesToSend) + if (bytesToSend > 0) { - usedSpace = bytesToSend; - slowConsumer = "Bluetooth"; + // Reduce bytes to send if we have more to send then the end of + // the buffer, we'll wrap next loop + if ((usbRingBufferTail + bytesToSend) > settings.gnssHandlerBufferSize) + bytesToSend = settings.gnssHandlerBufferSize - usbRingBufferTail; + + // Send data over USB serial to the PC + bytesToSend = systemWriteGnssDataToUsbSerial(&ringBuffer[usbRingBufferTail], bytesToSend); + + // Account for the data that was sent + if (bytesToSend > 0) + { + // Account for the sent or dropped data + usbRingBufferTail += bytesToSend; + if (usbRingBufferTail >= settings.gnssHandlerBufferSize) + usbRingBufferTail -= settings.gnssHandlerBufferSize; + + // Remember the maximum transfer time + deltaMillis = millis() - startMillis; + if (maxMillis[RBC_USB_SERIAL] < deltaMillis) + maxMillis[RBC_USB_SERIAL] = deltaMillis; + } + + // Determine the amount of data that remains in the buffer + bytesToSend = dataHead - usbRingBufferTail; + if (bytesToSend < 0) + bytesToSend += settings.gnssHandlerBufferSize; + if (usedSpace < bytesToSend) + { + usedSpace = bytesToSend; + slowConsumer = "USB Serial"; + } } } - } - //---------------------------------------------------------------------- - // Send data over USB serial - //---------------------------------------------------------------------- + //---------------------------------------------------------------------- + // Send data to the network clients + //---------------------------------------------------------------------- - startMillis = millis(); + startMillis = millis(); - // Determine USB serial connection state - if (!forwardGnssDataToUsbSerial) - // Discard the data - usbRingBufferTail = dataHead; - else - { - // Determine the amount of USB serial data in the buffer - bytesToSend = dataHead - usbRingBufferTail; - if (bytesToSend < 0) - bytesToSend += settings.gnssHandlerBufferSize; - if (bytesToSend > 0) + // Update space available for use in UART task + bytesToSend = tcpClientSendData(dataHead); + if (usedSpace < bytesToSend) + { + usedSpace = bytesToSend; + slowConsumer = "TCP client"; + } + + // Remember the maximum transfer time + deltaMillis = millis() - startMillis; + if (maxMillis[RBC_TCP_CLIENT] < deltaMillis) + maxMillis[RBC_TCP_CLIENT] = deltaMillis; + + startMillis = millis(); + + // Update space available for use in UART task + bytesToSend = tcpServerSendData(dataHead); + if (usedSpace < bytesToSend) { - // Reduce bytes to send if we have more to send then the end of - // the buffer, we'll wrap next loop - if ((usbRingBufferTail + bytesToSend) > settings.gnssHandlerBufferSize) - bytesToSend = settings.gnssHandlerBufferSize - usbRingBufferTail; + usedSpace = bytesToSend; + slowConsumer = "TCP server"; + } - // Send data over USB serial to the PC - bytesToSend = systemWriteGnssDataToUsbSerial(&ringBuffer[usbRingBufferTail], bytesToSend); + // Remember the maximum transfer time + deltaMillis = millis() - startMillis; + if (maxMillis[RBC_TCP_SERVER] < deltaMillis) + maxMillis[RBC_TCP_SERVER] = deltaMillis; - // Account for the data that was sent - if (bytesToSend > 0) - { - // Account for the sent or dropped data - usbRingBufferTail += bytesToSend; - if (usbRingBufferTail >= settings.gnssHandlerBufferSize) - usbRingBufferTail -= settings.gnssHandlerBufferSize; - - // Remember the maximum transfer time - deltaMillis = millis() - startMillis; - if (maxMillis[RBC_USB_SERIAL] < deltaMillis) - maxMillis[RBC_USB_SERIAL] = deltaMillis; - } + startMillis = millis(); - // Determine the amount of data that remains in the buffer - bytesToSend = dataHead - usbRingBufferTail; + // Update space available for use in UART task + bytesToSend = udpServerSendData(dataHead); + if (usedSpace < bytesToSend) + { + usedSpace = bytesToSend; + slowConsumer = "UDP server"; + } + + // Remember the maximum transfer time + deltaMillis = millis() - startMillis; + if (maxMillis[RBC_UDP_SERVER] < deltaMillis) + maxMillis[RBC_UDP_SERVER] = deltaMillis; + + //---------------------------------------------------------------------- + // Log data to the SD card + //---------------------------------------------------------------------- + + // Determine if the SD card is enabled for logging + connected = online.logging && (!logTimeExceeded()); + + // Block logging during Web Config to avoid SD collisions + // See issue: https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/issues/693 + if(webServerIsRunning() == true) + connected = false; + + // If user wants to log, record to SD + if (!connected) + // Discard the data + sdRingBufferTail = dataHead; + else + { + // Determine the amount of microSD card logging data in the buffer + bytesToSend = dataHead - sdRingBufferTail; if (bytesToSend < 0) bytesToSend += settings.gnssHandlerBufferSize; - if (usedSpace < bytesToSend) + if (bytesToSend > 0) { - usedSpace = bytesToSend; - slowConsumer = "USB Serial"; - } - } - } + // Attempt to gain access to the SD card, avoids collisions with file + // writing from other functions like recordSystemSettingsToFile() + if (xSemaphoreTake(sdCardSemaphore, loggingSemaphoreWait_ms) == pdPASS) + { + markSemaphore(FUNCTION_WRITESD); - //---------------------------------------------------------------------- - // Send data to the network clients - //---------------------------------------------------------------------- + do // Do the SD write in a do loop so we can break out if needed + { + if (settings.enablePrintSDBuffers && (!inMainMenu)) + { + int bufferAvailable = serialGNSS->available(); - startMillis = millis(); + int availableUARTSpace = settings.uartReceiveBufferSize - bufferAvailable; - // Update space available for use in UART task - bytesToSend = tcpClientSendData(dataHead); - if (usedSpace < bytesToSend) - { - usedSpace = bytesToSend; - slowConsumer = "TCP client"; - } + systemPrintf("SD Incoming Serial @ %s: %04d\tToRead: %04d\tMovedToBuffer: %04d\tavailableUARTSpace: " + "%04d\tavailableHandlerSpace: %04d\tToRecord: %04d\tRecorded: %04d\tBO: %d\r\n", + getTimeStamp(), bufferAvailable, 0, 0, availableUARTSpace, availableHandlerSpace, + bytesToSend, 0, bufferOverruns); + } - // Remember the maximum transfer time - deltaMillis = millis() - startMillis; - if (maxMillis[RBC_TCP_CLIENT] < deltaMillis) - maxMillis[RBC_TCP_CLIENT] = deltaMillis; + // For the SD card, we need to write everything we've got + // to prevent the ARP Write and Events from gatecrashing... + + int32_t sendTheseBytes = bytesToSend; - startMillis = millis(); + // Reduce bytes to record if we have more then the end of the buffer + if ((sdRingBufferTail + sendTheseBytes) > settings.gnssHandlerBufferSize) + sendTheseBytes = settings.gnssHandlerBufferSize - sdRingBufferTail; - // Update space available for use in UART task - bytesToSend = tcpServerSendData(dataHead); - if (usedSpace < bytesToSend) - { - usedSpace = bytesToSend; - slowConsumer = "TCP server"; - } + startMillis = millis(); - // Remember the maximum transfer time - deltaMillis = millis() - startMillis; - if (maxMillis[RBC_TCP_SERVER] < deltaMillis) - maxMillis[RBC_TCP_SERVER] = deltaMillis; + // Write the data to the file + int32_t bytesSent = logFile->write(&ringBuffer[sdRingBufferTail], sendTheseBytes); - startMillis = millis(); + // Account for the sent data or dropped + sdRingBufferTail += bytesSent; + if (sdRingBufferTail >= settings.gnssHandlerBufferSize) + sdRingBufferTail -= settings.gnssHandlerBufferSize; - // Update space available for use in UART task - bytesToSend = udpServerSendData(dataHead); - if (usedSpace < bytesToSend) - { - usedSpace = bytesToSend; - slowConsumer = "UDP server"; - } + if (bytesSent != sendTheseBytes) + { + systemPrintf("SD write mismatch (1) @ %s: wrote %d bytes of %d\r\n", + getTimeStamp(), bytesSent, sendTheseBytes); + break; // Exit the do loop + } - // Remember the maximum transfer time - deltaMillis = millis() - startMillis; - if (maxMillis[RBC_UDP_SERVER] < deltaMillis) - maxMillis[RBC_UDP_SERVER] = deltaMillis; + // If we have more data to write - and the first write was successful + if (bytesToSend > sendTheseBytes) + { + sendTheseBytes = bytesToSend - sendTheseBytes; - //---------------------------------------------------------------------- - // Log data to the SD card - //---------------------------------------------------------------------- + bytesSent = logFile->write(&ringBuffer[sdRingBufferTail], sendTheseBytes); - // Determine if the SD card is enabled for logging - connected = online.logging && ((systemTime_minutes - startLogTime_minutes) < settings.maxLogTime_minutes); + // Account for the sent data or dropped + sdRingBufferTail += bytesSent; + if (sdRingBufferTail >= settings.gnssHandlerBufferSize) // Should be redundant + sdRingBufferTail -= settings.gnssHandlerBufferSize; - // Block logging during Web Config to avoid SD collisions - // See issue: https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/issues/693 - if(webServerIsRunning() == true) - connected = false; + if (bytesSent != sendTheseBytes) + { + systemPrintf("SD write mismatch (2) @ %s: wrote %d bytes of %d\r\n", + getTimeStamp(), bytesSent, sendTheseBytes); + break; // Exit the do loop + } + } - // If user wants to log, record to SD - if (!connected) - // Discard the data - sdRingBufferTail = dataHead; - else - { - // Determine the amount of microSD card logging data in the buffer - bytesToSend = dataHead - sdRingBufferTail; - if (bytesToSend < 0) - bytesToSend += settings.gnssHandlerBufferSize; - if (bytesToSend > 0) - { - // Attempt to gain access to the SD card, avoids collisions with file - // writing from other functions like recordSystemSettingsToFile() - if (xSemaphoreTake(sdCardSemaphore, loggingSemaphoreWait_ms) == pdPASS) - { - markSemaphore(FUNCTION_WRITESD); + if (PERIODIC_DISPLAY(PD_SD_LOG_WRITE) && (bytesSent > 0) && (!inMainMenu)) + { + PERIODIC_CLEAR(PD_SD_LOG_WRITE); + systemPrintf("SD %d bytes written to log file\r\n", bytesToSend); + } - // Reduce bytes to record if we have more then the end of the buffer - if ((sdRingBufferTail + bytesToSend) > settings.gnssHandlerBufferSize) - bytesToSend = settings.gnssHandlerBufferSize - sdRingBufferTail; + sdFreeSpace -= bytesToSend; // Update remaining space on SD - if (settings.enablePrintSDBuffers && (!inMainMenu)) - { - int bufferAvailable = serialGNSS->available(); + // Record any pending trigger events + if (newEventToRecord == true) + { + newEventToRecord = false; - int availableUARTSpace = settings.uartReceiveBufferSize - bufferAvailable; + if ((settings.enablePrintLogFileStatus) && (!inMainMenu)) + systemPrintln("Log file: recording event"); - systemPrintf("SD Incoming Serial: %04d\tToRead: %04d\tMovedToBuffer: %04d\tavailableUARTSpace: " - "%04d\tavailableHandlerSpace: %04d\tToRecord: %04d\tRecorded: %04d\tBO: %d\r\n", - bufferAvailable, 0, 0, availableUARTSpace, availableHandlerSpace, bytesToSend, 0, - bufferOverruns); - } + // Record trigger count with Time Of Week of rising edge (ms), Millisecond fraction of Time Of Week of + // rising edge (ns), and accuracy estimate (ns) + char eventData[82]; // Max NMEA sentence length is 82 + snprintf(eventData, sizeof(eventData), "%lu,%lu,%lu,%lu", triggerCount, triggerTowMsR, triggerTowSubMsR, + triggerAccEst); - // Write the data to the file - long startTime = millis(); - startMillis = millis(); + char nmeaMessage[82]; // Max NMEA sentence length is 82 + createNMEASentence(CUSTOM_NMEA_TYPE_EVENT, nmeaMessage, sizeof(nmeaMessage), + eventData); // textID, buffer, sizeOfBuffer, text - bytesToSend = logFile->write(&ringBuffer[sdRingBufferTail], bytesToSend); - if (PERIODIC_DISPLAY(PD_SD_LOG_WRITE) && (bytesToSend > 0)) - { - PERIODIC_CLEAR(PD_SD_LOG_WRITE); - systemPrintf("SD %d bytes written to log file\r\n", bytesToSend); - } + logFile->write(nmeaMessage, strlen(nmeaMessage)); + const char *crlf = "\r\n"; + logFile->write(crlf, 2); - logFileSize = logFile->fileSize(); // Update file size + sdFreeSpace -= strlen(nmeaMessage) + 2; // Update remaining space on SD + } - sdFreeSpace -= bytesToSend; // Update remaining space on SD + // Record the Antenna Reference Position - if available + if (newARPAvailable == true && settings.enableARPLogging && + ((millis() - lastARPLog) > (settings.ARPLoggingInterval_s * 1000))) + { + lastARPLog = millis(); + newARPAvailable = false; // Clear flag. It doesn't matter if the ARP cannot be logged + + double x = ARPECEFX; + x /= 10000.0; // Convert to m + double y = ARPECEFY; + y /= 10000.0; // Convert to m + double z = ARPECEFZ; + z /= 10000.0; // Convert to m + double h = ARPECEFH; + h /= 10000.0; // Convert to m + char ARPData[82]; // Max NMEA sentence length is 82 + snprintf(ARPData, sizeof(ARPData), "%.4f,%.4f,%.4f,%.4f", x, y, z, h); + + if ((settings.enablePrintLogFileStatus) && (!inMainMenu)) + systemPrintf("Log file: recording Antenna Reference Position %s\r\n", ARPData); + + char nmeaMessage[82]; // Max NMEA sentence length is 82 + createNMEASentence(CUSTOM_NMEA_TYPE_ARP_ECEF_XYZH, nmeaMessage, sizeof(nmeaMessage), + ARPData); // textID, buffer, sizeOfBuffer, text + + logFile->write(nmeaMessage, strlen(nmeaMessage)); + const char *crlf = "\r\n"; + logFile->write(crlf, 2); + + sdFreeSpace -= strlen(nmeaMessage) + 2; // Update remaining space on SD + } - // Force file sync every 60s - if (millis() - lastUBXLogSyncTime > 60000) - { - baseStatusLedBlink(); // Blink LED to indicate logging activity + logFileSize = logFile->fileSize(); // Update file size - logFile->sync(); - sdUpdateFileAccessTimestamp(logFile); // Update the file access time & date + // Force file sync every 60s - or every two seconds if the size is not increasing + if (((logFileSize == lastLogSize) && ((millis() - lastUBXLogSyncTime) > 2000)) + || ((millis() - lastUBXLogSyncTime) > 60000)) + { + baseStatusLedBlink(); // Blink LED to indicate logging activity - baseStatusLedBlink(); // Blink LED to indicate logging activity + logFile->sync(); + sdUpdateFileAccessTimestamp(logFile); // Update the file access time & date - lastUBXLogSyncTime = millis(); - } + baseStatusLedBlink(); // Blink LED to indicate logging activity - // Remember the maximum transfer time - deltaMillis = millis() - startMillis; - if (maxMillis[RBC_SD_CARD] < deltaMillis) - maxMillis[RBC_SD_CARD] = deltaMillis; - long endTime = millis(); + lastUBXLogSyncTime = millis(); + } - if (settings.enablePrintBufferOverrun) - { - if (endTime - startTime > 150) - systemPrintf("Long Write! Time: %ld ms / Location: %ld / Recorded %d bytes / " - "spaceRemaining %d bytes\r\n", - endTime - startTime, logFileSize, bytesToSend, combinedSpaceRemaining); - } + // Remember the maximum transfer time + deltaMillis = millis() - startMillis; + if (maxMillis[RBC_SD_CARD] < deltaMillis) + maxMillis[RBC_SD_CARD] = deltaMillis; - xSemaphoreGive(sdCardSemaphore); + if (settings.enablePrintBufferOverrun) + { + if (deltaMillis > 150) + systemPrintf("Long Write! Time: %ld ms / Location: %ld / Recorded %d bytes / " + "spaceRemaining %d bytes\r\n", + deltaMillis, logFileSize, bytesToSend, combinedSpaceRemaining); + } + } while(0); - // Account for the sent data or dropped - if (bytesToSend > 0) + xSemaphoreGive(sdCardSemaphore); + } // End sdCardSemaphore + else { - sdRingBufferTail += bytesToSend; - if (sdRingBufferTail >= settings.gnssHandlerBufferSize) - sdRingBufferTail -= settings.gnssHandlerBufferSize; - } - } // End sdCardSemaphore - else - { - char semaphoreHolder[50]; - getSemaphoreFunction(semaphoreHolder); - log_w("sdCardSemaphore failed to yield for SD write, held by %s, Tasks.ino line %d", - semaphoreHolder, __LINE__); + char semaphoreHolder[50]; + getSemaphoreFunction(semaphoreHolder); + log_w("sdCardSemaphore failed to yield for SD write, held by %s, Tasks.ino line %d", + semaphoreHolder, __LINE__); - delay(1); // Needed to prevent WDT resets during long Record Settings locks - taskYIELD(); - } - - // Update space available for use in UART task - bytesToSend = dataHead - sdRingBufferTail; - if (bytesToSend < 0) - bytesToSend += settings.gnssHandlerBufferSize; - if (usedSpace < bytesToSend) - { - usedSpace = bytesToSend; - slowConsumer = "SD card"; - } - } // bytesToSend - } // End connected + feedWdt(); + taskYIELD(); + } - //---------------------------------------------------------------------- - // Update the available space in the ring buffer - //---------------------------------------------------------------------- + // Update space available for use in UART task + bytesToSend = dataHead - sdRingBufferTail; + if (bytesToSend < 0) + bytesToSend += settings.gnssHandlerBufferSize; + if (usedSpace < bytesToSend) + { + usedSpace = bytesToSend; + slowConsumer = "SD card"; + } + } // bytesToSend + } // End connected - freeSpace = settings.gnssHandlerBufferSize - usedSpace; + //---------------------------------------------------------------------- + // Update the available space in the ring buffer + //---------------------------------------------------------------------- - // Don't fill the last byte to prevent buffer overflow - if (freeSpace) - freeSpace -= 1; - availableHandlerSpace = freeSpace; + freeSpace = settings.gnssHandlerBufferSize - usedSpace; - //---------------------------------------------------------------------- - // Display the millisecond values for the different ring buffer consumers - //---------------------------------------------------------------------- + // Don't fill the last byte to prevent buffer overflow + if (freeSpace) + freeSpace -= 1; + availableHandlerSpace = freeSpace; - if (PERIODIC_DISPLAY(PD_RING_BUFFER_MILLIS)) - { - int milliseconds; - int seconds; + //---------------------------------------------------------------------- + // Display the millisecond values for the different ring buffer consumers + //---------------------------------------------------------------------- - PERIODIC_CLEAR(PD_RING_BUFFER_MILLIS); - for (int index = 0; index < RBC_MAX; index++) + if (PERIODIC_DISPLAY(PD_RING_BUFFER_MILLIS) && !inMainMenu) { - milliseconds = maxMillis[index]; - if (milliseconds > 1) + int milliseconds; + int seconds; + + PERIODIC_CLEAR(PD_RING_BUFFER_MILLIS); + for (int index = 0; index < RBC_MAX; index++) { - seconds = milliseconds / MILLISECONDS_IN_A_SECOND; - milliseconds %= MILLISECONDS_IN_A_SECOND; - systemPrintf("%s: %d:%03d Sec\r\n", ringBufferConsumer[index], seconds, milliseconds); + milliseconds = maxMillis[index]; + if (milliseconds > 1) + { + seconds = milliseconds / MILLISECONDS_IN_A_SECOND; + milliseconds %= MILLISECONDS_IN_A_SECOND; + systemPrintf("%s: %d:%03d Sec\r\n", ringBufferConsumer[index], seconds, milliseconds); + } } } + + //---------------------------------------------------------------------- + // processUart1Message will be chomping at the bit. Let it fly! + //---------------------------------------------------------------------- + + xSemaphoreGive(ringBufferSemaphore); + } + else + { + systemPrintf("handleGnssDataTask could not get ringBuffer semaphore - held by %s\r\n", ringBufferSemaphoreHolder); } //---------------------------------------------------------------------- // Let other tasks run, prevent watch dog timer (WDT) resets //---------------------------------------------------------------------- - delay(1); + feedWdt(); taskYIELD(); } @@ -1468,7 +1848,7 @@ void tickerGnssLedUpdate() ledCallCounter++; ledCallCounter %= gnssTaskUpdatesHz; // Wrap to X calls per 1 second - if (productVariant == RTK_TORCH) + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) { // Update the GNSS LED according to our state @@ -1492,7 +1872,7 @@ void tickerBatteryLedUpdate() batteryCallCounter++; batteryCallCounter %= batteryTaskUpdatesHz; // Wrap to X calls per 1 second - if (productVariant == RTK_TORCH) + if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) { // Update the Battery LED according to the battery level @@ -1543,7 +1923,8 @@ void tickerBeepUpdate() break; case BEEP_ON: - if (millis() >= beepNextEventMs) + // https://stackoverflow.com/a/3097744 - see issue #742 + if (!((long)(beepNextEventMs - millis()) > 0)) { if (beepCount == 1) { @@ -1561,7 +1942,7 @@ void tickerBeepUpdate() break; case BEEP_QUIET: - if (millis() >= beepNextEventMs) + if (!((long)(beepNextEventMs - millis()) > 0)) { beepCount--; @@ -1611,7 +1992,7 @@ void buttonCheckTask(void *e) while (task.buttonCheckTaskStopRequest == false) { // Display an alive message - if (PERIODIC_DISPLAY(PD_TASK_BUTTON_CHECK)) + if (PERIODIC_DISPLAY(PD_TASK_BUTTON_CHECK) && !inMainMenu) { PERIODIC_CLEAR(PD_TASK_BUTTON_CHECK); systemPrintln("ButtonCheckTask running"); @@ -1682,7 +2063,31 @@ void buttonCheckTask(void *e) // End button checking - if (present.imu_im19 && (present.display_type == DISPLAY_MAX_NONE)) + // If in direct connect mode. Note: this is just a flag not a STATE. + if (inDirectConnectMode) + { + // TODO: check if this works on both Torch and Flex. Note: Flex does not yet support buttons + if (singleTap || doubleTap) + { + // Beep to indicate exit + beepOn(); + delay(300); + beepOff(); + delay(100); + beepOn(); + delay(300); + beepOff(); + + systemPrintln("Exiting direct connection (passthrough) mode"); + systemFlush(); // Complete prints + + // See #763 . Do the file removal in the loop + task.endDirectConnectMode = true; // Indicate to loop that direct connection should be ended + } + } + // Torch is a special case. Handle tilt stop and web config mode + else if (productVariant == RTK_TORCH) + //else if (present.imu_im19 && (present.display_type == DISPLAY_MAX_NONE)) // TODO delete me { // Platform has no display and tilt corrections, ie RTK Torch @@ -1779,7 +2184,7 @@ void buttonCheckTask(void *e) else if ((systemState == STATE_BASE_NOT_STARTED) && (firstRoverStart == true) && (buttonPressedFor(500) == true)) { - lastSetupMenuChange = millis(); // Prevent a timeout during state change + lastSetupMenuChange.setTimerToMillis(); // Prevent a timeout during state change forceSystemStateUpdate = true; requestChangeState(STATE_TEST); } @@ -1812,7 +2217,7 @@ void buttonCheckTask(void *e) case STATE_NTPSERVER_SYNC: lastSystemState = systemState; // Remember this state to return if needed requestChangeState(STATE_DISPLAY_SETUP); - lastSetupMenuChange = millis(); + lastSetupMenuChange.setTimerToMillis(); setupSelectedButton = 0; // Highlight the first button showMenu = false; break; @@ -1821,11 +2226,11 @@ void buttonCheckTask(void *e) // If we are displaying the setup menu, a single tap will cycle through possible system states // Exit into new system state on double tap - see below // Exit display setup into previous state after ~10s - see updateSystemState() - lastSetupMenuChange = millis(); + lastSetupMenuChange.setTimerToMillis(); forceDisplayUpdate = true; // User is interacting so repaint display quickly - if (online.gpioExpander == true) + if (online.gpioExpanderButtons == true) { // React to five different buttons if (buttonLastPressed() == gpioExpander_up || buttonLastPressed() == gpioExpander_left) @@ -1858,7 +2263,7 @@ void buttonCheckTask(void *e) case STATE_TESTING: // If we are in testing, return to Base Not Started - lastSetupMenuChange = millis(); // Prevent a timeout during state change + lastSetupMenuChange.setTimerToMillis(); // Prevent a timeout during state change baseCasterDisableOverride(); // Leave Caster mode requestChangeState(STATE_BASE_NOT_STARTED); break; @@ -1878,11 +2283,12 @@ void buttonCheckTask(void *e) { switch (systemState) { - case STATE_DISPLAY_SETUP: { + case STATE_DISPLAY_SETUP: + { // If we are displaying the setup menu, a single tap will cycle through possible system states - see // above Exit into new system state on double tap Exit display setup into previous state after ~10s // - see updateSystemState() - lastSetupMenuChange = millis(); // Prevent a timeout during state change + lastSetupMenuChange.setTimerToMillis(); // Prevent a timeout during state change uint8_t thisIsButton = 0; for (auto it = setupButtons.begin(); it != setupButtons.end(); it = std::next(it)) { @@ -2015,7 +2421,7 @@ bool tasksStartGnssUart() availableHandlerSpace = settings.gnssHandlerBufferSize; - // Reads data from ZED and stores data into circular buffer + // Reads data from GNSS and stores data into circular buffer if (!task.gnssReadTaskRunning) xTaskCreatePinnedToCore(gnssReadTask, // Function to call "gnssRead", // Just for humans @@ -2077,7 +2483,7 @@ void sdSizeCheckTask(void *e) while (task.sdSizeCheckTaskStopRequest == false) { // Display an alive message - if (PERIODIC_DISPLAY(PD_TASK_SD_SIZE_CHECK)) + if (PERIODIC_DISPLAY(PD_TASK_SD_SIZE_CHECK) && !inMainMenu) { PERIODIC_CLEAR(PD_TASK_SD_SIZE_CHECK); systemPrintln("sdSizeCheckTask running"); @@ -2123,7 +2529,7 @@ void sdSizeCheckTask(void *e) } } - delay(1); + feedWdt(); taskYIELD(); // Let other tasks run } @@ -2158,7 +2564,7 @@ void bluetoothCommandTask(void *pvParameters) while (task.bluetoothCommandTaskStopRequest == false) { // Display an alive message - if (PERIODIC_DISPLAY(PD_TASK_BLUETOOTH_READ)) + if (PERIODIC_DISPLAY(PD_TASK_BLUETOOTH_READ) && !inMainMenu) { PERIODIC_CLEAR(PD_TASK_BLUETOOTH_READ); systemPrintln("bluetoothCommandTask running"); @@ -2176,12 +2582,12 @@ void bluetoothCommandTask(void *pvParameters) if (rxSpot > 2 && rxData[rxSpot - 1] == '\n' && rxData[rxSpot - 2] == '\r') { rxData[rxSpot - 2] = '\0'; // Remove \r\n - bluetoothProcessCommand(rxData); + processCommand(rxData); rxSpot = 0; // Reset } } - if (PERIODIC_DISPLAY(PD_BLUETOOTH_DATA_RX)) + if (PERIODIC_DISPLAY(PD_BLUETOOTH_DATA_RX) && !inMainMenu) { PERIODIC_CLEAR(PD_BLUETOOTH_DATA_RX); systemPrintf("Bluetooth received %d bytes\r\n", rxSpot); @@ -2200,3 +2606,45 @@ void bluetoothCommandTask(void *pvParameters) task.bluetoothCommandTaskRunning = false; vTaskDelete(NULL); } + +void beginRtcmParse() +{ + // Begin the RTCM parser - which will extract the base location from RTCM1005 / 1006 + rtcmParse = sempBeginParser(rtcmParserTable, rtcmParserCount, rtcmParserNames, rtcmParserNameCount, + 0, // Scratchpad bytes + 1050, // Buffer length + processRTCMMessage, // eom Call Back + "rtcmParse"); // Parser Name + if (!rtcmParse) + reportFatalError("Failed to initialize the RTCM parser"); + + if (settings.debugNtripClientRtcm) + { + sempEnableDebugOutput(rtcmParse); + sempPrintParserConfiguration(rtcmParse); + } +} + +// Check and record the base location in RTCM1005/1006 +void processRTCMMessage(SEMP_PARSE_STATE *parse, uint16_t type) +{ + SEMP_SCRATCH_PAD *scratchPad = (SEMP_SCRATCH_PAD *)parse->scratchPad; + + if (sempRtcmGetMessageNumber(parse) == 1005) + { + ARPECEFX = sempRtcmGetSignedBits(parse, 34, 38); + ARPECEFY = sempRtcmGetSignedBits(parse, 74, 38); + ARPECEFZ = sempRtcmGetSignedBits(parse, 114, 38); + ARPECEFH = 0; + newARPAvailable = true; + } + + if (sempRtcmGetMessageNumber(parse) == 1006) + { + ARPECEFX = sempRtcmGetSignedBits(parse, 34, 38); + ARPECEFY = sempRtcmGetSignedBits(parse, 74, 38); + ARPECEFZ = sempRtcmGetSignedBits(parse, 114, 38); + ARPECEFH = sempRtcmGetUnsignedBits(parse, 152, 16); + newARPAvailable = true; + } +} \ No newline at end of file diff --git a/Firmware/RTK_Everywhere/TcpClient.ino b/Firmware/RTK_Everywhere/TcpClient.ino index 1e2ff2706..e45def741 100644 --- a/Firmware/RTK_Everywhere/TcpClient.ino +++ b/Firmware/RTK_Everywhere/TcpClient.ino @@ -249,6 +249,9 @@ int32_t tcpClientSendData(uint16_t dataHead) bytesToSend = dataHead - tcpClientTail; if (bytesToSend < 0) bytesToSend += settings.gnssHandlerBufferSize; + + while(tcpClient->available()) + tcpClient->read(); // Absorb any unwanted incoming traffic } // Failed to write the data @@ -571,7 +574,7 @@ void tcpClientUpdate() } // Periodically display the TCP client state - if (PERIODIC_DISPLAY(PD_TCP_CLIENT_STATE)) + if (PERIODIC_DISPLAY(PD_TCP_CLIENT_STATE) && !inMainMenu) { systemPrintf("TCP Client state: %s%s\r\n", tcpClientStateName[tcpClientState], line); diff --git a/Firmware/RTK_Everywhere/TcpServer.ino b/Firmware/RTK_Everywhere/TcpServer.ino index 170f86979..f3ad3e840 100644 --- a/Firmware/RTK_Everywhere/TcpServer.ino +++ b/Firmware/RTK_Everywhere/TcpServer.ino @@ -79,10 +79,30 @@ const char *const tcpServerStateName[] = { "TCP_SERVER_STATE_WAIT_FOR_NETWORK", "TCP_SERVER_STATE_RUNNING", }; - const int tcpServerStateNameEntries = sizeof(tcpServerStateName) / sizeof(tcpServerStateName[0]); -const RtkMode_t tcpServerMode = RTK_MODE_BASE_FIXED | RTK_MODE_BASE_SURVEY_IN | RTK_MODE_ROVER; +// Define the TCP server client states +enum tcpServerClientStates +{ + TCP_SERVER_CLIENT_OFF = 0, + TCP_SERVER_CLIENT_WAIT_REQUEST, + TCP_SERVER_CLIENT_GET_REQUEST, + TCP_SERVER_CLIENT_SENDING_DATA, + // Insert new states here + TCP_SERVER_CLIENT_MAX // Last entry in the state list +}; + +const char *const tcpServerClientStateName[] = { + "TCP_SERVER_CLIENT_OFF", + "TCP_SERVER_CLIENT_WAIT_REQUEST", + "TCP_SERVER_CLIENT_GET_REQUEST", + "TCP_SERVER_CLIENT_SENDING_DATA", +}; +const int tcpServerClientStateNameEntries = sizeof(tcpServerClientStateName) / sizeof(tcpServerClientStateName[0]); + +const RtkMode_t baseCasterMode = RTK_MODE_BASE_FIXED; +const RtkMode_t tcpServerMode = RTK_MODE_ROVER + | RTK_MODE_BASE_SURVEY_IN; //---------------------------------------- // Locals @@ -90,15 +110,21 @@ const RtkMode_t tcpServerMode = RTK_MODE_BASE_FIXED | RTK_MODE_BASE_SURVEY_IN | // TCP server static NetworkServer *tcpServer = nullptr; +static uint16_t tcpServerPort; static uint8_t tcpServerState; static uint32_t tcpServerTimer; +static bool tcpServerWiFiSoftAp; +static const char * tcpServerName; // TCP server clients static volatile uint8_t tcpServerClientConnected; static volatile uint8_t tcpServerClientDataSent; +static volatile uint8_t tcpServerClientSendingData; +static uint32_t tcpServerClientTimer[TCP_SERVER_MAX_CLIENTS]; static volatile uint8_t tcpServerClientWriteError; static NetworkClient *tcpServerClient[TCP_SERVER_MAX_CLIENTS]; static IPAddress tcpServerClientIpAddress[TCP_SERVER_MAX_CLIENTS]; +static uint8_t tcpServerClientState[TCP_SERVER_MAX_CLIENTS]; static volatile RING_BUFFER_OFFSET tcpServerClientTails[TCP_SERVER_MAX_CLIENTS]; //---------------------------------------- @@ -146,11 +172,9 @@ int32_t tcpServerClientSendData(int index, uint8_t *data, uint16_t length) if (length > 0) tcpServerClientDataSent = tcpServerClientDataSent | (1 << index); if ((settings.debugTcpServer || PERIODIC_DISPLAY(PD_TCP_SERVER_CLIENT_DATA)) && (!inMainMenu)) - { - PERIODIC_CLEAR(PD_TCP_SERVER_CLIENT_DATA); - systemPrintf("TCP server wrote %d bytes to %s\r\n", length, + systemPrintf("%s wrote %d bytes to %s\r\n", + tcpServerName, length, tcpServerClientIpAddress[index].toString().c_str()); - } } // Failed to write the data @@ -169,23 +193,88 @@ int32_t tcpServerClientSendData(int index, uint8_t *data, uint16_t length) //---------------------------------------- bool tcpServerEnabled(const char ** line) { + bool casterMode; bool enabled; + const char * name; + uint16_t port; + bool softAP; do { + // Determine if the server is enabled enabled = false; + if ((settings.enableTcpServer + || settings.enableNtripCaster + || settings.baseCasterOverride) == false) + { + *line = ", Not enabled!"; + break; + } + + // Determine if the TCP server should be running + if ((EQ_RTK_MODE(tcpServerMode) && settings.enableTcpServer)) + { + // TCP server running in Rover mode + name = "TCP Server"; + casterMode = false; + port = settings.tcpServerPort; + softAP = false; + } + + // Determine if the base caster should be running + else if (EQ_RTK_MODE(baseCasterMode) + && (settings.enableNtripCaster || settings.baseCasterOverride)) + { + // TCP server running in caster mode + casterMode = true; - // Verify the operating mode - if (NEQ_RTK_MODE(tcpServerMode)) + // Select the base caster WiFi mode and port number + if (settings.baseCasterOverride || (settings.tcpOverWiFiStation == false)) + { + // Using soft AP + name = "Base Caster"; + port = 2101; + softAP = true; + } + else + { + name = "NTRIP Caster"; + // Using WiFi station + port = settings.tcpServerPort; + softAP = false; + } + } + + // Wrong mode for TCP server or base caster operation + else { *line = ", Wrong mode!"; break; } - // Verify still enabled - enabled = settings.enableTcpServer || settings.baseCasterOverride; - if (enabled == false) - *line = ", Not enabled!"; + // Only change modes when in off state + if (tcpServerState == TCP_SERVER_STATE_OFF) + { + // Update the TCP server configuration + tcpServerName = name; + tcpServerInCasterMode = casterMode; + tcpServerPort = port; + tcpServerWiFiSoftAp = softAP; + } + + // Shutdown and restart the TCP server when configuration changes + else if ((name != tcpServerName) + || (casterMode != tcpServerInCasterMode) + || (port != tcpServerPort) + || (softAP != tcpServerWiFiSoftAp)) + { + *line = ", Wrong state to switch configuration!"; + break; + } + + // The server is enabled and in the correct mode + *line = ""; + enabled = true; } while (0); return enabled; } @@ -207,7 +296,7 @@ int32_t tcpServerSendData(uint16_t dataHead) tail = tcpServerClientTails[index]; // Determine if the client is connected - if (!(tcpServerClientConnected & (1 << index))) + if ((tcpServerClientSendingData & (1 << index)) == 0) tail = dataHead; else { @@ -240,6 +329,8 @@ int32_t tcpServerSendData(uint16_t dataHead) } tcpServerClientTails[index] = tail; } + if (PERIODIC_DISPLAY(PD_TCP_SERVER_CLIENT_DATA)) + PERIODIC_CLEAR(PD_TCP_SERVER_CLIENT_DATA); // Return the amount of space that TCP server client is using in the buffer return usedSpace; @@ -249,6 +340,168 @@ int32_t tcpServerSendData(uint16_t dataHead) // TCP Server Routines //---------------------------------------- +//---------------------------------------- +// Update the TCP server client state +//---------------------------------------- +void tcpServerClientUpdate(uint8_t index) +{ + bool clientConnected; + bool dataSent; + char response[512]; + int spot; + + // Determine if the client data structure is in use + while (tcpServerClientConnected & (1 << index)) + { + // The client data structure is in use + // Check for a working TCP server client connection + clientConnected = tcpServerClient[index]->connected(); + dataSent = ((millis() - tcpServerClientTimer[index]) < TCP_SERVER_CLIENT_DATA_TIMEOUT) + || (tcpServerClientDataSent & (1 << index)); + if ((clientConnected && dataSent) == false) + { + // Broken connection, shutdown the TCP server client link + tcpServerStopClient(index); + break; + } + + // Periodically display this client connection + if (PERIODIC_DISPLAY(PD_TCP_SERVER_DATA) && (!inMainMenu)) + systemPrintf("%s client %d connected to %s\r\n", + tcpServerName, index, + tcpServerClientIpAddress[index].toString().c_str()); + + // Process the client state + switch (tcpServerClientState[index]) + { + // Wait until the request is received from the NTRIP client + case TCP_SERVER_CLIENT_WAIT_REQUEST: + if (tcpServerClient[index]->available()) + { + // Indicate that data was received + tcpServerClientDataSent = tcpServerClientDataSent | (1 << index); + tcpServerClientTimer[index] = millis(); + tcpServerClientState[index] = TCP_SERVER_CLIENT_GET_REQUEST; + } + break; + + // Process the request from the NTRIP client + case TCP_SERVER_CLIENT_GET_REQUEST: + // Read response from client + spot = 0; + while (tcpServerClient[index]->available()) + { + response[spot++] = tcpServerClient[index]->read(); + if (spot == sizeof(response)) + spot = 0; // Wrap + } + response[spot] = '\0'; // Terminate string + + // Handle the mount point table request + if (strnstr(response, "GET / ", sizeof(response)) != NULL) // No mount point in header + { + if (settings.debugTcpServer) + systemPrintln("Mount point table requested."); + + // Respond with a single mountpoint + const char fakeSourceTable[] = + "SOURCETABLE 200 OK\r\nServer: SparkPNT Caster/1.0\r\nContent-Type: " + "text/plain\r\nContent-Length: 96\r\n\r\nSTR;SparkBase;none;RTCM " + "3.0;none;none;none;none;none;none;none;none;none;none;none;B;N;none;none"; + + tcpServerClient[index]->write(fakeSourceTable, strlen(fakeSourceTable)); + + // Disconnect from client + tcpServerStopClient(index); + } + + // Check for unknown request + else if (strnstr(response, "GET /", sizeof(response)) == NULL) + { + // Unknown response + if (settings.debugTcpServer) + systemPrintf("Unknown response: %s\r\n", response); + + // Disconnect from client + tcpServerStopClient(index); + } + + // Handle the mount point request, ignore the mount point and start sending data + else + { + // NTRIP Client is sending us their mount point. Begin sending RTCM. + if (settings.debugTcpServer) + systemPrintln("NTRIP Client connected - Sending ICY 200 OK"); + + // Successfully connected to the mount point + char confirmConnection[] = "ICY 200 OK\r\n"; + tcpServerClient[index]->write(confirmConnection, strlen(confirmConnection)); + + // Start sending RTCM + tcpServerClientSendingData = tcpServerClientSendingData | (1 << index); + tcpServerClientState[index] = TCP_SERVER_CLIENT_SENDING_DATA; + } + break; + + case TCP_SERVER_CLIENT_SENDING_DATA: + break; + } + break; + } + + // Determine if the client data structure is not in use + while ((tcpServerClientConnected & (1 << index)) == 0) + { + // Data structure not in use + if(tcpServerClient[index] == nullptr) + { + tcpServerClient[index] = new NetworkClient; + + // Check for allocation failure + if(tcpServerClient[index] == nullptr) + { + if (settings.debugTcpServer) + systemPrintf("ERROR: Failed to allocate %s client!\r\n", tcpServerName); + break; + } + } + + // Check for another incoming TCP server client connection request + *tcpServerClient[index] = tcpServer->accept(); + + // Exit if no TCP server client found + if (!*tcpServerClient[index]) + break; + + // Get the remote IP address + tcpServerClientIpAddress[index] = tcpServerClient[index]->remoteIP(); + + // Display the connection + if ((settings.debugTcpServer || PERIODIC_DISPLAY(PD_TCP_SERVER_DATA)) && (!inMainMenu)) + systemPrintf("%s client %d connected to %s\r\n", + tcpServerName, index, + tcpServerClientIpAddress[index].toString().c_str()); + + // Mark this client as connected + tcpServerClientConnected = tcpServerClientConnected | (1 << index); + + // Start the data timer + tcpServerClientTimer[index] = millis(); + tcpServerClientDataSent = tcpServerClientDataSent | (1 << index); + + // Set the client state + if (tcpServerInCasterMode) + tcpServerClientState[index] = TCP_SERVER_CLIENT_WAIT_REQUEST; + else + { + // Make client online after any NTRIP injections so ring buffer can start outputting data to it + tcpServerClientSendingData = tcpServerClientSendingData | (1 << index); + tcpServerClientState[index] = TCP_SERVER_CLIENT_SENDING_DATA; + } + break; + } +} + //---------------------------------------- // Update the state of the TCP server state machine //---------------------------------------- @@ -266,7 +519,7 @@ void tcpServerSetState(uint8_t newState) { if (newState >= TCP_SERVER_STATE_MAX) { - systemPrintf("Unknown TCP Server state: %d\r\n", tcpServerState); + systemPrintf("Unknown %s state: %d\r\n", tcpServerName, tcpServerState); reportFatalError("Unknown TCP Server state"); } else @@ -282,14 +535,10 @@ bool tcpServerStart() IPAddress localIp; if (settings.debugTcpServer && (!inMainMenu)) - systemPrintln("TCP server starting the server"); - - uint16_t tcpPort = settings.tcpServerPort; - if(settings.baseCasterOverride == true) - tcpPort = 2101; + systemPrintf("%s starting the server\r\n", tcpServerName); // Start the TCP server - tcpServer = new NetworkServer(tcpPort, TCP_SERVER_MAX_CLIENTS); + tcpServer = new NetworkServer(tcpServerPort, TCP_SERVER_MAX_CLIENTS); if (!tcpServer) return false; @@ -297,12 +546,8 @@ bool tcpServerStart() online.tcpServer = true; localIp = networkGetIpAddress(); - if (settings.enableNtripCaster || settings.baseCasterOverride) - systemPrintf("TCP server online, IP address %s:%d, responding as NTRIP Caster\r\n", localIp.toString().c_str(), - tcpPort); - else - systemPrintf("TCP server online, IP address %s:%d\r\n", localIp.toString().c_str(), tcpPort); - + systemPrintf("%s online, IP address %s:%d\r\n", tcpServerName, + localIp.toString().c_str(), tcpServerPort); return true; } @@ -317,7 +562,8 @@ void tcpServerStop() if (online.tcpServer) { if (settings.debugTcpServer && (!inMainMenu)) - systemPrintf("TcpServer: Notifying GNSS UART task to stop sending data\r\n"); + systemPrintf("%s: Notifying GNSS UART task to stop sending data\r\n", + tcpServerName); // Notify the GNSS UART tasks of the TCP server shutdown online.tcpServer = false; @@ -337,7 +583,7 @@ void tcpServerStop() { // Stop the TCP server if (settings.debugTcpServer && (!inMainMenu)) - systemPrintln("TcpServer: Stopping the server"); + systemPrintf("%s: Stopping the server\r\n", tcpServerName); tcpServer->stop(); delete tcpServer; tcpServer = nullptr; @@ -345,7 +591,7 @@ void tcpServerStop() // Stop using the network if (settings.debugTcpServer && (!inMainMenu)) - systemPrintln("TcpServer: Stopping network consumers"); + systemPrintf("%s: Stopping network consumers\r\n", tcpServerName); networkConsumerOffline(NETCONSUMER_TCP_SERVER); if (tcpServerState != TCP_SERVER_STATE_OFF) { @@ -366,24 +612,28 @@ void tcpServerStopClient(int index) bool connected; bool dataSent; + // Stop sending data + tcpServerClientSendingData = tcpServerClientSendingData & ~(1 << index); + // Determine if a client was allocated if (tcpServerClient[index]) { // Done with this client connection if ((settings.debugTcpServer || PERIODIC_DISPLAY(PD_TCP_SERVER_DATA)) && (!inMainMenu)) { - PERIODIC_CLEAR(PD_TCP_SERVER_DATA); - // Determine the shutdown reason connected = tcpServerClient[index]->connected() && (!(tcpServerClientWriteError & (1 << index))); - dataSent = ((millis() - tcpServerTimer) < TCP_SERVER_CLIENT_DATA_TIMEOUT) + dataSent = ((millis() - tcpServerClientTimer[index]) < TCP_SERVER_CLIENT_DATA_TIMEOUT) || (tcpServerClientDataSent & (1 << index)); if (!dataSent) - systemPrintf("TCP Server: No data sent over %d seconds\r\n", TCP_SERVER_CLIENT_DATA_TIMEOUT / 1000); + systemPrintf("%s: No data sent over %d seconds\r\n", + tcpServerName, + TCP_SERVER_CLIENT_DATA_TIMEOUT / 1000); if (!connected) - systemPrintf("TCP Server: Link to client broken\r\n"); - systemPrintf("TCP server client %d disconnected from %s\r\n", index, + systemPrintf("%s: Link to client broken\r\n", tcpServerName); + systemPrintf("%s client %d disconnected from %s\r\n", + tcpServerName, index, tcpServerClientIpAddress[index].toString().c_str()); } @@ -401,9 +651,7 @@ void tcpServerStopClient(int index) //---------------------------------------- void tcpServerUpdate() { - bool clientConnected; bool connected; - bool dataSent; bool enabled; int index; IPAddress ipAddress; @@ -411,7 +659,8 @@ void tcpServerUpdate() // Shutdown the TCP server when the mode or setting changes DMW_st(tcpServerSetState, tcpServerState); - connected = networkConsumerIsConnected(NETCONSUMER_TCP_SERVER); + connected = networkConsumerIsConnected(NETCONSUMER_TCP_SERVER) + || (tcpServerWiFiSoftAp && wifiSoftApOnline); enabled = tcpServerEnabled(&line); if ((tcpServerState > TCP_SERVER_STATE_OFF) && !enabled) tcpServerStop(); @@ -448,11 +697,11 @@ void tcpServerUpdate() if (enabled) { if (settings.debugTcpServer && (!inMainMenu)) - systemPrintln("TCP server start"); - if (settings.tcpUdpOverWiFiStation == true) - networkConsumerAdd(NETCONSUMER_TCP_SERVER, NETWORK_ANY, __FILE__, __LINE__); - else + systemPrintf("%s start/r/n", tcpServerName); + if (tcpServerWiFiSoftAp) networkSoftApConsumerAdd(NETCONSUMER_TCP_SERVER, __FILE__, __LINE__); + else + networkConsumerAdd(NETCONSUMER_TCP_SERVER, NETWORK_ANY, __FILE__, __LINE__); tcpServerSetState(TCP_SERVER_STATE_WAIT_FOR_NETWORK); } break; @@ -460,7 +709,7 @@ void tcpServerUpdate() // Wait until the network is connected case TCP_SERVER_STATE_WAIT_FOR_NETWORK: // Wait until the network is connected to the media - if (connected || wifiSoftApOnline) + if (connected) { // Delay before starting the TCP server if ((millis() - tcpServerTimer) >= (1 * 1000)) @@ -472,6 +721,8 @@ void tcpServerUpdate() if (tcpServerStart()) { networkUserAdd(NETCONSUMER_TCP_SERVER, __FILE__, __LINE__); + for (index = 0; index < TCP_SERVER_MAX_CLIENTS; index++) + tcpServerClientState[index] = TCP_SERVER_CLIENT_OFF; tcpServerSetState(TCP_SERVER_STATE_RUNNING); } } @@ -481,126 +732,22 @@ void tcpServerUpdate() // Handle client connections and link failures case TCP_SERVER_STATE_RUNNING: // Determine if the network has failed - if ((connected == false && wifiSoftApOnline == false) || (!settings.enableTcpServer && !settings.baseCasterOverride)) + if (connected == false) { if ((settings.debugTcpServer || PERIODIC_DISPLAY(PD_TCP_SERVER_DATA)) && (!inMainMenu)) - { - PERIODIC_CLEAR(PD_TCP_SERVER_DATA); - systemPrintln("TCP server initiating shutdown"); - } + systemPrintf("%s initiating shutdown\r\n", tcpServerName); // Network connection failed, attempt to restart the network tcpServerStop(); + if (PERIODIC_DISPLAY(PD_TCP_SERVER_DATA)) + PERIODIC_CLEAR(PD_TCP_SERVER_DATA); break; } // Walk the list of TCP server clients for (index = 0; index < TCP_SERVER_MAX_CLIENTS; index++) - { - // Determine if the client data structure is in use - if (tcpServerClientConnected & (1 << index)) - { - // Data structure in use - // Check for a working TCP server client connection - clientConnected = tcpServerClient[index]->connected(); - dataSent = ((millis() - tcpServerTimer) < TCP_SERVER_CLIENT_DATA_TIMEOUT) || - (tcpServerClientDataSent & (1 << index)); - if (clientConnected && dataSent) - { - // Display this client connection - if (PERIODIC_DISPLAY(PD_TCP_SERVER_DATA) && (!inMainMenu)) - { - PERIODIC_CLEAR(PD_TCP_SERVER_DATA); - systemPrintf("TCP server client %d connected to %s\r\n", index, - tcpServerClientIpAddress[index].toString().c_str()); - } - } - - // Shutdown the TCP server client link - else - tcpServerStopClient(index); - } - } - - // Walk the list of TCP server clients - for (index = 0; index < TCP_SERVER_MAX_CLIENTS; index++) - { - // Determine if the client data structure is in use - if (!(tcpServerClientConnected & (1 << index))) - { - if(tcpServerClient[index] == nullptr) - tcpServerClient[index] = new NetworkClient; - - // Data structure not in use - // Check for another TCP server client - *tcpServerClient[index] = tcpServer->accept(); - - // Exit if no TCP server client found - if (! *tcpServerClient[index]) - break; - - // Start processing the new TCP server client connection - tcpServerClientIpAddress[index] = tcpServerClient[index]->remoteIP(); - - if ((settings.debugTcpServer || PERIODIC_DISPLAY(PD_TCP_SERVER_DATA)) && (!inMainMenu)) - { - PERIODIC_CLEAR(PD_TCP_SERVER_DATA); - systemPrintf("TCP server client %d connected to %s\r\n", index, - tcpServerClientIpAddress[index].toString().c_str()); - } - - // If we are acting as an NTRIP Caster, intercept the initial communication from the client - // and respond accordingly - if (settings.enableNtripCaster || settings.baseCasterOverride) - { - // Read response from client - char response[512]; - int spot = 0; - while (tcpServerClient[index]->available()) - { - response[spot++] = tcpServerClient[index]->read(); - if (spot == sizeof(response)) - spot = 0; // Wrap - } - response[spot] = '\0'; // Terminate string - - if (strnstr(response, "GET / ", sizeof(response)) != NULL) // No mount point in header - { - if (settings.debugTcpServer) - systemPrintln("Mount point table requested."); - - // Respond with a single mountpoint - const char fakeSourceTable[] = - "SOURCETABLE 200 OK\r\nServer: SparkPNT Caster/1.0\r\nContent-Type: " - "text/plain\r\nContent-Length: 96\r\n\r\nSTR;SparkBase;none;RTCM " - "3.0;none;none;none;none;none;none;none;none;none;none;none;B;N;none;none"; - - tcpServerClient[index]->write(fakeSourceTable, strlen(fakeSourceTable)); - - tcpServerStopClient(index); // Disconnect from client - } - else if (strnstr(response, "GET /", sizeof(response)) != NULL) // Mount point in header - { - // NTRIP Client is sending us their mount point. Begin sending RTCM. - if (settings.debugTcpServer) - systemPrintln("NTRIP Client connected - Sending ICY 200 OK"); - - char confirmConnection[] = "ICY 200 OK\r\n"; - tcpServerClient[index]->write(confirmConnection, strlen(confirmConnection)); - } - else - { - // Unknown response - if (settings.debugTcpServer) - systemPrintf("Unknown response: %s\r\n", response); - } - } // settings.enableNtripCaster == true || settings.baseCasterOverride == true - - // Make client online after any NTRIP injections so ring buffer can start outputting data to it - tcpServerClientConnected = tcpServerClientConnected | (1 << index); - tcpServerClientDataSent = tcpServerClientDataSent | (1 << index); - } - } + tcpServerClientUpdate(index); + PERIODIC_CLEAR(PD_TCP_SERVER_DATA); // Check for data moving across the connections if ((millis() - tcpServerTimer) >= TCP_SERVER_CLIENT_DATA_TIMEOUT) @@ -615,7 +762,7 @@ void tcpServerUpdate() // Periodically display the TCP state if (PERIODIC_DISPLAY(PD_TCP_SERVER_STATE) && (!inMainMenu)) { - systemPrintf("TCP Server state: %s%s\r\n", + systemPrintf("%s state: %s%s\r\n", tcpServerName, tcpServerStateName[tcpServerState], line); PERIODIC_CLEAR(PD_TCP_SERVER_STATE); } @@ -636,8 +783,12 @@ void tcpServerValidateTables() sizeof(tcpServerClientConnected) * 8); reportFatalError(line); } + + // Verify the state name tables if (tcpServerStateNameEntries != TCP_SERVER_STATE_MAX) reportFatalError("Fix tcpServerStateNameEntries to match tcpServerStates"); + if (tcpServerClientStateNameEntries != TCP_SERVER_CLIENT_MAX) + reportFatalError("Fix tcpServerClientStateNameEntries to match tcpServerClientStates"); } //---------------------------------------- diff --git a/Firmware/RTK_Everywhere/Tilt.ino b/Firmware/RTK_Everywhere/Tilt.ino index ae1f9d85a..5a0f452c9 100644 --- a/Firmware/RTK_Everywhere/Tilt.ino +++ b/Firmware/RTK_Everywhere/Tilt.ino @@ -60,7 +60,10 @@ void tiltUpdate() } if (tiltState != TILT_STARTED) // If we failed to begin, disable future attempts + { tiltFailedBegin = true; + tiltState = TILT_DISABLED; + } break; case TILT_STARTED: @@ -105,7 +108,7 @@ void tiltUpdate() tiltSensor->update(); // Check for the most recent incoming binary data // Check IMU state at 1Hz - if (millis() - lastTiltCheck > 1000) + if ((millis() - lastTiltCheck) > 1000) { lastTiltCheck = millis(); @@ -132,7 +135,7 @@ void tiltUpdate() tiltSensor->update(); // Check for the most recent incoming binary data // Check IMU state at 1Hz - if (millis() - lastTiltCheck > 1000) + if ((millis() - lastTiltCheck) > 1000) { lastTiltCheck = millis(); @@ -150,7 +153,7 @@ void tiltUpdate() } // If tilt compensation is active, play a short beep every 10 seconds - if (millis() - lastTiltBeepMs > 10000) + if ((millis() - lastTiltBeepMs) > 10000) { lastTiltBeepMs = millis(); beepDurationMs(250); @@ -260,9 +263,10 @@ void printTiltDebug() // Start communication with the IM19 IMU void beginTilt() { - tiltSensor = new IM19(); - SerialForTilt = new HardwareSerial(1); // Use UART1 on the ESP32 to receive IMU corrections + tiltSensor = new IM19(); + if (SerialForTilt == nullptr) + SerialForTilt = new HardwareSerial(1); // Use UART1 on the ESP32 to receive IMU corrections SerialForTilt->setRxBufferSize(1024 * 1); @@ -291,8 +295,15 @@ void beginTilt() result &= tiltSensor->sendCommand("NAVI_OUTPUT=UART1,ON"); // Set the distance of the IMU from the center line - x:6.78mm y:10.73mm z:19.25mm - if (present.imu_im19 == true) + if (productVariant == RTK_TORCH) result &= tiltSensor->sendCommand("LEVER_ARM=-0.00678,-0.01073,-0.0314"); // From stock firmware + else if (productVariant == RTK_FLEX) + { + result &= tiltSensor->sendCommand("LEVER_ARM=0.03391,0.00272,0.02370"); // -28.2, 0. -23.7mm + + //Send AT+INSTALL_ANGLE=180,0,0 if the IM19 module is mounted on the back of the GNSS receiver (so the IM19 faces downward instead of upward), before sending the save command. + result &= tiltSensor->sendCommand("INSTALL_ANGLE=180,0,-90"); //IMU is mounted facing down + } // Set the overall length of the GNSS setup in meters: rod length 1800mm + internal length 96.45mm + antenna // POC 19.25mm = 1915.7mm @@ -308,7 +319,10 @@ void beginTilt() result &= tiltSensor->sendCommand(clubVector); // Configure interface type. This allows IM19 to receive Unicore-style binary messages - result &= tiltSensor->sendCommand("GNSS_CARD=UNICORE"); + if (productVariant == RTK_TORCH) + result &= tiltSensor->sendCommand("GNSS_CARD=UNICORE"); + else if (productVariant == RTK_FLEX) + result &= tiltSensor->sendCommand("GNSS_CARD=OEM"); // Configure as tilt measurement mode result &= tiltSensor->sendCommand("WORK_MODE=408"); // From stock firmware @@ -323,7 +337,7 @@ void beginTilt() // Unknown new command for v2 result &= tiltSensor->sendCommand("CORRECT_HOLDER=ENABLE"); // From stock firmware - // Trigger IMU on PPS from UM980 + // Trigger IMU on PPS from GNSS result &= tiltSensor->sendCommand("SET_PPS_EDGE=RISING"); // Enable magnetic field mode @@ -1007,3 +1021,62 @@ void applyCompensationGGA(char *nmeaSentence, int sentenceLength) } #endif // COMPILE_IM19_IMU + +// Determine if a tilt sensor is available or not +// Records outcome to NVM +void tiltDetect() +{ + // Only test platforms that may have a tilt sensor on board + if (present.tiltPossible == false) + return; + + // Skip test if previously detected as present + if (settings.detectedTilt == true) + { + present.imu_im19 = true; // Allow tiltUpdate() to run + return; + } + + // Test for tilt only once + if (settings.testedTilt == true) + return; + +#ifdef COMPILE_IM19_IMU + // Locally instantiate the library and hardware so it will release on exit + IM19 *tiltSensor; + + tiltSensor = new IM19(); + + // On Flex, ESP UART2 is connected to SW3, then UART3 of the GNSS (where a tilt module resides, if populated) + HardwareSerial SerialTiltTest(1); // Use UART1 on the ESP32 to communicate with IMU + + // Confirm SW3 is in the correct position + gpioExpanderSelectImu(); + + // We must start the serial port before handing it over to the library + SerialTiltTest.begin(115200, SERIAL_8N1, pin_IMU_RX, pin_IMU_TX); + + if (settings.enableImuDebug == true) + tiltSensor->enableDebugging(); // Print all debug to Serial + + // Try multiple times to configure the IM19 + for (int x = 0; x < 3; x++) + { + if (tiltSensor->begin(SerialTiltTest) == true) + { + present.imu_im19 = true; // Allow tiltUpdate() to run + settings.detectedTilt = true; + settings.gnssConfiguredRover = false; // Update rover settings + break; + } + } + + SerialTiltTest.end(); // Release UART1 for reuse + +#endif // COMPILE_IM19_IMU + + systemPrintf("Tilt sensor %sdetected\r\n", settings.detectedTilt ? "" : "not "); + settings.testedTilt = true; //Record this test so we don't do it again + recordSystemSettings(); + return; +} diff --git a/Firmware/RTK_Everywhere/UdpServer.ino b/Firmware/RTK_Everywhere/UdpServer.ino index 692c7ef90..ea034b153 100644 --- a/Firmware/RTK_Everywhere/UdpServer.ino +++ b/Firmware/RTK_Everywhere/UdpServer.ino @@ -199,13 +199,20 @@ int32_t udpServerSendData(uint16_t dataHead) //---------------------------------------- int32_t udpServerSendDataBroadcast(uint8_t *data, uint16_t length) { + IPAddress broadcastAddress; + if (!length) return 0; // Send the data as broadcast - if (settings.enableUdpServer && online.udpServer && networkConsumerIsConnected(NETCONSUMER_UDP_SERVER)) + if (settings.enableUdpServer && online.udpServer + && ((settings.udpOverWiFiStation == false) + || networkConsumerIsConnected(NETCONSUMER_UDP_SERVER))) { - IPAddress broadcastAddress = networkGetBroadcastIpAddress(); + if (settings.udpOverWiFiStation) + broadcastAddress = networkGetBroadcastIpAddress(); + else + broadcastAddress = wifiSoftApGetBroadcastIpAddress(); udpServer->beginPacket(broadcastAddress, settings.udpServerPort); udpServer->write(data, length); if (udpServer->endPacket()) @@ -263,19 +270,24 @@ void udpServerSetState(uint8_t newState) //---------------------------------------- bool udpServerStart() { - IPAddress localIp; + IPAddress ipAddress; if (settings.debugUdpServer && (!inMainMenu)) systemPrintln("UDP server starting"); // Start the UDP server + if (settings.udpOverWiFiStation == false) + ipAddress = wifiSoftApGetIpAddress(); + else + ipAddress = networkGetIpAddress(); udpServer = new NetworkUDP; if (!udpServer) return false; - udpServer->begin(settings.udpServerPort); + udpServer->begin(ipAddress, settings.udpServerPort); online.udpServer = true; - systemPrintf("UDP server online, broadcasting to port %d\r\n", settings.udpServerPort); + systemPrintf("UDP server online, broadcasting on %s:%d\r\n", + ipAddress.toString().c_str(), settings.udpServerPort); return true; } @@ -360,7 +372,7 @@ void udpServerUpdate() { if (settings.debugUdpServer && (!inMainMenu)) systemPrintln("UDP server starting the network"); - if (settings.tcpUdpOverWiFiStation == true) + if (settings.udpOverWiFiStation == true) networkConsumerAdd(NETCONSUMER_UDP_SERVER, NETWORK_ANY, __FILE__, __LINE__); else networkSoftApConsumerAdd(NETCONSUMER_UDP_SERVER, __FILE__, __LINE__); diff --git a/Firmware/RTK_Everywhere/WebServer.ino b/Firmware/RTK_Everywhere/WebServer.ino index 54ad00be4..2ec59d49f 100644 --- a/Firmware/RTK_Everywhere/WebServer.ino +++ b/Firmware/RTK_Everywhere/WebServer.ino @@ -37,7 +37,7 @@ static const char *const webServerStateNames[] = { webServer->on(page, HTTP_GET, []() { \ String length; \ if (settings.debugWebServer == true) \ - Serial.printf("WebServer: Sending %s (%p, %d bytes)\r\n", page, (void *)data, sizeof(data)); \ + systemPrintf("WebServer: Sending %s (%p, %d bytes)\r\n", page, (void *)data, sizeof(data)); \ webServer->sendHeader("Content-Encoding", "gzip"); \ length = String(sizeof(data)); \ webServer->sendHeader("Content-Length", length.c_str()); \ @@ -63,8 +63,8 @@ static int last_ws_fd; static TaskHandle_t updateWebServerTaskHandle; static const uint8_t updateWebServerTaskPriority = 0; // 3 being the highest, and 0 being the lowest -static const int webServerTaskStackSize = 1024 * 4; -static const int webSocketStackSize = 1024 * 20; // Needs to be large enough to hold the file manager file list +static const int webServerTaskStackSize = 1024 * 4; // Needs to be large enough to hold the file manager file list +static const int webSocketStackSize = 1024 * 20; // Needs to be large enough to hold the full settingsCSV // Inspired by: // https://github.com/espressif/arduino-esp32/blob/master/libraries/WebServer/examples/MultiHomedServers/MultiHomedServers.ino @@ -217,7 +217,7 @@ void getFileList(String &returnText) returnText += "sdFreeSpace," + freeSpace + ","; char fileName[50]; // Handle long file names - + // Attempt to gain access to the SD card if (xSemaphoreTake(sdCardSemaphore, fatSemaphore_longWait_ms) == pdPASS) { @@ -239,6 +239,18 @@ void getFileList(String &returnText) String fileSize; stringHumanReadableSize(fileSize, file.fileSize()); returnText += "fmName," + String(fileName) + ",fmSize," + fileSize + ","; + + const int maxFiles = 20; //40 is too much + const int fileNameLength = 50; + const int maxStringLength = maxFiles * fileNameLength; + // It is not uncommon to have SD cards with 100+ files on them. String can get huge. + // Here we arbitrarily limit it. + // This could be larger but, left unchecked, it will absolutely explode the stack. + if(returnText.length() > maxStringLength) + { + systemPrintf("Limiting file list to %d characters\r\n", maxStringLength); + break; + } } } @@ -590,8 +602,12 @@ void notFound() { if (settings.enableCaptivePortal == true && knownCaptiveUrl(webServer->uri()) == true) { - String logmessage = "Known captive URI: " + webServer->client().remoteIP().toString() + " " + webServer->uri(); - systemPrintln(logmessage); + if (settings.debugWebServer == true) + { + String logmessage = + "Known captive URI: " + webServer->client().remoteIP().toString() + " " + webServer->uri(); + systemPrintln(logmessage); + } webServer->sendHeader("Location", "/"); webServer->send(302, "text/plain", "Redirect to Web Config"); return; @@ -669,13 +685,7 @@ bool parseIncomingSettings() } } - if (counter < maxAttempts) - { - // Confirm receipt - if (settings.debugWebServer == true) - systemPrintln("Sending receipt confirmation of settings"); - sendStringToWebsocket("confirmDataReceipt,1,"); - } + systemPrintln("Parsing complete"); return (true); } @@ -816,6 +826,8 @@ bool webServerAssignResources(int httpPort = 80) /* https://github.com/espressif/arduino-esp32/blob/master/libraries/DNSServer/examples/CaptivePortal/CaptivePortal.ino */ + // Note: MDNS should probably be begun by networkMulticastDNSUpdate, but that doesn't seem to be happening... + // Is the networkInterface aware that AP needs it? Let's start it manually... if (MDNS.begin(&settings.mdnsHostName[0]) == false) { systemPrintln("Error setting up MDNS responder!"); @@ -1089,16 +1101,8 @@ void webServerSetState(uint8_t newState) if (!online.rtc) systemPrintf("%s%s%s%s\r\n", asterisk, initialState, arrow, endingState); else - { // Timestamp the state change - // 1 2 - // 12345678901234567890123456 - // YYYY-mm-dd HH:MM:SS.xxxrn0 - struct tm timeinfo = rtc.getTimeStruct(); - char s[30]; - strftime(s, sizeof(s), "%Y-%m-%d %H:%M:%S", &timeinfo); - systemPrintf("%s%s%s%s, %s.%03ld\r\n", asterisk, initialState, arrow, endingState, s, rtc.getMillis()); - } + systemPrintf("%s%s%s%s, %s\r\n", asterisk, initialState, arrow, endingState, getTimeStamp()); } // Validate the state @@ -1339,6 +1343,8 @@ static esp_err_t ws_handler(httpd_req_t *req) for (int i = 0; i < ws_pkt.len; i++) { incomingSettings[incomingSettingsSpot++] = ws_pkt.payload[i]; + if (incomingSettingsSpot == AP_CONFIG_SETTING_SIZE) + systemPrintln("incomingSettings wrap-around. Increase AP_CONFIG_SETTING_SIZE"); incomingSettingsSpot %= AP_CONFIG_SETTING_SIZE; } timeSinceLastIncomingSetting = millis(); @@ -1377,6 +1383,34 @@ static const httpd_uri_t ws = {.uri = "/ws", //---------------------------------------- void httpdDisplayConfig(struct httpd_config *config) { + /* + httpd_config object: + 5: task_priority + 20480: stack_size + 2147483647: core_id + 81: server_port + 32768: ctrl_port + 7: max_open_sockets + 8: max_uri_handlers + 8: max_resp_headers + 5: backlog_conn + false: lru_purge_enable + 5: recv_wait_timeout + 5: send_wait_timeout + 0x0: global_user_ctx + 0x0: global_user_ctx_free_fn + 0x0: global_transport_ctx + 0x0: global_transport_ctx_free_fn + false: enable_so_linger + 0: linger_timeout + false: keep_alive_enable + 0: keep_alive_idle + 0: keep_alive_interval + 0: keep_alive_count + 0x0: open_fn + 0x0: close_fn + 0x0: uri_match_fn + */ systemPrintf("httpd_config object:\r\n"); systemPrintf("%10d: task_priority\r\n", config->task_priority); systemPrintf("%10d: stack_size\r\n", config->stack_size); @@ -1418,7 +1452,7 @@ bool websocketServerStart(void) // Use different ports for websocket and webServer - use port 81 for the websocket - also defined in main.js config.server_port = 81; - // Increase the stack size from 4K to handle page processing + // Increase the stack size from 4K to handle page processing (settingsCSV) config.stack_size = webSocketStackSize; // Start the httpd server diff --git a/Firmware/RTK_Everywhere/WiFi.ino b/Firmware/RTK_Everywhere/WiFi.ino index cd9713ea5..6b409d5d2 100644 --- a/Firmware/RTK_Everywhere/WiFi.ino +++ b/Firmware/RTK_Everywhere/WiFi.ino @@ -42,7 +42,7 @@ enum WIFI_STATION_STATES { WIFI_STATION_STATE_OFF, WIFI_STATION_STATE_WAIT_NO_USERS, - WIFI_STATION_STATE_RESTART, + WIFI_STATION_STATE_RESTART_DELAY, WIFI_STATION_STATE_STARTING, WIFI_STATION_STATE_ONLINE, WIFI_STATION_STATE_STABLE, @@ -51,9 +51,14 @@ enum WIFI_STATION_STATES }; uint8_t wifiStationState; -const char *wifiStationStateName[] = { - "WIFI_STATION_STATE_OFF", "WIFI_STATION_STATE_WAIT_NO_USERS", "WIFI_STATION_STATE_RESTART", - "WIFI_STATION_STATE_STARTING", "WIFI_STATION_STATE_ONLINE", "WIFI_STATION_STATE_STABLE", +const char * wifiStationStateName[] = +{ + "WIFI_STATION_STATE_OFF", + "WIFI_STATION_STATE_WAIT_NO_USERS", + "WIFI_STATION_STATE_RESTART_DELAY", + "WIFI_STATION_STATE_STARTING", + "WIFI_STATION_STATE_ONLINE", + "WIFI_STATION_STATE_STABLE", }; const int wifiStationStateNameEntries = sizeof(wifiStationStateName) / sizeof(wifiStationStateName[0]); @@ -581,11 +586,18 @@ void wifiDisplayState() } } +//********************************************************************* +// Get the ESP-NOW channel +WIFI_CHANNEL_t wifiEspNowChannelGet() +{ + return wifi.espNowChannelGet(); +} + //********************************************************************* // Set the ESP-NOW channel -void wifiEspNowSetChannel(WIFI_CHANNEL_t channel) +void wifiEspNowChannelSet(WIFI_CHANNEL_t channel) { - wifi.espNowSetChannel(channel); + wifi.espNowChannelSet(channel); } //********************************************************************* @@ -684,6 +696,30 @@ void wifiPromiscuousRxHandler(void *buf, wifi_promiscuous_pkt_type_t type) packetRSSI = ppkt->rx_ctrl.rssi; } +//********************************************************************* +// Get the soft AP channel +WIFI_CHANNEL_t wifiSoftApChannelGet() +{ + return wifi.softApChannelGet(); +} + +//********************************************************************* +// Set the soft AP channel +void wifiSoftApChannelSet(WIFI_CHANNEL_t channel) +{ + wifi.softApChannelSet(channel); +} + +//********************************************************************* +// Get the broadcast IP address being used for the software access point (AP) +// Outputs: +// Returns an IPAddress object containing the IP address used by the +// soft AP +IPAddress wifiSoftApGetBroadcastIpAddress() +{ + return wifi.softApOnline() ? WiFi.AP.broadcastIP() : IPAddress((uint32_t)0); +} + //********************************************************************* // Get the IP address being used for the software access point (AP) // Outputs: @@ -737,6 +773,12 @@ bool wifiSoftApOn(const char *fileName, uint32_t lineNumber) if (settings.debugWifiState) systemPrintf("wifiSoftApOn called in %s at line %d\r\n", fileName, lineNumber); + // Select the AP name + if (inWebConfigMode()) + wifiSoftApSsid = "RTK Config"; + else + wifiSoftApSsid = "RTK"; + return wifi.enable(wifiEspNowRunning, true, wifiStationRunning, __FILE__, __LINE__); } @@ -787,9 +829,10 @@ bool wifiStationEnabled(const char **reason) break; } - // Is WiFi the highest priority - if (networkIsHighestPriority(NETWORK_WIFI_STATION) == false) + // Determine if WiFi should be running (is the highest priority) + if (networkInterfaceRunning(NETWORK_WIFI_STATION) == false) { + // Another network has higher priority // Allocate the reason buffer once if (reasonBuffer == nullptr) reasonBuffer = (char *)rtkMalloc(64, "WiFi reasonBuffer"); @@ -809,7 +852,7 @@ bool wifiStationEnabled(const char **reason) // WiFi should start and continue running enabled = true; - *reason = ", is enabled"; + *reason = ""; } while (0); return enabled; } @@ -905,7 +948,71 @@ void wifiStationUpdate() static uint32_t timer; int users; - // Determine if WiFi station should stop +/* + WiFi Station States: + + WIFI_STATION_STATE_OFF <--------------+<---. + | ^ | + | enabled | | + | | | + V !enabled | | + .--> WIFI_STATION_STATE_RESTART_DELAY ----------' | + | | | + | | Timeout | + | | Complete | + | V !enabled | + | WIFI_STATION_STATE_STARTING -------------. | + | | | | + | | WiFi connected | | + | V !enabled | | + | WIFI_STATION_STATE_ONLINE ------------->+ | + | | ^ | + | | Long delay | | + | V | | + | WIFI_STATION_STATE_STABLE | | + | | | | + | | !enabled | | + | V | | + | Display +<--------------------------' | + | delay | | + | V | + | WIFI_STATION_STATE_WAIT_NO_USERS | + | | | + | | No Users | + | enabled V !enabled | + '-------------------+--------------------------------' + + Network Loss Handling: + + ARDUINO_EVENT_WIFI_STA_LOST_IP + | + | + V + networkInterfaceEventInternetLost + | + | Set internet lost event flag + V + networkUpdate + | + | Clear internet lost event flag + V + +<------- Fake connection loss + | + V + networkInterfaceInternetConnectionLost + | + | Notify Interface of connection loss + V + .----------------+----------------. + | | + | | + V V + networkInterfaceRunning Interface stop sequence + in wifiStationEnabled + +*/ + + // Determine if WiFi station should start or stop enabled = wifiStationEnabled(&reason); online = wifiStationOnline; if ((enabled == false) && (wifiStationState >= WIFI_STATION_STATE_STARTING)) @@ -934,24 +1041,6 @@ void wifiStationUpdate() // Update the WiFi station state switch (wifiStationState) { - // There are no WiFi station consumers - case WIFI_STATION_STATE_OFF: - if (enabled) - { - connectionAttempts = 0; - timer = millis(); - startTimeout = 0; - - // Display the major state transition - if (settings.debugWifiState) - systemPrintf("--------------- %s Starting ---------------\r\n", - networkInterfaceTable[NETWORK_WIFI_STATION].name); - - // Start WiFi station - wifiStationSetState(WIFI_STATION_STATE_STARTING); - } - break; - // Wait for WiFi station users to release resources before shutting // down WiFi station case WIFI_STATION_STATE_WAIT_NO_USERS: @@ -974,86 +1063,120 @@ void wifiStationUpdate() // No more network users else { + // Display the major state transition + if (wifiStationRunning) + { + if (settings.debugWifiState) + systemPrintf("--------------- %s Stopping ---------------\r\n", + networkInterfaceTable[NETWORK_WIFI_STATION].name); + wifiStationOff(__FILE__, __LINE__); + } + // Stop WiFi station if necessary if (enabled == false) - { - // Display the major state transition - if (wifiStationRunning) - { - if (settings.debugWifiState) - systemPrintf("--------------- %s Stopping ---------------\r\n", - networkInterfaceTable[NETWORK_WIFI_STATION].name); - wifiStationOff(__FILE__, __LINE__); - } + // Reset the start timeout wifiStationSetState(WIFI_STATION_STATE_OFF); - } // Restart WiFi after delay else { - // Clear the bits to perform the restart operation - wifi.clearStarted(WIFI_STA_RECONNECT); - wifiStationSetState(WIFI_STATION_STATE_RESTART); + // Display the restart delay and then start WiFi station + if (startTimeout && settings.debugWifiState) + { + // Display the delay + uint32_t seconds = startTimeout / MILLISECONDS_IN_A_SECOND; + uint32_t minutes = seconds / SECONDS_IN_A_MINUTE; + seconds -= minutes * SECONDS_IN_A_MINUTE; + systemPrintf("WiFi: Delaying %2d:%02d before restarting WiFi\r\n", minutes, seconds); + } + timer = millis(); + wifiStationSetState(WIFI_STATION_STATE_RESTART_DELAY); } } break; - // Display the restart delay and then start WiFi station - case WIFI_STATION_STATE_RESTART: - if (startTimeout && settings.debugWifiState) + // There are no WiFi station consumers + case WIFI_STATION_STATE_OFF: + // Check for disabled + if (!enabled) + break; + + // Reset the restart timeout when off + if (wifiStationState == WIFI_STATION_STATE_OFF) + { + connectionAttempts = 0; + timer = millis(); + startTimeout = 0; + } + + // Wait for the delay to complete + wifiStationSetState(WIFI_STATION_STATE_RESTART_DELAY); + + // | + // | Fall through + // V + + // Perform the restart delay + case WIFI_STATION_STATE_RESTART_DELAY: + // Stop WiFi station if necessary + if (enabled == false) { - // Display the delay - uint32_t seconds = startTimeout / MILLISECONDS_IN_A_SECOND; - uint32_t minutes = seconds / SECONDS_IN_A_MINUTE; - seconds -= minutes * SECONDS_IN_A_MINUTE; - systemPrintf("WiFi: Delaying %2d:%02d before restarting WiFi\r\n", minutes, seconds); + wifiStationSetState(WIFI_STATION_STATE_OFF); + break; } - timer = millis(); + + // Delay before starting WiFi + if ((millis() - timer) < startTimeout) + break; + + // Display the major state transition + if (settings.debugWifiState) + systemPrintf("--------------- %s Starting ---------------\r\n", + networkInterfaceTable[NETWORK_WIFI_STATION].name); + + // Timeout complete wifiStationSetState(WIFI_STATION_STATE_STARTING); - break; + + // | + // | Fall through + // V // At least one consumer is requesting a network case WIFI_STATION_STATE_STARTING: - // Delay before starting WiFi - if ((millis() - timer) >= startTimeout) - { - timer = millis(); + // Increase the timeout + startTimeout <<= 1; + if (!startTimeout) + startTimeout = WIFI_MIN_TIMEOUT; + else if (startTimeout > WIFI_MAX_TIMEOUT) + startTimeout = WIFI_MAX_TIMEOUT; - // Increase the timeout - startTimeout <<= 1; - if (!startTimeout) - startTimeout = WIFI_MIN_TIMEOUT; - else if (startTimeout > WIFI_MAX_TIMEOUT) - startTimeout = WIFI_MAX_TIMEOUT; + // Account for this connection attempt + connectionAttempts++; - // Account for this connection attempt - connectionAttempts++; - - // Attempt to start WiFi station - if (wifiStationOn(__FILE__, __LINE__)) - { - // Successfully connected to a remote AP - if (settings.debugWifiState) - systemPrintf("WiFi: WiFi station successfully started\r\n"); + // Attempt to start WiFi station + if (wifiStationOn(__FILE__, __LINE__) == false) + { + // Failed to connect to a remote AP + if (settings.debugWifiState) + systemPrintf("WiFi: WiFi station failed to start!\r\n"); - // WiFi station is now available - wifiStationSetState(WIFI_STATION_STATE_ONLINE); - } - else - { - // Failed to connect to a remote AP - if (settings.debugWifiState) - systemPrintf("WiFi: WiFi station failed to start!\r\n"); + // Start the next network interface if necessary + if (connectionAttempts >= 2) + networkStartNextInterface(NETWORK_WIFI_STATION); - // Restart WiFi after delay - // Clear the bits to perform the restart operation - wifi.clearStarted(WIFI_STA_RECONNECT); - wifiStationSetState(WIFI_STATION_STATE_RESTART); + // Perform the restart delay + timer = millis(); + wifiStationSetState(WIFI_STATION_STATE_RESTART_DELAY); + } + else + { + // Successfully connected to a remote AP + if (settings.debugWifiState) + systemPrintf("WiFi: WiFi station successfully started\r\n"); - // Start the next network interface if necessary - if (connectionAttempts >= 2) - networkStartNextInterface(NETWORK_WIFI_STATION); - } + // WiFi station is now available + timer = millis(); + wifiStationSetState(WIFI_STATION_STATE_ONLINE); } break; @@ -1062,6 +1185,7 @@ void wifiStationUpdate() // Wait until the WiFi link is stable if ((millis() - timer) >= WIFI_CONNECTION_STABLE_MSEC) { + // Reset restart timeout and the connection attempts connectionAttempts = 0; startTimeout = 0; wifiStationSetState(WIFI_STATION_STATE_STABLE); @@ -1074,7 +1198,7 @@ void wifiStationUpdate() } // Periodically display the WiFi state - if (PERIODIC_DISPLAY(PD_WIFI_STATE)) + if (PERIODIC_DISPLAY(PD_WIFI_STATE) && !inMainMenu) { systemPrintf("WiFi station state: %s%s\r\n", wifiStationStateName[wifiStationState], reason); PERIODIC_CLEAR(PD_WIFI_STATE); @@ -1140,6 +1264,14 @@ void wifiUpdateSettings() wifiSoftApSsidSet = (wifiSoftApSsid && strlen(wifiSoftApSsid)); } +//********************************************************************* +// Determine if any of the WiFi station SSID values are set +bool wifiAfterCommand(int cmdIndex) +{ + wifiUpdateSettings(); + return true; +} + //********************************************************************* // Verify the WiFi tables void wifiVerifyTables() @@ -1159,9 +1291,10 @@ void wifiVerifyTables() // Constructor // Inputs: // verbose: Set to true to display additional WiFi debug data +// For AP on RTK Firmware, we set the Gateway to 192.168.4.1, not 0.0.0.0. Let's do the same here. RTK_WIFI::RTK_WIFI(bool verbose) : _apChannel{0}, _apCount{0}, _apDnsAddress{IPAddress((uint32_t)0)}, _apFirstDhcpAddress{IPAddress("192.168.4.32")}, - _apGatewayAddress{(uint32_t)0}, _apIpAddress{IPAddress("192.168.4.1")}, _apMacAddress{0, 0, 0, 0, 0, 0}, + _apGatewayAddress{IPAddress("192.168.4.1")}, _apIpAddress{IPAddress("192.168.4.1")}, _apMacAddress{0, 0, 0, 0, 0, 0}, _apSubnetMask{IPAddress("255.255.255.0")}, _espNowChannel{0}, _scanRunning{false}, _staIpAddress{IPAddress((uint32_t)0)}, _staIpType{0}, _staMacAddress{0, 0, 0, 0, 0, 0}, _staRemoteApSsid{nullptr}, _staRemoteApPassword{nullptr}, _started{false}, _stationChannel{0}, _usingDefaultChannel{true}, _verbose{verbose} @@ -1203,10 +1336,7 @@ bool RTK_WIFI::connect(unsigned long timeout, bool startAP) // Enable WiFi station if necessary if (wifiStationRunning == false) - { - displayWiFiConnect(); started = enable(wifiEspNowRunning, wifiSoftApRunning, true, __FILE__, __LINE__); - } else if (startAP && !wifiSoftApRunning) started = enable(wifiEspNowRunning, true, wifiStationRunning, __FILE__, __LINE__); @@ -1300,7 +1430,7 @@ bool RTK_WIFI::enable(bool enableESPNow, bool enableSoftAP, bool enableStation, // Allocate the soft AP SSID if (!_apSsid) { - _apSsid = (char *)rtkMalloc(strlen(wifiSoftApSsid) + 1, "SSID string (_apSsid)"); + _apSsid = (char *)rtkMalloc(SSID_LENGTH + 1 + 4 + 1, "SSID string (_apSsid)"); if (_apSsid) _apSsid[0] = 0; else @@ -1361,23 +1491,32 @@ bool RTK_WIFI::enable(bool enableESPNow, bool enableSoftAP, bool enableStation, } //********************************************************************* -// Get the ESP-NOW status +// Get the ESP-NOW channel // Outputs: -// Returns true when ESP-NOW is online and ready for use -bool RTK_WIFI::espNowOnline() +// Returns the requested ESP-NOW channel +WIFI_CHANNEL_t RTK_WIFI::espNowChannelGet() { - return (_started & WIFI_EN_ESP_NOW_ONLINE) ? true : false; + return _espNowChannel; } //********************************************************************* // Set the ESP-NOW channel // Inputs: // channel: New ESP-NOW channel number -void RTK_WIFI::espNowSetChannel(WIFI_CHANNEL_t channel) +void RTK_WIFI::espNowChannelSet(WIFI_CHANNEL_t channel) { _espNowChannel = channel; } +//********************************************************************* +// Get the ESP-NOW status +// Outputs: +// Returns true when ESP-NOW is online and ready for use +bool RTK_WIFI::espNowOnline() +{ + return (_started & WIFI_EN_ESP_NOW_ONLINE) ? true : false; +} + //********************************************************************* // Handle the WiFi event void RTK_WIFI::eventHandler(arduino_event_id_t event, arduino_event_info_t info) @@ -1609,6 +1748,24 @@ bool RTK_WIFI::setWiFiProtocols(wifi_interface_t interface, bool enableWiFiProto return started; } +//********************************************************************* +// Get the soft AP channel +// Outputs: +// Returns the requested soft AP channel +WIFI_CHANNEL_t RTK_WIFI::softApChannelGet() +{ + return _apChannel; +} + +//********************************************************************* +// Set the soft AP channel +// Inputs: +// channel: Request the channel for WiFi soft AP +void RTK_WIFI::softApChannelSet(WIFI_CHANNEL_t channel) +{ + _apChannel = channel; +} + //********************************************************************* // Configure the soft AP // Inputs: @@ -1856,6 +2013,20 @@ bool RTK_WIFI::startAp(bool forceAP) return enable(wifiEspNowRunning, forceAP | settings.wifiConfigOverAP, wifiStationRunning, __FILE__, __LINE__); } +//********************************************************************* +// Get the station channel +WIFI_CHANNEL_t RTK_WIFI::stationChannelGet() +{ + return _stationChannel; +} + +//********************************************************************* +// Set the station channel +void RTK_WIFI::stationChannelSet(WIFI_CHANNEL_t channel) +{ + _stationChannel = channel; +} + //********************************************************************* // Connect the station to a remote AP // Return true if the connection was successful and false upon failure. @@ -2553,7 +2724,8 @@ bool RTK_WIFI::stopStart(WIFI_ACTION_t stopping, WIFI_ACTION_t starting) } // Stop the DNS server - if (stopping & _started & WIFI_AP_START_DNS_SERVER) + // if (stopping & _started & WIFI_AP_START_DNS_SERVER) ??? + if (stopping & WIFI_AP_START_DNS_SERVER) { if (settings.debugWifiState && _verbose) systemPrintf("Calling dnsServer.stop for soft AP\r\n"); @@ -2662,6 +2834,7 @@ bool RTK_WIFI::stopStart(WIFI_ACTION_t stopping, WIFI_ACTION_t starting) systemPrintf("channel: %d\r\n", channel); _started = _started | WIFI_STA_START_SCAN; + systemPrintln("Scanning for WiFi..."); displayWiFiConnect(); // Determine if WiFi scan failed, stop WiFi station startup @@ -2695,8 +2868,8 @@ bool RTK_WIFI::stopStart(WIFI_ACTION_t stopping, WIFI_ACTION_t starting) // Finish the channel selection if (starting & WIFI_SELECT_CHANNEL) { - _started = _started | starting & WIFI_SELECT_CHANNEL; - if (channel & (starting & WIFI_STA_START_SCAN)) + _started = _started | (starting & WIFI_SELECT_CHANNEL); + if (channel && (starting & WIFI_STA_START_SCAN)) { if (settings.debugWifiState && _verbose) systemPrintf("Channel: %d, determined by remote AP scan\r\n", channel); @@ -2719,12 +2892,12 @@ bool RTK_WIFI::stopStart(WIFI_ACTION_t stopping, WIFI_ACTION_t starting) // Set the soft AP subnet mask, IP, gateway, DNS, and first DHCP addresses if (starting & WIFI_AP_SET_IP_ADDR) { - // if (!softApSetIpAddress(_apIpAddress.toString().c_str(), _apSubnetMask.toString().c_str(), - // _apGatewayAddress.toString().c_str(), _apDnsAddress.toString().c_str(), - // _apFirstDhcpAddress.toString().c_str())) - // { - // break; - // } + if (!softApSetIpAddress(_apIpAddress.toString().c_str(), _apSubnetMask.toString().c_str(), + _apGatewayAddress.toString().c_str(), _apDnsAddress.toString().c_str(), + _apFirstDhcpAddress.toString().c_str())) + { + break; + } _started = _started | WIFI_AP_SET_IP_ADDR; } @@ -3016,7 +3189,7 @@ bool RTK_WIFI::stopStart(WIFI_ACTION_t stopping, WIFI_ACTION_t starting) // Return the enable status bool enabled = ((_started & allOnline) == expected); - if (!enabled) + if (settings.debugWifiState && !enabled) systemPrintf("ERROR: RTK_WIFI::stopStart failed!\r\n"); if (settings.debugWifiState && _verbose) { diff --git a/Firmware/RTK_Everywhere/bluetoothSelect.h b/Firmware/RTK_Everywhere/bluetoothSelect.h index d3964d8a0..cb74ea5ee 100644 --- a/Firmware/RTK_Everywhere/bluetoothSelect.h +++ b/Firmware/RTK_Everywhere/bluetoothSelect.h @@ -7,7 +7,9 @@ #include //Click here to get the library: http://librarymanager/All#ESP32_BleSerial by Avinab Malla -class BTSerialInterface +#include "esp_sdp_api.h" + +class BTSerialInterface : public virtual Stream { public: virtual bool begin(String deviceName, bool isMaster, bool disableBLE, uint16_t rxQueueSize, uint16_t txQueueSize, @@ -15,18 +17,33 @@ class BTSerialInterface virtual void disconnect() = 0; virtual void end() = 0; - // virtual esp_err_t register_callback(esp_spp_cb_t callback) = 0; + virtual esp_err_t register_callback(void * callback) = 0; virtual void setTimeout(unsigned long timeout) = 0; virtual int available() = 0; virtual size_t readBytes(uint8_t *buffer, size_t bufferSize) = 0; virtual int read() = 0; + virtual int peek() = 0; // virtual bool isCongested() = 0; virtual size_t write(const uint8_t *buffer, size_t size) = 0; virtual size_t write(uint8_t value) = 0; virtual void flush() = 0; + virtual bool connect(uint8_t remoteAddress[], int channel, + esp_spp_sec_t sec_mask = (ESP_SPP_SEC_ENCRYPT | ESP_SPP_SEC_AUTHENTICATE), + esp_spp_role_t role = ESP_SPP_ROLE_MASTER) = 0; // Needed for Apple Accessory virtual bool connected() = 0; + virtual void enableSSP(bool inputCapability, bool outputCapability) = 0; + virtual bool aclConnected() = 0; + virtual uint8_t *aclGetAddress() = 0; + virtual std::map getChannels(const BTAddress &remoteAddress) = 0; + + virtual void onConfirmRequest(void (*cbPtr)(uint32_t)) = 0; + virtual void confirmReply(bool confirm) = 0; + virtual void respondPasskey(uint32_t passkey) = 0; + + virtual void deleteAllBondedDevices() = 0; + virtual void memrelease() = 0; }; class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial @@ -50,10 +67,10 @@ class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial BluetoothSerial::end(); } - // esp_err_t register_callback(esp_spp_cb_t callback) - // { - // return BluetoothSerial::register_callback(callback); - // } + esp_err_t register_callback(void * callback) + { + return BluetoothSerial::register_callback((esp_spp_cb_t)callback); + } void setTimeout(unsigned long timeout) { @@ -75,6 +92,11 @@ class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial return BluetoothSerial::read(); } + int peek() + { + return BluetoothSerial::peek(); + } + size_t write(const uint8_t *buffer, size_t size) { return BluetoothSerial::write(buffer, size); @@ -90,10 +112,62 @@ class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial BluetoothSerial::flush(); } + bool connect(uint8_t remoteAddress[], int channel, + esp_spp_sec_t sec_mask = (ESP_SPP_SEC_ENCRYPT | ESP_SPP_SEC_AUTHENTICATE), + esp_spp_role_t role = ESP_SPP_ROLE_MASTER) + { + return (BluetoothSerial::connect(remoteAddress, channel, sec_mask, role)); + } + bool connected() { return (BluetoothSerial::connected()); } + + void enableSSP(bool inputCapability, bool outputCapability) + { + BluetoothSerial::enableSSP(inputCapability, outputCapability); + } + + bool aclConnected() + { + return (BluetoothSerial::aclConnected()); + } + + uint8_t *aclGetAddress() + { + return (BluetoothSerial::aclGetAddress()); + } + + std::map getChannels(const BTAddress &remoteAddress) + { + return (BluetoothSerial::getChannels(remoteAddress)); + } + + void onConfirmRequest(void (*cbPtr)(uint32_t)) + { + BluetoothSerial::onConfirmRequest(cbPtr); + } + + void confirmReply(bool confirm) + { + BluetoothSerial::confirmReply((boolean)confirm); + } + + void respondPasskey(uint32_t passkey) + { + BluetoothSerial::respondPasskey(passkey); + } + + void deleteAllBondedDevices() + { + BluetoothSerial::deleteAllBondedDevices(); + } + + void memrelease() + { + BluetoothSerial::memrelease(); + } }; class BTLESerial : public virtual BTSerialInterface, public BleSerial @@ -118,11 +192,10 @@ class BTLESerial : public virtual BTSerialInterface, public BleSerial BleSerial::end(); } - // esp_err_t register_callback(esp_spp_cb_t callback) - // { - // connectionCallback = callback; - // return ESP_OK; - // } + esp_err_t register_callback(void * callback) + { + return ESP_OK; + } void setTimeout(unsigned long timeout) { @@ -144,6 +217,11 @@ class BTLESerial : public virtual BTSerialInterface, public BleSerial return BleSerial::read(); } + int peek() + { + return BleSerial::peek(); + } + size_t write(const uint8_t *buffer, size_t size) { return BleSerial::write(buffer, size); @@ -159,11 +237,44 @@ class BTLESerial : public virtual BTSerialInterface, public BleSerial BleSerial::flush(); } + bool connect(uint8_t remoteAddress[], int channel, esp_spp_sec_t sec_mask, esp_spp_role_t role) + { + return false; + } + bool connected() { return (BleSerial::connected()); } + void enableSSP(bool inputCapability, bool outputCapability) {} + + bool aclConnected() + { + return false; + } + + uint8_t *aclGetAddress() + { + return nullptr; + } + + std::map getChannels(const BTAddress &remoteAddress) + { + std::map empty; + return empty; + } + + void onConfirmRequest(void (*cbPtr)(uint32_t)) {} + + void confirmReply(bool confirm) {} + + void respondPasskey(uint32_t passkey) {} + + void deleteAllBondedDevices() {} + + void memrelease() {} + // Callbacks removed in v2 of BleSerial. Using polled connected() in bluetoothUpdate() // override BLEServerCallbacks // void Server->onConnect(BLEServer *pServer) diff --git a/Firmware/RTK_Everywhere/form.h b/Firmware/RTK_Everywhere/form.h index bf598e838..010e96b43 100644 --- a/Firmware/RTK_Everywhere/form.h +++ b/Firmware/RTK_Everywhere/form.h @@ -26,1047 +26,1118 @@ // python main_js_zipper.py static const uint8_t main_js[] PROGMEM = { - 0x1F, 0x8B, 0x08, 0x08, 0x11, 0xE6, 0x77, 0x68, 0x02, 0xFF, 0x6D, 0x61, 0x69, 0x6E, 0x2E, 0x6A, + 0x1F, 0x8B, 0x08, 0x08, 0xAE, 0x0F, 0x15, 0x69, 0x02, 0xFF, 0x6D, 0x61, 0x69, 0x6E, 0x2E, 0x6A, 0x73, 0x2E, 0x67, 0x7A, 0x69, 0x70, 0x00, 0xED, 0x7D, 0x7B, 0x5F, 0x1B, 0x39, 0xB2, 0xE8, 0xFF, - 0xF9, 0x14, 0x5A, 0xDF, 0xBD, 0x6B, 0xB3, 0x18, 0xD3, 0x36, 0x8F, 0x40, 0x08, 0xD9, 0x4B, 0x80, - 0x24, 0xDC, 0xE5, 0x75, 0x31, 0x99, 0x99, 0x4C, 0x36, 0x87, 0xD3, 0xD8, 0xC2, 0xF4, 0x89, 0xDD, - 0xED, 0xED, 0x6E, 0x87, 0x30, 0x7B, 0xF8, 0x4E, 0xE7, 0x33, 0x9C, 0x4F, 0x76, 0xAB, 0x24, 0x75, - 0xB7, 0xA4, 0x56, 0x3F, 0x6D, 0x18, 0x76, 0x4F, 0xF2, 0xFB, 0x0D, 0x03, 0x2D, 0xD5, 0x43, 0xA5, - 0x52, 0xA9, 0x24, 0x95, 0x4A, 0xDF, 0x6C, 0x9F, 0x8C, 0xEC, 0x90, 0xDE, 0xD9, 0xF7, 0x64, 0x97, - 0xFC, 0xFB, 0x5D, 0xF0, 0x6A, 0x75, 0xF5, 0x8F, 0xFF, 0xB8, 0x73, 0xDC, 0xA1, 0x77, 0xD7, 0x19, - 0x7B, 0x03, 0x3B, 0x74, 0x3C, 0xB7, 0x73, 0xEB, 0x05, 0xA1, 0x6B, 0x4F, 0xE8, 0xC3, 0xAB, 0xAD, - 0xEE, 0xEA, 0x5D, 0xF0, 0xEF, 0x3B, 0x2F, 0xBE, 0x01, 0xDC, 0x1D, 0xBD, 0x0E, 0xBC, 0xC1, 0x57, - 0x1A, 0xEE, 0xBC, 0x78, 0x21, 0x20, 0xEC, 0xE1, 0xF0, 0xF0, 0x1B, 0x75, 0xC3, 0x63, 0x27, 0x08, - 0xA9, 0x4B, 0xFD, 0x56, 0x73, 0xEC, 0xD9, 0xC3, 0x66, 0x9B, 0x78, 0xEE, 0x31, 0xFC, 0xB2, 0x04, - 0x35, 0x6F, 0x66, 0xEE, 0x00, 0x91, 0x8A, 0x4F, 0x2D, 0x8A, 0xF5, 0x97, 0xC8, 0x3F, 0x5E, 0x10, - 0xF8, 0xE7, 0xB8, 0x4E, 0xF8, 0x33, 0xBD, 0xEE, 0x33, 0xB4, 0x2D, 0xA8, 0xFE, 0x20, 0x01, 0x68, - 0x85, 0x02, 0x24, 0xE6, 0x02, 0xF8, 0x77, 0xE9, 0x1D, 0x49, 0x6A, 0x88, 0x76, 0x01, 0x16, 0xA5, - 0x5E, 0xC7, 0x73, 0x27, 0x34, 0x08, 0xEC, 0x11, 0x05, 0x88, 0x18, 0x79, 0x6B, 0x12, 0x8C, 0x22, - 0x94, 0xF8, 0x6F, 0x6A, 0xFB, 0x01, 0x3D, 0x72, 0x07, 0xDE, 0xC4, 0x71, 0x47, 0x58, 0xD8, 0x19, - 0xDA, 0xA1, 0x2D, 0x70, 0x3D, 0xA8, 0x8C, 0x8D, 0x68, 0x8B, 0x46, 0xB0, 0x3E, 0x0D, 0x67, 0xBE, - 0x4B, 0x86, 0xDE, 0x60, 0x36, 0x81, 0x86, 0x75, 0x46, 0x34, 0x3C, 0x1C, 0x53, 0xFC, 0xF5, 0xED, - 0xFD, 0x11, 0xB4, 0x96, 0xB7, 0x09, 0xC5, 0x77, 0xE3, 0x7C, 0xA7, 0xC3, 0x63, 0x1B, 0xF9, 0xB6, - 0x76, 0xA4, 0x2F, 0x9E, 0x3B, 0x4A, 0x3E, 0x4D, 0xC7, 0x76, 0x78, 0xE3, 0xF9, 0x93, 0x73, 0x9F, - 0x42, 0x29, 0x7C, 0x6F, 0x34, 0x78, 0xC1, 0x88, 0x7A, 0x43, 0x1A, 0x3A, 0x03, 0x8E, 0x60, 0xDD, - 0xEA, 0x58, 0x5D, 0xAD, 0x00, 0x18, 0xDB, 0x25, 0x2B, 0x5D, 0x6B, 0xA3, 0xD3, 0xDD, 0x56, 0x8B, - 0xF6, 0xC6, 0x08, 0xD3, 0xDD, 0xB0, 0xAC, 0x8E, 0x00, 0xA2, 0x03, 0x7A, 0xF3, 0x0B, 0xAB, 0xDE, - 0xDB, 0xB2, 0x7A, 0xD6, 0x66, 0x67, 0x63, 0x73, 0x2B, 0x29, 0xF9, 0x84, 0x25, 0xEB, 0x2F, 0xBB, - 0x9B, 0x5B, 0xD6, 0x7A, 0x67, 0xDD, 0x5A, 0x4B, 0x4A, 0x7E, 0x65, 0xB4, 0xB7, 0x36, 0x37, 0x37, - 0x37, 0x3A, 0xEB, 0x5B, 0xEB, 0xBC, 0x60, 0x6C, 0x07, 0xE1, 0x3B, 0x67, 0x4C, 0x4F, 0x41, 0x63, - 0x24, 0x8E, 0x6F, 0xF0, 0xD3, 0x6C, 0x72, 0x4D, 0xFD, 0xA4, 0x79, 0x2E, 0xFB, 0xFB, 0xEC, 0x06, - 0xAB, 0x07, 0x7D, 0x3A, 0xA6, 0x83, 0x90, 0x0E, 0x93, 0xE2, 0x40, 0x7C, 0x61, 0xC5, 0x12, 0xAA, - 0xE0, 0xD6, 0x03, 0x85, 0x1B, 0xE1, 0x67, 0xD4, 0x34, 0xEC, 0x47, 0x7B, 0x1C, 0x50, 0x5E, 0xE8, - 0x5D, 0x87, 0xB6, 0xE3, 0xD2, 0xE1, 0x09, 0xEF, 0xE4, 0x52, 0x15, 0xDE, 0xDA, 0x01, 0x55, 0x2B, - 0x09, 0x12, 0xA2, 0xCE, 0xC5, 0xE5, 0xFE, 0x49, 0x1A, 0x11, 0xB6, 0xE8, 0xD2, 0xBE, 0x86, 0x1F, - 0xF4, 0x7B, 0x28, 0xB1, 0x37, 0xF0, 0x7C, 0x9F, 0x32, 0xD5, 0xD0, 0x0A, 0x84, 0xDE, 0x69, 0x5F, - 0x51, 0x5E, 0x82, 0xCE, 0xE5, 0xFD, 0x94, 0x66, 0x97, 0x08, 0x2E, 0xB1, 0x94, 0xF3, 0x68, 0x7F, - 0x8B, 0x5B, 0x81, 0xC2, 0x46, 0x11, 0x7D, 0xFE, 0xB2, 0x93, 0x2A, 0xFB, 0xC9, 0x1E, 0xCF, 0xD2, - 0x85, 0xFB, 0xB7, 0x74, 0xF0, 0xF5, 0xDA, 0xFB, 0x6E, 0x84, 0x8C, 0x0A, 0x15, 0x50, 0x56, 0x0C, - 0x2D, 0xF3, 0xFC, 0x61, 0x70, 0xB8, 0x7F, 0xF8, 0x4E, 0x02, 0x12, 0x5F, 0xDF, 0x0B, 0x0D, 0x93, - 0x4A, 0x6E, 0x66, 0xE3, 0xF1, 0x39, 0x30, 0xF1, 0x71, 0x0A, 0x03, 0x48, 0x12, 0xB2, 0x00, 0x0B, - 0x68, 0x78, 0xE9, 0x4C, 0xA8, 0x37, 0x0B, 0xA3, 0x2E, 0x77, 0x87, 0x07, 0x30, 0xD2, 0x94, 0x8F, - 0x03, 0xE4, 0xE6, 0x94, 0xDE, 0xBD, 0x73, 0xFC, 0xC9, 0x9D, 0xED, 0x53, 0xA5, 0x10, 0x46, 0x98, - 0xA9, 0xE8, 0xC5, 0xC0, 0x73, 0xA1, 0xC3, 0x40, 0xC3, 0xF6, 0xE3, 0xEE, 0x08, 0xFA, 0xDE, 0xCC, - 0x1F, 0xB0, 0xF6, 0x6C, 0xE9, 0x5D, 0x25, 0xCA, 0x74, 0x69, 0xA4, 0x2A, 0x9C, 0xFB, 0x8E, 0xE7, - 0x3B, 0xA1, 0x93, 0x48, 0x85, 0x13, 0xDA, 0xF7, 0x40, 0x00, 0x8E, 0x0B, 0x6D, 0xC4, 0xAE, 0xC2, - 0x42, 0x6E, 0x10, 0xF6, 0xCF, 0xCE, 0x2E, 0x0E, 0x8E, 0x4E, 0xF7, 0x2E, 0x0F, 0xAF, 0x8E, 0x4E, - 0xCF, 0x3F, 0x5E, 0x5E, 0x5D, 0x7E, 0x3A, 0x3F, 0xBC, 0x3A, 0x38, 0x78, 0x45, 0xAC, 0x36, 0x59, - 0x5D, 0x3D, 0xA0, 0x37, 0xF6, 0x0C, 0xC6, 0xE3, 0xC1, 0x41, 0x67, 0x18, 0xFD, 0xCB, 0x85, 0x3B, - 0x39, 0x79, 0x45, 0xBA, 0x0C, 0x12, 0x7E, 0xED, 0x4C, 0xF0, 0x5F, 0x6E, 0xFD, 0x2B, 0x04, 0xE8, - 0x71, 0x00, 0x52, 0x16, 0xE2, 0xEA, 0x60, 0xAF, 0xFF, 0xE1, 0x15, 0x59, 0xE3, 0x60, 0x2B, 0xA5, - 0xC1, 0xFA, 0x9F, 0x4E, 0xDE, 0x9E, 0x1D, 0xBF, 0x22, 0xEB, 0x1C, 0xF0, 0xBF, 0xFF, 0x2B, 0x82, - 0x9C, 0x4C, 0x9A, 0x05, 0xAD, 0xEA, 0xF7, 0x5F, 0x91, 0x8D, 0x98, 0x4D, 0xD2, 0xEF, 0x77, 0x02, - 0xF6, 0xAF, 0x98, 0x26, 0x00, 0x6E, 0xD6, 0x03, 0x14, 0xCD, 0x7C, 0x19, 0x37, 0x73, 0xA5, 0x12, - 0x74, 0xD4, 0xDA, 0xAD, 0xA4, 0xB5, 0xCD, 0x18, 0x41, 0xA3, 0xB0, 0xBD, 0x57, 0xA7, 0x67, 0x57, - 0x07, 0x87, 0xFB, 0x47, 0x27, 0x7B, 0x80, 0x63, 0x3B, 0xEA, 0xD2, 0x7E, 0x9F, 0xAC, 0x90, 0x53, - 0x8F, 0x0C, 0xE9, 0xC0, 0x99, 0xD8, 0xE3, 0x32, 0x7C, 0xC8, 0x78, 0xBA, 0x96, 0x2C, 0x8A, 0xCA, - 0xA8, 0x50, 0x20, 0x2A, 0xBE, 0xAE, 0x2C, 0x9C, 0xB2, 0xF8, 0x8E, 0x4E, 0x7F, 0xDA, 0x3B, 0x3E, - 0x3A, 0xB8, 0xFA, 0x78, 0xFA, 0xD7, 0xD3, 0xB3, 0x9F, 0x4F, 0x01, 0x4D, 0xAF, 0x1D, 0xCD, 0x7B, - 0x30, 0x5C, 0xBE, 0x51, 0x1F, 0xAC, 0x7A, 0x32, 0x62, 0xD0, 0xE2, 0x77, 0xAC, 0x68, 0xC0, 0x45, - 0x5F, 0x8F, 0xDC, 0xE9, 0x2C, 0x14, 0x16, 0x51, 0x1B, 0x5D, 0x9D, 0xAC, 0x66, 0xC8, 0x0E, 0x46, - 0x6A, 0x0A, 0x8F, 0xE6, 0xE8, 0xD5, 0x55, 0x1C, 0xB2, 0xDE, 0x98, 0x82, 0x87, 0x33, 0x6A, 0x35, - 0xA2, 0x2A, 0x91, 0x79, 0x7E, 0x45, 0x1A, 0x64, 0x99, 0x60, 0x7D, 0xC0, 0x86, 0xF5, 0x91, 0x2D, - 0x9C, 0xFD, 0x81, 0x0F, 0x74, 0x04, 0x82, 0xE9, 0xD8, 0x09, 0x5B, 0xCD, 0x76, 0x53, 0x78, 0x03, - 0x30, 0x3F, 0x93, 0xD6, 0x18, 0x1C, 0x90, 0xEF, 0x6C, 0xE6, 0x82, 0xFF, 0xBD, 0x66, 0xD5, 0x3B, - 0x63, 0xEA, 0x8E, 0xC2, 0x5B, 0x90, 0x59, 0x17, 0x3F, 0x2E, 0xEF, 0x92, 0x9E, 0xEC, 0x61, 0x20, - 0x56, 0x07, 0x27, 0x3B, 0xAC, 0xFB, 0xF9, 0xFB, 0x97, 0x1D, 0xA5, 0xE4, 0x9B, 0x3D, 0x8E, 0x8B, - 0x80, 0x9B, 0xAE, 0x54, 0xAC, 0xB1, 0xEF, 0x0C, 0x39, 0xC3, 0x80, 0x6B, 0x99, 0x34, 0xDA, 0x08, - 0xC9, 0x3F, 0xC0, 0x2F, 0x51, 0x0B, 0x38, 0x58, 0x7F, 0x0A, 0x1D, 0x07, 0x78, 0xA1, 0xB9, 0x13, - 0xDB, 0x1D, 0x06, 0x71, 0x91, 0x73, 0x43, 0x5A, 0xCE, 0xB0, 0xE3, 0xB8, 0x83, 0xF1, 0x6C, 0x48, - 0x83, 0x56, 0x23, 0x18, 0x9E, 0x78, 0x33, 0x17, 0xFA, 0xA8, 0xB1, 0x24, 0xB3, 0xCC, 0xD1, 0x5C, - 0xA2, 0x83, 0xE3, 0xB9, 0xAB, 0xDE, 0xCD, 0x0D, 0xE9, 0x1F, 0x10, 0x30, 0xBA, 0xB6, 0x52, 0x03, - 0xB1, 0x31, 0xF6, 0x61, 0xAA, 0x62, 0xC6, 0xBE, 0xA1, 0xE3, 0xC0, 0x7F, 0xB7, 0xCE, 0x90, 0xB6, - 0x1A, 0x38, 0x85, 0x9E, 0xD8, 0x2E, 0x48, 0xDD, 0x6F, 0x2C, 0xED, 0x28, 0x95, 0x1E, 0x94, 0xBF, - 0x28, 0xE0, 0x51, 0x30, 0x87, 0xFE, 0xCC, 0x8C, 0x18, 0x67, 0xEE, 0x92, 0x88, 0x93, 0xDF, 0x62, - 0xF4, 0xD8, 0x23, 0x80, 0x5D, 0xF5, 0xBB, 0x52, 0x74, 0x52, 0x6E, 0x19, 0x70, 0xA5, 0x12, 0x89, - 0x1D, 0xC0, 0xD0, 0x09, 0xC7, 0x6C, 0xD6, 0xBE, 0xB8, 0xFC, 0x2B, 0xEB, 0x16, 0x0D, 0x16, 0xFA, - 0x8C, 0xF4, 0xC1, 0x69, 0x9C, 0x36, 0x54, 0x04, 0xA9, 0x79, 0x13, 0x1B, 0xAC, 0x56, 0x31, 0xFA, - 0x19, 0xA9, 0xAE, 0xD0, 0x79, 0x85, 0x6A, 0x87, 0x3F, 0xFD, 0x35, 0x47, 0x74, 0xD7, 0xE0, 0x66, - 0xEC, 0x7B, 0xEE, 0x8D, 0x33, 0xD2, 0x25, 0x97, 0xD4, 0x99, 0x4E, 0x8B, 0x6A, 0xD0, 0xF0, 0x96, - 0xFA, 0x2E, 0x0D, 0x8B, 0xEA, 0xB9, 0x61, 0x21, 0xAA, 0xA9, 0xE7, 0x87, 0x41, 0x76, 0x25, 0xAE, - 0x49, 0x20, 0x01, 0xA0, 0x67, 0x8F, 0xCF, 0xA1, 0xF2, 0xD9, 0x94, 0x4D, 0xD8, 0xD9, 0x18, 0x61, - 0xE0, 0x5C, 0x7A, 0xFD, 0x83, 0x7D, 0xDB, 0x1F, 0x66, 0x63, 0x1C, 0xD9, 0x63, 0x50, 0x22, 0xEF, - 0x83, 0x0D, 0x9E, 0x69, 0x18, 0x82, 0x81, 0xC8, 0xAE, 0x1A, 0x3A, 0xE3, 0xB0, 0x88, 0xC1, 0x6B, - 0x4A, 0xA7, 0xD4, 0x87, 0x5A, 0xA1, 0xEF, 0x8D, 0xB3, 0x59, 0x9B, 0x05, 0x74, 0x2F, 0x08, 0xC0, - 0xD7, 0x3C, 0xF5, 0xEE, 0x22, 0x2F, 0x2C, 0xBB, 0xF6, 0x84, 0xDA, 0xC1, 0xCC, 0x67, 0xEB, 0x8B, - 0x8B, 0xC8, 0x64, 0x66, 0xB3, 0x30, 0xF1, 0x02, 0xDB, 0x19, 0x9C, 0x9E, 0x1C, 0xEE, 0xF5, 0x43, - 0x18, 0xB5, 0x93, 0x03, 0xDF, 0x9B, 0xC2, 0xB2, 0x2D, 0x4F, 0x52, 0x80, 0xFD, 0x1B, 0xBD, 0x3F, - 0x72, 0x85, 0x08, 0x82, 0x5C, 0xC6, 0x8F, 0x61, 0xC1, 0x38, 0x76, 0x7E, 0xA3, 0xC3, 0x03, 0xE0, - 0xDF, 0x77, 0xAE, 0x67, 0xD8, 0x0D, 0xC5, 0x8D, 0x00, 0xC8, 0x43, 0x17, 0xFD, 0xE8, 0xC3, 0xEF, - 0x21, 0x3A, 0x6B, 0x17, 0xF6, 0xD0, 0xF1, 0x72, 0x34, 0x4B, 0xAA, 0xD5, 0x3F, 0xDF, 0xBB, 0xB8, - 0x3C, 0xE5, 0x9E, 0x59, 0xD4, 0x9A, 0x1C, 0x1D, 0x61, 0x54, 0x4E, 0x41, 0x68, 0x67, 0x6E, 0x26, - 0x11, 0x5E, 0x35, 0xB8, 0x9D, 0x85, 0x88, 0xEC, 0xD4, 0xDB, 0xBF, 0xB5, 0xFD, 0x51, 0xE4, 0x57, - 0x9E, 0x38, 0xEE, 0x2C, 0xA4, 0x41, 0xD4, 0xA6, 0x03, 0x0A, 0x4B, 0x09, 0xD6, 0x99, 0x19, 0x68, - 0x98, 0x6F, 0x48, 0xC7, 0x63, 0xB6, 0x8E, 0x3E, 0xB5, 0xBF, 0x39, 0x03, 0xA8, 0x0C, 0x36, 0xF4, - 0xD4, 0x0B, 0x49, 0x30, 0x9B, 0xA2, 0x66, 0xC3, 0x82, 0x07, 0x26, 0xAB, 0x5F, 0x0F, 0x0F, 0xD2, - 0x38, 0xF8, 0xFA, 0x07, 0x06, 0x36, 0xAC, 0x30, 0x61, 0x14, 0x38, 0x6E, 0x78, 0x4E, 0xFD, 0x1B, - 0xF8, 0xD4, 0xA7, 0x3E, 0xA0, 0xA2, 0x26, 0xF6, 0x71, 0x22, 0x82, 0x75, 0x30, 0x1F, 0x02, 0x62, - 0x4D, 0xCC, 0xFF, 0x68, 0x35, 0xA1, 0x5B, 0x50, 0x00, 0xB8, 0x20, 0x6F, 0x5A, 0x4D, 0x93, 0x80, - 0x19, 0x41, 0x5C, 0xC6, 0xB7, 0x62, 0x1C, 0x6D, 0x32, 0x73, 0x87, 0x60, 0x3A, 0x60, 0xC5, 0x64, - 0x80, 0xC8, 0x22, 0xF5, 0x6E, 0x4C, 0xBF, 0x93, 0xD3, 0xCB, 0x8B, 0xA3, 0xF3, 0x55, 0x5C, 0x3C, - 0x21, 0xC5, 0xEE, 0x13, 0x50, 0x3C, 0x5E, 0x79, 0x0B, 0x33, 0x1B, 0x38, 0x29, 0x3E, 0x4C, 0xBC, - 0x7B, 0x13, 0xEA, 0x3B, 0x03, 0x1B, 0x69, 0xF7, 0xE6, 0xA7, 0x9D, 0x31, 0x1F, 0x99, 0xEC, 0xEB, - 0x3B, 0x7B, 0x00, 0xBD, 0xF0, 0xAD, 0x07, 0x46, 0xF6, 0x3F, 0xFF, 0x93, 0xE4, 0xD5, 0x20, 0xC7, - 0xC8, 0x6F, 0x7A, 0x96, 0x5D, 0x9C, 0x35, 0x16, 0x9A, 0x5F, 0x68, 0x8D, 0x79, 0xBD, 0xF9, 0xAD, - 0x71, 0x3C, 0x46, 0x7F, 0x58, 0xE3, 0x1F, 0xD6, 0xB8, 0xBA, 0x35, 0x5E, 0x84, 0x1D, 0x2D, 0x31, - 0x6A, 0x33, 0x87, 0x24, 0xEF, 0x94, 0x5F, 0x36, 0x1A, 0x3F, 0x46, 0xE4, 0x73, 0x1B, 0x91, 0xBC, - 0x5A, 0xD9, 0x11, 0x29, 0xC6, 0x58, 0xC9, 0x11, 0x29, 0xC6, 0x6F, 0x95, 0x11, 0x29, 0xFC, 0x84, - 0x12, 0x23, 0x32, 0x66, 0xFC, 0xB1, 0x47, 0x64, 0xEC, 0x09, 0x57, 0x1E, 0x91, 0x42, 0x47, 0x4A, - 0x8D, 0x48, 0xC5, 0x2B, 0x19, 0xDE, 0xBB, 0xF6, 0xC4, 0x19, 0x9C, 0x78, 0x43, 0x3A, 0xAE, 0xEA, - 0x8E, 0xF4, 0x43, 0x18, 0xCE, 0x83, 0x27, 0x70, 0x46, 0xFE, 0xDF, 0xCC, 0x46, 0x8D, 0x89, 0xA8, - 0x3D, 0xB2, 0x23, 0x72, 0x4E, 0x61, 0x0D, 0x0D, 0xDD, 0x6B, 0xBB, 0x0B, 0xF2, 0x3C, 0xF2, 0x88, - 0xED, 0xCD, 0x42, 0x6F, 0xE2, 0x85, 0xCE, 0x37, 0x8A, 0xC4, 0xD6, 0x1E, 0x97, 0xD8, 0x05, 0x98, - 0x48, 0x02, 0x46, 0x01, 0x49, 0xAD, 0x3F, 0x2E, 0xA9, 0x0F, 0xD4, 0xFE, 0x76, 0x4F, 0x4E, 0xEC, - 0xC1, 0x2D, 0x00, 0xFA, 0xF7, 0x48, 0x71, 0xE3, 0x71, 0x29, 0x7E, 0xDC, 0xFB, 0x09, 0xA9, 0x6C, - 0x3E, 0x32, 0x15, 0x77, 0xEC, 0x4C, 0x9C, 0x90, 0xFB, 0xE0, 0x2F, 0xEB, 0xD1, 0x4A, 0x81, 0x8C, - 0x98, 0xA5, 0xE3, 0x27, 0x15, 0xCC, 0xCA, 0xDD, 0x78, 0xB8, 0x23, 0xD0, 0x58, 0xEA, 0x04, 0x34, - 0xDC, 0x0B, 0xB9, 0xA9, 0xA1, 0xAD, 0x26, 0x6E, 0x27, 0xAD, 0x5C, 0x07, 0x2B, 0x9E, 0xEF, 0x8C, - 0x1C, 0x98, 0x0B, 0x56, 0xD8, 0xE6, 0x04, 0x72, 0x72, 0x79, 0x4B, 0xC9, 0xFB, 0xD3, 0x7E, 0x9F, - 0x0C, 0x6C, 0x97, 0xC0, 0x3A, 0x07, 0xCC, 0x24, 0x41, 0x3B, 0x48, 0xD0, 0x9B, 0x46, 0x07, 0xFE, - 0xDB, 0x1A, 0xB1, 0x43, 0x32, 0x74, 0x6E, 0x6E, 0xA8, 0x0F, 0xC6, 0x94, 0xF8, 0x40, 0x27, 0xE8, - 0x90, 0x77, 0x9E, 0xCF, 0xEA, 0xBD, 0x8A, 0xAC, 0x82, 0x4D, 0x02, 0x66, 0x3A, 0xD9, 0xAE, 0x18, - 0x85, 0xEE, 0x8B, 0x76, 0xD5, 0xDA, 0x0C, 0x15, 0xF0, 0x03, 0xFF, 0x27, 0xB0, 0x92, 0x81, 0x15, - 0x8C, 0x3D, 0x4E, 0x6A, 0x71, 0x28, 0x8E, 0x90, 0xD3, 0x7B, 0x95, 0x5D, 0x39, 0x3A, 0xBF, 0x1B, - 0xF9, 0xDE, 0x6C, 0xCA, 0x11, 0x73, 0xD3, 0x05, 0x75, 0x87, 0xCE, 0x37, 0x67, 0x38, 0x83, 0xDA, - 0xA2, 0x52, 0xD0, 0x31, 0x09, 0x19, 0x25, 0xE6, 0x87, 0x83, 0x49, 0x4D, 0x71, 0x21, 0x87, 0xC4, - 0x09, 0x48, 0xE8, 0xDB, 0x6E, 0x00, 0xDD, 0x89, 0xCE, 0xC7, 0xF5, 0x3D, 0x81, 0x29, 0x9D, 0xA0, - 0x77, 0x80, 0xA2, 0xB2, 0xC9, 0x50, 0x6C, 0xED, 0x7B, 0x37, 0xA4, 0xFB, 0xE1, 0x37, 0xC6, 0x7D, - 0xC4, 0x13, 0xE9, 0x5A, 0xD6, 0x46, 0x9B, 0x9C, 0xF4, 0x4F, 0xD6, 0x39, 0xFB, 0x56, 0x27, 0xAA, - 0xD2, 0xB5, 0xD6, 0xD6, 0x3A, 0xE4, 0xF2, 0x16, 0xB0, 0x63, 0x5F, 0x5C, 0x53, 0x32, 0xF6, 0xEE, - 0x40, 0xE6, 0x43, 0x56, 0xEA, 0xA3, 0x55, 0x0E, 0xC8, 0x9D, 0x03, 0xCB, 0x1B, 0xF8, 0x0E, 0xD4, - 0xDC, 0xE1, 0x9D, 0x33, 0x84, 0xBF, 0xA0, 0x10, 0xD7, 0xA2, 0x1E, 0xD6, 0x0C, 0xBD, 0x98, 0x33, - 0xC0, 0x7E, 0xBF, 0x6A, 0x8F, 0xC7, 0x4C, 0xA8, 0x89, 0x4C, 0xC8, 0x31, 0x6A, 0x61, 0xF0, 0x0A, - 0x09, 0x63, 0xF5, 0x4D, 0xCB, 0xCA, 0x94, 0x13, 0x4D, 0xCD, 0x3D, 0x35, 0x24, 0xC6, 0x27, 0x30, - 0x12, 0x79, 0x21, 0xBC, 0x21, 0xF2, 0xE9, 0xCA, 0xAB, 0x48, 0xCD, 0x60, 0xC8, 0xF0, 0x79, 0x98, - 0xEC, 0x9F, 0x9D, 0xF4, 0x3A, 0x44, 0x9C, 0x90, 0xBC, 0x22, 0xEF, 0x70, 0x2F, 0xB1, 0x59, 0x38, - 0x23, 0x95, 0x5C, 0x27, 0xFF, 0x58, 0x23, 0x3F, 0xDD, 0x1A, 0xD9, 0xE0, 0x6D, 0x5F, 0x7A, 0xFE, - 0xE0, 0xF6, 0x9F, 0xD8, 0xC9, 0x4E, 0xD5, 0x5A, 0x5D, 0xC5, 0xA3, 0x91, 0x8B, 0xBD, 0x83, 0xA3, - 0x33, 0x82, 0x75, 0x51, 0x8F, 0x59, 0x23, 0x33, 0x6A, 0x1E, 0xEC, 0x5D, 0xEE, 0x15, 0x54, 0xCC, - 0xDD, 0xD8, 0xCC, 0xA8, 0xAD, 0x79, 0xEE, 0x65, 0x96, 0x53, 0x7D, 0x90, 0x75, 0xC6, 0x6A, 0xEA, - 0xE3, 0xC9, 0xF6, 0x96, 0x35, 0xEF, 0x92, 0x8C, 0x23, 0xA9, 0xB6, 0xC0, 0xC6, 0x33, 0x27, 0x0F, - 0xEC, 0x24, 0x5A, 0xD4, 0xF3, 0xF3, 0x63, 0x02, 0xD5, 0xC8, 0xC9, 0xFB, 0xBD, 0xBF, 0x10, 0x8E, - 0xDD, 0xA7, 0x9D, 0x4E, 0xA7, 0xE2, 0x22, 0x3C, 0x73, 0xA9, 0xE3, 0xDB, 0x39, 0xDD, 0xBA, 0x38, - 0x67, 0x97, 0x2D, 0x14, 0x9E, 0xC0, 0xAA, 0x08, 0x3F, 0xA6, 0xFB, 0x94, 0x7E, 0x67, 0x6F, 0x81, - 0x8E, 0xCC, 0xEF, 0x3F, 0x2D, 0x77, 0xAD, 0x97, 0xEB, 0xF8, 0x73, 0x8B, 0xFD, 0xDC, 0xC6, 0x9F, - 0xDD, 0xDE, 0xEF, 0x3E, 0x51, 0x63, 0xE5, 0x9E, 0xD5, 0xC1, 0x11, 0x40, 0x5F, 0x11, 0x74, 0xD8, - 0x24, 0x4D, 0x67, 0xFE, 0x18, 0x36, 0xDD, 0xFB, 0x46, 0x7D, 0xDF, 0x19, 0x0E, 0xA9, 0x8B, 0xF5, - 0x91, 0xD7, 0xBB, 0x5B, 0x8A, 0x3E, 0x14, 0x61, 0xD1, 0x23, 0x13, 0x50, 0xDD, 0xCE, 0x8F, 0x39, - 0x74, 0x71, 0xF3, 0xD8, 0xB9, 0x17, 0x84, 0x03, 0x66, 0x6C, 0x7F, 0xEC, 0x17, 0x15, 0xCD, 0x3A, - 0x8F, 0xBD, 0x61, 0xF4, 0x63, 0x0F, 0xF7, 0x99, 0xEE, 0x18, 0x55, 0x73, 0x3A, 0x8E, 0xDF, 0xF7, - 0xB6, 0xAD, 0xF3, 0x0C, 0x82, 0x46, 0xAF, 0x23, 0x8B, 0xA2, 0x3C, 0x5F, 0x4B, 0x6D, 0xA9, 0x40, - 0x54, 0xF4, 0xB2, 0xE3, 0x1E, 0x8E, 0xE9, 0xB7, 0x58, 0x21, 0xEB, 0x20, 0xD8, 0x3F, 0x3D, 0x2B, - 0x03, 0xFF, 0x4F, 0x34, 0x25, 0x76, 0xE3, 0x89, 0xB1, 0xDB, 0x5D, 0x5B, 0xFF, 0x1F, 0x3E, 0x15, - 0xFE, 0xCB, 0x1D, 0xBB, 0xA6, 0x40, 0x94, 0xA0, 0xA3, 0xFD, 0x5B, 0xDB, 0x1D, 0xA1, 0x0A, 0xCD, - 0x86, 0x64, 0x0C, 0xA6, 0xA9, 0x91, 0xB5, 0xC7, 0x82, 0x7D, 0x8F, 0x53, 0xC8, 0x5B, 0xA8, 0x09, - 0x6A, 0xEB, 0xF1, 0x99, 0x24, 0x0A, 0x8D, 0x62, 0xF1, 0x52, 0xAB, 0xAB, 0x17, 0x74, 0x02, 0x9D, - 0x45, 0xB0, 0xCB, 0x6F, 0x7C, 0x6F, 0xC2, 0x30, 0xE6, 0xF7, 0x8A, 0x86, 0xB7, 0xBC, 0x80, 0xB6, - 0x37, 0x2D, 0x0B, 0xA5, 0xC2, 0xFE, 0xFF, 0xA8, 0x5D, 0xD1, 0xED, 0x6E, 0xF4, 0x38, 0x2D, 0xF1, - 0xDB, 0xA3, 0x52, 0xEB, 0xAD, 0x59, 0xEB, 0x9C, 0x9A, 0xF8, 0xED, 0x51, 0xA9, 0xAD, 0x6F, 0x5A, - 0x5B, 0x9C, 0x9A, 0xF8, 0xED, 0x51, 0xA9, 0x6D, 0xF7, 0xBA, 0x51, 0xAF, 0xF1, 0xDF, 0x16, 0xB7, - 0xD8, 0x40, 0xC3, 0xF9, 0x08, 0xEA, 0xA9, 0xA2, 0xFD, 0xA1, 0x9D, 0x3F, 0xB4, 0xB3, 0xDE, 0xEA, - 0xC3, 0x18, 0xA0, 0x28, 0xC5, 0x69, 0x8E, 0xDC, 0x20, 0x88, 0x22, 0xDF, 0x7F, 0xA2, 0x7E, 0x00, - 0x68, 0x8F, 0xDC, 0xD0, 0x14, 0xB4, 0x09, 0x3E, 0x90, 0x73, 0x73, 0x8F, 0x5B, 0xEA, 0xCC, 0xE9, - 0x24, 0xC3, 0x19, 0xC5, 0x59, 0xF1, 0x46, 0x00, 0x13, 0x76, 0x2A, 0xC1, 0x9C, 0xAA, 0x20, 0x15, - 0x41, 0x98, 0x1D, 0x42, 0x58, 0x10, 0xDD, 0x32, 0x67, 0xFC, 0xCB, 0xA2, 0xB6, 0x5E, 0x70, 0x24, - 0xE2, 0x04, 0xFC, 0x04, 0xF3, 0x6F, 0x9F, 0xCB, 0xD0, 0xE6, 0x27, 0x56, 0xBD, 0xA7, 0x3C, 0x68, - 0x5C, 0x7B, 0xCA, 0x0D, 0x9F, 0x47, 0x3E, 0xFD, 0xEB, 0x53, 0xFB, 0x09, 0x4E, 0xFC, 0xF6, 0x1C, - 0xFF, 0xDA, 0x83, 0x35, 0x35, 0xE9, 0x8E, 0x9E, 0xE0, 0xE4, 0x2F, 0xA6, 0xD6, 0x1B, 0xCD, 0x71, - 0xF6, 0x57, 0x99, 0xDA, 0x3A, 0xA3, 0xB6, 0xF5, 0xB8, 0xD4, 0x7E, 0xF6, 0x61, 0x4A, 0x64, 0x26, - 0xF0, 0x71, 0xE9, 0xBC, 0x75, 0xBE, 0x32, 0xF5, 0xEB, 0x2E, 0x68, 0x18, 0x47, 0x01, 0xE5, 0x6F, - 0x76, 0x49, 0xB7, 0xD7, 0x35, 0x19, 0xA1, 0xCA, 0x86, 0xA8, 0xC8, 0x18, 0x9D, 0xE0, 0xCA, 0x88, - 0xCF, 0xBB, 0xCD, 0x0C, 0xF0, 0xEA, 0xED, 0xC8, 0x93, 0xD9, 0xE1, 0x4A, 0x7F, 0xE0, 0xC1, 0x42, - 0x89, 0x13, 0xED, 0x2D, 0x8E, 0xE8, 0x43, 0xE1, 0xA4, 0xB5, 0xBA, 0xDA, 0x07, 0xF3, 0x84, 0xD3, - 0xCD, 0x08, 0x6F, 0x83, 0xDA, 0x62, 0xF1, 0x89, 0x91, 0xF0, 0x33, 0xD7, 0x09, 0x0B, 0x26, 0xB7, - 0x60, 0xF8, 0xCE, 0xA7, 0xB4, 0x3F, 0xB5, 0x71, 0xC5, 0xA5, 0xD0, 0x82, 0x49, 0x45, 0xAB, 0xD9, - 0x77, 0x7E, 0x2B, 0xAA, 0x74, 0x6B, 0xFB, 0x43, 0x9C, 0xEA, 0x8E, 0x0E, 0x0A, 0x2A, 0x1A, 0x26, - 0xD5, 0x02, 0x88, 0xA1, 0x7D, 0x1F, 0x80, 0x93, 0x68, 0x3B, 0x2E, 0xDB, 0xD4, 0xCA, 0xAD, 0x3B, - 0xF5, 0x3D, 0xBC, 0x9B, 0x60, 0xE1, 0x45, 0xB3, 0x72, 0x55, 0xBB, 0xE5, 0xAB, 0xF6, 0xCA, 0x57, - 0x5D, 0x2B, 0x5F, 0x75, 0xBD, 0x7C, 0xD5, 0x8D, 0xF2, 0x55, 0x37, 0xCB, 0x57, 0x7D, 0x59, 0xA2, - 0x2A, 0x5B, 0x11, 0x9E, 0xEC, 0xED, 0x17, 0x75, 0x15, 0xC5, 0x15, 0xFC, 0xDB, 0xCB, 0x42, 0x2D, - 0x80, 0x65, 0x6E, 0x74, 0x89, 0xB5, 0xA0, 0xE6, 0xB5, 0x1D, 0xC2, 0xE8, 0xBA, 0x3F, 0xA7, 0xFE, - 0x80, 0xA2, 0xF3, 0x15, 0x57, 0xD6, 0xED, 0x09, 0x98, 0x0F, 0x67, 0xB8, 0x04, 0x90, 0x30, 0x16, - 0x3E, 0x5C, 0x9E, 0x1C, 0xEB, 0xF7, 0x46, 0x8A, 0xBC, 0x3D, 0x3F, 0xFC, 0x9A, 0xD2, 0x4B, 0x03, - 0x0D, 0x63, 0xBD, 0x6C, 0xAA, 0xD9, 0x50, 0x1F, 0xA7, 0x23, 0x90, 0x2A, 0x6D, 0xCC, 0xC1, 0xF2, - 0x00, 0xB7, 0xBC, 0xFC, 0xC9, 0x05, 0xDE, 0xF3, 0x4C, 0x33, 0xCB, 0xAE, 0x7F, 0xEE, 0x7B, 0x93, - 0x29, 0x18, 0x4C, 0xDA, 0x5A, 0xAA, 0x8C, 0x16, 0x2F, 0x8A, 0x5E, 0xD0, 0x01, 0x75, 0xA6, 0x06, - 0xE4, 0xE9, 0x3A, 0x2A, 0x85, 0x02, 0x12, 0x42, 0xF5, 0xF8, 0x8D, 0x65, 0x03, 0xF6, 0x99, 0x8F, - 0x71, 0x30, 0xE7, 0x72, 0x2D, 0x93, 0x64, 0xFF, 0xD8, 0x6A, 0x38, 0xB8, 0x85, 0xFC, 0x19, 0xEF, - 0xCF, 0xEF, 0x0A, 0xA4, 0x6C, 0xA7, 0xF4, 0xCB, 0xE7, 0x6F, 0x78, 0xB9, 0x76, 0x17, 0xEF, 0x04, - 0x19, 0xB1, 0x2D, 0x93, 0xC6, 0x17, 0x90, 0x3D, 0xC0, 0x4C, 0x5B, 0x4D, 0x76, 0x05, 0x96, 0x6D, - 0x21, 0xE1, 0x3D, 0xA0, 0x0A, 0xA2, 0x8A, 0x3C, 0xFC, 0x8F, 0x53, 0xBC, 0x8A, 0x1F, 0x09, 0x3B, - 0xDD, 0x20, 0x73, 0xBD, 0x56, 0x6D, 0x4A, 0xE8, 0x09, 0xCF, 0x82, 0x22, 0x3A, 0xBC, 0x56, 0x8B, - 0x5F, 0x55, 0x2B, 0xBD, 0xEA, 0x49, 0xEE, 0xBE, 0x9B, 0x06, 0x80, 0x7C, 0x31, 0xDE, 0xA4, 0xE9, - 0x73, 0x8D, 0x41, 0xE9, 0x7A, 0x7D, 0x0E, 0x6D, 0x36, 0x09, 0x3F, 0x1A, 0xED, 0xBD, 0x71, 0x4E, - 0xBB, 0xF9, 0xE5, 0xFE, 0x85, 0xD3, 0x66, 0x19, 0x02, 0xD2, 0x54, 0xA3, 0xC4, 0x01, 0x8F, 0x42, - 0xEF, 0x93, 0x99, 0xDE, 0xA7, 0xC7, 0xA2, 0xF7, 0xAB, 0x99, 0xDE, 0xAF, 0x8F, 0x42, 0x2F, 0x98, - 0xBA, 0xDE, 0xDD, 0x39, 0xC5, 0x03, 0xAC, 0x99, 0x69, 0xC9, 0x1E, 0xBB, 0xA6, 0xC4, 0x5A, 0x32, - 0x6E, 0x5D, 0x4D, 0x01, 0x16, 0xE6, 0xBB, 0x40, 0x33, 0xCF, 0x8D, 0x46, 0x1D, 0x26, 0xAE, 0x32, - 0x19, 0xF8, 0x6C, 0x7D, 0x21, 0x7F, 0x00, 0xB4, 0x56, 0x83, 0xFC, 0xE9, 0x4F, 0xD8, 0xC6, 0xCF, - 0xDD, 0xE8, 0x83, 0xC9, 0x5F, 0xCE, 0xE4, 0x6C, 0x99, 0x09, 0x08, 0x8D, 0xDA, 0xEB, 0x6B, 0xFF, - 0x4D, 0xA3, 0xEE, 0x8E, 0x47, 0xC0, 0x17, 0xD8, 0x98, 0x7E, 0xC0, 0x34, 0x9F, 0xC4, 0xB9, 0x09, - 0x3A, 0xD3, 0x59, 0x70, 0x5B, 0xD1, 0xAE, 0x08, 0xDC, 0x51, 0x12, 0x83, 0x4C, 0xFC, 0x51, 0x85, - 0x3A, 0x34, 0x6E, 0x26, 0xDC, 0xA3, 0xD0, 0x51, 0x6B, 0x49, 0x33, 0x2A, 0xE9, 0xD2, 0xCD, 0x84, - 0xBB, 0xBF, 0x69, 0x53, 0x2B, 0xE7, 0xA7, 0x80, 0x0E, 0x68, 0xBC, 0x0E, 0x7D, 0x62, 0x8F, 0x9D, - 0x91, 0xBB, 0xDB, 0x1C, 0xD3, 0x9B, 0xB0, 0xA9, 0xF7, 0x83, 0x09, 0x62, 0xF8, 0x06, 0x67, 0x28, - 0x85, 0x3F, 0xEC, 0xC4, 0x55, 0x2C, 0x28, 0x0B, 0x1D, 0xF5, 0x7C, 0x69, 0xA0, 0xD7, 0x6C, 0xD2, - 0x24, 0xE1, 0xFD, 0x94, 0xEE, 0xF2, 0xB9, 0xEF, 0xDA, 0xFB, 0xDE, 0x04, 0xBF, 0x6B, 0xB7, 0x69, - 0xE2, 0xA6, 0x49, 0xD8, 0xF4, 0xDA, 0x44, 0x64, 0x47, 0x07, 0x4D, 0x32, 0x80, 0x0A, 0x01, 0xFC, - 0xE9, 0xF9, 0x93, 0x15, 0x06, 0xBD, 0xC2, 0xF1, 0x49, 0xB7, 0x82, 0xD9, 0x21, 0x6A, 0xF3, 0x4D, - 0x49, 0x96, 0x56, 0x43, 0x45, 0x67, 0x4B, 0xF4, 0x32, 0x3B, 0xA6, 0xD3, 0x7B, 0x04, 0xB3, 0x5B, - 0x20, 0xDF, 0x55, 0xA6, 0xD5, 0xD9, 0xF5, 0xF7, 0x93, 0x24, 0xB6, 0x97, 0xE1, 0xC4, 0x10, 0x32, - 0xF5, 0xF3, 0x15, 0x1E, 0x41, 0x5F, 0x1D, 0x5C, 0x9E, 0x68, 0xDF, 0xF1, 0xA4, 0xEB, 0x0A, 0x4F, - 0x82, 0xAE, 0xF0, 0x1C, 0x4F, 0xE1, 0x45, 0x4A, 0x48, 0x22, 0x94, 0xCE, 0x19, 0xEE, 0x64, 0xD5, - 0xB8, 0xE0, 0x77, 0x90, 0x53, 0x66, 0x50, 0x43, 0x72, 0x6C, 0x5F, 0xD3, 0xB1, 0xE9, 0x22, 0xB2, - 0x54, 0xEF, 0x40, 0xDC, 0xA4, 0x4F, 0xA0, 0xA2, 0x1B, 0xF5, 0x57, 0xFA, 0xDA, 0x14, 0x65, 0x21, - 0x41, 0x45, 0xDB, 0xF2, 0xB0, 0x5A, 0x5F, 0x33, 0xD9, 0x1E, 0x39, 0xC5, 0x0A, 0x4F, 0x1B, 0x20, - 0x01, 0x83, 0xD9, 0xDA, 0xC9, 0x93, 0xDB, 0x2E, 0x8B, 0x63, 0x36, 0xEE, 0x10, 0xE8, 0x09, 0x5A, - 0xFE, 0xB0, 0x2B, 0x93, 0xC9, 0xDA, 0x35, 0x48, 0xA7, 0x75, 0x91, 0x80, 0xCC, 0x6B, 0x70, 0x39, - 0x3F, 0x0C, 0x53, 0xBB, 0xDB, 0x94, 0xA5, 0xD4, 0x7C, 0x57, 0x0D, 0x52, 0xEE, 0x03, 0xB5, 0xED, - 0x38, 0x4A, 0xAE, 0x58, 0x5E, 0x03, 0xE9, 0x73, 0xCF, 0x24, 0x12, 0x55, 0x65, 0x00, 0x91, 0x59, - 0x7D, 0x72, 0xFA, 0x67, 0x77, 0x97, 0xAC, 0x67, 0x49, 0xA5, 0x2E, 0xA3, 0xC6, 0xCF, 0x6B, 0xC6, - 0x2E, 0x65, 0xFC, 0xAE, 0x5B, 0x2F, 0x7B, 0x57, 0x56, 0xC4, 0x3D, 0xFF, 0xAB, 0x70, 0x07, 0xE3, - 0x45, 0x6E, 0x67, 0x0C, 0x9D, 0x6F, 0x8A, 0x61, 0x61, 0xD1, 0xE7, 0xC4, 0xF7, 0xEE, 0xB8, 0x5D, - 0x9A, 0x04, 0x23, 0x89, 0xBF, 0xD8, 0x32, 0xE9, 0x1D, 0x98, 0x42, 0x3B, 0x66, 0x62, 0x00, 0x8C, - 0xDC, 0xB4, 0xE9, 0xF0, 0x11, 0xC9, 0x81, 0x37, 0x5E, 0x09, 0x26, 0x2B, 0xEB, 0x04, 0x7F, 0xD9, - 0x64, 0x3F, 0x19, 0x17, 0x0C, 0xBC, 0xF9, 0x46, 0x03, 0xE5, 0xB2, 0x05, 0xF8, 0x57, 0xAF, 0x57, - 0x59, 0x8D, 0x42, 0x36, 0xA4, 0xD6, 0x29, 0xA4, 0xD6, 0x9B, 0xAA, 0x31, 0xE6, 0x29, 0x9B, 0x34, - 0x13, 0xCB, 0x63, 0x70, 0x9A, 0x05, 0x34, 0x62, 0xF3, 0x9D, 0x6A, 0x23, 0x5F, 0x09, 0xC9, 0x65, - 0xCC, 0xE0, 0x94, 0x92, 0xDF, 0x34, 0x0B, 0xED, 0xA1, 0xEF, 0x7B, 0x09, 0xA3, 0x8E, 0x3B, 0x76, - 0x5C, 0xCA, 0xBF, 0x81, 0xD5, 0x9F, 0x16, 0xE2, 0x5D, 0x05, 0x89, 0xBC, 0xE1, 0x3F, 0x2B, 0x58, - 0xFE, 0x89, 0x6C, 0xAA, 0x53, 0x5B, 0x05, 0xA2, 0xF4, 0x48, 0xDC, 0x68, 0x40, 0xDD, 0x34, 0x1D, - 0xD6, 0xC8, 0x42, 0x60, 0x06, 0xEA, 0xFD, 0x39, 0x98, 0xA8, 0x9C, 0x4A, 0x88, 0xE8, 0x02, 0xE3, - 0x1D, 0x98, 0xF2, 0xC3, 0x58, 0xED, 0xE6, 0x54, 0x0E, 0xB0, 0x4E, 0x3C, 0xCA, 0x73, 0x2A, 0xCB, - 0x6C, 0x4A, 0xD8, 0x7B, 0x6B, 0x56, 0x09, 0x80, 0x84, 0x80, 0x5E, 0xBF, 0xCE, 0xC4, 0xC3, 0x72, - 0xB9, 0xBC, 0x83, 0x15, 0x63, 0xA8, 0xF9, 0x5B, 0x05, 0x93, 0x90, 0x5E, 0xED, 0xEF, 0x33, 0x70, - 0x7F, 0x6E, 0x1C, 0xB6, 0x56, 0xD7, 0xCB, 0xB3, 0xFA, 0x32, 0xBF, 0xB7, 0xF0, 0x9F, 0x82, 0x35, - 0xBE, 0xAF, 0xD2, 0xC8, 0xB3, 0x2E, 0xF5, 0x26, 0xC4, 0x42, 0xEB, 0xB9, 0xF3, 0x2F, 0x68, 0xC3, - 0x12, 0xE9, 0xFE, 0xB0, 0x67, 0xBF, 0x97, 0x3D, 0xE3, 0xD1, 0x8D, 0x68, 0x8B, 0xF2, 0xEC, 0x55, - 0x52, 0xEB, 0xEA, 0xFD, 0xFB, 0xBD, 0xFA, 0x83, 0xFE, 0x11, 0x5C, 0xC9, 0x85, 0x8C, 0x9C, 0x7F, - 0x81, 0x69, 0x5E, 0x9C, 0x65, 0xF1, 0xE5, 0x92, 0x91, 0x91, 0x4C, 0xA5, 0x96, 0x47, 0xC8, 0x50, - 0x44, 0x53, 0x92, 0xC9, 0xF5, 0x4A, 0xAF, 0xB8, 0xF1, 0x3C, 0xAE, 0x26, 0x1A, 0x16, 0x56, 0xF3, - 0xCD, 0xD9, 0xCD, 0xCD, 0xEB, 0x55, 0xFE, 0xB5, 0x22, 0x70, 0xB7, 0xF9, 0x86, 0xAB, 0x59, 0xB7, - 0x26, 0x82, 0x5E, 0x84, 0xA0, 0x57, 0x1A, 0xC1, 0x2A, 0x97, 0x5A, 0xB9, 0x21, 0xA6, 0xEB, 0x2B, - 0x0C, 0x8F, 0xBE, 0xFD, 0x8D, 0xB2, 0x90, 0x4B, 0x14, 0x3B, 0xBB, 0x46, 0xC0, 0x78, 0x21, 0x76, - 0x40, 0xEE, 0x28, 0x86, 0x4C, 0x36, 0x43, 0x76, 0xD9, 0x11, 0xAB, 0xF0, 0x92, 0x7B, 0x1A, 0x76, - 0x14, 0xFC, 0xB7, 0x50, 0xD7, 0xF5, 0x42, 0x2C, 0x20, 0xD7, 0x94, 0xBA, 0xC4, 0x1E, 0x0E, 0x79, - 0xD4, 0x64, 0xBC, 0xC5, 0xA2, 0xAE, 0x34, 0xF5, 0xDC, 0x90, 0x7C, 0xB3, 0x42, 0xEA, 0x54, 0x6D, - 0x80, 0xA4, 0x13, 0x46, 0xD6, 0xD9, 0xDE, 0x10, 0xF8, 0x79, 0xF0, 0xF1, 0xB0, 0xC8, 0xBF, 0x91, - 0xAA, 0x95, 0xF2, 0x2F, 0xA4, 0xFA, 0x0B, 0x72, 0x2F, 0x9E, 0xAB, 0xA5, 0x49, 0x6D, 0x60, 0x90, - 0x49, 0xB8, 0xB2, 0x56, 0xD6, 0xCA, 0xA4, 0xB7, 0x3F, 0xB8, 0xF9, 0xC8, 0x36, 0x3F, 0x6F, 0xC4, - 0xFD, 0xCC, 0x2C, 0xFB, 0x52, 0xD6, 0xBC, 0xF0, 0x99, 0x35, 0x63, 0xFB, 0xA5, 0x99, 0xB9, 0x9F, - 0x53, 0xD9, 0x9A, 0xCE, 0x3B, 0xD2, 0xE2, 0xF3, 0x94, 0x05, 0x8D, 0x34, 0x25, 0x99, 0x6A, 0xA9, - 0xA1, 0xA6, 0x66, 0x58, 0xAD, 0x33, 0xD6, 0xA4, 0xCB, 0xB3, 0x22, 0x29, 0xE9, 0x7D, 0x7A, 0xB0, - 0xA9, 0x39, 0x4C, 0x73, 0x06, 0x44, 0x52, 0x29, 0x42, 0x16, 0xB9, 0xDD, 0xE0, 0xFF, 0x66, 0x38, - 0xDD, 0x09, 0x8C, 0x18, 0x1F, 0x2A, 0xA5, 0xCC, 0x21, 0x92, 0x66, 0x2A, 0x1A, 0x29, 0x2A, 0xC6, - 0xF4, 0x60, 0x41, 0x21, 0x98, 0x73, 0xB6, 0x46, 0x9B, 0x0F, 0xAF, 0xCD, 0x29, 0x5F, 0x4D, 0x6E, - 0x7B, 0x06, 0x22, 0xD6, 0x15, 0x06, 0xF6, 0x0C, 0x21, 0x10, 0x39, 0xD9, 0x61, 0x75, 0x34, 0x91, - 0x54, 0x8B, 0x6F, 0x1A, 0xFD, 0x23, 0x3F, 0xF4, 0xFA, 0xD2, 0xF3, 0xC8, 0xC4, 0x76, 0xEF, 0x65, - 0xE2, 0x24, 0xE0, 0xAD, 0x7C, 0x85, 0x09, 0x20, 0x73, 0xE5, 0x53, 0x3B, 0xD4, 0x90, 0x0D, 0x18, - 0xC7, 0x1D, 0x49, 0xB9, 0x76, 0x0D, 0xA7, 0xA2, 0xE9, 0x4A, 0x55, 0xB6, 0x3A, 0xDD, 0x04, 0x2C, - 0xF3, 0x80, 0x3B, 0x5D, 0xA7, 0xF2, 0xE9, 0x21, 0x0B, 0x81, 0xCC, 0x6D, 0x47, 0xBA, 0x4E, 0x95, - 0x66, 0x78, 0xA1, 0x1D, 0x81, 0x65, 0x9D, 0x82, 0xA6, 0xAA, 0x54, 0x6C, 0x84, 0x88, 0x39, 0x38, - 0x02, 0xCD, 0x48, 0xA2, 0x14, 0x4C, 0xB1, 0x00, 0xC6, 0x8A, 0x9D, 0xC0, 0x1F, 0x54, 0x3F, 0xC9, - 0x4F, 0xE5, 0x65, 0x35, 0x9D, 0xB9, 0x9B, 0x92, 0xB7, 0x56, 0x3B, 0xCC, 0x10, 0x69, 0xD1, 0x4D, - 0xC7, 0x19, 0x71, 0xC2, 0xF4, 0x1A, 0x18, 0x3D, 0x8C, 0xCC, 0x31, 0xA3, 0xE4, 0x19, 0xD7, 0xAB, - 0x85, 0x62, 0xD0, 0x6B, 0xCF, 0x8B, 0xB2, 0x01, 0xE6, 0x1F, 0xDE, 0x65, 0x1C, 0x92, 0x69, 0x18, - 0x3A, 0x7C, 0x9E, 0x32, 0x6C, 0xB1, 0xAB, 0x69, 0x18, 0x30, 0x0C, 0x53, 0x44, 0x53, 0x74, 0xC4, - 0x1C, 0x66, 0xCC, 0x0D, 0xAA, 0x5F, 0xD1, 0x62, 0xE1, 0x9B, 0x98, 0x00, 0x87, 0x01, 0xF3, 0xBC, - 0x85, 0x41, 0xA3, 0x8E, 0x31, 0xCA, 0x63, 0xDE, 0xAA, 0xCE, 0xBA, 0x48, 0x07, 0x9E, 0x71, 0x31, - 0xAD, 0x0E, 0xEF, 0x85, 0xC7, 0x7C, 0xB9, 0xA9, 0x1D, 0x6B, 0x75, 0x66, 0x11, 0xCA, 0xE2, 0xDE, - 0x2D, 0x97, 0x6F, 0xB2, 0x74, 0xA7, 0xE7, 0xA3, 0x9B, 0xB7, 0xFB, 0x4B, 0x37, 0xD7, 0x5A, 0x58, - 0x63, 0x73, 0xD5, 0x64, 0xCE, 0xD6, 0x3E, 0xC8, 0x49, 0x92, 0xF7, 0x79, 0x7A, 0x6A, 0x70, 0xF6, - 0xA2, 0xAC, 0xD0, 0x13, 0xF4, 0xFD, 0xF0, 0x2D, 0x0C, 0xCC, 0x29, 0x03, 0xC6, 0x34, 0x28, 0xD0, - 0x2F, 0xDB, 0x0D, 0xA9, 0xEB, 0xDA, 0x1F, 0xA8, 0x33, 0xBA, 0x0D, 0xAF, 0x26, 0x13, 0xB3, 0x61, - 0xD6, 0x6A, 0xA9, 0x3A, 0x42, 0x56, 0xF1, 0xDE, 0x1D, 0xCB, 0x89, 0x6D, 0x66, 0x92, 0x2D, 0x09, - 0x40, 0x46, 0x34, 0x80, 0xAA, 0x3C, 0x97, 0xCA, 0xF5, 0x2C, 0x0C, 0xE5, 0xE8, 0xFD, 0x72, 0x19, - 0x93, 0x43, 0xFF, 0xDE, 0xDC, 0xC9, 0x18, 0xDD, 0x90, 0xA7, 0x6B, 0x0F, 0xE0, 0x4D, 0x87, 0x83, - 0x5B, 0xD2, 0xA2, 0xB8, 0x05, 0xB5, 0x54, 0xE4, 0xB5, 0xF4, 0xC1, 0x9B, 0xBE, 0x04, 0x24, 0xC4, - 0x09, 0x02, 0xF8, 0xC9, 0x2E, 0x03, 0x1E, 0x1D, 0x44, 0x99, 0xAB, 0xAB, 0x8C, 0xE5, 0xFC, 0xD4, - 0xD2, 0x25, 0xDB, 0x63, 0x50, 0xA7, 0x1A, 0x0D, 0x62, 0x19, 0x69, 0x2A, 0xB7, 0x48, 0xEA, 0xC7, - 0xBD, 0xF1, 0x98, 0xF8, 0x74, 0x34, 0x1B, 0x63, 0x2E, 0x70, 0xB6, 0x74, 0xE2, 0x7D, 0x1A, 0x2F, - 0x5C, 0xB4, 0xEE, 0xAC, 0xD0, 0xD6, 0x4C, 0x8B, 0x53, 0xB1, 0x9D, 0x47, 0x35, 0xFA, 0xEB, 0xC1, - 0x94, 0x66, 0x3D, 0xBA, 0xEF, 0x4C, 0x30, 0xEE, 0x8B, 0x26, 0xF7, 0xC4, 0x59, 0xC4, 0x08, 0x0F, - 0x7C, 0xE3, 0xB7, 0x0A, 0xC5, 0x26, 0x84, 0x16, 0xD7, 0xD2, 0x6C, 0xEE, 0xBC, 0x48, 0xA6, 0x1F, - 0x98, 0x07, 0x44, 0xB0, 0xDC, 0x49, 0x30, 0x32, 0xD4, 0x14, 0x0C, 0x1C, 0x78, 0xB8, 0xE0, 0x9B, - 0xF1, 0x14, 0xDA, 0xA0, 0x3C, 0x78, 0x85, 0x0B, 0xD6, 0x81, 0x3E, 0xC6, 0x03, 0xC2, 0x1A, 0x8C, - 0xDC, 0xC1, 0x5A, 0x2F, 0xF1, 0x59, 0xA0, 0x0B, 0x6E, 0xBC, 0x17, 0x91, 0xC9, 0xD7, 0x13, 0x70, - 0xF3, 0x41, 0x20, 0xCB, 0x2B, 0xF3, 0x69, 0x8B, 0xA4, 0x83, 0xDF, 0x79, 0xE0, 0x7F, 0x43, 0xDF, - 0xF1, 0x9B, 0xA9, 0x9C, 0x91, 0xA4, 0x4F, 0x47, 0xE9, 0x0C, 0x85, 0x1F, 0x7E, 0x83, 0xD6, 0x0C, - 0x9D, 0x60, 0x8A, 0x7D, 0xC4, 0xDE, 0xD2, 0xC1, 0x70, 0x6C, 0xB2, 0x3F, 0x0B, 0x60, 0x0E, 0xE4, - 0x7F, 0xC3, 0xDA, 0x15, 0xC5, 0xD4, 0x5C, 0x92, 0x7A, 0xC1, 0x80, 0xA9, 0x4F, 0x07, 0xB5, 0x51, - 0xE1, 0xD5, 0x60, 0x74, 0xDE, 0xFA, 0xE2, 0xAE, 0xFA, 0xDC, 0x88, 0xDE, 0xA1, 0xA3, 0x55, 0x1B, - 0x0B, 0x73, 0xD3, 0xDE, 0xB2, 0x34, 0x0A, 0xF2, 0x33, 0x00, 0x3C, 0x08, 0x68, 0xB1, 0x38, 0xDF, - 0x53, 0xAF, 0x36, 0x4A, 0x71, 0x19, 0x3E, 0xF4, 0x9D, 0x29, 0xDE, 0x14, 0xC6, 0xB0, 0xD1, 0xF9, - 0x31, 0xED, 0x8F, 0x1D, 0x16, 0x55, 0x5C, 0x13, 0x53, 0x74, 0x13, 0x11, 0x87, 0x96, 0x8B, 0x37, - 0x16, 0x6A, 0xE2, 0x31, 0x5E, 0x83, 0x9E, 0xAB, 0x75, 0x87, 0x51, 0x82, 0x89, 0x19, 0xB3, 0xE3, - 0x0B, 0xC1, 0xF5, 0x41, 0xC4, 0xF8, 0xF3, 0x47, 0xA8, 0xBC, 0xD1, 0x88, 0xC5, 0xE3, 0xCF, 0x87, - 0x3A, 0x98, 0x9E, 0x7A, 0x77, 0x73, 0x22, 0x39, 0xF6, 0x7C, 0xBB, 0x36, 0x0A, 0xE1, 0x29, 0x9C, - 0xDF, 0xA2, 0xB2, 0x52, 0x3C, 0x5C, 0x64, 0x4E, 0xC5, 0x9C, 0x0C, 0x2D, 0x42, 0x36, 0x02, 0xCB, - 0xC5, 0xD1, 0xE9, 0xE1, 0x2F, 0x73, 0xA2, 0xDA, 0xBB, 0x38, 0x5F, 0x0C, 0x4F, 0xB8, 0x58, 0x78, - 0x17, 0xC7, 0x18, 0x0F, 0xD9, 0x39, 0xFC, 0xDC, 0x08, 0xA3, 0x65, 0x4B, 0x3D, 0x3C, 0x59, 0x79, - 0x3C, 0x2A, 0x21, 0x8C, 0x31, 0xF2, 0x49, 0x04, 0x6D, 0x1F, 0xBE, 0x48, 0x25, 0xEF, 0x4B, 0xF0, - 0x92, 0x28, 0x3A, 0x51, 0x2F, 0x0D, 0x07, 0xC2, 0x96, 0xBC, 0x45, 0x17, 0x43, 0x2B, 0xE1, 0xF6, - 0x2A, 0x55, 0x32, 0x1B, 0x4E, 0x53, 0xDF, 0x86, 0xB7, 0x83, 0xE9, 0xA1, 0x48, 0x46, 0x93, 0xA6, - 0x0E, 0xEB, 0x73, 0x5C, 0x4F, 0xA7, 0x0B, 0xF6, 0x53, 0xBB, 0x95, 0x4E, 0x82, 0xF7, 0x41, 0x79, - 0x4F, 0x8D, 0x39, 0xF5, 0xE0, 0x64, 0x88, 0xA9, 0x56, 0x38, 0x34, 0x41, 0x78, 0x0F, 0xAE, 0x04, - 0x0A, 0x6C, 0xCC, 0x1E, 0xAB, 0x6B, 0xB8, 0x9E, 0x4B, 0x1B, 0xEA, 0x4B, 0x6C, 0x6C, 0xF1, 0x53, - 0x0C, 0x79, 0x0D, 0xDE, 0xFC, 0x57, 0x0E, 0x0A, 0xBE, 0xB4, 0x4F, 0x71, 0xF6, 0xDE, 0xEF, 0xFF, - 0x84, 0xF9, 0x2F, 0xD0, 0x43, 0x10, 0x97, 0x64, 0xD9, 0xEB, 0x2B, 0x12, 0x6E, 0xF1, 0x32, 0x55, - 0xFC, 0xF2, 0x1C, 0x7F, 0xAE, 0x8A, 0x55, 0x45, 0x60, 0xE9, 0x00, 0x61, 0x75, 0xF5, 0x28, 0x71, - 0xE6, 0xE2, 0xBA, 0x83, 0x71, 0x20, 0x9E, 0x82, 0xC3, 0xD7, 0xA1, 0xE2, 0x07, 0x42, 0xFE, 0x3E, - 0xA3, 0xFE, 0x3D, 0x7F, 0xFB, 0xCC, 0xF3, 0xC1, 0x21, 0x6C, 0x35, 0x3A, 0xF2, 0x21, 0x74, 0x9B, - 0x74, 0x94, 0x13, 0xB7, 0x46, 0xCE, 0xAB, 0x33, 0x12, 0x05, 0xB1, 0xDD, 0x07, 0xDF, 0x97, 0x97, - 0x65, 0x9F, 0x45, 0x62, 0x78, 0x79, 0x57, 0x06, 0xF8, 0xFC, 0xFD, 0x4B, 0x47, 0x3C, 0x21, 0xC3, - 0x6E, 0x24, 0xA8, 0x25, 0xDC, 0x9B, 0x64, 0x85, 0x51, 0x8F, 0xBD, 0x48, 0x2D, 0x45, 0xDA, 0x86, - 0x95, 0x48, 0x7C, 0x7B, 0x1E, 0x7D, 0x35, 0xDC, 0xB7, 0xC4, 0xD8, 0x4B, 0xF6, 0x07, 0x2F, 0xAF, - 0x2A, 0x94, 0xE4, 0x34, 0xE1, 0x95, 0xEB, 0x85, 0xAD, 0x8E, 0x1E, 0xD1, 0xB9, 0x14, 0xC9, 0xCB, - 0x97, 0x53, 0xDE, 0x3C, 0xAD, 0xB0, 0xA2, 0x65, 0x46, 0x5A, 0x5C, 0x26, 0x3E, 0xE4, 0xA0, 0xE5, - 0x52, 0x7C, 0x28, 0x31, 0xD0, 0x40, 0x04, 0xDF, 0x90, 0x69, 0xB6, 0x9B, 0xF0, 0x53, 0x42, 0x05, - 0x7C, 0x54, 0xA3, 0x1F, 0x07, 0x35, 0x57, 0xE2, 0x21, 0x8E, 0x95, 0x36, 0xF1, 0x11, 0x15, 0x96, - 0xE7, 0x25, 0x77, 0xEB, 0xBA, 0x88, 0x25, 0xC3, 0x79, 0x08, 0x8B, 0x18, 0x34, 0x23, 0xE5, 0x4C, - 0x71, 0x7E, 0x73, 0xB6, 0xF1, 0xCD, 0xBC, 0x6B, 0x0B, 0x1B, 0x17, 0xFC, 0xC7, 0x11, 0x5F, 0x1B, - 0x25, 0x3C, 0xA5, 0xDE, 0x9D, 0x44, 0x03, 0xD2, 0x52, 0xCA, 0x5F, 0x44, 0x31, 0xC1, 0xD2, 0x8B, - 0x77, 0x20, 0x8C, 0xE4, 0x4D, 0xBC, 0x56, 0x54, 0xD8, 0x26, 0x3D, 0xCB, 0xB2, 0x96, 0xD2, 0xD6, - 0x8E, 0x05, 0x80, 0x80, 0x95, 0x6B, 0x13, 0xB6, 0x9C, 0xC3, 0x13, 0x2C, 0xC5, 0xFA, 0x61, 0x1B, - 0x79, 0x90, 0x88, 0xB6, 0x48, 0xC2, 0x28, 0x7C, 0x56, 0xF0, 0x8A, 0xA0, 0x08, 0x62, 0x68, 0x24, - 0x11, 0x53, 0x18, 0x8C, 0xA9, 0xED, 0x47, 0x24, 0xCA, 0xE1, 0x6D, 0xA6, 0x79, 0xEC, 0xCF, 0x06, - 0x03, 0x58, 0xD3, 0x31, 0x2E, 0xA5, 0x67, 0xB8, 0x62, 0x3C, 0xA2, 0xDC, 0xC4, 0x61, 0x93, 0xBF, - 0xC4, 0x95, 0x66, 0x2A, 0xC1, 0x59, 0x16, 0x9D, 0x81, 0x31, 0x58, 0x3B, 0x46, 0x4C, 0x09, 0xF9, - 0x45, 0x8B, 0xB8, 0xF8, 0x41, 0xD2, 0x1B, 0xB1, 0x4E, 0x36, 0xAD, 0xFF, 0xD2, 0xEB, 0xEF, 0x68, - 0x9F, 0x01, 0xCF, 0x3F, 0x71, 0xFE, 0xED, 0xF8, 0xCC, 0xF8, 0xB5, 0x44, 0xB4, 0x4E, 0xCC, 0xD9, - 0x4E, 0x3E, 0x14, 0x5E, 0xC2, 0x55, 0x02, 0x7C, 0x8C, 0x27, 0x03, 0x7C, 0x19, 0xFF, 0x0F, 0x65, - 0xCD, 0xAD, 0xED, 0x12, 0x54, 0xE6, 0x30, 0x45, 0xAE, 0x88, 0x3F, 0x43, 0x93, 0xF2, 0x39, 0x34, - 0x5C, 0x9C, 0xC9, 0xEC, 0x69, 0xD1, 0x47, 0x89, 0x8E, 0x4B, 0xDA, 0x23, 0xF7, 0x5F, 0x43, 0x28, - 0xB2, 0x78, 0xB7, 0x2D, 0xBE, 0x23, 0xA7, 0x2B, 0x8D, 0xD4, 0xDF, 0x9A, 0x8B, 0x60, 0xD0, 0x14, - 0xF6, 0xC6, 0x29, 0xE2, 0x65, 0x17, 0x74, 0xF8, 0x66, 0xA6, 0x84, 0x0F, 0x6D, 0xBC, 0x1C, 0x2E, - 0xF1, 0xF1, 0xED, 0x2F, 0x92, 0x32, 0xB2, 0x62, 0x31, 0x27, 0xB0, 0x62, 0x46, 0xD7, 0x82, 0x61, - 0xBC, 0xB1, 0x01, 0xFC, 0x9E, 0x80, 0x93, 0x87, 0x69, 0xB2, 0xAE, 0x69, 0x78, 0x87, 0x47, 0xCC, - 0x16, 0xDB, 0xF1, 0x81, 0xB2, 0x46, 0x1B, 0xED, 0xD8, 0x78, 0x6C, 0x4F, 0x03, 0x8A, 0xF9, 0xB8, - 0x79, 0xCA, 0x30, 0xB6, 0xC7, 0xA1, 0xAA, 0xAF, 0x89, 0x3E, 0xAE, 0x66, 0x1F, 0x93, 0x07, 0xC4, - 0x5F, 0xCC, 0x07, 0x66, 0x7B, 0x2D, 0xC3, 0xC5, 0x66, 0x36, 0x13, 0x9B, 0xF3, 0xC8, 0x01, 0xE9, - 0x97, 0x95, 0x44, 0x3D, 0x1E, 0x8C, 0x72, 0x10, 0x15, 0xFB, 0x7C, 0x1E, 0x01, 0xC3, 0x3D, 0xE0, - 0x37, 0xE8, 0x07, 0xB0, 0x0E, 0x91, 0x4D, 0xB2, 0x28, 0x30, 0x0D, 0x41, 0x54, 0xE9, 0x68, 0x20, - 0x41, 0x4D, 0x0E, 0x69, 0x1A, 0xAA, 0x30, 0xFD, 0xAC, 0xB0, 0xD2, 0x15, 0xF4, 0x08, 0x2B, 0x82, - 0xCC, 0xA6, 0x79, 0x00, 0x7C, 0x68, 0xA7, 0x09, 0xC8, 0x6D, 0x05, 0x67, 0xD0, 0x41, 0x97, 0xFE, - 0x9D, 0x43, 0xC7, 0xC3, 0xA0, 0x95, 0x3C, 0xAB, 0xB8, 0x2F, 0x84, 0x20, 0xBC, 0xE8, 0x41, 0x92, - 0x4E, 0x46, 0x17, 0x4F, 0x2C, 0x58, 0xB1, 0x8B, 0x27, 0x52, 0xE3, 0x81, 0xC4, 0xA3, 0xAD, 0x40, - 0xA4, 0x1E, 0xB9, 0x6F, 0x99, 0xD0, 0x49, 0xB7, 0x20, 0x28, 0x5E, 0xDC, 0xAF, 0x0A, 0x87, 0x2A, - 0x25, 0x40, 0xE1, 0xD7, 0x72, 0xD0, 0x6F, 0x93, 0x84, 0x9E, 0x00, 0xCA, 0xD2, 0x7B, 0x56, 0xA7, - 0xCA, 0x94, 0x48, 0x80, 0x97, 0xA6, 0x7C, 0x7E, 0x2E, 0x09, 0x4A, 0xDA, 0x91, 0x29, 0x09, 0x2D, - 0xE5, 0xFD, 0x64, 0x08, 0xF0, 0xCF, 0x52, 0x90, 0x3F, 0x3B, 0xEF, 0x9C, 0x04, 0xF0, 0xCE, 0xB9, - 0x71, 0xCA, 0xC1, 0x5D, 0xEE, 0x9F, 0x7F, 0x3C, 0x90, 0x78, 0x86, 0x95, 0xE6, 0xC7, 0xE1, 0xB4, - 0x1C, 0x2C, 0xBB, 0x24, 0x9D, 0x80, 0x32, 0x7F, 0xBE, 0x1C, 0x64, 0x7A, 0xA9, 0x79, 0x9F, 0xE0, - 0x91, 0x7C, 0xBD, 0x72, 0xD8, 0xFA, 0xF7, 0x41, 0x48, 0x27, 0x09, 0x82, 0x80, 0xFF, 0x5D, 0x0A, - 0xF6, 0x50, 0x4D, 0xDA, 0x0A, 0xD0, 0x71, 0x1A, 0xD7, 0x52, 0xF0, 0xA7, 0x97, 0x92, 0xF0, 0x30, - 0xB3, 0x6B, 0x29, 0xA8, 0x77, 0xD2, 0xDB, 0x97, 0x00, 0x27, 0x2F, 0x91, 0x22, 0x78, 0xEE, 0x2C, - 0xE8, 0xB3, 0x1B, 0x1F, 0xC5, 0x62, 0x48, 0x12, 0x4E, 0x39, 0x65, 0x40, 0x79, 0x4A, 0x8F, 0xE4, - 0x82, 0x3C, 0x46, 0x14, 0xB4, 0xF1, 0x49, 0xE2, 0xF5, 0x6D, 0xC9, 0x98, 0xB2, 0x57, 0x05, 0xD6, - 0xB7, 0x01, 0xD2, 0xF6, 0xED, 0x01, 0x9E, 0x9A, 0xC9, 0xE6, 0x54, 0x1D, 0xF5, 0x4B, 0x31, 0x69, - 0xF6, 0x04, 0x45, 0x06, 0x5D, 0x6E, 0xB8, 0x0D, 0xFB, 0xE5, 0x6D, 0x7C, 0x3C, 0xD6, 0xB2, 0xBA, - 0xBD, 0x36, 0x7B, 0xFD, 0x36, 0x6D, 0xCF, 0x79, 0x29, 0xB3, 0xEA, 0x5D, 0x8B, 0x01, 0x98, 0x0C, - 0x48, 0x24, 0x55, 0x24, 0xB9, 0x2F, 0x67, 0x19, 0x65, 0xBB, 0x14, 0x99, 0xEC, 0xF0, 0xD4, 0xA0, - 0x0D, 0x36, 0x9D, 0x6C, 0x5B, 0x99, 0xD3, 0xC9, 0xB6, 0x55, 0x82, 0x6C, 0x0A, 0xF5, 0xFE, 0xE9, - 0xD9, 0x5C, 0x98, 0x63, 0x1F, 0x36, 0x6B, 0x53, 0x39, 0x3E, 0x11, 0x4B, 0x7B, 0xB7, 0xA6, 0x3E, - 0x77, 0x13, 0xE0, 0x7D, 0x1B, 0x24, 0xE4, 0x7F, 0xF0, 0x82, 0x50, 0xF4, 0xFE, 0x46, 0xAA, 0xF7, - 0x37, 0x32, 0x7A, 0x3F, 0xDD, 0xFA, 0x0C, 0x09, 0xA4, 0xC8, 0xA1, 0x05, 0xE3, 0xE4, 0xB6, 0xF1, - 0x9F, 0x4E, 0x91, 0x7D, 0xAC, 0x46, 0xC9, 0xD0, 0x32, 0xF6, 0xF4, 0xED, 0x39, 0x5A, 0x57, 0x4E, - 0x6A, 0xCD, 0xD2, 0xE9, 0xAC, 0x59, 0xB5, 0x5B, 0xC6, 0xDB, 0xF1, 0x31, 0xA0, 0x7E, 0xB6, 0x34, - 0xD3, 0x05, 0x58, 0x9F, 0x19, 0xC1, 0xF0, 0x6B, 0x6F, 0xE4, 0x75, 0x06, 0xDE, 0x04, 0xFF, 0xC2, - 0xAF, 0x64, 0x82, 0x8C, 0x61, 0x7A, 0x7C, 0x30, 0x2C, 0x0E, 0x78, 0xAC, 0x13, 0xDB, 0x19, 0x63, - 0xC8, 0xA2, 0x0F, 0x3E, 0x51, 0x3E, 0x6B, 0xD1, 0x29, 0x1D, 0xE1, 0xA7, 0x64, 0x18, 0x80, 0x7B, - 0x07, 0xB6, 0x52, 0x1C, 0xF6, 0x61, 0x10, 0xA5, 0xC8, 0x0B, 0x1B, 0x10, 0xB0, 0x59, 0xB4, 0x43, - 0x38, 0x3D, 0xFB, 0x9E, 0xDC, 0xD9, 0x60, 0x32, 0x40, 0x0E, 0x43, 0x9E, 0xD8, 0x94, 0x27, 0x1C, - 0xC5, 0x6D, 0x1F, 0x16, 0x38, 0x39, 0xF6, 0x38, 0x37, 0x84, 0x7E, 0x07, 0x8F, 0x02, 0x37, 0xD2, - 0xA2, 0xAC, 0x73, 0x9D, 0x88, 0xA2, 0xB4, 0x4C, 0x81, 0xBF, 0xF8, 0x3E, 0x10, 0xAE, 0x34, 0xB9, - 0x8C, 0x72, 0x24, 0x23, 0x09, 0x40, 0xB4, 0xA2, 0x1C, 0xBC, 0x50, 0x9C, 0x5E, 0xD7, 0xEA, 0x96, - 0x84, 0x53, 0xB4, 0xA0, 0x71, 0x3D, 0x1E, 0xFA, 0x57, 0xFD, 0xA9, 0xED, 0x7F, 0x7D, 0x37, 0x73, - 0xBB, 0x8D, 0xCA, 0x38, 0xCE, 0x7F, 0xAE, 0xC6, 0x6F, 0xD4, 0xE1, 0x21, 0x0D, 0xC2, 0xFF, 0x83, - 0x3F, 0xAA, 0x37, 0x19, 0x51, 0x00, 0x59, 0x40, 0xA2, 0xC1, 0x8D, 0xD4, 0x91, 0x75, 0x29, 0xB2, - 0xEE, 0xBE, 0x7F, 0xBF, 0x97, 0x11, 0x5E, 0x02, 0x70, 0xDA, 0x76, 0x1F, 0xFA, 0x77, 0xB0, 0xE0, - 0x88, 0x1F, 0xE2, 0x49, 0x36, 0x3A, 0x57, 0x57, 0x27, 0x6C, 0xD1, 0x87, 0x35, 0x9C, 0x61, 0x40, - 0x82, 0xD0, 0xF6, 0x99, 0x0E, 0x30, 0xA5, 0xD2, 0x6E, 0x6A, 0xBE, 0xF8, 0x9D, 0x32, 0x0C, 0xE2, - 0xD2, 0x2E, 0x61, 0x25, 0x7F, 0xE3, 0xB1, 0xC9, 0xD3, 0xB7, 0x38, 0xC3, 0x7F, 0xDB, 0xD5, 0xB8, - 0xFF, 0x22, 0x2F, 0x7A, 0x4D, 0xBB, 0x59, 0x12, 0x89, 0xAC, 0x2D, 0x2C, 0x73, 0xC0, 0xBA, 0x04, - 0xC8, 0x77, 0x1A, 0x77, 0xD2, 0x51, 0x96, 0xFA, 0xDA, 0xD3, 0x1C, 0x6E, 0x2C, 0xE7, 0xE2, 0x2A, - 0xDF, 0x31, 0x2C, 0xB8, 0x7E, 0xB1, 0xD2, 0x62, 0x28, 0x9F, 0x95, 0xC4, 0xD8, 0x1A, 0x31, 0x4F, - 0x6A, 0x26, 0x9D, 0xC7, 0xC5, 0xA5, 0x41, 0xEB, 0xAB, 0xBD, 0x74, 0x23, 0xB1, 0x5F, 0x5A, 0x9A, - 0xFA, 0x8D, 0xD0, 0x42, 0x51, 0x4E, 0x6A, 0xC9, 0x71, 0x52, 0x49, 0x88, 0x6C, 0xA9, 0x5F, 0xA4, - 0x78, 0x73, 0xB6, 0x36, 0xB9, 0x1C, 0xF2, 0x3F, 0xAA, 0xC9, 0xE5, 0xC6, 0xCB, 0x53, 0xB5, 0xB8, - 0xEA, 0x58, 0x51, 0xDF, 0x52, 0xE5, 0x79, 0xDC, 0xA3, 0x6B, 0xB1, 0xC5, 0x23, 0x26, 0xE7, 0x25, - 0xD6, 0x39, 0x24, 0x9B, 0xBA, 0xCD, 0xFC, 0x7B, 0x49, 0x57, 0xF1, 0x71, 0x25, 0x58, 0x5C, 0xC7, - 0x80, 0xBB, 0x89, 0x4F, 0xB1, 0x99, 0x97, 0x31, 0x5D, 0xBE, 0x31, 0x85, 0xE5, 0xB9, 0xFB, 0x63, - 0x0B, 0x55, 0x48, 0xFD, 0x4E, 0xF7, 0xBF, 0xA4, 0xD4, 0xA2, 0x1D, 0xBD, 0x0C, 0xA5, 0x66, 0xEF, - 0x05, 0x48, 0xCB, 0xD2, 0x68, 0x45, 0x65, 0x08, 0x93, 0x2A, 0xB9, 0xA0, 0x12, 0x0B, 0x1C, 0xEF, - 0x3A, 0x40, 0xE1, 0xB2, 0x07, 0x31, 0xE8, 0xC0, 0x73, 0x87, 0xE8, 0xB2, 0x6F, 0x5A, 0xAC, 0x39, - 0x86, 0xC6, 0x6C, 0x5A, 0xE2, 0xAD, 0x3E, 0xB9, 0x21, 0x6F, 0x8D, 0xCF, 0xCB, 0xE4, 0x13, 0x3B, - 0xF7, 0x02, 0x07, 0xFF, 0xBF, 0x37, 0x18, 0xCC, 0x60, 0x19, 0x73, 0xCF, 0x17, 0x3A, 0x1B, 0x28, - 0xC8, 0x14, 0xD1, 0x6E, 0x87, 0x51, 0xDD, 0xE8, 0xE4, 0x50, 0x4D, 0xC8, 0x2A, 0x3E, 0x29, 0x8B, - 0xB1, 0x3A, 0x64, 0x99, 0xC3, 0xDA, 0x64, 0xA5, 0xDB, 0xDB, 0xB2, 0x7A, 0xD6, 0x66, 0x67, 0x63, - 0x73, 0x4B, 0x66, 0xD4, 0x0C, 0xF1, 0x09, 0x21, 0xD6, 0x5F, 0x76, 0x37, 0xB7, 0xAC, 0xF5, 0xCE, - 0xBA, 0xB5, 0x56, 0x0C, 0xF1, 0x2B, 0x40, 0xAC, 0x5B, 0x5B, 0x9B, 0x9B, 0x9B, 0x1B, 0x9D, 0xF5, - 0xAD, 0xF5, 0x7C, 0x80, 0x63, 0x3B, 0x64, 0x0F, 0x69, 0x20, 0x48, 0xC7, 0xDA, 0xB6, 0x7A, 0xDB, - 0xEB, 0x2F, 0xB7, 0x0B, 0x40, 0x3C, 0x77, 0x24, 0x60, 0x56, 0xBA, 0x16, 0xC8, 0x6A, 0x6B, 0xC3, - 0xDA, 0x78, 0xB9, 0xD9, 0xCD, 0x87, 0xDA, 0x1B, 0x87, 0x4E, 0x38, 0x1B, 0xB2, 0x2D, 0x92, 0x8D, - 0x4D, 0xA0, 0xB5, 0xB5, 0xAD, 0x2C, 0xBF, 0xB4, 0x03, 0x1B, 0x15, 0x43, 0x86, 0x7A, 0x64, 0x52, - 0xCC, 0xEF, 0x61, 0xE8, 0x41, 0xB9, 0xAB, 0x22, 0x25, 0xCE, 0x0F, 0xAE, 0xCB, 0xD1, 0xE7, 0x9A, - 0xA2, 0xAD, 0x2F, 0xDE, 0x4A, 0x22, 0x2E, 0xB0, 0x20, 0x9A, 0x6E, 0xBE, 0xB4, 0xD8, 0xBF, 0x36, - 0x89, 0x7F, 0x89, 0xC7, 0x41, 0x54, 0x86, 0x83, 0x40, 0xFC, 0x5A, 0x3C, 0xFC, 0x8A, 0x88, 0x7E, - 0xFA, 0x3D, 0x88, 0xFE, 0xFA, 0x18, 0x44, 0x1F, 0xF2, 0x22, 0x94, 0xAB, 0x9B, 0x83, 0x7A, 0x26, - 0xA1, 0x92, 0x59, 0x48, 0xCB, 0x2B, 0x09, 0x5A, 0x02, 0x63, 0xFF, 0x13, 0xF5, 0x31, 0x53, 0x3E, - 0x7C, 0x5B, 0x65, 0x37, 0x83, 0x92, 0x64, 0x11, 0xA5, 0x04, 0x2D, 0x69, 0xE3, 0x4A, 0xB7, 0x6B, - 0xAD, 0xAD, 0xB7, 0xC9, 0xD6, 0x96, 0xB2, 0x35, 0xCA, 0x3F, 0xA3, 0x90, 0xB1, 0xA0, 0x84, 0x51, - 0xCD, 0x20, 0xA7, 0xDF, 0x20, 0x40, 0x82, 0xF8, 0x54, 0xCF, 0x86, 0x42, 0x6B, 0x83, 0x3D, 0x7E, - 0xB3, 0x51, 0x5B, 0x7B, 0xCC, 0xD1, 0x87, 0x40, 0xAB, 0xC7, 0x67, 0xDC, 0x9E, 0x36, 0xF1, 0xF2, - 0xEF, 0xFC, 0x85, 0x1E, 0xAB, 0x53, 0x5A, 0x81, 0x1E, 0x32, 0xF7, 0x2A, 0xE3, 0x50, 0xDA, 0x3A, - 0x7B, 0x95, 0x1C, 0x38, 0xD9, 0x43, 0xBA, 0xB2, 0x4A, 0xEF, 0x55, 0xCB, 0xF0, 0x8C, 0x69, 0xAB, - 0xCC, 0x6E, 0xA5, 0x4C, 0x10, 0x37, 0x9D, 0x22, 0x82, 0xF9, 0xFB, 0x95, 0xE5, 0x69, 0x65, 0xB6, - 0x0E, 0xB7, 0x7B, 0x18, 0x31, 0x4B, 0x6B, 0x9D, 0x35, 0x67, 0xEB, 0x72, 0x29, 0x9E, 0xFF, 0xFC, - 0x54, 0x34, 0x93, 0xBD, 0xB4, 0x47, 0xE9, 0xC3, 0x5C, 0x8A, 0x4F, 0xD7, 0x4A, 0x49, 0x53, 0xBB, - 0xF5, 0x29, 0x76, 0x6B, 0x69, 0xAA, 0x20, 0xA8, 0x6B, 0xAA, 0x95, 0xAF, 0xA9, 0xDD, 0x7A, 0x9A, - 0xFA, 0x18, 0xAD, 0x2B, 0xD2, 0xD4, 0x27, 0xA2, 0x29, 0x69, 0xEA, 0x93, 0x53, 0x7C, 0xBA, 0x56, - 0x4A, 0x9A, 0xDA, 0xAB, 0x4F, 0xB1, 0x57, 0x4B, 0x53, 0x7B, 0xB5, 0x34, 0xB5, 0x57, 0x4F, 0x53, - 0x1F, 0xA3, 0x75, 0x45, 0x9A, 0xFA, 0x44, 0x34, 0x25, 0x4D, 0x7D, 0x72, 0x8A, 0x4F, 0xD7, 0x4A, - 0x49, 0x53, 0xD7, 0xEA, 0x53, 0x5C, 0xAB, 0xA5, 0xA9, 0x6B, 0xB5, 0x34, 0x75, 0xAD, 0x9E, 0xA6, - 0x3E, 0x46, 0xEB, 0x8A, 0x34, 0xF5, 0x89, 0x68, 0x4A, 0x9A, 0xFA, 0xE4, 0x14, 0x17, 0xD4, 0xCA, - 0xE7, 0x7E, 0xDC, 0x6A, 0x74, 0x95, 0x2B, 0x1D, 0xB8, 0x1A, 0x7D, 0xDF, 0x52, 0x47, 0xAE, 0x46, - 0x47, 0xB6, 0xEA, 0xE1, 0x67, 0x86, 0x6F, 0xDA, 0x28, 0x0B, 0xA9, 0x79, 0x98, 0xFC, 0xCC, 0x77, - 0x78, 0xE7, 0x86, 0x77, 0x6E, 0xAF, 0x3A, 0x8E, 0x88, 0xFA, 0xCF, 0x17, 0x1B, 0x77, 0x17, 0xDE, - 0xFA, 0x87, 0x6A, 0xFC, 0xC7, 0x1E, 0x60, 0xA3, 0x86, 0xD8, 0x99, 0x07, 0x50, 0x5D, 0xE6, 0x35, - 0xC8, 0x49, 0x8E, 0x55, 0x1D, 0x31, 0xD7, 0x84, 0xAB, 0x4A, 0x51, 0x73, 0x55, 0xEA, 0x88, 0xB4, - 0x57, 0x4F, 0xA4, 0xBD, 0xDA, 0x22, 0xED, 0xD5, 0x14, 0x69, 0xAF, 0xB6, 0x48, 0x7B, 0x35, 0x45, - 0xBA, 0x56, 0x53, 0xA4, 0x6B, 0xF5, 0x44, 0xBA, 0x56, 0x5B, 0xA4, 0x6B, 0x35, 0x45, 0xBA, 0x56, - 0x5B, 0xA4, 0x3A, 0x64, 0x7C, 0xA0, 0x70, 0x2E, 0xC5, 0x6E, 0xA6, 0xE2, 0xDD, 0xCE, 0xD3, 0x57, - 0x6D, 0x5B, 0x49, 0x88, 0x1C, 0xCA, 0xCE, 0x74, 0x16, 0x61, 0xBE, 0x54, 0x5B, 0xED, 0x38, 0x82, - 0xCA, 0xD0, 0x78, 0x05, 0xE5, 0x2D, 0x3F, 0x03, 0xE0, 0xD8, 0xD8, 0xA2, 0x7B, 0xD3, 0x4A, 0x6D, - 0x1B, 0x76, 0xF9, 0xA1, 0x44, 0x1B, 0xBF, 0x6A, 0x5B, 0x86, 0xE7, 0xE6, 0x97, 0xE6, 0x8B, 0x48, - 0x1F, 0xB3, 0x93, 0xA3, 0x05, 0x11, 0x8C, 0x85, 0x8E, 0x41, 0xAC, 0x45, 0x41, 0x8D, 0x18, 0xDA, - 0x7A, 0x0A, 0x8D, 0xF6, 0xFC, 0xAF, 0x57, 0x56, 0xBF, 0x7F, 0x74, 0x50, 0x7A, 0xE2, 0x37, 0x84, - 0xCA, 0x1A, 0x42, 0xFB, 0x8C, 0x74, 0xCE, 0xED, 0x20, 0x80, 0xDF, 0x86, 0x4F, 0x40, 0xAB, 0xFB, - 0x44, 0x6D, 0xEA, 0x3E, 0x61, 0x9B, 0x7A, 0x4F, 0xD4, 0xA6, 0xDE, 0x13, 0xB6, 0x69, 0xED, 0x89, - 0xDA, 0xB4, 0xB6, 0xA0, 0x36, 0x89, 0x21, 0x76, 0xB9, 0x7F, 0xBE, 0xFA, 0xF1, 0xE0, 0x3C, 0xDB, - 0x3E, 0x5D, 0x0E, 0x2A, 0xC7, 0x9E, 0x0A, 0x03, 0x11, 0x5F, 0x5F, 0x4E, 0x62, 0x40, 0x37, 0x37, - 0x36, 0xD6, 0x52, 0x51, 0xA7, 0xEC, 0xA3, 0xCC, 0xA8, 0x12, 0x83, 0x5E, 0xE0, 0xFF, 0xC7, 0x44, - 0xA4, 0xB8, 0xD6, 0xF2, 0x51, 0xCD, 0x26, 0x4A, 0x0F, 0x66, 0x21, 0x54, 0xDD, 0xD4, 0x4E, 0x84, - 0xC0, 0x21, 0x17, 0x21, 0x04, 0x13, 0x6B, 0x1F, 0x87, 0x75, 0x59, 0x9B, 0x0D, 0x17, 0xCE, 0xDA, - 0xEA, 0xEA, 0x99, 0x4B, 0xA2, 0x10, 0xFA, 0x36, 0x81, 0x8A, 0x84, 0xF7, 0x0E, 0x3B, 0xD1, 0xE7, - 0xD4, 0x30, 0xA7, 0x27, 0x5B, 0x06, 0x01, 0x7E, 0xDE, 0x84, 0x21, 0xB1, 0x79, 0x26, 0xDD, 0x00, - 0x23, 0x0B, 0x42, 0x98, 0xC5, 0xA2, 0x53, 0xFC, 0x19, 0x20, 0xF1, 0x5C, 0x82, 0x9A, 0xDB, 0xC6, - 0x1A, 0xF7, 0x0C, 0xF8, 0x9A, 0x76, 0x3A, 0xD1, 0x4A, 0x89, 0x07, 0x7F, 0x8B, 0xFC, 0x53, 0x27, - 0xB3, 0x90, 0x7E, 0x4F, 0x2B, 0x2E, 0x06, 0xF1, 0x6B, 0xDD, 0x08, 0x9F, 0x6A, 0x33, 0x97, 0x27, - 0x8A, 0xE8, 0x06, 0x35, 0xBB, 0x55, 0x9D, 0x39, 0xA6, 0x44, 0x72, 0x89, 0x6A, 0xDD, 0x35, 0x06, - 0xA0, 0xF8, 0xC0, 0xD7, 0xF1, 0xDC, 0x77, 0x3E, 0xFD, 0xFB, 0x8C, 0xBA, 0xEC, 0xA0, 0x78, 0xDB, - 0x5A, 0x83, 0x1F, 0xBD, 0x97, 0x52, 0xD7, 0xC1, 0x27, 0xB6, 0x65, 0xD1, 0x7B, 0x29, 0xF3, 0x2B, - 0x5F, 0xD1, 0xC8, 0x9F, 0xDE, 0x91, 0x1C, 0xC8, 0xC4, 0xB1, 0xC7, 0x2C, 0x9E, 0xC4, 0x66, 0x37, - 0x16, 0xC4, 0x25, 0xD7, 0x2B, 0x1C, 0x44, 0xDD, 0x54, 0xD0, 0x43, 0xD7, 0x14, 0xEC, 0x60, 0xA0, - 0x98, 0x84, 0x1E, 0x49, 0xF9, 0x30, 0xF3, 0xEF, 0x10, 0xA4, 0xEE, 0xFB, 0x06, 0xC7, 0xCE, 0x0D, - 0x15, 0xBD, 0x81, 0x47, 0x68, 0x3D, 0x99, 0x11, 0x7E, 0x82, 0xD6, 0x53, 0xF8, 0xC8, 0xBE, 0x62, - 0xB2, 0x24, 0xE5, 0x00, 0x08, 0xA0, 0x23, 0x58, 0xE2, 0x9F, 0x7C, 0x76, 0x16, 0x78, 0x90, 0xF7, - 0x94, 0x07, 0x78, 0xA2, 0x99, 0xFC, 0x7E, 0x4C, 0x9E, 0x7A, 0x46, 0x69, 0x3D, 0xAA, 0x69, 0xE8, - 0xC4, 0xFE, 0x0E, 0xA0, 0x97, 0x4E, 0x74, 0xBD, 0xA4, 0x6B, 0x6D, 0x40, 0x27, 0xA4, 0xFC, 0xC0, - 0x6E, 0x1B, 0xBE, 0xB7, 0x7B, 0xAA, 0x9A, 0x28, 0x77, 0x76, 0xF2, 0x35, 0x93, 0x93, 0x91, 0x3D, - 0xCE, 0x79, 0x09, 0x95, 0x08, 0xEC, 0x50, 0xDA, 0xB6, 0x69, 0x91, 0x3F, 0x93, 0x5E, 0x76, 0xC0, - 0x8A, 0xC6, 0xA1, 0x5A, 0xDD, 0x78, 0x6E, 0xAA, 0x24, 0x53, 0xA9, 0x26, 0xF5, 0x04, 0x34, 0x0A, - 0xFC, 0x8A, 0xDD, 0xF0, 0xB4, 0x07, 0xBE, 0x08, 0x51, 0x98, 0x09, 0x5A, 0xB9, 0xCD, 0x33, 0xA5, - 0x78, 0xA9, 0xD6, 0x4C, 0x5B, 0x42, 0xC1, 0xEC, 0x7D, 0x94, 0xBB, 0x30, 0x39, 0xAC, 0x35, 0x9F, - 0xD6, 0x6E, 0x2F, 0xA0, 0xC9, 0x39, 0xC4, 0x0B, 0xDB, 0x9D, 0x4A, 0xA0, 0x59, 0xAA, 0xB9, 0x6A, - 0xBE, 0x4E, 0xEE, 0xEA, 0xF5, 0xB6, 0xD7, 0xB7, 0x37, 0x5F, 0xA6, 0xFC, 0xBD, 0x36, 0x7C, 0x6F, - 0x43, 0xC1, 0x02, 0xDA, 0x99, 0xA2, 0xCA, 0xE2, 0x2B, 0xF0, 0x51, 0x26, 0xB1, 0x93, 0x69, 0x6A, - 0x6A, 0xF5, 0xDC, 0x90, 0xA5, 0x24, 0x50, 0x90, 0xB2, 0x92, 0xDF, 0x06, 0xB6, 0xD6, 0xB7, 0x14, - 0x35, 0x17, 0x33, 0xD0, 0x7A, 0x7B, 0x6B, 0x21, 0xAA, 0x5E, 0xCC, 0x43, 0x9E, 0x80, 0x56, 0x57, - 0x23, 0x57, 0x28, 0x96, 0x57, 0xE6, 0xAD, 0x09, 0xB3, 0x28, 0x8E, 0xCE, 0xF7, 0xF8, 0xBD, 0xA0, - 0x56, 0x7C, 0x0D, 0xF1, 0xE8, 0xBC, 0x21, 0xB5, 0xD7, 0x75, 0xDD, 0x8E, 0xF4, 0x9F, 0xDC, 0x64, - 0xED, 0x26, 0x63, 0x86, 0x4D, 0x35, 0x50, 0x38, 0x38, 0xED, 0x3F, 0x36, 0x89, 0xF7, 0x60, 0x01, - 0xEE, 0xEC, 0xFB, 0xC7, 0x26, 0xD3, 0x9F, 0x5D, 0xC3, 0xCF, 0x85, 0x52, 0x89, 0x36, 0x3F, 0x44, - 0xE5, 0xD3, 0x70, 0x2A, 0xBC, 0x67, 0x2B, 0xED, 0x3D, 0x5B, 0x46, 0xEF, 0xD9, 0x4C, 0x27, 0x56, - 0x99, 0xD3, 0xCB, 0xF3, 0xBA, 0xDA, 0x12, 0x9F, 0x6B, 0x01, 0x4F, 0xE3, 0xF1, 0xE1, 0xF7, 0xA9, - 0xE7, 0x72, 0xF7, 0x17, 0x9C, 0xC3, 0xAE, 0x6C, 0x37, 0x98, 0x67, 0xD8, 0x55, 0x0C, 0x46, 0x72, - 0x6F, 0xB5, 0xE8, 0xD0, 0x6C, 0x0A, 0xDC, 0x0C, 0x1C, 0x96, 0xEA, 0x1B, 0x5C, 0x12, 0xBC, 0x6A, - 0xA7, 0xF8, 0x22, 0x6B, 0xAC, 0xD5, 0x56, 0x4D, 0xDC, 0x17, 0x60, 0x7E, 0x0E, 0xE8, 0x98, 0xA9, - 0x86, 0xD5, 0x66, 0x29, 0x55, 0xB5, 0xAD, 0x24, 0x86, 0xBE, 0x6B, 0xDC, 0x4A, 0xAA, 0x4A, 0xC7, - 0x09, 0xA6, 0x22, 0x67, 0xF9, 0x63, 0x10, 0x4B, 0x4E, 0xA8, 0xA6, 0x17, 0xF4, 0x86, 0xFA, 0xE0, - 0xAA, 0xD3, 0xA3, 0xA1, 0x58, 0xA2, 0xA6, 0x56, 0xA8, 0x6C, 0x81, 0x1A, 0xE4, 0x12, 0x78, 0x88, - 0x72, 0x5C, 0x64, 0xBC, 0x64, 0xAD, 0x65, 0xBB, 0xC0, 0x3C, 0x64, 0xA2, 0x8A, 0x94, 0x00, 0x4B, - 0xCD, 0x03, 0x20, 0xDD, 0x37, 0x95, 0xAF, 0x16, 0xEF, 0x92, 0xAE, 0x92, 0xB5, 0x27, 0xCE, 0x5A, - 0xD3, 0xC4, 0x87, 0x10, 0xDE, 0x86, 0x6E, 0x13, 0xF8, 0x3C, 0x07, 0x4B, 0x09, 0xA6, 0x93, 0x19, - 0x4C, 0x96, 0xC7, 0x43, 0xC2, 0xB0, 0x0C, 0x1F, 0xD8, 0x9F, 0x0D, 0xDD, 0x47, 0x8A, 0xB2, 0xC0, - 0xC4, 0x98, 0xA4, 0x0A, 0x8F, 0xFA, 0xF2, 0xF6, 0x83, 0x7A, 0x89, 0x41, 0x62, 0xF6, 0xCD, 0xC2, - 0x5A, 0x1B, 0x3C, 0xCB, 0xE6, 0xFE, 0x43, 0x4D, 0x0B, 0x59, 0x22, 0x71, 0xEB, 0xB1, 0x67, 0x63, - 0x7E, 0xA4, 0x0E, 0x11, 0xAD, 0xBE, 0xB3, 0x9D, 0x10, 0x96, 0xDC, 0x4D, 0x39, 0x6C, 0xDC, 0xAC, - 0x83, 0xE6, 0x7B, 0x0A, 0xD1, 0x25, 0x85, 0x74, 0x43, 0x5F, 0x45, 0xCC, 0x8B, 0xF4, 0xB7, 0x12, - 0x85, 0x24, 0x7B, 0x9B, 0xEE, 0x66, 0xAB, 0x9D, 0x23, 0x15, 0xCB, 0xA9, 0x8B, 0xE4, 0xCE, 0xEB, - 0xDB, 0xDF, 0xB0, 0x39, 0x9D, 0x8E, 0x12, 0xA4, 0xA9, 0xE5, 0x79, 0x6A, 0x24, 0x19, 0x6A, 0xDB, - 0x79, 0x82, 0x6F, 0x2B, 0x48, 0x46, 0x34, 0x2B, 0x33, 0x46, 0x2A, 0x47, 0x87, 0x9C, 0x2C, 0x64, - 0x9E, 0x1C, 0x19, 0xF3, 0xE7, 0xC9, 0x98, 0x27, 0x57, 0xC6, 0x62, 0xF2, 0x65, 0xCC, 0x9F, 0x33, - 0x63, 0xBE, 0xBC, 0x19, 0xF3, 0xE4, 0xCE, 0x98, 0x37, 0x7F, 0xC6, 0x7C, 0x39, 0x34, 0x16, 0x9F, - 0x47, 0x23, 0x17, 0x63, 0xB2, 0x25, 0x92, 0x20, 0x72, 0x92, 0x6F, 0xA5, 0xF1, 0x14, 0xE4, 0xE4, - 0x28, 0x46, 0x50, 0x32, 0x31, 0x47, 0xFD, 0xE4, 0x1C, 0xF3, 0x26, 0xE8, 0x48, 0x67, 0xC5, 0x44, - 0x0B, 0xC4, 0xE9, 0xFD, 0x13, 0x4C, 0xC0, 0xCF, 0x6B, 0x7E, 0xCC, 0x59, 0x9B, 0x65, 0x5B, 0x7F, - 0xC3, 0x84, 0x51, 0x6A, 0x46, 0x10, 0xFE, 0x77, 0x2A, 0x49, 0x95, 0x9E, 0x53, 0x44, 0xCA, 0x30, - 0xD7, 0xE2, 0x76, 0x5F, 0x2A, 0xBF, 0x7A, 0x7F, 0xDE, 0x57, 0xD7, 0xB8, 0x3C, 0x2D, 0x5D, 0xCC, - 0xCA, 0x9F, 0xFE, 0x44, 0x4C, 0x50, 0xA0, 0x10, 0x63, 0x96, 0xC1, 0xBA, 0x2A, 0xE4, 0x5B, 0xEA, - 0x1C, 0x78, 0xB3, 0x3A, 0x24, 0x8F, 0xCF, 0x4E, 0xF7, 0xFA, 0x46, 0x66, 0x97, 0x34, 0x67, 0xC1, - 0x94, 0x8A, 0xA2, 0x68, 0x5A, 0x93, 0xF4, 0x83, 0x4D, 0x5D, 0x8A, 0x10, 0x65, 0x55, 0xB9, 0xF5, - 0x30, 0x0E, 0x0A, 0xD6, 0x28, 0x44, 0xE1, 0x4F, 0xD6, 0x91, 0x44, 0x89, 0x96, 0x97, 0x75, 0xC5, - 0x30, 0xA9, 0x45, 0x23, 0x4D, 0xD1, 0x98, 0x7E, 0xCC, 0x78, 0x60, 0x2F, 0x75, 0x6F, 0x76, 0xFE, - 0x6C, 0x9E, 0x56, 0x55, 0x7B, 0x58, 0x24, 0xCA, 0xDC, 0xAF, 0x83, 0x1D, 0x50, 0x84, 0x12, 0x6E, - 0xC1, 0xA5, 0xF7, 0x95, 0xBA, 0x8D, 0xD8, 0xCF, 0xD1, 0xDE, 0x2A, 0x99, 0xD1, 0xF8, 0xAD, 0x74, - 0xC0, 0x9D, 0x79, 0xC5, 0x23, 0x4E, 0xE5, 0x93, 0x4F, 0x05, 0x96, 0x7C, 0x9B, 0xFC, 0xBF, 0x64, - 0xCD, 0xB7, 0x99, 0x95, 0xD9, 0xE7, 0xDC, 0x70, 0x81, 0x05, 0xB9, 0x72, 0xF9, 0x89, 0x23, 0x13, - 0x3F, 0x48, 0x07, 0x94, 0x24, 0xF5, 0x9A, 0x8A, 0xD4, 0xD7, 0x06, 0x71, 0x61, 0x67, 0x5F, 0xDE, - 0x3A, 0x01, 0x51, 0x82, 0x27, 0x02, 0x5E, 0x48, 0xF0, 0xF8, 0xC2, 0xF1, 0xF1, 0xE9, 0x84, 0x90, - 0xA0, 0x46, 0x84, 0x4C, 0x15, 0xD8, 0x91, 0xBF, 0xA0, 0xDC, 0x48, 0x67, 0x35, 0x34, 0x70, 0x5D, - 0xA4, 0x8F, 0x3A, 0xA4, 0x7C, 0x0C, 0x5A, 0x06, 0x36, 0xAD, 0x83, 0x25, 0x2F, 0x51, 0x71, 0x8D, - 0x34, 0xAA, 0x51, 0xEA, 0x91, 0x90, 0x12, 0x7B, 0x51, 0x85, 0x5D, 0xDE, 0x68, 0xE8, 0x69, 0xC8, - 0x67, 0xA1, 0xF7, 0x57, 0x7A, 0x7F, 0x41, 0x5D, 0x7A, 0x67, 0x8F, 0x73, 0x5E, 0xA2, 0x29, 0xC9, - 0xEF, 0x43, 0x7A, 0x20, 0xBD, 0x75, 0xC2, 0x13, 0x7B, 0x9A, 0x64, 0xE8, 0x9B, 0x38, 0x2E, 0xFC, - 0xB0, 0xBF, 0xB7, 0xC9, 0x35, 0x2B, 0x91, 0x92, 0x9C, 0xB6, 0xE3, 0xD9, 0xF5, 0xE8, 0x40, 0x9A, - 0x0E, 0xA3, 0x81, 0x13, 0xBF, 0x80, 0xC1, 0x69, 0x4D, 0xEC, 0xE0, 0x2B, 0x2F, 0xE0, 0x88, 0x94, - 0x42, 0x66, 0x81, 0x39, 0xEC, 0x6B, 0x24, 0xC9, 0x53, 0x8A, 0x44, 0x43, 0x13, 0xC8, 0xF3, 0x0F, - 0x2D, 0x86, 0x04, 0x6C, 0x60, 0x97, 0xBC, 0x7E, 0xCD, 0x69, 0x2D, 0x09, 0x3D, 0xD6, 0x0C, 0x5D, - 0x4E, 0x76, 0x54, 0x73, 0xC6, 0x55, 0x09, 0x56, 0x6A, 0x55, 0x91, 0x3A, 0xE5, 0x99, 0x33, 0xF3, - 0x3C, 0x17, 0x3F, 0xDC, 0xF1, 0x20, 0x52, 0x5F, 0xB3, 0xCB, 0xFA, 0xD0, 0x7E, 0xC3, 0x65, 0x37, - 0x18, 0x49, 0x3E, 0x86, 0xA4, 0x0E, 0x9C, 0x29, 0x38, 0x46, 0x6C, 0x33, 0x52, 0xED, 0xAC, 0xF8, - 0xD2, 0x9C, 0x94, 0x0E, 0xDB, 0x41, 0x6D, 0x50, 0xAF, 0x81, 0xEE, 0x24, 0xF9, 0xAF, 0xE3, 0xA6, - 0x91, 0x5D, 0xE3, 0x99, 0x52, 0xF2, 0xC0, 0xC7, 0x90, 0x86, 0xA0, 0x30, 0x74, 0xF8, 0xCE, 0xF3, - 0x27, 0x02, 0x4F, 0xF2, 0xA2, 0x49, 0x9C, 0x66, 0xFB, 0x5B, 0xF4, 0x6A, 0x0A, 0xDE, 0x57, 0xE5, - 0x0F, 0x83, 0x39, 0x43, 0xD0, 0x6E, 0xE7, 0xE6, 0x3E, 0x7E, 0x7E, 0xAC, 0x25, 0x2B, 0xC3, 0x52, - 0xDC, 0xDF, 0x2A, 0xD8, 0x2E, 0x51, 0xEF, 0xBE, 0x06, 0x9D, 0xFD, 0xB3, 0xB3, 0x8B, 0x83, 0xA3, - 0xD3, 0xBD, 0xCB, 0xC3, 0xAB, 0xA3, 0xD3, 0xF3, 0x8F, 0x97, 0x57, 0x97, 0x9F, 0xCE, 0xF1, 0xD7, - 0x9F, 0xF6, 0x8E, 0x8F, 0x0E, 0xAE, 0x3E, 0x9E, 0xFE, 0xF5, 0xF4, 0xEC, 0xE7, 0x53, 0x3D, 0x31, - 0x41, 0xDC, 0xA3, 0xC8, 0x64, 0x82, 0x11, 0x6F, 0xC9, 0x43, 0x2B, 0xC8, 0xCC, 0xFD, 0xEA, 0x62, - 0x02, 0xEF, 0x9D, 0xE7, 0xA6, 0x2B, 0x6C, 0x00, 0x0C, 0xF8, 0xBB, 0x47, 0x74, 0x28, 0x31, 0xFE, - 0x9A, 0xAC, 0x74, 0xB7, 0x2C, 0xAE, 0xFE, 0xA6, 0x72, 0xF0, 0xE5, 0xB6, 0xAC, 0xA5, 0x5C, 0x31, - 0x24, 0xE7, 0x97, 0x5B, 0x7C, 0xFB, 0x6B, 0xCB, 0x7A, 0x76, 0x02, 0xC8, 0x1C, 0x2A, 0x5C, 0x5D, - 0x24, 0x9D, 0x8E, 0xEE, 0x28, 0xEF, 0x18, 0xF4, 0x8F, 0xBF, 0x22, 0x57, 0x5D, 0x01, 0x19, 0xDC, - 0x0F, 0x0D, 0xFC, 0xA1, 0x81, 0xD9, 0x1A, 0x98, 0xD2, 0x97, 0x3F, 0xEC, 0x2A, 0x86, 0x2F, 0xB7, - 0xFD, 0xDC, 0x86, 0x06, 0x3C, 0x51, 0x1C, 0xCB, 0x01, 0xF5, 0x4C, 0x9A, 0x9F, 0x6B, 0xEC, 0x65, - 0x3E, 0xA6, 0xE0, 0xA5, 0x86, 0x38, 0x03, 0x25, 0x83, 0xAA, 0xDE, 0x68, 0xC9, 0x14, 0x7B, 0x5D, - 0x36, 0x94, 0x4E, 0x10, 0xEF, 0x49, 0xE0, 0x84, 0x36, 0xC4, 0x38, 0x23, 0x0C, 0xF3, 0x31, 0x3C, - 0x88, 0xD9, 0x8E, 0x46, 0x23, 0x96, 0xC3, 0xB2, 0x62, 0x75, 0x8C, 0x3D, 0x1A, 0x62, 0x6F, 0xF1, - 0x84, 0x52, 0xF1, 0x34, 0xAB, 0xBD, 0xA8, 0x91, 0xE4, 0x10, 0x56, 0x67, 0xD8, 0x64, 0x66, 0x14, - 0x23, 0x84, 0x91, 0x6A, 0x45, 0x75, 0xDA, 0x26, 0x26, 0x92, 0x0C, 0xC0, 0x9A, 0x65, 0xCB, 0x45, - 0x06, 0x95, 0xF2, 0xB0, 0xA5, 0xEF, 0xD2, 0xF3, 0xD3, 0xF9, 0x40, 0xDC, 0x6E, 0xE1, 0xF2, 0x15, - 0xCD, 0x4F, 0x7B, 0x7F, 0xA9, 0x04, 0xCD, 0x89, 0xFB, 0x57, 0xD3, 0xED, 0x2B, 0xE9, 0xD9, 0x09, - 0x04, 0xE8, 0x59, 0xFC, 0x4E, 0xAE, 0x1C, 0x7F, 0xD6, 0x38, 0x71, 0x8F, 0x76, 0x33, 0xB3, 0xFB, - 0x18, 0x5E, 0x12, 0xAC, 0xB3, 0xAC, 0x7E, 0xA8, 0x4C, 0x9A, 0xA7, 0xC8, 0xC9, 0x21, 0x2F, 0x07, - 0x07, 0x95, 0x27, 0x5F, 0xCB, 0x2A, 0x66, 0xA9, 0x8E, 0x58, 0xCF, 0x2E, 0x58, 0x77, 0x92, 0x97, - 0xA5, 0x55, 0x15, 0x4A, 0x96, 0xD8, 0xA8, 0x49, 0x8B, 0x52, 0x1C, 0x43, 0x7F, 0x98, 0x6E, 0x94, - 0x2F, 0xA8, 0x23, 0x94, 0x7C, 0x90, 0x32, 0x89, 0x39, 0x40, 0xAD, 0x4A, 0xFD, 0x1F, 0x4D, 0xFF, - 0x45, 0x6D, 0xEE, 0x3E, 0xEB, 0x36, 0x77, 0x1F, 0xA5, 0xCD, 0xBD, 0x67, 0xDD, 0xE6, 0xDE, 0xA3, - 0xB4, 0x79, 0xED, 0x59, 0xB7, 0x79, 0xAD, 0x6A, 0x9B, 0x75, 0x94, 0x8F, 0xED, 0x30, 0x66, 0x99, - 0xC6, 0x24, 0x9E, 0x45, 0x79, 0x2B, 0xA6, 0x9A, 0x4D, 0x44, 0xDF, 0x12, 0x1F, 0xC5, 0xE2, 0xCF, - 0x8A, 0x82, 0x05, 0x0C, 0xA6, 0x63, 0x27, 0x6C, 0x35, 0x3B, 0x11, 0xDB, 0xCC, 0x68, 0x62, 0x8D, - 0xC8, 0x36, 0x82, 0xA3, 0xBA, 0x9E, 0xEC, 0x3F, 0xB2, 0x6D, 0x14, 0x2C, 0xFE, 0x6C, 0x7D, 0x11, - 0xF3, 0x2D, 0xFB, 0xE6, 0x04, 0xA7, 0xF6, 0x69, 0x8B, 0x1F, 0x8A, 0x46, 0xE5, 0x4B, 0x4B, 0xBC, - 0x2C, 0xAA, 0xFE, 0x9A, 0x58, 0xEA, 0x87, 0x37, 0xF8, 0x56, 0xC5, 0x92, 0x09, 0x79, 0xB7, 0x00, - 0x79, 0x57, 0x45, 0xDE, 0xD5, 0x91, 0x77, 0xF3, 0x90, 0xF7, 0x0A, 0x90, 0xF7, 0x54, 0xE4, 0x3D, - 0x1D, 0x79, 0x2F, 0x0F, 0xF9, 0x5A, 0x01, 0xF2, 0x35, 0x15, 0xF9, 0x9A, 0x8E, 0x7C, 0x2D, 0x46, - 0xFE, 0xFC, 0xB6, 0xA4, 0x2A, 0xAB, 0xAC, 0x94, 0x2A, 0xFB, 0xD6, 0x0B, 0x40, 0x55, 0x67, 0xF0, - 0x2B, 0xFC, 0xF4, 0xC7, 0x05, 0x0A, 0x2C, 0xF6, 0xDC, 0x11, 0x48, 0xA8, 0x6F, 0x27, 0xF4, 0x8E, - 0xBD, 0x3B, 0x76, 0x1F, 0x90, 0xB6, 0x96, 0x92, 0xB7, 0x9A, 0x01, 0xD7, 0x52, 0xC6, 0xD6, 0x3B, - 0x12, 0x33, 0x6E, 0xAF, 0xEB, 0x4E, 0x41, 0xD7, 0xE8, 0x12, 0xAC, 0x6F, 0x9B, 0x5E, 0x7D, 0x46, - 0xA4, 0x35, 0x3B, 0xA2, 0x7A, 0x67, 0x94, 0xDD, 0x6E, 0xCE, 0xDA, 0x6C, 0x66, 0x12, 0x28, 0xD3, - 0x8B, 0xA2, 0x62, 0xFA, 0xC4, 0x4B, 0xB9, 0x48, 0xE1, 0x0C, 0xBB, 0x6D, 0xE2, 0x0C, 0x7B, 0x25, - 0x3A, 0x8F, 0xEF, 0x99, 0x74, 0x0D, 0x31, 0x9E, 0xE2, 0x0C, 0x0A, 0xD0, 0xA4, 0x0B, 0x53, 0x2A, - 0xDF, 0xAD, 0xAF, 0xF3, 0x40, 0xE0, 0xD9, 0xEE, 0xE1, 0x76, 0xCD, 0x21, 0x2C, 0x28, 0x13, 0xE3, - 0xCE, 0xBA, 0xBC, 0xEF, 0x8F, 0xC6, 0x9F, 0xEF, 0x44, 0xA9, 0xEF, 0x1F, 0x49, 0xAF, 0x45, 0x47, - 0xFA, 0x9E, 0x37, 0x4C, 0xD9, 0x03, 0xCC, 0x97, 0xDE, 0x3B, 0x1B, 0xE3, 0x71, 0xEE, 0x0F, 0x44, - 0xDE, 0x02, 0x75, 0x89, 0xAA, 0x96, 0xA5, 0x9F, 0x69, 0x6E, 0x44, 0x45, 0x64, 0x6F, 0x0A, 0xD3, - 0x08, 0x1D, 0x2A, 0x01, 0x42, 0x2C, 0xB5, 0xE8, 0x90, 0x8A, 0xB3, 0x1D, 0xA0, 0x86, 0xA7, 0xAB, - 0xC6, 0x17, 0xD5, 0x34, 0x4A, 0x2C, 0x40, 0xBA, 0xDD, 0x6D, 0x37, 0xCC, 0x2C, 0x1B, 0x62, 0x1A, - 0x52, 0xEC, 0x97, 0x7A, 0x99, 0x2E, 0x79, 0x22, 0x2E, 0x2B, 0xD1, 0x69, 0xC1, 0xAB, 0x72, 0xBB, - 0xE4, 0xBB, 0x12, 0xAC, 0x59, 0xF0, 0x4C, 0xA6, 0xDC, 0x96, 0xDF, 0xA8, 0xEF, 0x45, 0xE9, 0xAE, - 0xA5, 0xE7, 0x77, 0xA4, 0x04, 0xDF, 0x6C, 0x1B, 0xBF, 0x30, 0xFF, 0x3A, 0x69, 0xE1, 0xE5, 0x24, - 0x43, 0xA2, 0xEE, 0xA5, 0x17, 0x8F, 0x90, 0x26, 0xBD, 0x66, 0xC2, 0xEF, 0x4A, 0xC9, 0xBE, 0x47, - 0x6A, 0x9A, 0xE2, 0x58, 0xAF, 0x2D, 0xF5, 0x5E, 0x19, 0x97, 0x94, 0x9E, 0x53, 0xFB, 0xC5, 0xC2, - 0x93, 0x73, 0xD7, 0xC9, 0x8F, 0x5B, 0x3E, 0x37, 0x6E, 0x66, 0x63, 0x3B, 0x56, 0x51, 0x7B, 0x93, - 0xAC, 0xDA, 0xFC, 0x7C, 0x6C, 0xA1, 0xF9, 0xB9, 0x9F, 0x57, 0xAB, 0xF9, 0x5B, 0x54, 0xD8, 0x0C, - 0xC3, 0x80, 0x10, 0x98, 0xFA, 0xA1, 0x4F, 0xED, 0x49, 0xA2, 0x04, 0xE5, 0xE4, 0xC1, 0xB1, 0xCA, - 0x02, 0x91, 0xF0, 0xFC, 0xDE, 0xD2, 0xC8, 0x51, 0x80, 0x54, 0x26, 0xEC, 0xB9, 0x94, 0x20, 0x8D, - 0xED, 0x77, 0x6E, 0x7A, 0xB7, 0x93, 0xD7, 0xF8, 0x43, 0x7E, 0x0F, 0x73, 0x31, 0x6D, 0x4F, 0x21, - 0xFB, 0x9D, 0x9A, 0x9E, 0x1C, 0xC5, 0xB3, 0xC8, 0x1B, 0x93, 0x1B, 0x80, 0x73, 0x06, 0xDA, 0xF6, - 0xFC, 0x79, 0xA3, 0xCC, 0xC3, 0x10, 0xA6, 0x59, 0x63, 0x91, 0x33, 0x86, 0x9A, 0xFA, 0xFE, 0x39, - 0xCF, 0x1A, 0x71, 0xA2, 0xFE, 0x45, 0xCC, 0x1C, 0xE9, 0xAC, 0xFF, 0xCF, 0x72, 0xF6, 0xD0, 0xF3, - 0xC1, 0x2F, 0xCC, 0x76, 0x3C, 0x87, 0xB6, 0x97, 0x36, 0x1D, 0x73, 0xB7, 0x5C, 0xC7, 0xF5, 0x7C, - 0x0D, 0x87, 0x70, 0x9C, 0x79, 0x8E, 0x7B, 0xB0, 0x0B, 0x29, 0x77, 0x59, 0xF5, 0x46, 0x77, 0x7E, - 0xAF, 0x47, 0x7D, 0x70, 0xD1, 0xA1, 0x19, 0x25, 0x36, 0x11, 0xF3, 0x77, 0x8D, 0xE2, 0x1E, 0xDE, - 0x29, 0x06, 0xE8, 0x57, 0x06, 0xB8, 0xAC, 0x0A, 0xF0, 0x93, 0x04, 0xB0, 0x5E, 0x0C, 0x70, 0x71, - 0xB2, 0x9F, 0xA6, 0xF0, 0x50, 0xE3, 0xE9, 0x99, 0x11, 0x7B, 0x41, 0x4F, 0xF5, 0x56, 0xDF, 0x9F, - 0xAB, 0x22, 0xB2, 0x3A, 0x1B, 0x3B, 0x45, 0x00, 0xFD, 0xCA, 0x00, 0x97, 0x55, 0x01, 0x64, 0x11, - 0xC5, 0xE3, 0x32, 0x1B, 0x40, 0x15, 0x51, 0x4C, 0xE1, 0x61, 0x9E, 0xD7, 0x46, 0xD8, 0x7D, 0x54, - 0xE6, 0xD2, 0x45, 0x86, 0x8A, 0x11, 0xB3, 0x24, 0x42, 0x9B, 0x78, 0xCC, 0x39, 0x09, 0xE8, 0x60, - 0xC3, 0xB2, 0x8A, 0xE0, 0xBA, 0x12, 0xDC, 0x4B, 0x84, 0x03, 0xB0, 0xAE, 0xA9, 0x59, 0x92, 0x1B, - 0x99, 0xAB, 0xBD, 0x86, 0xEA, 0xFD, 0x8A, 0xD5, 0x2F, 0xAB, 0x55, 0x97, 0x3B, 0xA5, 0x57, 0x54, - 0x3D, 0xA5, 0xB5, 0xA6, 0xFA, 0x69, 0xF7, 0x11, 0x7F, 0xEB, 0x5A, 0x6B, 0x6B, 0x32, 0xAC, 0x95, - 0x18, 0xE6, 0x87, 0x94, 0x69, 0x12, 0xF7, 0xC7, 0x7F, 0x18, 0xA6, 0x67, 0x60, 0x98, 0xF2, 0x20, - 0x2E, 0x7E, 0x39, 0xB9, 0xBA, 0xD8, 0xFB, 0xF9, 0x97, 0xD2, 0x3C, 0x21, 0x40, 0xFF, 0xDD, 0xC5, - 0xDB, 0x5F, 0x7E, 0x18, 0xBF, 0xCA, 0xC6, 0x2F, 0x0B, 0x42, 0x1F, 0x67, 0xDD, 0xED, 0x92, 0xA4, - 0x74, 0xC0, 0x9E, 0x55, 0x13, 0x70, 0xBD, 0x57, 0x17, 0x70, 0xB3, 0x91, 0xE9, 0xAA, 0xFD, 0xB0, - 0xF0, 0xFF, 0x0A, 0x16, 0xDE, 0x04, 0x9E, 0x5A, 0x63, 0x4B, 0x7A, 0x9B, 0x15, 0x82, 0x5E, 0x0C, - 0xCE, 0xB4, 0xB7, 0x3E, 0x38, 0xD3, 0xE1, 0x39, 0xC0, 0x37, 0x33, 0xC0, 0x8D, 0xAE, 0x37, 0xC2, - 0x18, 0x27, 0x37, 0x75, 0x3D, 0xFF, 0x8C, 0x26, 0x38, 0xB6, 0xA4, 0x41, 0xB6, 0xAF, 0xBA, 0x96, - 0xB5, 0x51, 0xD6, 0xDE, 0xCB, 0x50, 0x2F, 0xD7, 0x6B, 0x41, 0xBD, 0x6C, 0xA4, 0x56, 0xEF, 0xC5, - 0x50, 0x5B, 0xB5, 0x68, 0x6D, 0x69, 0xB4, 0x4A, 0x82, 0x6D, 0xD7, 0x22, 0xB6, 0x5D, 0xA7, 0x61, - 0xDD, 0x5E, 0x1D, 0x5A, 0xDD, 0x5E, 0x1D, 0x5A, 0xBD, 0x35, 0x65, 0x3A, 0x28, 0x2B, 0x8F, 0x75, - 0xEB, 0x65, 0x4F, 0xB1, 0xB6, 0x25, 0xE9, 0x31, 0xB8, 0x6E, 0x23, 0x63, 0xAB, 0x66, 0x2E, 0xB7, - 0x20, 0x5E, 0x92, 0xF3, 0xA1, 0xAA, 0xAA, 0x6F, 0xC1, 0x6C, 0x25, 0xC1, 0x65, 0xF8, 0xAF, 0xC5, - 0x80, 0xAA, 0xE6, 0x97, 0x87, 0xDB, 0xAA, 0x09, 0xB7, 0x5D, 0x0F, 0x4E, 0x53, 0xAE, 0x85, 0xCD, - 0xC6, 0x59, 0x3B, 0x43, 0x75, 0xE7, 0x0C, 0xBD, 0x2B, 0xAB, 0x19, 0x6D, 0x9D, 0x74, 0x0D, 0xE8, - 0x93, 0xFE, 0xC9, 0x7A, 0x55, 0x6B, 0x7F, 0xEC, 0xDD, 0xA1, 0x99, 0xBD, 0x73, 0x86, 0xE1, 0xED, - 0x3F, 0xBB, 0xC5, 0xB7, 0x6A, 0x99, 0xFC, 0xDE, 0x13, 0x9A, 0xFC, 0xDE, 0x53, 0x9A, 0xFC, 0xDE, - 0x13, 0x9A, 0xFC, 0xDE, 0x0F, 0x93, 0x3F, 0xB7, 0xC9, 0xEF, 0x3D, 0xB5, 0xC9, 0xEF, 0xD5, 0x34, - 0xF9, 0xBD, 0x9A, 0x26, 0xBF, 0x57, 0xD3, 0xE4, 0xF7, 0x9E, 0xC8, 0xE4, 0x5B, 0x1B, 0xFF, 0xB9, - 0x59, 0x46, 0xAE, 0xE5, 0x67, 0x8C, 0x32, 0xC0, 0xC2, 0x6A, 0x2B, 0x8D, 0xFD, 0x97, 0x99, 0x69, - 0x66, 0x01, 0x7B, 0xDE, 0x33, 0xB9, 0x44, 0x13, 0xA4, 0x6F, 0x97, 0xF0, 0x77, 0x1A, 0x13, 0x09, - 0x50, 0xFC, 0x7B, 0x27, 0x5D, 0xE7, 0x93, 0x56, 0xE7, 0x93, 0xA1, 0xCE, 0xAF, 0x5A, 0x9D, 0x5F, - 0x77, 0xE4, 0x5D, 0x3C, 0xE0, 0xE6, 0x3D, 0xF5, 0x86, 0x34, 0x74, 0x06, 0xB9, 0x1C, 0xA5, 0xEF, - 0xBB, 0x8C, 0x04, 0x18, 0x94, 0x14, 0xDF, 0x67, 0x89, 0x2B, 0x7B, 0xAE, 0x56, 0xF9, 0xC3, 0xDE, - 0xE1, 0xDE, 0xF9, 0xBE, 0xA1, 0xEA, 0xDE, 0x38, 0x14, 0xBD, 0xAE, 0x66, 0x57, 0x9A, 0xD8, 0xFE, - 0x57, 0x25, 0xB5, 0x52, 0xB7, 0x20, 0x7F, 0x52, 0x01, 0x78, 0xCF, 0x04, 0xCE, 0x73, 0x28, 0x08, - 0xFA, 0xF6, 0xF0, 0x3F, 0x66, 0x41, 0x08, 0x8C, 0xEA, 0xA1, 0x40, 0xEC, 0xB4, 0xF6, 0x94, 0xDE, - 0x1D, 0x7B, 0xC9, 0x0D, 0xA1, 0x54, 0x2A, 0xA2, 0xA4, 0x8E, 0x21, 0x30, 0x8A, 0x7E, 0x77, 0x42, - 0x2D, 0xAF, 0xC8, 0xAD, 0x33, 0x64, 0x99, 0x51, 0x1D, 0xF7, 0x9C, 0xE5, 0x73, 0xE2, 0x8D, 0xC0, - 0xD8, 0x35, 0x4C, 0xEA, 0x08, 0x5E, 0xCA, 0x91, 0x7B, 0xEE, 0x7B, 0x98, 0x06, 0x23, 0xBE, 0xE6, - 0xAF, 0xD3, 0x44, 0xAC, 0x7B, 0xEE, 0x50, 0x8E, 0xC6, 0xC2, 0x6A, 0xDC, 0xC7, 0xE1, 0x79, 0x0F, - 0x41, 0xD0, 0xC9, 0x1F, 0xAD, 0x84, 0x0D, 0x96, 0x92, 0xD6, 0x32, 0x85, 0x6F, 0xED, 0x7B, 0x93, - 0xE9, 0x98, 0x86, 0x49, 0x76, 0x05, 0x16, 0xA3, 0x16, 0x61, 0x90, 0x71, 0x0B, 0x72, 0xE6, 0x86, - 0xF0, 0xAF, 0xE9, 0x86, 0x68, 0x8D, 0x8C, 0xA8, 0x35, 0xA2, 0x9B, 0x5D, 0xFB, 0xF6, 0x18, 0x33, - 0x38, 0xDF, 0xDD, 0x52, 0x7E, 0xB9, 0xEB, 0xB0, 0x7F, 0xBE, 0xD6, 0x23, 0xB7, 0x76, 0x80, 0x77, - 0xA5, 0x6E, 0x1C, 0x7F, 0x02, 0x85, 0x3E, 0xE8, 0xB7, 0x33, 0x0D, 0x89, 0x77, 0xC3, 0x23, 0xA5, - 0x71, 0xD1, 0x9F, 0x08, 0x87, 0xDC, 0xF8, 0xDE, 0x84, 0xEC, 0x9D, 0x73, 0x80, 0x11, 0x99, 0x02, - 0x57, 0x52, 0xA4, 0x1E, 0xC7, 0x82, 0x59, 0x47, 0x2E, 0x38, 0x1A, 0xE9, 0x90, 0xFE, 0x00, 0x38, - 0xF1, 0x27, 0x8E, 0x4B, 0x81, 0xBE, 0x33, 0xB8, 0x25, 0x89, 0x06, 0x60, 0x82, 0x61, 0x64, 0xC7, - 0xF3, 0x9D, 0x11, 0x8C, 0x9D, 0x31, 0x23, 0x1C, 0x7B, 0x86, 0x51, 0x1E, 0x93, 0x48, 0xE8, 0x7F, - 0xD8, 0x25, 0xEE, 0x6C, 0x3C, 0x5E, 0xD2, 0xA3, 0x0B, 0x23, 0x29, 0x6A, 0xF5, 0xCB, 0x64, 0x3F, - 0xE1, 0xDF, 0x5E, 0x91, 0xBD, 0xF1, 0x98, 0xF4, 0xE1, 0xFB, 0x30, 0x3F, 0x27, 0xA6, 0xE7, 0x06, - 0xDE, 0x98, 0x76, 0xC6, 0xA0, 0xB1, 0x8D, 0x8F, 0xFC, 0x46, 0x2A, 0x81, 0xFF, 0x40, 0x4E, 0x20, - 0xB4, 0xB4, 0x0C, 0xCC, 0xF9, 0x02, 0x6E, 0xE2, 0xFC, 0xAF, 0x63, 0xCF, 0x1E, 0xFE, 0x6C, 0x3B, - 0xA1, 0x72, 0x11, 0x1D, 0x33, 0x19, 0x88, 0x14, 0x1A, 0xC1, 0xEC, 0x7A, 0xE2, 0x84, 0x51, 0xBE, - 0x55, 0x4C, 0xBD, 0x03, 0x83, 0x0D, 0xCB, 0x83, 0xCF, 0xD6, 0x97, 0x24, 0xAE, 0x1D, 0xA7, 0x2C, - 0x11, 0xDB, 0xEE, 0xD2, 0x3B, 0x82, 0xB7, 0x00, 0xE5, 0xF4, 0x2F, 0x51, 0x71, 0xC7, 0x9E, 0x4E, - 0xF9, 0xA0, 0x4A, 0xA3, 0x6D, 0x33, 0xB2, 0x4B, 0x09, 0x4E, 0xFB, 0x3F, 0xEC, 0xEF, 0x02, 0xDF, - 0x2F, 0x27, 0xC7, 0x1F, 0x42, 0xCC, 0xDD, 0xF7, 0xF7, 0x19, 0x0D, 0xC2, 0x08, 0x2B, 0x56, 0xE8, - 0x78, 0x80, 0xB0, 0xD5, 0x38, 0x3F, 0xEB, 0x5F, 0x62, 0xDA, 0x85, 0xD5, 0x19, 0x6B, 0x51, 0x84, - 0xB8, 0x21, 0xD7, 0x64, 0x43, 0x2B, 0xE2, 0x24, 0x1A, 0x79, 0xDC, 0x8C, 0xC9, 0xD2, 0x30, 0xC4, - 0x5A, 0xBE, 0xBE, 0xF6, 0xDF, 0xF0, 0x42, 0x07, 0xEF, 0xF0, 0x4D, 0x95, 0x4C, 0x6C, 0x8D, 0x9D, - 0x1C, 0xD1, 0xF6, 0x43, 0x3B, 0x9C, 0x05, 0x18, 0xDE, 0xAC, 0x1A, 0xE4, 0x7C, 0x82, 0x50, 0x3D, - 0x0F, 0x69, 0x6A, 0x20, 0xF3, 0x61, 0x67, 0xAE, 0xD4, 0xC8, 0x1C, 0xCC, 0x0A, 0x01, 0xCF, 0x1F, - 0xD1, 0xF0, 0xDC, 0x76, 0x7C, 0x98, 0x11, 0xD1, 0xB8, 0xAA, 0x33, 0xC8, 0x75, 0xE8, 0xBE, 0x63, - 0x35, 0x78, 0x99, 0x41, 0x44, 0xA8, 0xBD, 0x2C, 0x41, 0x56, 0xC0, 0x70, 0x79, 0x61, 0x48, 0xDD, - 0x8E, 0x94, 0x93, 0x60, 0x4A, 0xA9, 0x7F, 0xB2, 0xB7, 0x1F, 0xE8, 0x70, 0xA7, 0x9E, 0x4B, 0xB3, - 0x22, 0x53, 0x19, 0xC5, 0xC3, 0x60, 0x7A, 0xEA, 0xDD, 0x9D, 0x03, 0x78, 0x60, 0x30, 0xBF, 0xC0, - 0x18, 0x33, 0x92, 0x7A, 0x72, 0xC5, 0x51, 0x64, 0xA2, 0x44, 0x81, 0x81, 0x63, 0x06, 0xC7, 0x42, - 0x75, 0x44, 0x16, 0xBC, 0xAC, 0x08, 0x59, 0x19, 0x4F, 0xC2, 0x42, 0x1C, 0xAE, 0x60, 0x0F, 0x87, - 0x87, 0xDF, 0xE0, 0x17, 0x0C, 0x53, 0xA6, 0x80, 0xBF, 0xD5, 0x38, 0x38, 0x3B, 0x01, 0x5B, 0x1C, - 0xE2, 0x37, 0xE8, 0x08, 0x8A, 0x79, 0x26, 0x5B, 0x14, 0xAB, 0x2C, 0x91, 0xDD, 0x37, 0xC0, 0x60, - 0xAC, 0xE1, 0x42, 0x60, 0x25, 0x62, 0x1F, 0xD2, 0xD9, 0xFA, 0x94, 0x88, 0x07, 0x76, 0x97, 0x1E, - 0x9D, 0x7A, 0x76, 0x6B, 0x0F, 0x7E, 0xE1, 0x98, 0xE3, 0x88, 0x07, 0x07, 0xC3, 0x20, 0xEC, 0xEF, - 0xF0, 0x8B, 0x1A, 0xFA, 0xC0, 0xAB, 0x7D, 0x76, 0xBE, 0x74, 0x3C, 0x77, 0x30, 0x76, 0x06, 0x98, - 0xE6, 0x23, 0x96, 0x6D, 0x2B, 0xF5, 0x5C, 0xB9, 0x9A, 0xC7, 0x32, 0xE3, 0x11, 0x62, 0xEE, 0x62, - 0xD9, 0xC1, 0xCC, 0x67, 0x41, 0xD3, 0xE8, 0x08, 0x7F, 0xF8, 0x0D, 0x84, 0x9F, 0x96, 0x13, 0xC7, - 0x87, 0x03, 0xDF, 0x48, 0xD2, 0x80, 0xA8, 0x4F, 0x07, 0xEA, 0xB6, 0x09, 0x59, 0xCD, 0xA4, 0x27, - 0x05, 0x63, 0x3F, 0xC8, 0xA3, 0xDD, 0x88, 0x72, 0x11, 0xCC, 0x25, 0x54, 0xF3, 0x78, 0x93, 0x9A, - 0x60, 0x60, 0x0E, 0xF3, 0xF3, 0xE1, 0x9D, 0x60, 0x1E, 0x2F, 0x72, 0xE4, 0xD6, 0x61, 0x2D, 0x4A, - 0x9A, 0x64, 0xC0, 0x55, 0xF0, 0x1E, 0x3D, 0xB7, 0x23, 0x81, 0xA8, 0x6F, 0x7E, 0xE4, 0x9A, 0xDB, - 0x11, 0xE6, 0xF9, 0x65, 0xBE, 0x46, 0x6D, 0x6A, 0xD1, 0x3B, 0x84, 0x58, 0x44, 0x73, 0x22, 0x44, - 0xA5, 0xDA, 0x92, 0xC1, 0x67, 0xD2, 0x90, 0xEC, 0xC6, 0x1A, 0xDA, 0xC2, 0xB0, 0xF1, 0x4B, 0x74, - 0xF2, 0x05, 0x7A, 0x5C, 0x0D, 0xCC, 0xD3, 0xB2, 0x7C, 0xB4, 0xA5, 0xDA, 0x89, 0xEB, 0x82, 0xBC, - 0x66, 0x8E, 0xE2, 0x25, 0x42, 0xFD, 0x66, 0xBE, 0x67, 0xA9, 0xD1, 0x16, 0xDD, 0xCA, 0xF7, 0x7A, - 0xC2, 0x35, 0x53, 0x23, 0x79, 0x23, 0xB2, 0x1B, 0xC9, 0x85, 0x90, 0x6E, 0xA4, 0x52, 0x29, 0x6B, - 0xA7, 0x2F, 0xB5, 0xBE, 0xAE, 0xB1, 0xA5, 0xA7, 0xA4, 0x7A, 0x32, 0x3E, 0x19, 0x21, 0x1D, 0x89, - 0x6E, 0x75, 0x36, 0xF0, 0x74, 0x73, 0x0F, 0x9C, 0x5B, 0x98, 0x8A, 0xD1, 0x6F, 0x3B, 0xEE, 0xAE, - 0x1E, 0xF7, 0x14, 0x64, 0x0F, 0xEA, 0x45, 0xA4, 0xC2, 0xED, 0x81, 0x6F, 0xE9, 0xDB, 0xAE, 0xA5, - 0xF9, 0xD9, 0xEE, 0x6C, 0x2E, 0x90, 0x9F, 0xF4, 0x7E, 0x51, 0x15, 0x66, 0xBA, 0xDD, 0xCD, 0x85, - 0x4A, 0x47, 0xCF, 0xD1, 0x5D, 0x85, 0x97, 0x75, 0xDC, 0xB7, 0xA8, 0xC1, 0x4A, 0x3D, 0x6A, 0xCA, - 0xE6, 0x8A, 0x8A, 0xD9, 0x30, 0x46, 0xF9, 0x9B, 0x06, 0xA7, 0xC9, 0x0D, 0xDB, 0x79, 0x86, 0xA6, - 0x09, 0x59, 0x29, 0xB3, 0x63, 0xB8, 0x1C, 0x5C, 0x32, 0x2D, 0x1B, 0x1F, 0xD1, 0x25, 0xE0, 0xB3, - 0x5A, 0x1D, 0x3F, 0x84, 0xB5, 0x88, 0x56, 0x97, 0x79, 0x55, 0x4B, 0x6B, 0x35, 0x07, 0xA9, 0xDF, - 0xEA, 0x7C, 0x78, 0x43, 0xAB, 0xB5, 0xEB, 0x62, 0xF3, 0xB7, 0x3C, 0x8D, 0xB0, 0xA0, 0xF5, 0x86, - 0x8B, 0x69, 0x00, 0x24, 0x1E, 0x5B, 0xD0, 0xA2, 0x60, 0x0B, 0x45, 0x51, 0x88, 0x4C, 0xDD, 0xB8, - 0x33, 0x88, 0x05, 0x97, 0x71, 0x98, 0x5C, 0x18, 0xD3, 0x67, 0xBB, 0x74, 0x3C, 0x8F, 0x40, 0xD2, - 0xA8, 0xE2, 0xAC, 0x26, 0x96, 0x59, 0x07, 0x22, 0x88, 0xB7, 0xF6, 0x6C, 0x78, 0xE0, 0x7B, 0x53, - 0x7C, 0x99, 0xC2, 0x3C, 0xF5, 0x2A, 0x6F, 0x33, 0x16, 0xEA, 0x4B, 0x09, 0x8E, 0xBA, 0xE6, 0xD9, - 0xB1, 0x0C, 0x47, 0xC2, 0x59, 0xA8, 0xC4, 0x51, 0x5D, 0x5A, 0x15, 0x5A, 0xAF, 0x74, 0xAB, 0x39, - 0xD7, 0x67, 0xED, 0xAE, 0xCD, 0x4B, 0x1D, 0x2A, 0x84, 0x09, 0x26, 0xFE, 0xDD, 0x98, 0x7E, 0x27, - 0xB8, 0x15, 0x4C, 0x0C, 0x6D, 0x98, 0x82, 0x89, 0xE2, 0x6F, 0x42, 0xB3, 0x99, 0xFF, 0x74, 0xAF, - 0x74, 0x2F, 0x16, 0x10, 0xEF, 0x49, 0xC4, 0x8F, 0x57, 0x10, 0x37, 0x39, 0xDD, 0x33, 0x74, 0x58, - 0x75, 0x06, 0x10, 0x6D, 0x11, 0x75, 0x0B, 0xF7, 0xC5, 0xC4, 0x78, 0x9B, 0xA7, 0xD5, 0x4A, 0xEF, - 0xCD, 0x02, 0x7A, 0xEC, 0x0D, 0xEC, 0xB1, 0xF3, 0x1B, 0x1D, 0x02, 0x72, 0xB0, 0x74, 0xD7, 0x33, - 0x9E, 0x49, 0xB6, 0x7E, 0x17, 0xE6, 0xE0, 0x14, 0x16, 0xCB, 0x3C, 0x46, 0xC7, 0x26, 0xA0, 0x4B, - 0x58, 0xBB, 0x1E, 0xC3, 0x6A, 0x7C, 0x6C, 0xD2, 0xDB, 0x12, 0xAA, 0x5F, 0x17, 0xA9, 0xC1, 0xA2, - 0xEB, 0xCF, 0xCD, 0xCE, 0x69, 0xCF, 0x2B, 0xBC, 0x5E, 0x9B, 0x6B, 0x0B, 0x0E, 0x68, 0x68, 0x3B, - 0xE3, 0xA0, 0xA2, 0x5C, 0xAA, 0x20, 0xCA, 0x91, 0xC5, 0x07, 0xDB, 0x1F, 0xE2, 0x26, 0x16, 0x17, - 0x44, 0xFC, 0x0C, 0xD7, 0x82, 0x44, 0x93, 0x81, 0xBD, 0x92, 0xA4, 0x64, 0xD8, 0xF9, 0x44, 0x55, - 0x0A, 0x93, 0x49, 0x56, 0x6C, 0x4B, 0x6C, 0x01, 0x52, 0x89, 0xF0, 0x94, 0x6A, 0x3F, 0xDB, 0x2B, - 0xAA, 0xD7, 0xE0, 0x7C, 0x50, 0x93, 0xAF, 0x23, 0x6D, 0x36, 0x2E, 0xC0, 0xD1, 0x51, 0xB1, 0x65, - 0xD8, 0x0C, 0xC3, 0x3E, 0xE7, 0x7C, 0xDE, 0x4D, 0x2E, 0xB2, 0x42, 0xEF, 0x46, 0x79, 0x9D, 0x72, - 0x4E, 0x01, 0x14, 0xBF, 0x71, 0x29, 0x1B, 0x4D, 0xDF, 0xAE, 0xD7, 0xCB, 0xB9, 0x90, 0xC6, 0xB6, - 0xD5, 0x1E, 0xDD, 0xC8, 0xEA, 0x07, 0x20, 0xAA, 0x0E, 0x9E, 0x68, 0x4B, 0x32, 0x9B, 0xD6, 0xC5, - 0xD1, 0xE9, 0xE1, 0x2F, 0x8B, 0x90, 0xA7, 0x82, 0xAD, 0x9C, 0xF9, 0x48, 0x41, 0xD6, 0x34, 0x1E, - 0xE5, 0xF1, 0x18, 0xE4, 0xA0, 0xBC, 0x6D, 0x38, 0xA7, 0x14, 0xCA, 0xBE, 0x93, 0xA8, 0xCB, 0x20, - 0x81, 0x9B, 0x47, 0x02, 0x25, 0xB0, 0x98, 0xDA, 0x6F, 0x7A, 0xFC, 0x70, 0x5E, 0x39, 0x54, 0x7C, - 0x50, 0x31, 0x25, 0x0F, 0x80, 0x9F, 0xD8, 0xA1, 0x33, 0x50, 0x91, 0xCC, 0x25, 0x9C, 0x8A, 0x28, - 0x33, 0x24, 0x15, 0x3D, 0x97, 0xB8, 0x00, 0x01, 0x95, 0x78, 0x79, 0x31, 0x53, 0x2E, 0x0C, 0x76, - 0x21, 0xE2, 0xC8, 0xC7, 0xA4, 0x48, 0xA1, 0xF4, 0x4B, 0x8A, 0xB5, 0x85, 0xB3, 0x88, 0xB7, 0x1A, - 0xA5, 0x5D, 0xFB, 0x5C, 0x6C, 0xF5, 0xA4, 0x57, 0x13, 0x67, 0x7A, 0x33, 0x79, 0x6F, 0x1C, 0x3A, - 0xE1, 0x6C, 0x58, 0x6B, 0xB0, 0x29, 0xC1, 0x1B, 0x29, 0xF4, 0xFA, 0xEB, 0xBF, 0x8F, 0x45, 0x20, - 0xB5, 0x6D, 0xB7, 0x60, 0x32, 0x6A, 0x28, 0xCD, 0x02, 0x91, 0xC7, 0x37, 0xA2, 0xEF, 0xF9, 0x8D, - 0xE8, 0x7B, 0xF2, 0x9A, 0xB8, 0xB3, 0xC9, 0x7E, 0xEA, 0x11, 0x67, 0x28, 0x4A, 0xDF, 0x8B, 0x86, - 0xE5, 0x4D, 0xE8, 0xB9, 0xE2, 0x5A, 0x34, 0x7B, 0xB5, 0x08, 0xF3, 0xEA, 0xBC, 0x65, 0x5F, 0xF1, - 0x65, 0x99, 0x7B, 0x25, 0xB4, 0x2A, 0xA9, 0x6D, 0x6C, 0x02, 0x1E, 0x30, 0x66, 0xB6, 0x20, 0xCA, - 0xF9, 0x93, 0xE0, 0xDF, 0xC7, 0xFA, 0xAD, 0x7B, 0x59, 0xBD, 0xA4, 0x07, 0x62, 0x96, 0xE4, 0x30, - 0x9E, 0x0C, 0x77, 0x40, 0x4A, 0x8A, 0x55, 0x2D, 0xAE, 0xAE, 0xE0, 0x0D, 0xE6, 0x12, 0x33, 0xBC, - 0xE0, 0xE1, 0x84, 0x61, 0x9F, 0x67, 0x8A, 0x2F, 0x40, 0x64, 0x0C, 0x12, 0x59, 0x18, 0xFB, 0x0B, - 0x60, 0xDC, 0xC4, 0xB2, 0x12, 0x4D, 0x97, 0x97, 0xB8, 0x29, 0x27, 0xA5, 0x54, 0x86, 0x0E, 0x6B, - 0x77, 0xFB, 0xEB, 0x6B, 0x7F, 0x92, 0x4D, 0x36, 0x3B, 0x0F, 0xD5, 0x3D, 0x4B, 0x38, 0xF8, 0xDD, - 0x74, 0xBE, 0x50, 0x66, 0xF0, 0x7C, 0xDF, 0x31, 0x1D, 0x14, 0xC8, 0x83, 0x08, 0xF3, 0x5A, 0x8B, - 0x50, 0x02, 0x96, 0x53, 0x5A, 0x63, 0x05, 0x2B, 0x21, 0x17, 0x05, 0xE7, 0x06, 0x6A, 0x42, 0x33, - 0xC3, 0x18, 0xC3, 0x6F, 0xFC, 0xEF, 0x24, 0x62, 0x8A, 0x1C, 0xB9, 0x03, 0x9F, 0xC5, 0xB9, 0x4C, - 0x45, 0xA6, 0x2F, 0xB2, 0x42, 0x82, 0x3B, 0x7B, 0xCA, 0xA2, 0xA5, 0x78, 0xF2, 0x1E, 0x98, 0x93, - 0x12, 0x9E, 0x48, 0xC0, 0x78, 0xE2, 0x89, 0x4F, 0xB0, 0x8E, 0x8B, 0x49, 0xB9, 0x6F, 0xC1, 0x2E, - 0xD3, 0x20, 0x79, 0x74, 0x37, 0x21, 0x95, 0x7E, 0xB8, 0xC7, 0x27, 0x13, 0xFB, 0x2B, 0x3D, 0xA1, - 0x1F, 0x10, 0xC6, 0xDF, 0x31, 0x94, 0xB0, 0x34, 0x84, 0x3B, 0xE9, 0xDE, 0xAD, 0xAC, 0x17, 0x65, - 0x7A, 0xF7, 0x3B, 0xEB, 0xDD, 0xB4, 0x6C, 0xE4, 0x7F, 0x32, 0xC3, 0x49, 0x4E, 0x32, 0xF3, 0xD9, - 0x50, 0x39, 0x7A, 0xB2, 0x84, 0x56, 0x48, 0x77, 0x29, 0x9B, 0x2A, 0x13, 0x46, 0x1E, 0xD1, 0x87, - 0x05, 0x0A, 0x8A, 0x99, 0x4C, 0xB9, 0xB5, 0x26, 0xBE, 0x0A, 0x5A, 0xB7, 0x82, 0xD7, 0xA8, 0x64, - 0xD5, 0x2A, 0x10, 0x96, 0x44, 0x93, 0xB5, 0xD5, 0x44, 0x12, 0xB0, 0x9D, 0x7A, 0x21, 0x7D, 0xA5, - 0x3C, 0xA9, 0x67, 0x22, 0xBE, 0x0C, 0xC4, 0x1B, 0xC4, 0x73, 0xC7, 0xF7, 0x04, 0xDF, 0x33, 0x0A, - 0x22, 0x66, 0xE1, 0x6F, 0xE7, 0xC6, 0x84, 0x36, 0x07, 0x1F, 0x7B, 0xDC, 0xC5, 0x71, 0xC3, 0x36, - 0xC1, 0x5C, 0x3E, 0x01, 0xCB, 0x9B, 0xDD, 0x21, 0x1F, 0x71, 0xAC, 0xD8, 0x3E, 0xBE, 0xD3, 0x17, - 0xE2, 0x58, 0xA1, 0x94, 0xD8, 0xD7, 0xDE, 0x37, 0x5A, 0x55, 0x4C, 0xCB, 0x91, 0x98, 0x0E, 0x68, - 0xAE, 0x98, 0x1E, 0x94, 0x5C, 0x2B, 0xE4, 0xE8, 0x86, 0xD8, 0x63, 0xA8, 0x3F, 0xBC, 0x67, 0xA3, - 0x4F, 0x0C, 0xBC, 0x78, 0xF4, 0xB6, 0x99, 0x24, 0x89, 0x13, 0x92, 0x31, 0xC8, 0x52, 0x8C, 0x48, - 0xCD, 0x92, 0xB3, 0x30, 0xA2, 0xBD, 0xC9, 0x07, 0x0E, 0xFA, 0xB4, 0xE3, 0xCC, 0xE2, 0x7B, 0xE1, - 0xC4, 0x22, 0x4E, 0x40, 0x3E, 0x48, 0x56, 0x43, 0x41, 0x15, 0x33, 0x97, 0xD6, 0x7B, 0xFC, 0x77, - 0x0D, 0xED, 0xFF, 0xFA, 0x34, 0xC3, 0x01, 0x1F, 0x91, 0x88, 0xB9, 0x79, 0xE4, 0xC1, 0x90, 0x71, - 0xAA, 0x5C, 0x98, 0x22, 0xD1, 0xD8, 0x26, 0xB4, 0x2A, 0x8C, 0xF0, 0x71, 0xA2, 0x07, 0xD9, 0xCA, - 0x55, 0x35, 0xB9, 0x22, 0xBA, 0x7D, 0xFB, 0x87, 0xEF, 0xE2, 0xA9, 0x5B, 0x7E, 0x49, 0x31, 0xBE, - 0xF4, 0xE3, 0xC2, 0xA4, 0x83, 0x11, 0x6D, 0x58, 0x33, 0x3E, 0xFF, 0xF6, 0xE9, 0x04, 0x06, 0xCB, - 0x5B, 0x7B, 0x88, 0x6B, 0x8D, 0xA0, 0x95, 0xAE, 0x13, 0x79, 0xB4, 0xC6, 0x87, 0x9D, 0xA5, 0xDA, - 0xE2, 0x59, 0xE7, 0xED, 0xD4, 0xBB, 0xCE, 0xDB, 0x19, 0xAF, 0xAE, 0xC9, 0x69, 0xB1, 0x77, 0x5E, - 0x64, 0x3C, 0x54, 0x2D, 0x85, 0xF5, 0xB7, 0xC9, 0xCA, 0xCB, 0xE8, 0x79, 0xEA, 0x97, 0xA9, 0x77, - 0xAA, 0xA3, 0x32, 0x24, 0x29, 0x7E, 0xAD, 0x4F, 0xEC, 0xD3, 0x53, 0x12, 0xFB, 0x75, 0x91, 0xC4, - 0x32, 0xDE, 0xD2, 0x54, 0xA6, 0xFC, 0xE8, 0x0D, 0x2D, 0xEC, 0x39, 0x62, 0x8F, 0x6C, 0x7C, 0xCC, - 0x94, 0x3F, 0xEC, 0xE1, 0x48, 0x8A, 0xC9, 0x1F, 0x0A, 0x1A, 0xD2, 0xEF, 0xEA, 0x6D, 0x27, 0x36, - 0x88, 0x77, 0x44, 0xC9, 0x6B, 0x0C, 0x1D, 0xF7, 0xFC, 0x61, 0xC0, 0xD4, 0x25, 0x0A, 0x7B, 0x5C, - 0x5E, 0x66, 0xA5, 0xFA, 0xE8, 0x44, 0x84, 0x60, 0xA8, 0xC3, 0x80, 0x69, 0x5D, 0x0C, 0xF6, 0x99, - 0x55, 0xFE, 0x12, 0xA5, 0xE5, 0x26, 0x7A, 0x36, 0xE0, 0xC8, 0xAB, 0x56, 0x74, 0x4D, 0x3A, 0x4F, - 0x63, 0x28, 0x31, 0xF7, 0xB6, 0x61, 0xA8, 0xA6, 0xC9, 0xE0, 0xF0, 0x4C, 0x0F, 0x83, 0x65, 0xD2, - 0x64, 0xA9, 0x71, 0x13, 0x6D, 0xCB, 0x2A, 0xF8, 0x94, 0x55, 0xF0, 0xAB, 0x9E, 0x76, 0xB9, 0xA2, - 0x71, 0xE4, 0xEF, 0xE5, 0x30, 0x71, 0xEF, 0x1A, 0xA4, 0xAA, 0xBE, 0x87, 0x28, 0x97, 0x4F, 0x67, - 0xC1, 0x6D, 0xEB, 0x51, 0xDB, 0xB4, 0x64, 0x48, 0xF9, 0x8A, 0x84, 0x70, 0x8D, 0xA9, 0x1B, 0xA2, - 0x21, 0xC5, 0xE8, 0xE7, 0xD8, 0x16, 0xC5, 0x31, 0xB7, 0x80, 0x48, 0x84, 0xB6, 0x63, 0x6C, 0x36, - 0xD4, 0x94, 0x6E, 0xCD, 0xC8, 0x3D, 0x9A, 0xDC, 0x0E, 0x45, 0x88, 0x37, 0x2C, 0xAD, 0xB8, 0x3A, - 0x53, 0x9A, 0x54, 0x08, 0xEA, 0x9A, 0x15, 0x08, 0x01, 0x50, 0x36, 0x62, 0x35, 0x10, 0xE9, 0x8A, - 0xF6, 0xCC, 0xA3, 0x88, 0xDF, 0x6F, 0x35, 0x0E, 0x18, 0xF7, 0x04, 0x0F, 0x1B, 0x59, 0x6B, 0x70, - 0xB9, 0x10, 0x83, 0x2F, 0x93, 0xC6, 0x5F, 0x1A, 0x4B, 0x59, 0xDB, 0x41, 0x72, 0x97, 0x20, 0x27, - 0x03, 0x8A, 0x2D, 0x00, 0x9B, 0x98, 0xB1, 0x76, 0xCC, 0x17, 0x23, 0x86, 0x92, 0x2B, 0x06, 0xFD, - 0x77, 0x94, 0x61, 0xE6, 0xED, 0x2A, 0x2E, 0xCD, 0xEE, 0x97, 0x8C, 0xAA, 0x9F, 0x52, 0x55, 0x7B, - 0x59, 0x55, 0x7F, 0x4D, 0x55, 0x5D, 0xD3, 0xAA, 0x9A, 0x47, 0xBF, 0xD4, 0xA1, 0xA6, 0x87, 0x1C, - 0x65, 0xAE, 0x0B, 0x6A, 0x7C, 0x2A, 0xAC, 0xF1, 0x6B, 0x56, 0x0D, 0x95, 0x35, 0xE5, 0xAD, 0xC2, - 0xF8, 0x59, 0x25, 0x49, 0xD0, 0xE0, 0xC5, 0xFA, 0x36, 0xF8, 0x85, 0x5C, 0x01, 0x08, 0x46, 0x1F, - 0x4C, 0x3C, 0xD7, 0x0B, 0xA6, 0x36, 0xAC, 0xE2, 0x58, 0x94, 0x3C, 0x33, 0xC3, 0xDA, 0x4A, 0x3D, - 0x51, 0x14, 0x29, 0xD4, 0x3E, 0x53, 0x0D, 0x44, 0x46, 0xF7, 0x64, 0xEA, 0x47, 0x65, 0x48, 0x1B, - 0x95, 0xD4, 0xCC, 0xC0, 0xF7, 0x13, 0xB2, 0xD0, 0x26, 0xCD, 0x97, 0x9B, 0x8C, 0x37, 0xD6, 0xF4, - 0xCB, 0x05, 0xD2, 0x7B, 0x4B, 0x98, 0x9B, 0xD3, 0xF3, 0xE9, 0xB0, 0x91, 0x73, 0xBB, 0x86, 0xEF, - 0x84, 0xCC, 0x4D, 0x56, 0x94, 0xBE, 0x22, 0xBF, 0xAC, 0x7E, 0x5A, 0xFD, 0xB5, 0xA1, 0x66, 0xC0, - 0x37, 0xB4, 0xFE, 0x35, 0xD9, 0x58, 0x4A, 0x1D, 0x1F, 0x66, 0xCA, 0x34, 0x70, 0x7E, 0xA3, 0xC4, - 0x64, 0x9A, 0x15, 0xEB, 0x18, 0xFB, 0xB8, 0xC9, 0xD4, 0x59, 0x75, 0xAE, 0xC4, 0x01, 0xEA, 0x4D, - 0x59, 0xDF, 0x4B, 0x57, 0x14, 0xD0, 0x5B, 0x05, 0x35, 0x10, 0x29, 0xD1, 0x9B, 0xBC, 0x82, 0x3C, - 0x4C, 0xF9, 0x17, 0xB6, 0x77, 0x61, 0x9C, 0x60, 0x53, 0x35, 0xA3, 0x31, 0xC4, 0x8A, 0xD5, 0xD1, - 0x96, 0x29, 0x04, 0xCC, 0x07, 0xCF, 0xC1, 0xD5, 0x49, 0xE1, 0x8F, 0xAD, 0xC6, 0xFF, 0x32, 0x03, - 0x09, 0x6A, 0x00, 0x4B, 0xED, 0xC1, 0x6D, 0xCB, 0xBC, 0x0B, 0x29, 0xDB, 0xA4, 0x3F, 0xB6, 0xC2, - 0x5B, 0x27, 0xE0, 0x9B, 0x30, 0xAD, 0xA5, 0x5C, 0xAB, 0xEE, 0xAA, 0x56, 0xBD, 0x13, 0xCC, 0xAE, - 0xF9, 0xAA, 0xB0, 0x05, 0xFE, 0x53, 0x77, 0x43, 0x82, 0x50, 0x90, 0xC6, 0xA0, 0x30, 0xE1, 0xF1, - 0x94, 0xF8, 0x91, 0x25, 0x8B, 0xA7, 0xC0, 0xC8, 0x5E, 0x69, 0x1F, 0xD6, 0xBE, 0x70, 0x14, 0xC9, - 0x66, 0xAF, 0xE6, 0x84, 0x47, 0x77, 0x42, 0xCB, 0x39, 0xE2, 0x51, 0xED, 0x22, 0x67, 0x5C, 0xAD, - 0x57, 0xC6, 0x21, 0x8F, 0x20, 0x16, 0xE5, 0x94, 0x27, 0x0F, 0xA4, 0xE5, 0xBA, 0xB3, 0xF1, 0x81, - 0x03, 0x78, 0xB4, 0xDD, 0xAE, 0xB5, 0xB6, 0xDE, 0x26, 0x5B, 0x5B, 0x0A, 0x75, 0xFE, 0x19, 0x59, - 0xC0, 0x82, 0xCA, 0x4E, 0xB3, 0x7E, 0xEE, 0x80, 0x74, 0x36, 0xB0, 0xAF, 0x15, 0x12, 0x1B, 0xEC, - 0xC9, 0xC4, 0x8D, 0xBA, 0xD8, 0xB5, 0x43, 0x07, 0xA0, 0xD1, 0xB3, 0xAC, 0x8E, 0xC5, 0xAE, 0x78, - 0x76, 0x14, 0xCF, 0x9C, 0x7D, 0x40, 0x62, 0xEC, 0x97, 0x67, 0xE7, 0x95, 0xC7, 0x7A, 0x53, 0xDD, - 0x33, 0x8F, 0x40, 0xAB, 0x7A, 0xE7, 0xB1, 0xE2, 0x55, 0xF3, 0xD0, 0x35, 0x72, 0x92, 0x97, 0xAE, - 0x8D, 0x11, 0xC5, 0x47, 0x15, 0x97, 0xAB, 0x8D, 0x45, 0xE2, 0x2E, 0xB5, 0xA9, 0x2C, 0xD2, 0x52, - 0xAD, 0x4C, 0xD3, 0x2D, 0x73, 0xA9, 0xAA, 0x1B, 0x8F, 0xE0, 0xF3, 0x6B, 0x7D, 0x66, 0xF4, 0xFB, - 0xE3, 0x3A, 0x8A, 0xEF, 0xFF, 0x4F, 0x20, 0x29, 0xD3, 0x4A, 0x22, 0x62, 0x3B, 0x7B, 0x35, 0x91, - 0x32, 0xAA, 0x45, 0xCE, 0xB0, 0xAE, 0x84, 0x95, 0x1D, 0xE2, 0x58, 0x1D, 0x9F, 0xCF, 0xC2, 0x22, - 0xEE, 0xDD, 0xF2, 0x8B, 0x8B, 0x3C, 0xC9, 0x4A, 0x27, 0x97, 0xF2, 0x32, 0xED, 0xD6, 0xA6, 0x27, - 0x34, 0xBC, 0xF5, 0x86, 0x99, 0xB7, 0x23, 0x95, 0xAB, 0x91, 0x49, 0x52, 0x80, 0x57, 0x51, 0x0E, - 0x80, 0xD4, 0xDB, 0x5B, 0x80, 0x32, 0x91, 0xBF, 0x84, 0x5F, 0x8B, 0xA8, 0x4E, 0x9F, 0xC6, 0x66, - 0xC7, 0x80, 0x99, 0x0E, 0xB8, 0x33, 0x83, 0xBC, 0x80, 0x24, 0x7C, 0x13, 0x0F, 0x52, 0x65, 0xA4, - 0x4F, 0x58, 0x22, 0x2B, 0xA4, 0x25, 0x55, 0x49, 0x1F, 0x6F, 0x8B, 0x6A, 0xCB, 0x24, 0x5D, 0xCB, - 0x7C, 0xB5, 0x64, 0x89, 0xAC, 0x92, 0x2E, 0x4F, 0x09, 0x90, 0xC7, 0x76, 0x34, 0xF3, 0x03, 0x97, - 0x1D, 0x8C, 0x67, 0x81, 0xD2, 0xD6, 0x5A, 0xDE, 0x4D, 0xF4, 0x5C, 0x39, 0xA5, 0xB3, 0x6E, 0xE4, - 0x88, 0x49, 0x13, 0xAA, 0x59, 0x4E, 0x3A, 0xAB, 0x28, 0x82, 0x27, 0x94, 0x54, 0x2A, 0xCB, 0x85, - 0x59, 0x4E, 0xFA, 0xD2, 0xF9, 0xD9, 0x5A, 0x8C, 0xD9, 0xE4, 0x5C, 0xC0, 0x31, 0x78, 0x65, 0x05, - 0x11, 0x51, 0x8C, 0x2B, 0xBD, 0xD9, 0x25, 0x9B, 0xA6, 0xA9, 0x7A, 0x6C, 0x87, 0x11, 0x96, 0xA4, - 0xF2, 0x0A, 0x59, 0x47, 0x41, 0xF6, 0x0C, 0xEF, 0x01, 0x66, 0x4E, 0xCD, 0x86, 0xE5, 0x73, 0x41, - 0xF2, 0x92, 0xF4, 0x92, 0x3F, 0xE2, 0x3A, 0x66, 0xEA, 0x4D, 0xFA, 0xA6, 0x84, 0xB2, 0x30, 0x9A, - 0xC0, 0x6A, 0x30, 0x62, 0xBF, 0xBB, 0x23, 0xFD, 0xF9, 0x3A, 0x6E, 0x98, 0xF4, 0x35, 0x7D, 0x0E, - 0x50, 0xC8, 0xE5, 0xF2, 0xAE, 0xE2, 0xB3, 0x27, 0x04, 0x96, 0x89, 0xCE, 0x78, 0x7A, 0xCF, 0xFF, - 0x21, 0x43, 0x12, 0xE9, 0xD4, 0x2C, 0x42, 0x14, 0x80, 0x35, 0x62, 0xFB, 0x79, 0x49, 0x45, 0xE7, - 0x38, 0x4F, 0x2C, 0xD9, 0x8D, 0x28, 0x2D, 0x21, 0x83, 0x4D, 0xE3, 0x84, 0x24, 0x0D, 0x5D, 0x33, - 0x28, 0x5A, 0x86, 0x01, 0x31, 0x81, 0xF7, 0xB2, 0xC1, 0x33, 0xAF, 0xF7, 0xA5, 0x90, 0x74, 0xBF, - 0x68, 0xF7, 0x53, 0xEB, 0x64, 0xC9, 0x89, 0xD2, 0xDC, 0x54, 0xC0, 0xD3, 0xCB, 0xC9, 0xB6, 0xA3, - 0xE0, 0x51, 0x62, 0x8A, 0xB2, 0x9E, 0xB9, 0x33, 0x0C, 0xEA, 0x9D, 0xCC, 0xBA, 0xEA, 0x28, 0x29, - 0xAA, 0x17, 0xEB, 0x4D, 0x41, 0xC5, 0xA4, 0xC3, 0xB3, 0x2B, 0xA6, 0x3A, 0xB7, 0xB0, 0xAA, 0xDE, - 0x91, 0x25, 0x03, 0x61, 0x94, 0xFC, 0x2C, 0x01, 0x37, 0xEF, 0x91, 0x68, 0x08, 0xB3, 0xC6, 0x7C, - 0x25, 0x9E, 0x11, 0x16, 0x93, 0xDE, 0xA9, 0x8B, 0x81, 0x6B, 0xED, 0xD6, 0xA9, 0x9E, 0x57, 0xEE, - 0x8E, 0x9D, 0x64, 0x95, 0xF3, 0x76, 0xED, 0xB4, 0x65, 0x41, 0xE9, 0x9D, 0x3B, 0x93, 0x7E, 0xE8, - 0xBA, 0xF3, 0x88, 0x3B, 0x78, 0x35, 0xC9, 0xC7, 0x3B, 0x79, 0xA0, 0xB5, 0xAB, 0xA8, 0x91, 0xAB, - 0xA0, 0x6D, 0xE6, 0x0D, 0x3D, 0x5D, 0x30, 0x25, 0x37, 0xF5, 0x24, 0xB1, 0xAB, 0x1B, 0x7B, 0xFA, - 0x9A, 0xB9, 0xE2, 0xE6, 0x5E, 0x99, 0x25, 0xF7, 0x22, 0x37, 0xF8, 0xB4, 0x85, 0xF3, 0x7C, 0x9B, - 0x7C, 0x92, 0x50, 0xAA, 0x6D, 0xF4, 0xC5, 0xA3, 0xE5, 0x77, 0xDD, 0xEC, 0x53, 0xD4, 0x43, 0xF6, - 0xAF, 0xD0, 0x93, 0x7A, 0xA9, 0xCF, 0x98, 0x0B, 0xDB, 0x12, 0x4C, 0xCD, 0x97, 0x6A, 0x85, 0x75, - 0x1D, 0x62, 0x43, 0xFF, 0xB0, 0x59, 0x84, 0xE2, 0xA5, 0xB2, 0xED, 0x58, 0x68, 0x0C, 0x1F, 0x65, - 0xB3, 0x53, 0xD2, 0x81, 0x87, 0x54, 0x9A, 0x33, 0x65, 0xD7, 0x52, 0xCA, 0xBA, 0xC4, 0x5D, 0x6E, - 0xF8, 0x29, 0xF5, 0x6C, 0xE7, 0x3F, 0x3C, 0xC7, 0x6D, 0x35, 0x9B, 0x71, 0xCA, 0x29, 0xAD, 0x4A, - 0xBB, 0xB8, 0xCA, 0xDF, 0xFE, 0x96, 0xAA, 0xE3, 0xD3, 0x70, 0xE6, 0xBB, 0xCC, 0x5D, 0xD7, 0xB8, - 0x1B, 0xD1, 0x10, 0x13, 0x5D, 0x29, 0xA6, 0x98, 0xE5, 0x18, 0x03, 0x93, 0x05, 0xDA, 0x13, 0x95, - 0xA1, 0x45, 0xE5, 0xD3, 0xBA, 0x66, 0xD6, 0x94, 0x3A, 0x62, 0x85, 0x25, 0x6D, 0xDA, 0x1D, 0xDD, - 0xB0, 0x4D, 0xBA, 0xD0, 0xBE, 0x26, 0x77, 0x76, 0x40, 0x70, 0xEE, 0x26, 0x98, 0x1C, 0x8B, 0x0E, - 0xDB, 0x84, 0x0F, 0x69, 0x2C, 0x1B, 0x53, 0x9E, 0x45, 0x2D, 0x18, 0xF8, 0xF8, 0x38, 0x93, 0xB6, - 0xD0, 0x19, 0xD3, 0x13, 0xDB, 0xB5, 0x47, 0xD4, 0xBF, 0xC4, 0x9A, 0xA9, 0x34, 0x58, 0x0C, 0xFE, - 0xCD, 0xEB, 0xD0, 0x27, 0xF6, 0xD8, 0x19, 0xB9, 0xBB, 0xCD, 0x31, 0xBD, 0x09, 0x9B, 0xF0, 0xE1, - 0xF6, 0x0D, 0xEE, 0x1F, 0xBC, 0x5E, 0x85, 0x5F, 0xF0, 0x8F, 0x3E, 0x18, 0x32, 0xF1, 0xC7, 0xF0, - 0xCD, 0x6B, 0xFE, 0x9C, 0x66, 0x78, 0x3F, 0xA5, 0xBB, 0xDC, 0xE3, 0xB8, 0xF6, 0xBE, 0x37, 0x89, - 0x33, 0xDC, 0x6D, 0x22, 0x41, 0xBE, 0x9C, 0xDF, 0x1B, 0x8F, 0x9B, 0x84, 0xBD, 0xF6, 0x0A, 0x5F, - 0x3D, 0x7F, 0xB2, 0xC2, 0x2A, 0xAE, 0x70, 0x50, 0x89, 0x2F, 0xB6, 0x33, 0xD9, 0x24, 0x22, 0x70, - 0x91, 0x63, 0x88, 0x58, 0xF6, 0x46, 0x23, 0x4C, 0x4B, 0x04, 0xFC, 0xAC, 0x22, 0xD9, 0xD5, 0xD0, - 0x8F, 0x7F, 0x30, 0xBE, 0x25, 0xB3, 0x8D, 0x60, 0xAC, 0x89, 0x97, 0xDC, 0x86, 0x35, 0x1A, 0x92, - 0x28, 0xBF, 0x4F, 0xC6, 0xB7, 0x61, 0x38, 0xCD, 0x4D, 0x3D, 0x26, 0xD5, 0x13, 0x19, 0xC8, 0xDE, - 0x1F, 0xF2, 0x04, 0x64, 0x38, 0x0B, 0xB3, 0xFC, 0x68, 0x8D, 0xB4, 0x77, 0x16, 0x41, 0xB0, 0xBC, - 0x52, 0xB2, 0x9D, 0x10, 0x61, 0x63, 0x03, 0x6F, 0x82, 0x66, 0x24, 0xAA, 0xE6, 0xD3, 0x60, 0x0A, - 0xEE, 0x04, 0x63, 0x72, 0x09, 0x43, 0x76, 0x44, 0xB6, 0x3D, 0xB2, 0xDF, 0xFF, 0x89, 0xE7, 0xC7, - 0x73, 0xDC, 0xD0, 0x63, 0x93, 0xFF, 0x8B, 0xF2, 0x1D, 0x09, 0xEE, 0xB7, 0xD2, 0xFC, 0x82, 0xC9, - 0x54, 0xD5, 0xBA, 0xCC, 0x77, 0xAE, 0x40, 0xB9, 0x45, 0xDE, 0xD9, 0x94, 0x7E, 0x7B, 0xD7, 0xA1, - 0xED, 0x80, 0x1A, 0x4A, 0xE5, 0x46, 0x1D, 0x37, 0xD6, 0xD3, 0xF5, 0x5C, 0x4A, 0xE0, 0x89, 0x15, - 0x74, 0x15, 0x95, 0xFA, 0x58, 0xD4, 0x92, 0x7A, 0x38, 0x6E, 0x16, 0x66, 0xD9, 0x3B, 0x49, 0x1E, - 0xF2, 0x42, 0xFB, 0xFF, 0xF9, 0x8B, 0xB9, 0x9C, 0x6D, 0xC8, 0x1B, 0x2B, 0x44, 0x17, 0x34, 0x32, - 0x31, 0x44, 0x15, 0x14, 0x14, 0x0B, 0xD4, 0xB2, 0x28, 0x93, 0xF5, 0xEF, 0xA8, 0x68, 0x59, 0x3D, - 0xB1, 0xBC, 0x2B, 0x8B, 0x5F, 0x31, 0x53, 0xE4, 0x82, 0x4E, 0x05, 0x76, 0xDB, 0xBD, 0xE7, 0x92, - 0x8A, 0x2A, 0xB3, 0x23, 0x87, 0x80, 0xF9, 0xB6, 0xDF, 0xB8, 0xD0, 0x56, 0x88, 0xD3, 0xA1, 0x1D, - 0x66, 0xD8, 0xC4, 0x17, 0x74, 0x7D, 0xF0, 0x4F, 0x7C, 0x41, 0x83, 0xF0, 0x47, 0x44, 0xC8, 0x50, - 0xDC, 0xBA, 0x0E, 0x72, 0x23, 0xFC, 0x52, 0xDD, 0x9E, 0xF5, 0x20, 0x9C, 0x68, 0x5D, 0xAA, 0xFE, - 0xE7, 0xEF, 0x5F, 0x92, 0xF5, 0x5C, 0x5A, 0x49, 0x3E, 0xCB, 0x5E, 0xCF, 0x43, 0x61, 0x9B, 0x23, - 0x53, 0x58, 0xA5, 0xD1, 0x2C, 0x43, 0x01, 0x8F, 0xB2, 0x4F, 0x10, 0xD0, 0x12, 0xCD, 0x56, 0x94, - 0x35, 0xAF, 0xDD, 0x6C, 0x42, 0x4A, 0x6B, 0xAF, 0x08, 0xD2, 0x6C, 0xE0, 0x68, 0xCC, 0xCA, 0xA7, - 0x93, 0x26, 0xC4, 0x04, 0x96, 0x95, 0x8A, 0x37, 0x27, 0x8F, 0x4F, 0x0E, 0x03, 0x4C, 0xD3, 0x6B, - 0x73, 0xA0, 0xED, 0x34, 0x56, 0x88, 0xB4, 0x94, 0x56, 0x75, 0xAA, 0xA9, 0x23, 0x47, 0x41, 0x30, - 0x13, 0x51, 0xEF, 0x47, 0x07, 0xAF, 0xD8, 0x86, 0xBA, 0x99, 0x8F, 0x2A, 0x51, 0xFA, 0x2A, 0x0D, - 0x5C, 0x13, 0x16, 0x99, 0x54, 0xAC, 0x53, 0xD6, 0xAC, 0xF2, 0xBA, 0x05, 0xA6, 0x15, 0x2B, 0xD5, - 0x37, 0xAF, 0xCF, 0xC6, 0x3A, 0xB2, 0x66, 0x3C, 0x0B, 0x0B, 0x99, 0x12, 0x68, 0x55, 0x2B, 0xF9, - 0xC3, 0x62, 0xFC, 0x4B, 0x58, 0x0C, 0x36, 0xFA, 0x9C, 0xC7, 0xB0, 0x1A, 0x92, 0xDF, 0x77, 0x00, - 0xD3, 0x21, 0x1E, 0x40, 0x24, 0x39, 0x62, 0xC5, 0x8D, 0x1D, 0x74, 0xE6, 0xCA, 0xA7, 0x1C, 0x45, - 0x8C, 0x47, 0x07, 0xD2, 0xA1, 0x1A, 0x67, 0xC7, 0x65, 0x27, 0x2A, 0x67, 0x37, 0x0C, 0x59, 0x3F, - 0xBA, 0x0B, 0x54, 0x1B, 0xA9, 0xB2, 0xC5, 0x81, 0xA5, 0xFC, 0xC4, 0x26, 0x89, 0x2C, 0xC0, 0x51, - 0xFA, 0x8E, 0x27, 0x1D, 0x85, 0xC1, 0xD1, 0xC7, 0x8C, 0xDC, 0x98, 0x13, 0x17, 0xAC, 0x2F, 0x96, - 0xA8, 0x29, 0xBD, 0xE3, 0xAA, 0x92, 0xBD, 0x94, 0x71, 0xEE, 0x9A, 0xB9, 0x5F, 0x12, 0x2B, 0xB7, - 0xE4, 0xBC, 0x70, 0xE6, 0x8F, 0x43, 0x4C, 0xF6, 0x82, 0x6B, 0xBE, 0xC6, 0x2A, 0xA2, 0xF8, 0x0B, - 0x63, 0x9F, 0xF5, 0x95, 0x2C, 0xCD, 0xCF, 0x09, 0x7A, 0x7C, 0x2F, 0x16, 0x8F, 0x51, 0xFF, 0x64, - 0x33, 0x6E, 0x76, 0x87, 0xA2, 0x1B, 0x84, 0x79, 0x94, 0xB5, 0x22, 0x46, 0x2F, 0x64, 0x0A, 0x9E, - 0x36, 0xD4, 0xEE, 0x44, 0x27, 0xB3, 0x9D, 0x5B, 0x9F, 0xDE, 0xE0, 0xC3, 0xCB, 0x51, 0xB5, 0xE8, - 0x3E, 0x67, 0x4C, 0x6B, 0x79, 0x79, 0x27, 0xAB, 0xF7, 0xA3, 0xB5, 0x90, 0x74, 0xE8, 0x94, 0x8C, - 0xFD, 0xAA, 0xFD, 0x94, 0x95, 0x69, 0x16, 0x37, 0x8D, 0x12, 0xAC, 0x4A, 0xAE, 0x59, 0x37, 0x95, - 0x69, 0x36, 0xA9, 0x88, 0xD9, 0x66, 0x93, 0xF1, 0x15, 0x2D, 0x57, 0xE2, 0x65, 0x60, 0x72, 0x4D, - 0x71, 0xA7, 0x40, 0xC3, 0xA9, 0x9A, 0x03, 0x79, 0x51, 0xFA, 0xFD, 0x22, 0xEB, 0xCC, 0x3C, 0xD5, - 0xEF, 0xD1, 0xA6, 0x0E, 0xF4, 0x37, 0x63, 0x2C, 0x10, 0x87, 0xE7, 0xA9, 0x29, 0x58, 0xD6, 0x2C, - 0x7D, 0x07, 0x4F, 0xB6, 0xBB, 0x06, 0xE4, 0xC6, 0xD7, 0x8A, 0xCB, 0x6B, 0xE6, 0xF7, 0x94, 0x42, - 0xB2, 0xB6, 0x34, 0x76, 0x4A, 0xCF, 0xB4, 0xB9, 0x53, 0x6D, 0xCC, 0x48, 0xF1, 0x04, 0x2B, 0xB5, - 0x7D, 0x75, 0xF5, 0x82, 0xDE, 0xC0, 0x8C, 0x7A, 0xCB, 0x13, 0x8D, 0xC7, 0x61, 0x45, 0xB9, 0xCB, - 0x4D, 0x65, 0xF7, 0x64, 0x47, 0xBB, 0x42, 0xCA, 0x73, 0x7E, 0x6B, 0x1A, 0x2F, 0x65, 0x31, 0xC7, - 0x5F, 0xBB, 0x0B, 0x49, 0x5C, 0xCE, 0x31, 0xD5, 0xCC, 0x55, 0xCE, 0x19, 0x35, 0x5C, 0x8D, 0x86, - 0xB9, 0x7E, 0xE4, 0x63, 0x1E, 0xFD, 0x36, 0x89, 0x7E, 0xFD, 0x00, 0xD3, 0xFB, 0x98, 0xFA, 0xAA, - 0x60, 0x19, 0x96, 0x34, 0x38, 0xB3, 0x30, 0x6D, 0xB0, 0x2E, 0x3C, 0xE5, 0x77, 0x15, 0x50, 0x7E, - 0x18, 0xD1, 0xE6, 0x87, 0x12, 0x55, 0x00, 0xED, 0x6B, 0xCF, 0x0F, 0x01, 0x90, 0xFD, 0x3F, 0x1B, - 0x30, 0x23, 0x3D, 0xFB, 0x38, 0x3F, 0x35, 0xBB, 0xF4, 0xBE, 0x85, 0x26, 0x8F, 0x28, 0x91, 0x76, - 0xD2, 0xCD, 0x53, 0xEA, 0x0F, 0xF8, 0xFD, 0x58, 0x5E, 0xD6, 0x19, 0xB3, 0xA4, 0xDB, 0x64, 0x95, - 0xF0, 0x3F, 0x43, 0x2F, 0xC4, 0x7D, 0xC0, 0x3F, 0xE3, 0xD1, 0xBE, 0x94, 0x8F, 0x5C, 0xA0, 0x7D, - 0x6B, 0xFB, 0xD2, 0x21, 0xDD, 0x89, 0x1D, 0xDE, 0x76, 0x7C, 0x6F, 0x06, 0xDC, 0x08, 0xB4, 0x4B, - 0x09, 0xC8, 0x4C, 0xCA, 0xE8, 0xAE, 0x39, 0xC6, 0x06, 0x38, 0x1C, 0x74, 0xFF, 0x5B, 0xA8, 0x26, - 0x1D, 0xF2, 0x3C, 0xF1, 0xF1, 0x96, 0xB0, 0x60, 0xF9, 0x0D, 0xBE, 0xA9, 0x62, 0xA5, 0x9E, 0x86, - 0xCA, 0xA6, 0xD3, 0x38, 0x4F, 0x52, 0xCF, 0xB7, 0xC9, 0x1D, 0x5E, 0xC1, 0x72, 0x47, 0x5C, 0xD1, - 0xC1, 0xFB, 0x64, 0xDA, 0x7D, 0x0F, 0x1D, 0x34, 0x69, 0x18, 0x9E, 0xFB, 0xD5, 0xB4, 0x43, 0x15, - 0x64, 0x11, 0x5D, 0x9E, 0x53, 0x9E, 0xC4, 0x49, 0xE5, 0x8B, 0x04, 0x19, 0x1D, 0x1C, 0x2D, 0x62, - 0xA8, 0xB3, 0x6F, 0xB1, 0x39, 0xC7, 0x94, 0xF0, 0xFC, 0x68, 0xE2, 0xED, 0xFD, 0xD1, 0xB0, 0x2A, - 0xD7, 0x92, 0x3C, 0x64, 0x8D, 0xAF, 0x25, 0x8C, 0x77, 0x36, 0x30, 0x39, 0x54, 0x91, 0xCA, 0xA3, - 0xA1, 0x16, 0xD2, 0x3D, 0x44, 0x20, 0xB0, 0x26, 0x68, 0xC3, 0x81, 0xC8, 0x17, 0xFA, 0x16, 0x67, - 0x50, 0xC5, 0xB5, 0x49, 0xEE, 0xF9, 0x5F, 0x0E, 0x4A, 0xE5, 0x31, 0xE5, 0x27, 0x64, 0x31, 0x46, - 0x35, 0x16, 0xD5, 0xB8, 0x0D, 0xC8, 0x8F, 0xF4, 0x32, 0x20, 0xA2, 0xB6, 0xC5, 0xC5, 0x98, 0x17, - 0x52, 0x7E, 0xFB, 0x67, 0x7B, 0x7D, 0xCB, 0x34, 0x93, 0x43, 0x7D, 0x9E, 0xF8, 0xB5, 0xA0, 0x49, - 0x65, 0x12, 0xD2, 0xC6, 0x4D, 0x32, 0xA5, 0x92, 0xCD, 0x6F, 0x52, 0x56, 0xF2, 0xD9, 0x91, 0x5C, - 0x5C, 0xB2, 0x49, 0xB3, 0xE1, 0x34, 0xAF, 0x31, 0x1F, 0x87, 0x15, 0x1A, 0x33, 0x1B, 0xC6, 0xE9, - 0x17, 0x4B, 0x37, 0x27, 0x13, 0x26, 0xD6, 0xBF, 0xA1, 0xB9, 0x41, 0x5D, 0xAB, 0xDB, 0xB5, 0x4C, - 0x2D, 0x1A, 0xDE, 0x0E, 0xA6, 0x87, 0xB0, 0x8C, 0xF4, 0x5D, 0x1A, 0xA6, 0x5B, 0x25, 0x0A, 0x0E, - 0x3E, 0xEC, 0x9F, 0xE7, 0x37, 0x49, 0xCA, 0x19, 0x7F, 0x74, 0xAE, 0xB2, 0x18, 0x61, 0xCF, 0x6D, - 0x9E, 0x94, 0xCB, 0xBD, 0x18, 0x5E, 0xE6, 0x1F, 0x0A, 0xF0, 0xB2, 0x37, 0x8B, 0x73, 0x56, 0xBD, - 0x61, 0x2D, 0x10, 0x1E, 0xBF, 0xDD, 0x39, 0x37, 0xCE, 0x29, 0x07, 0x28, 0xE5, 0x40, 0x3A, 0xC3, - 0x7F, 0xDB, 0x95, 0x60, 0xBE, 0x34, 0xC9, 0x9F, 0xFE, 0x44, 0xE2, 0xB2, 0x3F, 0xEE, 0xF6, 0xFB, - 0xBA, 0xF3, 0xAC, 0xF9, 0x7B, 0x32, 0xC1, 0x2C, 0x77, 0x0F, 0x85, 0x2D, 0xD7, 0x43, 0x8F, 0x8E, - 0x75, 0x5B, 0x7C, 0xA2, 0x48, 0xAC, 0x25, 0x2D, 0x02, 0x01, 0x9A, 0x86, 0x6B, 0x03, 0xC9, 0xE3, - 0x8A, 0x0E, 0xA5, 0x58, 0x99, 0xE6, 0x3D, 0xB1, 0x7E, 0x3B, 0xA5, 0x77, 0x51, 0xAA, 0x28, 0xA5, - 0x9F, 0xF5, 0xBC, 0x29, 0x7F, 0x88, 0x53, 0x6A, 0x43, 0x5B, 0x5B, 0x9A, 0x78, 0x59, 0x28, 0x80, - 0xAE, 0xCA, 0x27, 0xC1, 0x88, 0x07, 0x56, 0x34, 0xA3, 0xF7, 0x49, 0xF6, 0x05, 0x41, 0x28, 0xC1, - 0x07, 0x70, 0x7E, 0x76, 0xDE, 0x39, 0x6C, 0x62, 0xC0, 0x8B, 0xDF, 0x74, 0x32, 0x0D, 0xEF, 0x65, - 0xB5, 0x35, 0xB8, 0xCE, 0x22, 0xB7, 0xDE, 0xBE, 0xC6, 0x77, 0x56, 0x00, 0xA2, 0x60, 0x22, 0x93, - 0x3E, 0xE8, 0x91, 0x8B, 0xD7, 0x9A, 0x61, 0x22, 0x85, 0x39, 0x54, 0x34, 0xA9, 0xA1, 0xBD, 0x20, - 0x85, 0xFA, 0x21, 0x9E, 0x0B, 0xC1, 0x1D, 0x1F, 0xE9, 0xC4, 0x08, 0x96, 0xA3, 0xE0, 0xBC, 0x90, - 0xC1, 0xCC, 0xF7, 0x71, 0x4A, 0x67, 0xAD, 0xC1, 0x9E, 0x67, 0xDB, 0x33, 0xE7, 0x3F, 0x07, 0x89, - 0xCA, 0x8D, 0x03, 0x31, 0x71, 0xD5, 0xD3, 0xAE, 0x1C, 0x45, 0x92, 0x50, 0x67, 0xE9, 0x91, 0xC4, - 0xFC, 0xF2, 0xAE, 0x0C, 0x90, 0x2C, 0x11, 0xDA, 0xB8, 0x7C, 0xD0, 0x4A, 0xA2, 0x80, 0x6A, 0x28, - 0x54, 0xFA, 0x40, 0xB5, 0x6C, 0x17, 0xFB, 0x52, 0x27, 0xE8, 0x76, 0x20, 0x83, 0x85, 0x14, 0x68, - 0x1B, 0x6B, 0x47, 0x64, 0xD0, 0x00, 0x94, 0x06, 0x64, 0x3D, 0xD5, 0x8E, 0x3A, 0x44, 0xAB, 0xAD, - 0xAB, 0x37, 0xBE, 0xE0, 0x12, 0xDD, 0x5B, 0x91, 0xF7, 0x68, 0xA2, 0x72, 0xB6, 0x81, 0x00, 0xF0, - 0x62, 0x4F, 0x26, 0x46, 0xB6, 0x64, 0x7C, 0x1C, 0x46, 0x29, 0x4F, 0x6E, 0x73, 0x48, 0xF4, 0x8C, - 0xCF, 0x75, 0xA5, 0x98, 0x32, 0x3D, 0xDA, 0xC5, 0x2A, 0x01, 0x72, 0xD3, 0xD8, 0x54, 0x1E, 0x9D, - 0xCA, 0x20, 0xB9, 0x94, 0xDE, 0x73, 0x68, 0xEC, 0x23, 0x1C, 0x53, 0x75, 0xC1, 0x16, 0xAA, 0x53, - 0x06, 0x7C, 0x7C, 0x5F, 0xA4, 0x70, 0x04, 0x09, 0x46, 0xE3, 0x67, 0x8A, 0x08, 0x4C, 0x31, 0x01, - 0x0B, 0xBF, 0xD8, 0xD1, 0xCC, 0x71, 0x4C, 0xE3, 0x27, 0x5E, 0xA3, 0x75, 0xA3, 0xFE, 0xAD, 0xB4, - 0x2F, 0x93, 0xA6, 0xF4, 0x74, 0xAB, 0x06, 0xCF, 0x76, 0xFC, 0x4E, 0xCF, 0xAE, 0x8E, 0x4E, 0x2F, - 0x0F, 0x2F, 0x4E, 0x61, 0x8D, 0x5A, 0xD9, 0x1C, 0x9D, 0x7A, 0xB8, 0x95, 0xAB, 0xCC, 0x29, 0x52, - 0xDE, 0x6B, 0xE7, 0xDB, 0x7B, 0x1A, 0x2A, 0x46, 0x47, 0x9D, 0x61, 0x0B, 0xED, 0x92, 0xB6, 0x9F, - 0xA8, 0x9A, 0x37, 0x65, 0x4B, 0x33, 0xA3, 0x65, 0xFD, 0xC3, 0x8B, 0x9F, 0x0E, 0x2F, 0x6A, 0xB4, - 0x8B, 0xDB, 0x11, 0x02, 0xFD, 0xCD, 0x7D, 0x00, 0x96, 0xBB, 0xC4, 0xFE, 0x06, 0x4E, 0x2C, 0x3F, - 0x22, 0x7E, 0x6E, 0x6D, 0xDD, 0xFF, 0x78, 0x71, 0x71, 0x78, 0x6A, 0xEC, 0xC1, 0xCC, 0x46, 0xC6, - 0x83, 0x18, 0xA6, 0x92, 0xD9, 0x14, 0xED, 0x39, 0x4F, 0xC7, 0xF8, 0xC4, 0x6D, 0x2B, 0x35, 0x6A, - 0xE0, 0xB7, 0x64, 0xC0, 0xC4, 0xFD, 0xF0, 0x87, 0x86, 0xB4, 0xE2, 0x04, 0x2E, 0x74, 0x36, 0xF5, - 0x45, 0x03, 0x0B, 0x06, 0x84, 0x76, 0x7E, 0x6B, 0xB0, 0xAB, 0x32, 0x8A, 0x18, 0xF3, 0x11, 0x99, - 0x1B, 0xA3, 0x3E, 0x4F, 0x86, 0xD8, 0xCF, 0xB3, 0x16, 0x78, 0xE6, 0x71, 0xAA, 0x02, 0x49, 0xA3, - 0x55, 0xE4, 0xCD, 0x37, 0x49, 0x5E, 0x3B, 0xF9, 0xD2, 0x0D, 0xDE, 0xF3, 0xF1, 0x46, 0x9E, 0x4E, - 0x7B, 0x4A, 0xF4, 0x5A, 0xE2, 0xE2, 0x94, 0xB2, 0x96, 0x29, 0x7D, 0x4C, 0xF7, 0x14, 0xB4, 0xFF, - 0xBD, 0x78, 0x13, 0xCD, 0x95, 0xB4, 0xB3, 0xF1, 0xC3, 0x0B, 0x4A, 0x79, 0x41, 0x06, 0x4F, 0x43, - 0xD5, 0xDC, 0xC7, 0xF6, 0x33, 0x54, 0x6A, 0x46, 0x2F, 0x43, 0x63, 0xC8, 0xE4, 0x63, 0x8C, 0x38, - 0x5E, 0x79, 0xC4, 0x49, 0x51, 0x73, 0xD1, 0xB5, 0x13, 0x34, 0xC7, 0xDD, 0x46, 0xE6, 0xA3, 0x97, - 0x46, 0x56, 0x96, 0x8C, 0x86, 0x3E, 0xC2, 0x76, 0x78, 0x71, 0x71, 0xA6, 0x4E, 0x62, 0x8F, 0x34, - 0xB4, 0x8A, 0xAC, 0x30, 0xB3, 0x06, 0x91, 0x18, 0x54, 0xAD, 0x57, 0xDE, 0xA0, 0x55, 0xD7, 0x95, - 0x5E, 0x68, 0x47, 0xD4, 0xC5, 0x0B, 0x8F, 0x62, 0x4B, 0x2F, 0xDA, 0x6A, 0x32, 0xFA, 0x69, 0x59, - 0x72, 0x2A, 0x3F, 0x3C, 0x35, 0x2A, 0x7C, 0x8F, 0x51, 0x7F, 0xE9, 0xB1, 0xAC, 0x09, 0xD7, 0x90, - 0x49, 0x27, 0x1F, 0x3A, 0x99, 0xDD, 0xD4, 0x3E, 0xA5, 0xF6, 0xA0, 0xAC, 0x92, 0x6B, 0xE2, 0xBD, - 0xF3, 0x8D, 0xBA, 0xC4, 0xC6, 0x97, 0x89, 0xFD, 0x66, 0x20, 0xD2, 0xA3, 0xA1, 0x30, 0xEF, 0x71, - 0xA2, 0x82, 0x6E, 0x76, 0x43, 0xE7, 0x86, 0x27, 0x29, 0xC3, 0xA0, 0x40, 0x66, 0x22, 0xC4, 0x02, - 0x15, 0xBF, 0x25, 0xF1, 0xDE, 0xE0, 0x88, 0x91, 0x83, 0x83, 0xCE, 0x30, 0xFA, 0xC7, 0x76, 0xE3, - 0x6D, 0x29, 0xC6, 0x3D, 0xC2, 0x75, 0x84, 0xB6, 0x02, 0x1F, 0x13, 0x6B, 0x21, 0xCD, 0x43, 0x17, - 0x48, 0xA9, 0x8B, 0xFD, 0x08, 0x63, 0x5C, 0x11, 0x9A, 0xAF, 0x3E, 0x43, 0x16, 0x74, 0xF6, 0xCF, - 0xCE, 0x2E, 0x0E, 0x8E, 0x4E, 0xF7, 0x2E, 0x0F, 0xC1, 0x7B, 0x3C, 0xFF, 0x78, 0x79, 0x75, 0xF9, - 0xE9, 0x1C, 0x7F, 0xFD, 0x69, 0xEF, 0xF8, 0xE8, 0xE0, 0xEA, 0xE3, 0xE9, 0x5F, 0x4F, 0xCF, 0x7E, - 0x3E, 0x4D, 0x76, 0xFC, 0x87, 0x76, 0x70, 0x2B, 0x5D, 0xA7, 0x8F, 0xCD, 0x23, 0xC6, 0xE3, 0x1B, - 0xBE, 0x0F, 0xE9, 0xC0, 0x99, 0xD8, 0x63, 0x43, 0x09, 0x37, 0x55, 0x67, 0x37, 0xC7, 0x94, 0x3D, - 0x2F, 0xAA, 0x1F, 0x7D, 0x82, 0xF1, 0x00, 0x67, 0x2D, 0xC4, 0x57, 0xEC, 0x62, 0xB9, 0xF0, 0xC7, - 0xA2, 0xF0, 0xA2, 0x36, 0xAA, 0x17, 0xB9, 0xBB, 0xB5, 0xD9, 0x74, 0x35, 0x62, 0x82, 0x07, 0x19, - 0xCF, 0x82, 0xD8, 0x2A, 0x0F, 0x6C, 0x97, 0x50, 0x14, 0x08, 0x33, 0x99, 0x8E, 0x0B, 0x9D, 0xEF, - 0x0C, 0xD9, 0x95, 0xFB, 0x40, 0x54, 0xD9, 0x23, 0xFC, 0x1B, 0xAF, 0x85, 0xEF, 0xF1, 0xB2, 0x24, - 0x79, 0xFC, 0x90, 0x34, 0x68, 0x93, 0x95, 0x36, 0x06, 0xE3, 0xB6, 0x59, 0x37, 0x75, 0xD4, 0x83, - 0x40, 0xC9, 0xF8, 0xC6, 0x82, 0xD7, 0x4D, 0xAF, 0x7A, 0xC7, 0x38, 0x18, 0x3A, 0x23, 0x27, 0x4C, - 0xBA, 0x09, 0x4F, 0xB8, 0xB3, 0xEE, 0x9B, 0x22, 0x80, 0x2A, 0x36, 0x76, 0xD5, 0xC0, 0x28, 0xAF, - 0xE5, 0xE5, 0xBC, 0xA7, 0x58, 0x64, 0x72, 0x88, 0xA5, 0xB9, 0xD2, 0x5C, 0x4A, 0x3A, 0x70, 0x79, - 0x99, 0x3D, 0xF2, 0x35, 0x1E, 0x93, 0x91, 0xE7, 0x0D, 0x4B, 0x40, 0x13, 0x80, 0x4E, 0xFA, 0xB9, - 0x32, 0x78, 0x07, 0x89, 0x4B, 0xED, 0xCA, 0x43, 0x10, 0x6D, 0xDC, 0xD4, 0x52, 0x56, 0x71, 0x58, - 0xCE, 0xD6, 0x7B, 0xA0, 0x46, 0x18, 0x06, 0x14, 0x28, 0x2A, 0xC0, 0xB2, 0x2E, 0xA8, 0x27, 0x73, - 0xB0, 0x38, 0x40, 0x25, 0x9A, 0x7A, 0x41, 0xE0, 0x60, 0xB0, 0x30, 0xD7, 0x0A, 0x1C, 0xA7, 0x91, - 0xBE, 0x24, 0x43, 0x32, 0xF9, 0x70, 0x72, 0xD2, 0x99, 0xF0, 0x7F, 0xC9, 0x37, 0x62, 0xFA, 0xB8, - 0x62, 0xFA, 0x78, 0x72, 0xD2, 0xEF, 0x77, 0x02, 0xF6, 0x4F, 0x01, 0x27, 0x86, 0xCF, 0x80, 0x60, - 0x25, 0xF9, 0xFC, 0xC2, 0xA8, 0x27, 0xEC, 0x8A, 0xDB, 0xFC, 0x92, 0xFB, 0xBF, 0x18, 0x41, 0xED, - 0x7A, 0x1D, 0xB2, 0x0E, 0xA3, 0x6D, 0xDB, 0x5A, 0x5B, 0x5B, 0x7F, 0xC9, 0x92, 0x13, 0x32, 0xF9, - 0x75, 0x92, 0xF0, 0xED, 0x64, 0xC4, 0xBF, 0xC1, 0x17, 0x7D, 0xE6, 0x27, 0x7C, 0x86, 0xE3, 0xCF, - 0x62, 0x09, 0x33, 0x60, 0xA4, 0xF5, 0x88, 0x3D, 0xC6, 0x94, 0x8D, 0x43, 0x64, 0x84, 0x58, 0x1B, - 0xA4, 0xB7, 0xD1, 0xE9, 0x59, 0xEB, 0xDB, 0x06, 0x56, 0x12, 0x9B, 0xF4, 0x86, 0xAC, 0x2D, 0x98, - 0x93, 0x1E, 0x63, 0x66, 0x2D, 0x61, 0x66, 0xA5, 0x6B, 0x6D, 0xAC, 0x74, 0xBB, 0x2B, 0xD6, 0x46, - 0xA7, 0xBB, 0xD9, 0x33, 0xB1, 0x63, 0xB6, 0x6C, 0x6F, 0xF0, 0x06, 0xC4, 0x82, 0x58, 0x7B, 0x89, - 0x3C, 0xDD, 0xD0, 0x3B, 0xEA, 0x73, 0x7E, 0xBA, 0x5D, 0xE4, 0x66, 0x6B, 0x6B, 0x7B, 0xBB, 0x47, - 0x5A, 0x07, 0x5C, 0xB3, 0xB0, 0x0A, 0xFF, 0x6D, 0x29, 0xE6, 0x31, 0x71, 0x67, 0x5D, 0x3A, 0xB2, - 0x43, 0xB0, 0x9B, 0x7D, 0x67, 0xE4, 0xAA, 0xDE, 0x83, 0x3A, 0x76, 0xAD, 0xC4, 0x70, 0x24, 0x56, - 0x2A, 0x2E, 0xE6, 0x7E, 0x17, 0xDE, 0x3A, 0xD8, 0x93, 0x8C, 0x5B, 0x1B, 0x45, 0x87, 0x17, 0x03, - 0xD8, 0x31, 0x18, 0x5E, 0x4D, 0x00, 0xE3, 0xC5, 0x44, 0xC1, 0xCD, 0x47, 0x72, 0x11, 0x49, 0x65, - 0x42, 0x8D, 0x7A, 0x8A, 0x3B, 0x75, 0x65, 0x05, 0x11, 0x61, 0x96, 0xD1, 0xA4, 0x9F, 0xC1, 0x5A, - 0xE3, 0x9C, 0xC9, 0x77, 0x2C, 0xD8, 0xE3, 0xE5, 0xC1, 0x2D, 0xE5, 0x16, 0x9C, 0x27, 0x27, 0x65, - 0x79, 0x3B, 0x04, 0xD1, 0x88, 0x0C, 0x09, 0x80, 0x8E, 0xBE, 0x9B, 0x27, 0xEB, 0x31, 0x37, 0xB4, - 0xB8, 0xA6, 0x92, 0x66, 0xB9, 0xF8, 0x5B, 0x46, 0xBF, 0xEE, 0xB2, 0xAB, 0x2D, 0xF8, 0x76, 0x66, - 0x66, 0xF9, 0xE6, 0x12, 0x2C, 0xC8, 0x56, 0x57, 0xD3, 0x23, 0x5E, 0x7E, 0xDF, 0xBC, 0xFE, 0x5C, - 0xCD, 0xF1, 0x4A, 0x21, 0x0B, 0x3C, 0x47, 0x09, 0x3B, 0x91, 0xE2, 0x77, 0x9C, 0xD8, 0x39, 0x2D, - 0x88, 0xD7, 0x1D, 0x44, 0x57, 0xC7, 0x13, 0x87, 0x81, 0x75, 0x13, 0x38, 0x9F, 0x44, 0xE8, 0x8D, - 0x82, 0x45, 0xD8, 0x17, 0x15, 0x85, 0x84, 0x9A, 0x5F, 0x1C, 0xB7, 0x64, 0x1C, 0xC9, 0xC4, 0x97, - 0x54, 0x5B, 0xD9, 0x8D, 0x4D, 0x15, 0x3F, 0x90, 0x56, 0x2E, 0x9B, 0xB3, 0x3C, 0xC7, 0x3C, 0xB7, - 0x7E, 0x3E, 0xA1, 0x98, 0xCC, 0xC9, 0x89, 0x1C, 0x34, 0xF8, 0xCE, 0x81, 0x29, 0x1A, 0xA6, 0x17, - 0x65, 0xCA, 0x4D, 0x26, 0x66, 0x76, 0xF3, 0xEA, 0xEC, 0xA6, 0xC5, 0x26, 0x20, 0xE8, 0x8D, 0x95, - 0xAE, 0x7E, 0x70, 0x30, 0xAF, 0xE8, 0xAF, 0x4E, 0xCF, 0xAE, 0x0E, 0x0E, 0xF7, 0x8F, 0x4E, 0xF6, - 0x8E, 0xB5, 0x5E, 0x08, 0x28, 0x4C, 0x40, 0x43, 0x6C, 0x56, 0xCC, 0x8F, 0x26, 0x6E, 0x59, 0x1D, - 0xF8, 0xE2, 0x8A, 0x43, 0x18, 0x45, 0x96, 0x0C, 0x28, 0x59, 0xD0, 0x32, 0x48, 0x24, 0xC7, 0x3F, - 0xC7, 0xF2, 0x12, 0x00, 0x20, 0x32, 0x29, 0x46, 0xCF, 0xE0, 0x5A, 0x45, 0xC4, 0x96, 0x13, 0x24, - 0xAB, 0x64, 0x13, 0xA6, 0x00, 0x96, 0x71, 0x20, 0xA2, 0xB1, 0x4A, 0xD6, 0x36, 0x31, 0xD5, 0xCE, - 0x92, 0x76, 0x65, 0x5E, 0x19, 0xC9, 0x66, 0xBF, 0xC6, 0x44, 0xF6, 0xCF, 0xD8, 0x1D, 0xF2, 0x03, - 0xA0, 0x0F, 0xA6, 0xD5, 0x93, 0x36, 0x44, 0x71, 0x34, 0xAA, 0x03, 0x94, 0x8D, 0xCF, 0xCC, 0xE1, - 0xB7, 0x81, 0xA3, 0x33, 0xB3, 0x74, 0x3D, 0x1E, 0x9B, 0xCA, 0x0C, 0xBD, 0xB8, 0xA1, 0x59, 0x72, - 0x60, 0x26, 0x23, 0x52, 0xD1, 0x90, 0x8C, 0xE1, 0xA8, 0x0F, 0x8D, 0xAA, 0x03, 0x30, 0x73, 0xF8, - 0x99, 0xF5, 0x54, 0x11, 0x0D, 0x0B, 0x83, 0x16, 0x00, 0x06, 0xC4, 0x66, 0x25, 0xAD, 0xAA, 0x74, - 0x8F, 0xAC, 0x5F, 0xAA, 0x82, 0x29, 0xDA, 0xD4, 0xE5, 0xFA, 0xB0, 0xF2, 0x48, 0x0A, 0x71, 0x75, - 0x72, 0x72, 0x75, 0xB0, 0xD7, 0xFF, 0xA0, 0xA9, 0x85, 0x08, 0xC6, 0x4A, 0xCC, 0x96, 0xB8, 0x6A, - 0xB7, 0xA2, 0x5F, 0xC5, 0x4C, 0x74, 0x40, 0x98, 0x72, 0x84, 0xC4, 0xE4, 0x4E, 0x49, 0x87, 0x65, - 0x74, 0xAD, 0x5C, 0xBF, 0xFB, 0x45, 0x32, 0xA6, 0xA9, 0xDE, 0x7D, 0x66, 0x9D, 0x95, 0xDD, 0x57, - 0xBD, 0xB8, 0xAF, 0x22, 0xEF, 0x78, 0xE1, 0x7D, 0x05, 0xE6, 0xFD, 0x99, 0x75, 0xD7, 0xB3, 0x99, - 0xFB, 0x24, 0xF1, 0x94, 0x99, 0x02, 0xE5, 0x06, 0xF5, 0x92, 0x06, 0xA5, 0xE7, 0xC0, 0x7F, 0xF6, - 0x09, 0x8A, 0x2B, 0x65, 0xB2, 0x81, 0xB3, 0x50, 0x9D, 0xDC, 0x29, 0x10, 0x53, 0x62, 0xC0, 0x7F, - 0x37, 0x01, 0x08, 0x0B, 0x4A, 0x1E, 0xCF, 0x82, 0x96, 0x1C, 0x8D, 0xE4, 0x87, 0xF1, 0xCC, 0xEB, - 0xA7, 0x5E, 0xDC, 0x4F, 0xE4, 0x71, 0xD6, 0x25, 0xDC, 0x40, 0x3C, 0xA3, 0xCE, 0x7A, 0x6E, 0xA6, - 0xF3, 0x7F, 0x9A, 0xD5, 0x14, 0x1B, 0x5A, 0xCA, 0xC9, 0x90, 0x01, 0x01, 0x3F, 0x1C, 0x32, 0x14, - 0xC4, 0xA9, 0xC7, 0xB6, 0x97, 0xB4, 0xBC, 0x03, 0x86, 0xEE, 0xE0, 0x67, 0x3E, 0xC9, 0xC6, 0xBC, - 0xB4, 0xC3, 0x8E, 0x9B, 0xBA, 0xC9, 0xFD, 0xFC, 0x36, 0xF1, 0x66, 0x21, 0xFE, 0x61, 0x8B, 0x5D, - 0x7B, 0x00, 0xEA, 0x7B, 0xEA, 0x1E, 0x3C, 0x6E, 0x28, 0x5F, 0x83, 0xB4, 0x26, 0x94, 0x34, 0xB5, - 0x21, 0xD3, 0x6C, 0x13, 0x1A, 0x0E, 0xE4, 0x88, 0x63, 0xC6, 0x37, 0xE3, 0x43, 0xE2, 0xAB, 0x6D, - 0x52, 0x19, 0xF3, 0x7E, 0xBD, 0xD8, 0xBC, 0x94, 0x0E, 0x1A, 0xF9, 0xC5, 0x0C, 0x83, 0xC6, 0x95, - 0x57, 0xB9, 0x25, 0xE3, 0xB0, 0x4E, 0x34, 0x2C, 0xF9, 0xB6, 0x24, 0x89, 0x59, 0x3F, 0xAD, 0x95, - 0xD9, 0x30, 0x9F, 0x75, 0xCD, 0xC9, 0xE6, 0x95, 0xB4, 0xE6, 0x81, 0x75, 0xDB, 0x9C, 0xD8, 0x16, - 0x8A, 0x2C, 0x72, 0xDD, 0x17, 0x8C, 0xB2, 0xFF, 0xE9, 0xE4, 0xED, 0xD9, 0x31, 0x43, 0xAA, 0xDF, - 0x78, 0x19, 0x7B, 0xEE, 0x88, 0x25, 0x79, 0x3A, 0xA0, 0x23, 0x9F, 0xEA, 0xFB, 0x23, 0xA9, 0x9E, - 0xD0, 0xBA, 0x16, 0x16, 0x67, 0x3A, 0x02, 0x63, 0x3D, 0x18, 0xAE, 0x9B, 0xD6, 0x8E, 0x96, 0x38, - 0x33, 0x2E, 0x7D, 0x4D, 0x32, 0x2D, 0x1F, 0x1F, 0xE8, 0x92, 0xE9, 0x52, 0xF4, 0x6A, 0x90, 0x1E, - 0xB6, 0x2F, 0x97, 0x52, 0x09, 0x3A, 0xE7, 0xEC, 0xDE, 0x2C, 0xD6, 0xE2, 0x21, 0x94, 0x12, 0xE1, - 0x32, 0x8C, 0x2A, 0x66, 0x5D, 0xA2, 0xAA, 0x3B, 0xE9, 0xC3, 0x8B, 0x05, 0x29, 0x4A, 0x2D, 0xE6, - 0x56, 0x9E, 0x82, 0x3B, 0xAE, 0x73, 0xB5, 0xF8, 0xFB, 0xEF, 0xFF, 0x52, 0x19, 0xC4, 0x6F, 0xCD, - 0x86, 0xCA, 0x66, 0x1D, 0xBC, 0xC4, 0xD4, 0x6E, 0xCD, 0xB6, 0x2C, 0xA4, 0xE9, 0xFD, 0x25, 0x79, - 0x00, 0xCF, 0xAF, 0x82, 0x0B, 0x46, 0x28, 0xAD, 0xAA, 0x1E, 0x03, 0xAF, 0xDE, 0xF3, 0x0B, 0x12, - 0x81, 0xE4, 0xCA, 0x3C, 0x06, 0xD7, 0x8F, 0x8B, 0x5D, 0x5B, 0xC1, 0x2E, 0xFD, 0xB3, 0x9B, 0x61, - 0x85, 0xE7, 0x13, 0xD3, 0xD6, 0x7A, 0x15, 0x9E, 0x05, 0x82, 0x3C, 0x9E, 0x4B, 0x4F, 0x00, 0x9B, - 0x0B, 0x9F, 0x00, 0xE4, 0xD1, 0x57, 0x71, 0x0A, 0x48, 0x89, 0xE8, 0x89, 0xA6, 0x86, 0xD4, 0xE8, - 0xAE, 0x3A, 0x3B, 0x98, 0x18, 0x5F, 0x79, 0x22, 0xCE, 0xE7, 0x9E, 0x39, 0x4C, 0xCC, 0x37, 0xD3, - 0x53, 0xCA, 0xDF, 0x1A, 0x8D, 0xC7, 0x6A, 0xC3, 0x52, 0xED, 0xE9, 0xC9, 0xC4, 0x3B, 0x79, 0x6C, - 0xC1, 0x67, 0x9A, 0xD7, 0x05, 0xA9, 0xBB, 0x74, 0x8B, 0xD3, 0x68, 0x16, 0x16, 0xAC, 0x40, 0x73, - 0xB6, 0x24, 0xBF, 0x1F, 0x9E, 0xB8, 0x2D, 0xFA, 0xC4, 0xB1, 0xF8, 0x11, 0x9D, 0xD7, 0xA0, 0xD4, - 0x2D, 0x27, 0x95, 0x9E, 0x16, 0xF3, 0x18, 0x05, 0x21, 0x0D, 0xF0, 0xC5, 0x49, 0x01, 0xB3, 0xFA, - 0xB7, 0xE1, 0x6A, 0x27, 0xC4, 0xFB, 0xDA, 0x83, 0xA5, 0x1D, 0xA2, 0xE6, 0x93, 0x88, 0xCE, 0xF5, - 0x61, 0x49, 0xDC, 0xE6, 0xE9, 0x2B, 0x61, 0x05, 0x7B, 0xEB, 0xCB, 0x41, 0x92, 0x3C, 0xF7, 0xE6, - 0x1B, 0x5C, 0x35, 0x47, 0xF7, 0xB2, 0x56, 0xA4, 0x20, 0x14, 0xF8, 0xAC, 0x2C, 0xD2, 0xB1, 0x9A, - 0x92, 0x35, 0x52, 0x64, 0xE6, 0x5C, 0x46, 0xBC, 0x18, 0x0D, 0xAA, 0x94, 0x73, 0xE4, 0xCB, 0x2C, - 0xC7, 0xBE, 0xBC, 0x8E, 0x77, 0x95, 0x95, 0xBB, 0x40, 0x6D, 0xE3, 0x83, 0x9F, 0x2E, 0x4F, 0xF4, - 0x27, 0xD6, 0xF0, 0xD2, 0x55, 0x6A, 0x51, 0x92, 0xC4, 0xCB, 0xE5, 0xAC, 0xC4, 0x83, 0x3B, 0x27, - 0x1C, 0xDC, 0x92, 0xBC, 0x2A, 0x2C, 0x3C, 0x81, 0xDE, 0xD8, 0xB3, 0x71, 0xF8, 0x4A, 0x7B, 0x2A, - 0x80, 0xF7, 0x44, 0xE3, 0xA3, 0xFB, 0xD5, 0xF5, 0xEE, 0x5C, 0x3D, 0xDF, 0xAE, 0xF6, 0x2C, 0xC5, - 0x00, 0xEF, 0x34, 0xB7, 0x4A, 0xAF, 0xDF, 0x33, 0x68, 0xC9, 0xDB, 0x14, 0x0B, 0x25, 0x08, 0x8B, - 0xAB, 0x4C, 0x92, 0xC9, 0xBE, 0xE7, 0x42, 0x49, 0x5E, 0xE5, 0xD1, 0x24, 0x8F, 0x47, 0x94, 0xCF, - 0xC7, 0x99, 0x94, 0x57, 0x1E, 0x89, 0x32, 0xF3, 0x5E, 0x72, 0x64, 0x1C, 0x6F, 0x31, 0x2D, 0xBC, - 0xBD, 0x79, 0x74, 0x95, 0xCD, 0xAD, 0x47, 0xA0, 0x5C, 0x2C, 0xEC, 0x95, 0xC7, 0x21, 0xAF, 0x4F, - 0xA4, 0xB9, 0x92, 0x7F, 0x8C, 0x86, 0x97, 0xA1, 0xCD, 0xA5, 0xFF, 0x58, 0x62, 0x2F, 0xC5, 0x02, - 0xEF, 0x81, 0x1C, 0x16, 0x1E, 0x5E, 0x64, 0x59, 0xBB, 0x87, 0x17, 0xFF, 0x1F, 0x05, 0x0E, 0xB1, - 0x58, 0x1D, 0xAA, 0x00 + 0xF9, 0x14, 0x5A, 0xDF, 0xBD, 0x6B, 0xB3, 0x01, 0xD3, 0x36, 0x8F, 0x40, 0x08, 0x39, 0x97, 0x00, + 0x49, 0xB8, 0xCB, 0xC3, 0x8B, 0xC9, 0xCC, 0x64, 0x72, 0x72, 0x38, 0x8D, 0x2D, 0x4C, 0x9F, 0xD8, + 0xDD, 0xDE, 0xEE, 0x76, 0x08, 0xBB, 0x87, 0xEF, 0x74, 0x3E, 0xC3, 0xFD, 0x64, 0xB7, 0x4A, 0x52, + 0x77, 0x4B, 0x6A, 0xF5, 0xD3, 0x86, 0x30, 0x33, 0xC9, 0x6F, 0x97, 0x81, 0x96, 0xEA, 0xA1, 0x52, + 0xA9, 0x54, 0x7A, 0x55, 0x7D, 0xB5, 0x7D, 0x32, 0xB2, 0x43, 0x7A, 0x6B, 0xDF, 0x91, 0x5D, 0xF2, + 0x9F, 0xB7, 0xC1, 0xCB, 0xD5, 0xD5, 0x3F, 0xFF, 0xEB, 0xD6, 0x71, 0x87, 0xDE, 0x6D, 0x7B, 0xEC, + 0x0D, 0xEC, 0xD0, 0xF1, 0xDC, 0xF6, 0x8D, 0x17, 0x84, 0xAE, 0x3D, 0xA1, 0xF7, 0x2F, 0xB7, 0x3A, + 0xAB, 0xB7, 0xC1, 0x7F, 0xEE, 0x3C, 0xFB, 0x0A, 0x70, 0xB7, 0xF4, 0x2A, 0xF0, 0x06, 0x5F, 0x68, + 0xB8, 0xF3, 0xEC, 0x99, 0x80, 0xB0, 0x87, 0xC3, 0xC3, 0xAF, 0xD4, 0x0D, 0x8F, 0x9D, 0x20, 0xA4, + 0x2E, 0xF5, 0x5B, 0xCD, 0xB1, 0x67, 0x0F, 0x9B, 0xCB, 0xC4, 0x73, 0x8F, 0xE1, 0x97, 0x25, 0xA8, + 0x79, 0x3D, 0x73, 0x07, 0x88, 0x54, 0x7C, 0x6A, 0x51, 0xAC, 0xBF, 0x44, 0xFE, 0xF5, 0x8C, 0xC0, + 0x3F, 0xC7, 0x75, 0xC2, 0x9F, 0xE9, 0x55, 0x9F, 0xA1, 0x6D, 0x41, 0xF5, 0x7B, 0x09, 0x40, 0x2B, + 0x14, 0x20, 0x31, 0x17, 0xC0, 0xBF, 0x4B, 0x6F, 0x49, 0x52, 0x43, 0xB4, 0x0B, 0xB0, 0x28, 0xF5, + 0xDA, 0x9E, 0x3B, 0xA1, 0x41, 0x60, 0x8F, 0x28, 0x40, 0xC4, 0xC8, 0x5B, 0x93, 0x60, 0x14, 0xA1, + 0xC4, 0x7F, 0x53, 0xDB, 0x0F, 0xE8, 0x91, 0x3B, 0xF0, 0x26, 0x8E, 0x3B, 0xC2, 0xC2, 0xF6, 0xD0, + 0x0E, 0x6D, 0x81, 0xEB, 0x5E, 0x65, 0x6C, 0x44, 0x5B, 0x34, 0x82, 0xF5, 0x69, 0x38, 0xF3, 0x5D, + 0x32, 0xF4, 0x06, 0xB3, 0x09, 0x34, 0xAC, 0x3D, 0xA2, 0xE1, 0xE1, 0x98, 0xE2, 0xAF, 0x6F, 0xEE, + 0x8E, 0xA0, 0xB5, 0xBC, 0x4D, 0x28, 0xBE, 0x6B, 0xE7, 0x1B, 0x1D, 0x1E, 0xDB, 0xC8, 0xB7, 0xB5, + 0x23, 0x7D, 0xF1, 0xDC, 0x51, 0xF2, 0x69, 0x3A, 0xB6, 0xC3, 0x6B, 0xCF, 0x9F, 0xF4, 0x7C, 0x0A, + 0xA5, 0xF0, 0xBD, 0xD1, 0xE0, 0x05, 0x23, 0xEA, 0x0D, 0x69, 0xE8, 0x0C, 0x38, 0x82, 0x75, 0xAB, + 0x6D, 0x75, 0xB4, 0x02, 0x60, 0x6C, 0x97, 0xAC, 0x74, 0xAC, 0x8D, 0x76, 0x67, 0x5B, 0x2D, 0xDA, + 0x1B, 0x23, 0x4C, 0x67, 0xC3, 0xB2, 0xDA, 0x02, 0x88, 0x0E, 0xE8, 0xF5, 0x2F, 0xAC, 0x7A, 0x77, + 0xCB, 0xEA, 0x5A, 0x9B, 0xED, 0x8D, 0xCD, 0xAD, 0xA4, 0xE4, 0x23, 0x96, 0xAC, 0xBF, 0xE8, 0x6C, + 0x6E, 0x59, 0xEB, 0xED, 0x75, 0x6B, 0x2D, 0x29, 0xF9, 0x95, 0xD1, 0xDE, 0xDA, 0xDC, 0xDC, 0xDC, + 0x68, 0xAF, 0x6F, 0xAD, 0xF3, 0x82, 0xB1, 0x1D, 0x84, 0x6F, 0x9D, 0x31, 0x3D, 0x05, 0x8D, 0x91, + 0x38, 0xBE, 0xC6, 0x4F, 0xB3, 0xC9, 0x15, 0xF5, 0x93, 0xE6, 0xB9, 0xEC, 0xEF, 0xB3, 0x6B, 0xAC, + 0x1E, 0xF4, 0xE9, 0x98, 0x0E, 0x42, 0x3A, 0x4C, 0x8A, 0x03, 0xF1, 0x85, 0x15, 0x4B, 0xA8, 0x82, + 0x1B, 0x0F, 0x14, 0x6E, 0x84, 0x9F, 0x51, 0xD3, 0xB0, 0x1F, 0xED, 0x71, 0x40, 0x79, 0xA1, 0x77, + 0x15, 0xDA, 0x8E, 0x4B, 0x87, 0x27, 0xBC, 0x93, 0x4B, 0x55, 0x78, 0x63, 0x07, 0x54, 0xAD, 0x24, + 0x48, 0x88, 0x3A, 0xE7, 0x17, 0xFB, 0x27, 0x69, 0x44, 0xD8, 0xA2, 0x0B, 0xFB, 0x0A, 0x7E, 0xD0, + 0x6F, 0xA1, 0xC4, 0xDE, 0xC0, 0xF3, 0x7D, 0xCA, 0x54, 0x43, 0x2B, 0x10, 0x7A, 0xA7, 0x7D, 0x45, + 0x79, 0x09, 0x3A, 0x17, 0x77, 0x53, 0x9A, 0x5D, 0x22, 0xB8, 0xC4, 0x52, 0xCE, 0xA3, 0xFD, 0x35, + 0x6E, 0x05, 0x0A, 0x1B, 0x45, 0xF4, 0xE9, 0xF3, 0x4E, 0xAA, 0xEC, 0x27, 0x7B, 0x3C, 0x4B, 0x17, + 0xEE, 0xDF, 0xD0, 0xC1, 0x97, 0x2B, 0xEF, 0x9B, 0x11, 0x32, 0x2A, 0x54, 0x40, 0x59, 0x31, 0xB4, + 0xCC, 0xF3, 0x87, 0xC1, 0xE1, 0xFE, 0xE1, 0x5B, 0x09, 0x48, 0x7C, 0x7D, 0x27, 0x34, 0x4C, 0x2A, + 0xB9, 0x9E, 0x8D, 0xC7, 0x3D, 0x60, 0xE2, 0xC3, 0x14, 0x06, 0x90, 0x24, 0x64, 0x01, 0x16, 0xD0, + 0xF0, 0xC2, 0x99, 0x50, 0x6F, 0x16, 0x46, 0x5D, 0xEE, 0x0E, 0x0F, 0x60, 0xA4, 0x29, 0x1F, 0x07, + 0xC8, 0xCD, 0x29, 0xBD, 0x7D, 0xEB, 0xF8, 0x93, 0x5B, 0xDB, 0xA7, 0x4A, 0x21, 0x8C, 0x30, 0x53, + 0xD1, 0xB3, 0x81, 0xE7, 0x42, 0x87, 0x81, 0x86, 0xED, 0xC7, 0xDD, 0x11, 0xF4, 0xBD, 0x99, 0x3F, + 0x60, 0xED, 0xD9, 0xD2, 0xBB, 0x4A, 0x94, 0xE9, 0xD2, 0x48, 0x55, 0xE8, 0xF9, 0x8E, 0xE7, 0x3B, + 0xA1, 0x93, 0x48, 0x85, 0x13, 0xDA, 0xF7, 0x40, 0x00, 0x8E, 0x0B, 0x6D, 0xC4, 0xAE, 0xC2, 0x42, + 0x6E, 0x10, 0xF6, 0xCF, 0xCE, 0xCE, 0x0F, 0x8E, 0x4E, 0xF7, 0x2E, 0x0E, 0x2F, 0x8F, 0x4E, 0x7B, + 0x1F, 0x2E, 0x2E, 0x2F, 0x3E, 0xF6, 0x0E, 0x2F, 0x0F, 0x0E, 0x5E, 0x12, 0x6B, 0x99, 0xAC, 0xAE, + 0x1E, 0xD0, 0x6B, 0x7B, 0x06, 0xE3, 0xF1, 0xE0, 0xA0, 0x3D, 0x8C, 0xFE, 0xE5, 0xC2, 0x9D, 0x9C, + 0xBC, 0x24, 0x1D, 0x06, 0x09, 0xBF, 0xB6, 0x27, 0xF8, 0x2F, 0xB7, 0xFE, 0x25, 0x02, 0x74, 0x39, + 0x00, 0x29, 0x0B, 0x71, 0x79, 0xB0, 0xD7, 0x7F, 0xFF, 0x92, 0xAC, 0x71, 0xB0, 0x95, 0xD2, 0x60, + 0xFD, 0x8F, 0x27, 0x6F, 0xCE, 0x8E, 0x5F, 0x92, 0x75, 0x0E, 0xF8, 0xFF, 0xFE, 0x27, 0x82, 0x9C, + 0x4C, 0x9A, 0x05, 0xAD, 0xEA, 0xF7, 0x5F, 0x92, 0x8D, 0x98, 0x4D, 0xD2, 0xEF, 0xB7, 0x03, 0xF6, + 0xAF, 0x98, 0x26, 0x00, 0x6E, 0xD6, 0x03, 0x14, 0xCD, 0x7C, 0x11, 0x37, 0x73, 0xA5, 0x12, 0x74, + 0xD4, 0xDA, 0xAD, 0xA4, 0xB5, 0xCD, 0x18, 0x41, 0xA3, 0xB0, 0xBD, 0x97, 0xA7, 0x67, 0x97, 0x07, + 0x87, 0xFB, 0x47, 0x27, 0x7B, 0x80, 0x63, 0x3B, 0xEA, 0xD2, 0x7E, 0x9F, 0xAC, 0x90, 0x53, 0x8F, + 0x0C, 0xE9, 0xC0, 0x99, 0xD8, 0xE3, 0x32, 0x7C, 0xC8, 0x78, 0x3A, 0x96, 0x2C, 0x8A, 0xCA, 0xA8, + 0x50, 0x20, 0x2A, 0xBE, 0x8E, 0x2C, 0x9C, 0xB2, 0xF8, 0x8E, 0x4E, 0x7F, 0xDA, 0x3B, 0x3E, 0x3A, + 0xB8, 0xFC, 0x70, 0xFA, 0xB7, 0xD3, 0xB3, 0x9F, 0x4F, 0x01, 0x4D, 0x77, 0x39, 0x9A, 0xF7, 0x60, + 0xB8, 0x7C, 0xA5, 0x3E, 0x58, 0xF5, 0x64, 0xC4, 0xA0, 0xC5, 0x6F, 0x5B, 0xD1, 0x80, 0x8B, 0xBE, + 0x1E, 0xB9, 0xD3, 0x59, 0x28, 0x2C, 0xA2, 0x36, 0xBA, 0xDA, 0x59, 0xCD, 0x10, 0x76, 0x05, 0x5D, + 0x05, 0xC7, 0x1E, 0xF7, 0x69, 0x18, 0x82, 0x11, 0x67, 0x83, 0xF1, 0x5E, 0xF6, 0x3D, 0x52, 0xB3, + 0x7B, 0x34, 0x7D, 0xAF, 0xAE, 0xE2, 0x68, 0xF6, 0xC6, 0x14, 0x9C, 0x9F, 0x51, 0xAB, 0x11, 0x55, + 0x89, 0x2C, 0xF7, 0x4B, 0xD2, 0x20, 0xCF, 0x09, 0xD6, 0x07, 0x6C, 0x58, 0x1F, 0x89, 0xA1, 0x63, + 0x00, 0x14, 0xD0, 0x47, 0x08, 0xA6, 0x63, 0x27, 0x6C, 0x35, 0x97, 0x9B, 0xC2, 0x51, 0x80, 0xA9, + 0x9B, 0xB4, 0xC6, 0xE0, 0x9B, 0x7C, 0x63, 0x93, 0x1A, 0xFC, 0xE7, 0x15, 0xAB, 0xDE, 0x1E, 0x53, + 0x77, 0x14, 0xDE, 0x80, 0x38, 0x3B, 0xF8, 0xF1, 0xF9, 0x2E, 0xE9, 0xCA, 0xCE, 0x07, 0x6B, 0x02, + 0xCE, 0x83, 0x58, 0xF7, 0xD3, 0xB7, 0xCF, 0x3B, 0x4A, 0xC9, 0x57, 0x7B, 0x1C, 0x17, 0x01, 0x37, + 0x1D, 0xA9, 0x58, 0x63, 0xDF, 0x19, 0x72, 0x86, 0x01, 0xD7, 0x73, 0xD2, 0x58, 0x46, 0x48, 0xFE, + 0x01, 0x7E, 0x89, 0x5A, 0xC0, 0xC1, 0xFA, 0x53, 0xE8, 0x53, 0xC0, 0x0B, 0xCD, 0x9D, 0xD8, 0xEE, + 0x30, 0x88, 0x8B, 0x9C, 0x6B, 0xD2, 0x72, 0x86, 0x6D, 0xC7, 0x1D, 0x8C, 0x67, 0x43, 0x1A, 0xB4, + 0x1A, 0xC1, 0xF0, 0xC4, 0x9B, 0xB9, 0xD0, 0x7D, 0x8D, 0x25, 0x99, 0x65, 0x8E, 0xE6, 0x02, 0x7D, + 0x1F, 0xCF, 0x5D, 0xF5, 0xAE, 0xAF, 0x49, 0xFF, 0x80, 0x80, 0x3D, 0xB6, 0x95, 0x1A, 0x88, 0x8D, + 0xB1, 0x0F, 0xB3, 0x18, 0x9B, 0x07, 0x1A, 0x3A, 0x0E, 0xFC, 0x77, 0xE3, 0x0C, 0x69, 0xAB, 0x81, + 0xB3, 0xEB, 0x89, 0xED, 0x82, 0xD4, 0xFD, 0xC6, 0xD2, 0x8E, 0x52, 0xE9, 0x5E, 0xF9, 0x8B, 0x02, + 0x1E, 0x05, 0x73, 0xE8, 0xCF, 0xCC, 0x88, 0x71, 0x52, 0x2F, 0x89, 0x38, 0xF9, 0x2D, 0x46, 0x8F, + 0x3D, 0x02, 0xD8, 0x55, 0x97, 0x2C, 0x45, 0x27, 0xE5, 0xB1, 0x01, 0x57, 0x2A, 0x91, 0xD8, 0x37, + 0x0C, 0x9D, 0x70, 0xCC, 0x26, 0xF4, 0xF3, 0x8B, 0xBF, 0xB1, 0x6E, 0xD1, 0x60, 0xA1, 0xCF, 0x08, + 0xA8, 0xF0, 0x6C, 0xDA, 0x50, 0x11, 0xA4, 0xA6, 0x54, 0x6C, 0xB0, 0x5A, 0xC5, 0xE8, 0x82, 0xA4, + 0xBA, 0x42, 0xE7, 0x15, 0xAA, 0x1D, 0xFE, 0xF4, 0xB7, 0x1C, 0xD1, 0x5D, 0x81, 0x07, 0xB2, 0xEF, + 0xB9, 0xD7, 0xCE, 0x48, 0x97, 0x5C, 0x52, 0x67, 0x3A, 0x2D, 0xAA, 0x41, 0xC3, 0x1B, 0xEA, 0xBB, + 0x34, 0x2C, 0xAA, 0xE7, 0x86, 0x85, 0xA8, 0xA6, 0x9E, 0x1F, 0x06, 0xD9, 0x95, 0xB8, 0x26, 0x81, + 0x04, 0x80, 0x9E, 0x3D, 0xEE, 0x41, 0xE5, 0xB3, 0x29, 0x9B, 0xCB, 0xB3, 0x31, 0xC2, 0xC0, 0xB9, + 0xF0, 0xFA, 0x07, 0xFB, 0xB6, 0x3F, 0xCC, 0xC6, 0x38, 0xB2, 0xC7, 0xA0, 0x44, 0xDE, 0x7B, 0x3B, + 0x10, 0x26, 0x26, 0xBB, 0xEA, 0x78, 0xD4, 0xDD, 0xB6, 0xA6, 0xEF, 0xDC, 0x20, 0xAA, 0x1A, 0x64, + 0xD7, 0x0D, 0x9D, 0x71, 0x58, 0xD4, 0x98, 0x2B, 0x4A, 0xA7, 0xD4, 0x87, 0x5A, 0xA1, 0xEF, 0x8D, + 0xB3, 0x9B, 0x31, 0xA1, 0x76, 0x30, 0xF3, 0xD9, 0xC2, 0xE3, 0x3C, 0xB2, 0xA5, 0xD9, 0x48, 0x27, + 0x5E, 0x60, 0x3B, 0x83, 0xD3, 0x93, 0xC3, 0xBD, 0x7E, 0x08, 0x63, 0x76, 0x72, 0xE0, 0x7B, 0x53, + 0x58, 0xCF, 0xE5, 0xC9, 0x09, 0xB0, 0x7F, 0xA5, 0x77, 0x47, 0xAE, 0xDC, 0xAA, 0x8C, 0xAA, 0xB3, + 0x80, 0x1E, 0xBA, 0xE8, 0x27, 0x1F, 0x7E, 0x0B, 0xD1, 0x19, 0x3B, 0xB7, 0x87, 0x8E, 0x97, 0xA3, + 0x1E, 0x52, 0xAD, 0x7E, 0x6F, 0xEF, 0xFC, 0xE2, 0x94, 0x7B, 0x5E, 0x11, 0x53, 0x39, 0x1D, 0xCD, + 0xA8, 0x9C, 0x42, 0xDB, 0xCF, 0xDC, 0x98, 0x48, 0x46, 0xDD, 0xE0, 0x66, 0x16, 0x22, 0xB6, 0x53, + 0x6F, 0xFF, 0xC6, 0xF6, 0x47, 0x91, 0xE3, 0x78, 0xE2, 0xB8, 0xB3, 0x90, 0x06, 0x91, 0xFF, 0x7B, + 0x40, 0x61, 0xAD, 0x30, 0xCE, 0x41, 0xC3, 0x9C, 0x3F, 0x3A, 0x1E, 0xB3, 0x85, 0xF2, 0xA9, 0xFD, + 0xD5, 0x19, 0x40, 0x65, 0xB0, 0x84, 0xA7, 0x5E, 0x48, 0x82, 0xD9, 0x14, 0xF5, 0x13, 0x56, 0x34, + 0x30, 0xE5, 0xFC, 0x7A, 0x78, 0x60, 0x90, 0x0F, 0x5B, 0xE0, 0xC0, 0xF0, 0x84, 0x25, 0x24, 0xE8, + 0xB2, 0xE3, 0x86, 0x3D, 0xEA, 0x5F, 0xC3, 0xA7, 0x3E, 0xF5, 0x01, 0x15, 0x35, 0x35, 0x15, 0xA7, + 0x13, 0x58, 0xE8, 0x72, 0x45, 0x16, 0x8B, 0x5E, 0xFE, 0x47, 0xAB, 0x79, 0xE0, 0x04, 0x28, 0x01, + 0x5C, 0x71, 0x37, 0xAD, 0xA6, 0x49, 0xC2, 0x8C, 0x20, 0xAE, 0xD3, 0x5B, 0x31, 0x8E, 0x65, 0x32, + 0x73, 0x87, 0x60, 0x00, 0x60, 0x49, 0x64, 0x80, 0xC8, 0x22, 0xF5, 0x76, 0x4C, 0xBF, 0x91, 0xD3, + 0x8B, 0xF3, 0xA3, 0xDE, 0x2A, 0xAE, 0x8E, 0x90, 0x62, 0xE7, 0x11, 0x28, 0x1E, 0xAF, 0xBC, 0x81, + 0xF9, 0x09, 0xBC, 0x10, 0x1F, 0xA6, 0xCF, 0xBD, 0x09, 0xF5, 0x9D, 0x81, 0x4D, 0x5A, 0x07, 0x74, + 0x0A, 0xE6, 0x0E, 0xF4, 0x7C, 0xB8, 0x84, 0x8C, 0x74, 0x1F, 0x81, 0x91, 0x93, 0xBF, 0x5F, 0x5C, + 0xA4, 0x08, 0x6F, 0xCC, 0x4F, 0x38, 0x63, 0x6E, 0x33, 0xD9, 0xEA, 0xB7, 0xF6, 0x00, 0x74, 0xE1, + 0x6B, 0x17, 0x0C, 0xF6, 0x7F, 0xFF, 0x37, 0xC9, 0xAB, 0x41, 0x8E, 0x51, 0x6A, 0xE9, 0x19, 0x7B, + 0x71, 0x96, 0x5D, 0x0C, 0xC0, 0x42, 0xCB, 0xCE, 0xEB, 0xCD, 0x6F, 0xD9, 0x63, 0x53, 0xF1, 0xC3, + 0xB2, 0x3F, 0x86, 0x65, 0xFF, 0x0D, 0x19, 0xF6, 0x4A, 0x16, 0xB9, 0xC4, 0xC8, 0xCB, 0x1C, 0x56, + 0x5C, 0xB4, 0xBF, 0x6C, 0x34, 0x7E, 0x8C, 0xAA, 0xDF, 0xF2, 0xA8, 0x12, 0xE3, 0xA4, 0xE4, 0xA8, + 0x12, 0x63, 0xB0, 0xCA, 0xA8, 0x12, 0xFE, 0xC6, 0x03, 0xF8, 0x4B, 0xB1, 0x7B, 0x5B, 0x79, 0x58, + 0x89, 0x8E, 0x2E, 0x35, 0xAC, 0x14, 0x27, 0x65, 0x78, 0xE7, 0xDA, 0x13, 0x67, 0x70, 0xE2, 0x0D, + 0xE9, 0xB8, 0xAA, 0x77, 0xD2, 0x0F, 0x61, 0x4C, 0x0E, 0x1E, 0xC1, 0x37, 0xF9, 0xFB, 0xCC, 0x0E, + 0x9C, 0x20, 0xA6, 0xF6, 0xC0, 0x7E, 0x49, 0x8F, 0xC2, 0xC2, 0x38, 0xF4, 0x1D, 0xDB, 0x7D, 0x04, + 0xDF, 0x63, 0x6F, 0x16, 0x7A, 0x13, 0x2F, 0x74, 0xBE, 0x52, 0x24, 0xB6, 0xF6, 0xB0, 0xC4, 0xCE, + 0xC1, 0xCE, 0x11, 0x18, 0xD9, 0x48, 0x6A, 0xFD, 0x61, 0x49, 0xBD, 0xA7, 0xF6, 0xD7, 0x3B, 0x72, + 0x62, 0x0F, 0x6E, 0x00, 0xD0, 0xBF, 0x5B, 0x90, 0x33, 0x95, 0x47, 0xF1, 0xC3, 0xDE, 0x4F, 0x48, + 0x65, 0xF3, 0x81, 0xA9, 0xB8, 0x63, 0x67, 0xE2, 0x84, 0xDC, 0x25, 0x7F, 0x51, 0x8F, 0x56, 0x0A, + 0x64, 0xC4, 0x0C, 0x16, 0x3F, 0x99, 0x60, 0xC6, 0xEA, 0xDA, 0xC3, 0x65, 0x7E, 0x63, 0xA9, 0x1D, + 0xD0, 0x70, 0x2F, 0x04, 0x5D, 0xBC, 0x82, 0x45, 0x4C, 0xAB, 0x89, 0x7B, 0x44, 0x2B, 0x57, 0xC1, + 0x8A, 0xE7, 0x3B, 0x23, 0x07, 0x0C, 0xFA, 0x0A, 0xDB, 0x71, 0x40, 0x4E, 0x2E, 0x6E, 0x28, 0x79, + 0x77, 0xDA, 0xEF, 0x93, 0x81, 0xED, 0x12, 0x58, 0xF6, 0x80, 0xB5, 0x23, 0x68, 0xCE, 0x08, 0x3A, + 0xD7, 0xE8, 0xCF, 0x7F, 0x5D, 0x23, 0x76, 0x48, 0x86, 0xCE, 0xF5, 0x35, 0xF5, 0xC1, 0x26, 0x12, + 0x1F, 0xE8, 0x04, 0x6D, 0xF2, 0xD6, 0xF3, 0x59, 0xBD, 0x97, 0x91, 0x55, 0xB0, 0x49, 0xC0, 0x2C, + 0x20, 0xDB, 0xEA, 0xA2, 0xD0, 0x7D, 0xD1, 0x56, 0xD9, 0x32, 0x43, 0x05, 0xFC, 0xC0, 0x7F, 0x09, + 0x2C, 0x6C, 0x60, 0x41, 0x63, 0x8F, 0x93, 0x5A, 0x1C, 0x8A, 0x23, 0xE4, 0xF4, 0x5E, 0x66, 0x57, + 0x8E, 0xCE, 0xEB, 0x46, 0xBE, 0x37, 0x9B, 0x72, 0xC4, 0xDC, 0x74, 0x41, 0xDD, 0xA1, 0xF3, 0xD5, + 0x19, 0xCE, 0xA0, 0xB6, 0xA8, 0x14, 0xB4, 0x4D, 0x42, 0x46, 0x89, 0xF9, 0xE1, 0x60, 0x52, 0x53, + 0x5C, 0xC8, 0x21, 0x71, 0x02, 0x12, 0xFA, 0xB6, 0x1B, 0x40, 0x77, 0xA2, 0x07, 0x71, 0x75, 0x47, + 0x60, 0x5E, 0x26, 0x38, 0xC5, 0xA3, 0xA8, 0x6C, 0x32, 0x14, 0x5B, 0xF9, 0xDE, 0x35, 0xE9, 0xBC, + 0xFF, 0x27, 0xE3, 0x3E, 0xE2, 0x89, 0x74, 0x2C, 0x6B, 0x63, 0x99, 0x9C, 0xF4, 0x4F, 0xD6, 0x39, + 0xFB, 0x56, 0x3B, 0xAA, 0xD2, 0xB1, 0xD6, 0xD6, 0xDA, 0xE4, 0xE2, 0x06, 0xB0, 0x63, 0x5F, 0x5C, + 0x51, 0x32, 0xF6, 0x6E, 0x41, 0xE6, 0x43, 0x56, 0xEA, 0xA3, 0x55, 0x0E, 0xC8, 0xAD, 0x03, 0xAB, + 0x1D, 0xF8, 0x0E, 0xD4, 0xDC, 0xE1, 0xAD, 0x33, 0x84, 0xBF, 0xA0, 0x10, 0x97, 0xA6, 0x1E, 0xD6, + 0x0C, 0xBD, 0x98, 0x33, 0xC0, 0x7E, 0xB7, 0x6A, 0x8F, 0xC7, 0x4C, 0xA8, 0x89, 0x4C, 0xC8, 0x31, + 0x6A, 0x61, 0xF0, 0x12, 0x09, 0x63, 0xF5, 0x4D, 0xCB, 0xCA, 0x94, 0x13, 0x4D, 0xCD, 0x3D, 0x35, + 0x24, 0xC6, 0x27, 0x30, 0x12, 0xB9, 0x12, 0xBC, 0x21, 0xF2, 0x69, 0xCA, 0xCB, 0x48, 0xCD, 0x60, + 0xC8, 0xF0, 0xE9, 0x94, 0xEC, 0x9F, 0x9D, 0x74, 0xDB, 0x44, 0x9C, 0x88, 0xBC, 0x24, 0x6F, 0x71, + 0x83, 0xB0, 0x59, 0x38, 0x23, 0x95, 0x5C, 0x36, 0xFF, 0x58, 0x32, 0xFF, 0xD1, 0x96, 0xCC, 0x06, + 0xC7, 0xFD, 0xC2, 0xF3, 0x07, 0x37, 0xBF, 0x61, 0x7F, 0x3D, 0x55, 0x6B, 0x75, 0x15, 0x0F, 0x64, + 0xCE, 0xF7, 0x0E, 0x8E, 0xCE, 0x08, 0xD6, 0xC5, 0xD1, 0xC4, 0x1A, 0x99, 0x51, 0xF3, 0x60, 0xEF, + 0x62, 0xAF, 0xA0, 0x62, 0xEE, 0x9E, 0x69, 0x96, 0xD3, 0xAE, 0x2E, 0x02, 0xCA, 0xAC, 0xCC, 0xFA, + 0x20, 0xEB, 0x8C, 0x85, 0xD9, 0x87, 0x93, 0xED, 0x2D, 0x6B, 0xDE, 0xD5, 0x1D, 0x47, 0x92, 0x21, + 0xD6, 0xB9, 0xD7, 0x23, 0x15, 0xD7, 0xE6, 0x99, 0x6B, 0x27, 0xDF, 0xCE, 0xE9, 0xDC, 0xC5, 0x39, + 0xDE, 0x6C, 0xED, 0xF1, 0x08, 0x16, 0x4E, 0xF8, 0x54, 0x9D, 0xC7, 0xF4, 0x81, 0xBB, 0x0B, 0x74, + 0xAA, 0xBE, 0xBF, 0x8B, 0xD0, 0xB1, 0x5E, 0xAC, 0xE3, 0xCF, 0x2D, 0xF6, 0x73, 0x1B, 0x7F, 0x76, + 0xBA, 0xDF, 0xDD, 0x69, 0xC0, 0xCA, 0x5D, 0xAB, 0x0D, 0x16, 0x24, 0xA4, 0x2F, 0x09, 0x3A, 0x8F, + 0x92, 0xA6, 0x33, 0xDF, 0x10, 0x9B, 0xEE, 0x7D, 0xA5, 0xBE, 0xEF, 0x0C, 0x87, 0xD4, 0xC5, 0xFA, + 0xC8, 0xEB, 0xED, 0x0D, 0x45, 0x7F, 0x8E, 0xB0, 0x9B, 0x2B, 0x13, 0x50, 0xDD, 0xF6, 0x8F, 0xF9, + 0xFC, 0x77, 0x30, 0x8D, 0xF6, 0xBC, 0x20, 0x1C, 0x30, 0x5B, 0xFF, 0x63, 0xE7, 0x2B, 0x7B, 0xD2, + 0xAB, 0x30, 0xD5, 0x08, 0x84, 0x0F, 0xBD, 0xF5, 0xF5, 0x3B, 0xDA, 0x51, 0x7E, 0x9C, 0xAD, 0xAF, + 0x6A, 0x7E, 0xCB, 0xF1, 0x3B, 0xE8, 0xBF, 0x5E, 0x06, 0x41, 0xA3, 0xE3, 0x92, 0x45, 0x51, 0x9E, + 0xEC, 0xA5, 0xB6, 0x54, 0x26, 0x3A, 0x71, 0xDC, 0xC3, 0x31, 0xFD, 0x5A, 0xA4, 0xF6, 0x50, 0x6D, + 0xFF, 0xF4, 0x2C, 0xC7, 0x13, 0x79, 0xBA, 0x73, 0x63, 0x27, 0x9E, 0x21, 0x3B, 0x9D, 0xB5, 0xF5, + 0x3F, 0xF8, 0x9C, 0xF8, 0xC7, 0x3E, 0x1A, 0x5E, 0xE4, 0xBC, 0x68, 0x1E, 0x01, 0xA8, 0x43, 0x38, + 0x35, 0xBC, 0xB1, 0x67, 0x60, 0xF2, 0xDB, 0x1E, 0x9F, 0x21, 0xA2, 0xCB, 0x5C, 0xEC, 0x86, 0xD7, + 0xEA, 0xEA, 0x39, 0x9D, 0x40, 0xA7, 0x13, 0x54, 0x9D, 0x6B, 0xDF, 0x9B, 0x90, 0xB1, 0x13, 0x84, + 0xF9, 0xBD, 0xAB, 0xE1, 0x2D, 0xDF, 0xEC, 0xED, 0x4D, 0xCB, 0xC2, 0x46, 0xB2, 0xFF, 0x3E, 0xA8, + 0x80, 0x3B, 0x9D, 0x8D, 0x2E, 0xA7, 0x25, 0x7E, 0x7B, 0x50, 0x6A, 0xDD, 0x35, 0x6B, 0x9D, 0x53, + 0x13, 0xBF, 0x3D, 0x28, 0xB5, 0xF5, 0x4D, 0x6B, 0x8B, 0x53, 0x13, 0xBF, 0x3D, 0x28, 0xB5, 0xED, + 0x6E, 0x27, 0xEA, 0x35, 0xFE, 0xDB, 0xE2, 0xF4, 0x13, 0x0D, 0xF0, 0x03, 0xA8, 0xA7, 0x8A, 0xF6, + 0x87, 0x76, 0xFE, 0xD0, 0xCE, 0x07, 0xDC, 0x9C, 0x23, 0xBF, 0x74, 0xFF, 0x10, 0xFB, 0x73, 0xD0, + 0xCE, 0xD2, 0x5B, 0x74, 0xA6, 0xBA, 0xF3, 0xEF, 0xD2, 0x31, 0x67, 0x12, 0x6F, 0xE9, 0xE2, 0x4A, + 0x2E, 0xD9, 0x0E, 0x7C, 0x7C, 0x1F, 0xF8, 0xFB, 0xAD, 0x9B, 0x4C, 0x0D, 0x88, 0x25, 0x3E, 0xEF, + 0x16, 0xDF, 0xC3, 0xDE, 0xAC, 0xE4, 0xD8, 0xB3, 0x96, 0x4B, 0xBC, 0x6F, 0x0F, 0xA3, 0xC3, 0x97, + 0x73, 0x71, 0xF8, 0xE2, 0xBA, 0x30, 0x70, 0xC1, 0xDF, 0x2D, 0xA5, 0x58, 0x8F, 0x70, 0x55, 0xE7, + 0xC7, 0x32, 0xE7, 0xC7, 0x16, 0xE0, 0x8F, 0x2D, 0xC0, 0x27, 0xB9, 0x05, 0x68, 0x7C, 0xFF, 0x20, + 0x3D, 0x03, 0x19, 0x81, 0xB5, 0x8D, 0xDE, 0xDC, 0xFD, 0x44, 0xFD, 0x00, 0xD0, 0x1E, 0xB9, 0xA1, + 0xE9, 0x4D, 0x08, 0x8C, 0x6E, 0xE7, 0xFA, 0x0E, 0x0F, 0xF7, 0xF9, 0x5B, 0x9C, 0xE1, 0x8C, 0xA2, + 0x6E, 0x5C, 0x0B, 0x60, 0xC2, 0xEE, 0x47, 0xB0, 0x19, 0x21, 0x48, 0x3D, 0x50, 0xC8, 0x7E, 0xA1, + 0x50, 0x70, 0xE1, 0x75, 0xCE, 0x2B, 0xB1, 0x8B, 0x3A, 0x78, 0xC1, 0x79, 0x19, 0x55, 0xF1, 0x11, + 0x34, 0xB1, 0xCF, 0x65, 0x68, 0xF3, 0xBB, 0x33, 0xDD, 0xC7, 0xBC, 0xF2, 0xB4, 0xF6, 0x98, 0xC7, + 0x3D, 0x0F, 0x7C, 0x0F, 0xA9, 0x4F, 0xED, 0x47, 0xB8, 0x7B, 0xB4, 0xE7, 0xF8, 0x57, 0x1E, 0xB8, + 0xA0, 0xA4, 0x33, 0x7A, 0x84, 0x3B, 0x48, 0x31, 0xB5, 0xEE, 0x68, 0x8E, 0x5B, 0x48, 0x95, 0xA9, + 0xAD, 0x33, 0x6A, 0x5B, 0x0F, 0x4B, 0xED, 0x67, 0x1F, 0xD6, 0xAF, 0x6C, 0xBD, 0xF2, 0xB0, 0x74, + 0xDE, 0x38, 0x5F, 0x98, 0xFA, 0x75, 0x16, 0x34, 0x8C, 0xA3, 0xF7, 0x6A, 0xAF, 0x77, 0x49, 0xA7, + 0xDB, 0x31, 0x19, 0xA1, 0xCA, 0x86, 0xA8, 0xC8, 0x18, 0x9D, 0xA0, 0x7F, 0xC0, 0x17, 0xC9, 0xCD, + 0x0C, 0xF0, 0xEA, 0xED, 0xC8, 0x93, 0xD9, 0xE1, 0x4A, 0x7F, 0xE0, 0x81, 0xBB, 0xC0, 0x89, 0x76, + 0x17, 0x47, 0xF4, 0xBE, 0x70, 0xD2, 0x5A, 0x5D, 0x05, 0x77, 0x9B, 0x4D, 0x37, 0x23, 0x8C, 0x43, + 0x61, 0x0B, 0x57, 0x0C, 0x1F, 0xDA, 0xCD, 0x5C, 0x27, 0x2C, 0x98, 0xDC, 0x82, 0xE1, 0x5B, 0x9F, + 0xD2, 0xFE, 0xD4, 0x46, 0xBF, 0x43, 0xA1, 0x05, 0x93, 0x8A, 0x56, 0xB3, 0xEF, 0xFC, 0xB3, 0xA8, + 0xD2, 0x0D, 0x2C, 0xB0, 0x70, 0xAA, 0x3B, 0x3A, 0x28, 0xA8, 0x68, 0x98, 0x54, 0x0B, 0x20, 0x86, + 0xF6, 0x5D, 0x70, 0x4E, 0x27, 0xB6, 0xE3, 0xB2, 0x15, 0x52, 0x6E, 0xDD, 0xA9, 0xEF, 0xE1, 0xD3, + 0x47, 0x0B, 0x9F, 0xB8, 0x97, 0xAB, 0xDA, 0x29, 0x5F, 0xB5, 0x5B, 0xBE, 0xEA, 0x5A, 0xF9, 0xAA, + 0xEB, 0xE5, 0xAB, 0x6E, 0x94, 0xAF, 0xBA, 0x59, 0xBE, 0xEA, 0x8B, 0x12, 0x55, 0x99, 0xAF, 0x7D, + 0xB2, 0xB7, 0x5F, 0xD4, 0x55, 0x14, 0xFD, 0xD8, 0x37, 0x17, 0x85, 0x5A, 0x00, 0xCB, 0xF4, 0x28, + 0x7C, 0x46, 0x41, 0xCD, 0x2B, 0x1B, 0xD6, 0x18, 0xFE, 0x1D, 0x78, 0xCA, 0x03, 0x8A, 0xCE, 0x57, + 0x5C, 0x59, 0xB7, 0x27, 0x60, 0x3E, 0x9C, 0xE1, 0x12, 0x40, 0xC2, 0x58, 0x78, 0x7F, 0x71, 0x72, + 0xAC, 0x3F, 0x4B, 0x2D, 0xF2, 0xF6, 0xFC, 0xF0, 0x4B, 0x4A, 0x2F, 0x0D, 0x34, 0x8C, 0xF5, 0xB2, + 0xA9, 0x66, 0x43, 0x7D, 0x98, 0x8E, 0x40, 0xAA, 0xB4, 0x31, 0x07, 0xCB, 0x03, 0x5C, 0xE6, 0xF9, + 0x93, 0x73, 0x8C, 0x30, 0x91, 0x66, 0x96, 0x05, 0x9E, 0xD8, 0xF7, 0x26, 0x53, 0x30, 0x98, 0xB4, + 0xB5, 0x54, 0x19, 0x2D, 0x86, 0xA8, 0x38, 0xA7, 0x03, 0xEA, 0x4C, 0x0D, 0xC8, 0xD3, 0x75, 0x54, + 0x0A, 0x05, 0x24, 0x84, 0xEA, 0xF1, 0x58, 0x29, 0x06, 0xEC, 0x33, 0x1F, 0x6F, 0xE4, 0xF6, 0xE4, + 0x5A, 0x26, 0xC9, 0xFE, 0xB9, 0xD5, 0x70, 0x70, 0x73, 0xE2, 0x13, 0x46, 0xEE, 0xD9, 0x15, 0x48, + 0xD9, 0x8A, 0xFC, 0xF3, 0xA7, 0xAF, 0x18, 0xD6, 0x63, 0x17, 0x9F, 0x1C, 0x1B, 0xB1, 0x3D, 0x27, + 0x8D, 0xCF, 0x20, 0x7B, 0x80, 0x99, 0xB6, 0x9A, 0x2C, 0xF8, 0x06, 0x5B, 0x4C, 0xE1, 0x33, 0xE3, + 0x0A, 0xA2, 0x8A, 0x3C, 0xFC, 0x0F, 0x53, 0x0C, 0x02, 0x14, 0x09, 0x3B, 0xDD, 0x20, 0x73, 0xBD, + 0x56, 0x6D, 0x4A, 0xE8, 0x09, 0xCF, 0x82, 0x22, 0x3A, 0xBC, 0x56, 0x8B, 0xBF, 0x84, 0x2F, 0xBD, + 0xEA, 0x49, 0xA2, 0xEE, 0x98, 0x06, 0x80, 0x1C, 0x92, 0xC7, 0xA4, 0xE9, 0x73, 0x8D, 0x41, 0x29, + 0xB0, 0x4F, 0x0E, 0x6D, 0x36, 0x09, 0x3F, 0x18, 0xED, 0xBD, 0x71, 0x4E, 0xBB, 0x79, 0x58, 0xA1, + 0x85, 0xD3, 0x66, 0xB1, 0x89, 0xD2, 0x54, 0xA3, 0x90, 0x45, 0x0F, 0x42, 0xEF, 0xA3, 0x99, 0xDE, + 0xC7, 0x87, 0xA2, 0xF7, 0xAB, 0x99, 0xDE, 0xAF, 0x0F, 0x42, 0x2F, 0x98, 0xBA, 0xDE, 0x6D, 0x8F, + 0xE2, 0xCD, 0x90, 0x99, 0x69, 0xC9, 0x1E, 0xBB, 0xA6, 0xC4, 0x5A, 0x32, 0x6E, 0x91, 0x4D, 0x01, + 0x16, 0xE6, 0xBB, 0x40, 0x33, 0xCF, 0x8D, 0x46, 0x1D, 0x26, 0x2E, 0x33, 0x19, 0xF8, 0x64, 0x7D, + 0x26, 0x7F, 0x02, 0xB4, 0x56, 0x83, 0xFC, 0xE5, 0x2F, 0xD8, 0xC6, 0x4F, 0x9D, 0xE8, 0x83, 0xC9, + 0x5F, 0xCE, 0xE4, 0xEC, 0x39, 0x13, 0x10, 0x1A, 0xB5, 0x57, 0x57, 0xFE, 0xEB, 0x46, 0xDD, 0x1D, + 0x8F, 0x80, 0x2F, 0xB0, 0x31, 0xF0, 0x91, 0x69, 0x3E, 0x89, 0xA3, 0x22, 0xB5, 0xA7, 0xB3, 0xE0, + 0xA6, 0xA2, 0x5D, 0x11, 0xB8, 0xA3, 0xF0, 0x49, 0x99, 0xF8, 0xA3, 0x0A, 0x75, 0x68, 0x5C, 0x4F, + 0xB8, 0x47, 0xA1, 0xA3, 0xD6, 0xC2, 0x75, 0x55, 0xD2, 0xA5, 0xEB, 0x09, 0x77, 0x7F, 0xD3, 0xA6, + 0x56, 0x8E, 0x8C, 0x05, 0x1D, 0xD0, 0x78, 0x15, 0xFA, 0xC4, 0x1E, 0x3B, 0x23, 0x77, 0xB7, 0x39, + 0xA6, 0xD7, 0x61, 0x53, 0xEF, 0x07, 0x13, 0xC4, 0xF0, 0x35, 0xCE, 0x50, 0x0A, 0x7F, 0xD8, 0x89, + 0xAB, 0x58, 0x50, 0x16, 0x3A, 0xEA, 0xF9, 0xD2, 0x40, 0xAF, 0xD8, 0xA4, 0x49, 0xC2, 0xBB, 0x29, + 0xDD, 0xE5, 0x73, 0xDF, 0x95, 0xF7, 0xAD, 0x09, 0x7E, 0xD7, 0x6E, 0xD3, 0xC4, 0x4D, 0x93, 0xB0, + 0xE9, 0xB5, 0x89, 0xC8, 0x8E, 0x0E, 0x9A, 0x64, 0x00, 0x15, 0x02, 0xF8, 0xD3, 0xF3, 0x27, 0x2B, + 0x0C, 0x7A, 0x85, 0xE3, 0x93, 0x82, 0x8E, 0xB0, 0xD8, 0x02, 0xCD, 0xD7, 0x25, 0x59, 0x5A, 0x0D, + 0x15, 0x9D, 0x2D, 0xD1, 0xCB, 0x6C, 0xD3, 0x5A, 0xEF, 0x11, 0x8C, 0xAB, 0x85, 0x7C, 0x57, 0x99, + 0x56, 0x67, 0x57, 0xDF, 0x4E, 0x92, 0x57, 0x46, 0x0C, 0x27, 0x9E, 0x51, 0xA9, 0x9F, 0x2F, 0xF1, + 0x6C, 0xE3, 0xF2, 0xE0, 0xE2, 0x44, 0xFB, 0x8E, 0xFB, 0xBD, 0x97, 0xB8, 0x27, 0x7A, 0x89, 0xBB, + 0xDA, 0x0A, 0x2F, 0x52, 0x28, 0x34, 0xA1, 0x74, 0xCE, 0x70, 0x27, 0xAB, 0xC6, 0x39, 0x0F, 0x71, + 0x92, 0x32, 0x83, 0x1A, 0x92, 0x63, 0xFB, 0x8A, 0x8E, 0x4D, 0x71, 0x4E, 0xA4, 0x7A, 0x07, 0x22, + 0x50, 0x4F, 0x02, 0x15, 0x05, 0xEC, 0xB9, 0xD4, 0xD7, 0xA6, 0x28, 0x0B, 0x09, 0x2A, 0x3A, 0x43, + 0x87, 0xD5, 0xFA, 0x9A, 0xC9, 0xF6, 0xC8, 0xC1, 0xDD, 0x78, 0xC0, 0x22, 0x09, 0x18, 0xCC, 0xD6, + 0x4E, 0x9E, 0xDC, 0x76, 0xD9, 0x8B, 0x2A, 0xE3, 0x0E, 0x81, 0x1E, 0x1A, 0xEE, 0x4F, 0xBB, 0x32, + 0x99, 0xAC, 0x5D, 0x83, 0x74, 0x40, 0x39, 0x09, 0xC8, 0xBC, 0x06, 0x97, 0x23, 0xD3, 0x31, 0xB5, + 0xBB, 0x49, 0x59, 0x4A, 0xCD, 0x77, 0xD5, 0x20, 0xE5, 0x3E, 0x50, 0xDB, 0x8E, 0xA3, 0xE4, 0x92, + 0x85, 0x4D, 0x92, 0x3E, 0x77, 0x4D, 0x22, 0x51, 0x55, 0x06, 0x10, 0x99, 0xD5, 0x27, 0xA7, 0x7F, + 0x76, 0x77, 0xC9, 0x7A, 0x96, 0x54, 0xEA, 0x32, 0x6A, 0xFC, 0xBC, 0x66, 0xEC, 0x52, 0xC6, 0xEF, + 0xBA, 0xF5, 0xA2, 0x7B, 0x69, 0x45, 0xDC, 0xF3, 0xBF, 0x0A, 0x77, 0x30, 0x9E, 0xE5, 0x76, 0xC6, + 0xD0, 0xF9, 0xAA, 0x18, 0x16, 0xF6, 0x0E, 0x8E, 0xF8, 0xDE, 0x2D, 0xB7, 0x4B, 0x93, 0x60, 0x24, + 0xF1, 0x17, 0x5B, 0x26, 0xBD, 0x03, 0x53, 0x68, 0xC7, 0x4C, 0x0C, 0x80, 0x91, 0x9B, 0x36, 0x1D, + 0x3E, 0x22, 0x39, 0xF0, 0xC6, 0x2B, 0xC1, 0x64, 0x65, 0x9D, 0xE0, 0x2F, 0x9B, 0xEC, 0x27, 0xE3, + 0x82, 0x81, 0x37, 0x5F, 0x6B, 0xA0, 0x5C, 0xB6, 0x00, 0xFF, 0xF2, 0xD5, 0x2A, 0xAB, 0x51, 0xC8, + 0x86, 0xD4, 0x3A, 0x85, 0xD4, 0x7A, 0x53, 0x35, 0xC6, 0x3C, 0x58, 0xA4, 0x66, 0x62, 0xF9, 0xE5, + 0xD6, 0x66, 0x01, 0x8D, 0xD8, 0x7C, 0xA7, 0xDA, 0xC8, 0x57, 0x42, 0x72, 0x19, 0x33, 0x38, 0xA5, + 0xE4, 0x37, 0xCD, 0x42, 0x7B, 0xE8, 0xFB, 0x5E, 0xC2, 0xA8, 0xE3, 0x8E, 0x1D, 0x97, 0xF2, 0x6F, + 0x60, 0xF5, 0xA7, 0x85, 0x78, 0x57, 0x41, 0x22, 0xAF, 0xF9, 0xCF, 0x0A, 0x96, 0x5F, 0x62, 0xBF, + 0xF7, 0xF7, 0x8B, 0x13, 0xD3, 0x51, 0x0C, 0xD1, 0xEA, 0x5C, 0x1E, 0xF6, 0x0E, 0xEB, 0x5B, 0xE6, + 0x07, 0x30, 0xBB, 0x85, 0x63, 0x74, 0xA7, 0xE2, 0x48, 0x61, 0x53, 0x30, 0x99, 0x84, 0x2B, 0x6B, + 0x65, 0x87, 0x43, 0x7A, 0x02, 0xE7, 0x7A, 0x9E, 0x3D, 0x4E, 0x5E, 0x8B, 0xB7, 0x8E, 0x59, 0x03, + 0xA1, 0xEC, 0x38, 0xE0, 0xBA, 0x9E, 0xE1, 0x40, 0x34, 0x33, 0x3D, 0x92, 0xCA, 0xC3, 0x3E, 0x52, + 0x2C, 0x5D, 0x39, 0xFA, 0xF6, 0x57, 0xCA, 0x0E, 0xAB, 0xD1, 0xA3, 0x61, 0xA7, 0xCD, 0x6C, 0x70, + 0x10, 0x3B, 0x20, 0xB7, 0x14, 0x0F, 0x99, 0x9B, 0x21, 0x7B, 0xA2, 0x1B, 0xEF, 0x08, 0x90, 0x3B, + 0x1A, 0xB6, 0x15, 0xFC, 0x37, 0x50, 0xD7, 0xF5, 0x42, 0x2C, 0x20, 0x57, 0x94, 0xBA, 0xC4, 0x1E, + 0x0E, 0xF9, 0x39, 0x73, 0xEC, 0x8E, 0xAB, 0x5E, 0x49, 0x2A, 0x10, 0x29, 0xF7, 0x6C, 0xA5, 0x36, + 0x69, 0x1A, 0x62, 0x88, 0x4E, 0x5A, 0xC7, 0x19, 0x9E, 0xC8, 0x7E, 0x4D, 0x6A, 0x5F, 0x4D, 0x94, + 0x1E, 0x89, 0x87, 0xC8, 0x68, 0xC8, 0x8B, 0x86, 0x13, 0x9B, 0xCD, 0xDF, 0xF5, 0x60, 0x3E, 0xCF, + 0xA9, 0x84, 0x88, 0xCE, 0xF1, 0x88, 0x9C, 0xCD, 0x14, 0x30, 0xB1, 0x75, 0x72, 0x2A, 0x07, 0x58, + 0x27, 0x9E, 0x12, 0x73, 0x2A, 0xCB, 0x6C, 0x4A, 0xD8, 0xBB, 0x6B, 0x56, 0x09, 0x80, 0x84, 0x80, + 0x5E, 0xBF, 0x8E, 0x97, 0xC6, 0xE2, 0x2A, 0xBE, 0x1D, 0x7B, 0x76, 0xA8, 0xF5, 0x47, 0x81, 0xE9, + 0xD0, 0xAB, 0xFD, 0x63, 0x06, 0x6B, 0x85, 0x6B, 0x87, 0x6D, 0x6C, 0xE9, 0xE5, 0x59, 0x7D, 0x99, + 0xDF, 0x5B, 0xF8, 0x4F, 0xC1, 0x1A, 0x3F, 0x33, 0x6F, 0xE4, 0x4D, 0xC5, 0x4F, 0xC4, 0x8C, 0xFD, + 0x16, 0x26, 0xFC, 0x44, 0xBA, 0x3F, 0x26, 0xFF, 0xEF, 0x35, 0xF9, 0xF3, 0x3B, 0x66, 0x68, 0x8B, + 0xF2, 0xEC, 0x55, 0x52, 0xEB, 0xF2, 0xDD, 0xBB, 0xBD, 0xDF, 0x9F, 0x03, 0xF0, 0x3B, 0xF0, 0x89, + 0xC5, 0xC1, 0x2F, 0xDF, 0x5B, 0x30, 0x32, 0x92, 0xA9, 0xD4, 0xF2, 0x08, 0x19, 0x8A, 0x4B, 0x75, + 0x64, 0x72, 0xB5, 0xD2, 0x2D, 0x6E, 0x3C, 0xBF, 0x31, 0x1E, 0x0D, 0x0B, 0xAB, 0xF9, 0xFA, 0xEC, + 0xFA, 0xFA, 0xD5, 0x2A, 0xFF, 0x5A, 0x11, 0xB8, 0xD3, 0x7C, 0xCD, 0xD5, 0xAC, 0x53, 0x13, 0x41, + 0x37, 0x42, 0xD0, 0x2D, 0x8D, 0x60, 0x95, 0x4B, 0xED, 0xC1, 0x1D, 0x20, 0xAC, 0xC2, 0x4B, 0x16, + 0xE3, 0x00, 0xC9, 0x21, 0xDC, 0x4B, 0xF9, 0x3F, 0x4A, 0x5C, 0xF7, 0x39, 0xDC, 0x1F, 0xEE, 0xB8, + 0x0E, 0x8B, 0xFC, 0x1B, 0xA9, 0x5A, 0x29, 0xFF, 0x42, 0xAA, 0xBF, 0x20, 0xF7, 0xE2, 0xC7, 0x52, + 0xE3, 0xC7, 0x52, 0xE3, 0xB7, 0xBA, 0xD4, 0x90, 0x62, 0xDE, 0x88, 0xDC, 0x01, 0x77, 0xE9, 0xC1, + 0xA6, 0xA6, 0x1A, 0xC8, 0x19, 0x10, 0x49, 0xA5, 0x08, 0x59, 0xE4, 0x76, 0x83, 0xFF, 0x9B, 0xE1, + 0x74, 0x27, 0x30, 0x62, 0x7C, 0xA8, 0x94, 0x32, 0x87, 0x48, 0x9A, 0xA9, 0x68, 0xA4, 0xA8, 0x18, + 0xD3, 0x83, 0x05, 0x85, 0x60, 0x4E, 0xAD, 0x10, 0xED, 0xD4, 0xBD, 0x32, 0x67, 0x66, 0x30, 0xB9, + 0xED, 0x19, 0x88, 0x58, 0x57, 0x18, 0xD8, 0x33, 0xDC, 0x17, 0xCA, 0x49, 0xE2, 0xA0, 0xA3, 0x89, + 0xA4, 0x5A, 0xFC, 0x8A, 0xC5, 0xC4, 0xA8, 0x14, 0x7B, 0xFD, 0xC2, 0xF3, 0xC8, 0xC4, 0x76, 0xEF, + 0x64, 0xE2, 0x24, 0xE0, 0xAD, 0x7C, 0x89, 0xC1, 0xD8, 0x73, 0xE5, 0x53, 0xFB, 0x5E, 0x2E, 0x1B, + 0x30, 0x8E, 0x3B, 0x92, 0x52, 0x62, 0x18, 0xAE, 0x10, 0xA4, 0x2B, 0x55, 0x39, 0x17, 0x70, 0x13, + 0xB0, 0xCC, 0xDB, 0x20, 0xE9, 0x3A, 0x95, 0x8F, 0xDA, 0xD9, 0x7D, 0xE1, 0xDC, 0x76, 0xA4, 0xEB, + 0x54, 0x69, 0x86, 0x17, 0xDA, 0x11, 0x58, 0xD6, 0x95, 0x81, 0x54, 0x95, 0x8A, 0x8D, 0x10, 0x17, + 0x74, 0x8E, 0x40, 0x33, 0x92, 0x2B, 0x3D, 0xA6, 0x8B, 0x33, 0xC6, 0x8A, 0xED, 0xC0, 0x1F, 0x54, + 0xBF, 0xF6, 0x92, 0x4A, 0x9F, 0x60, 0xBA, 0xA0, 0x62, 0xCA, 0xB1, 0x50, 0xED, 0xE4, 0x4F, 0x64, + 0x2F, 0x32, 0x9D, 0xFD, 0xC5, 0x79, 0x8D, 0x6A, 0x60, 0xF4, 0xF0, 0x1A, 0x9B, 0x19, 0x25, 0x4F, + 0x8C, 0x54, 0xED, 0xDE, 0x12, 0xBD, 0xF2, 0xBC, 0x28, 0xA6, 0x77, 0xFE, 0x49, 0x77, 0xC6, 0x89, + 0xB2, 0x86, 0xA1, 0xCD, 0xE7, 0x29, 0xC3, 0x79, 0x54, 0x04, 0xC0, 0xDF, 0xBF, 0xE0, 0x9D, 0x65, + 0x71, 0xF5, 0xA8, 0x2D, 0xE6, 0x30, 0x63, 0x9C, 0x7E, 0x3D, 0x20, 0x01, 0xBB, 0xEB, 0x8C, 0x71, + 0x2B, 0x19, 0x30, 0x8F, 0x3E, 0x1E, 0x34, 0xEA, 0x18, 0xA3, 0x3C, 0xE6, 0xAD, 0xEA, 0xAC, 0x8B, + 0xAC, 0x3D, 0x79, 0x6F, 0x7E, 0x2A, 0xF2, 0x5E, 0x78, 0x26, 0x9E, 0x1B, 0xA0, 0xBD, 0x56, 0x67, + 0x16, 0xA1, 0x2C, 0xEE, 0xDD, 0x72, 0x51, 0xE3, 0x4B, 0x77, 0x7A, 0x3E, 0xBA, 0x79, 0xBB, 0xBF, + 0x74, 0x73, 0xAD, 0x85, 0x35, 0x36, 0x57, 0x4D, 0xE6, 0x6C, 0xED, 0xBD, 0x9C, 0xB0, 0x64, 0x9F, + 0x67, 0x91, 0x01, 0x67, 0x2F, 0xCA, 0xD0, 0x32, 0x41, 0xDF, 0x0F, 0x53, 0xD6, 0x61, 0x28, 0x48, + 0x30, 0xA6, 0x41, 0x81, 0x7E, 0xD9, 0x6E, 0x48, 0x5D, 0xD7, 0x7E, 0x4F, 0x9D, 0xD1, 0x4D, 0x78, + 0x39, 0x99, 0x98, 0x0D, 0xB3, 0x56, 0x4B, 0xD5, 0x11, 0xB2, 0x8A, 0x4F, 0xB6, 0x58, 0xEA, 0x1A, + 0x33, 0x93, 0x6C, 0x49, 0x00, 0x32, 0xA2, 0x01, 0x54, 0xE5, 0x21, 0x10, 0xAF, 0x66, 0x61, 0x28, + 0x3F, 0x75, 0x29, 0x97, 0xBD, 0x24, 0xF4, 0xEF, 0xCC, 0x9D, 0x8C, 0x57, 0x81, 0xF2, 0x74, 0xED, + 0x1E, 0xBC, 0xE9, 0x70, 0x70, 0x43, 0x5A, 0x14, 0xB7, 0xA0, 0x96, 0x8A, 0xBC, 0x96, 0x3E, 0x78, + 0xD3, 0x17, 0x80, 0x84, 0x38, 0x41, 0x00, 0x3F, 0xD9, 0xFB, 0xB1, 0xA3, 0x83, 0x28, 0x8B, 0x4C, + 0x95, 0xB1, 0x9C, 0x9F, 0xE6, 0xA5, 0x64, 0x7B, 0x0C, 0xEA, 0x54, 0xA3, 0x41, 0x2C, 0x90, 0x64, + 0xE5, 0x16, 0x49, 0xFD, 0xB8, 0x37, 0x1E, 0x13, 0x9F, 0x8E, 0x66, 0x63, 0x96, 0x5A, 0x08, 0x97, + 0x4E, 0xBC, 0x4F, 0xE3, 0x85, 0x8B, 0xD6, 0x9D, 0x15, 0xDA, 0x9A, 0x69, 0x71, 0x2A, 0xB6, 0xF3, + 0xA8, 0x46, 0x7F, 0xDD, 0x9B, 0x52, 0x1E, 0xC5, 0x39, 0x93, 0xF0, 0x92, 0x24, 0x4D, 0x22, 0x1B, + 0xB1, 0xEB, 0x55, 0xFC, 0x96, 0x28, 0x8C, 0x5E, 0x77, 0x44, 0xC5, 0x26, 0x84, 0x76, 0x09, 0xAC, + 0xD9, 0xDC, 0x79, 0x96, 0x4C, 0x3F, 0x30, 0x0F, 0x88, 0x9B, 0xA5, 0x27, 0xC1, 0xC8, 0x50, 0x53, + 0x30, 0x70, 0xE0, 0xE1, 0x82, 0x6F, 0xC6, 0xD3, 0xD9, 0x80, 0xF2, 0xE0, 0x3B, 0x44, 0x58, 0x07, + 0xFA, 0x78, 0x79, 0x16, 0xD6, 0x60, 0xE4, 0x16, 0xD6, 0x7A, 0x89, 0xCF, 0x02, 0x5D, 0x70, 0xED, + 0x3D, 0x8B, 0x4C, 0xBE, 0x9E, 0x0C, 0x87, 0x0F, 0x02, 0x59, 0x5E, 0x99, 0x19, 0xE8, 0x92, 0x0E, + 0x7E, 0xEB, 0x81, 0xFF, 0x0D, 0x7D, 0xC7, 0x1F, 0x33, 0x72, 0x46, 0x92, 0x3E, 0x1D, 0xA5, 0xE3, + 0x83, 0xBF, 0xFF, 0x27, 0xB4, 0x66, 0xE8, 0x04, 0x53, 0xEC, 0x23, 0x96, 0xF2, 0x12, 0xDF, 0x2E, + 0x90, 0xFD, 0x59, 0x00, 0x73, 0x20, 0xFF, 0x1B, 0xD6, 0xAE, 0x28, 0xA6, 0xE6, 0x92, 0xD4, 0x0B, + 0x06, 0x4C, 0x7D, 0x3A, 0xA8, 0x8D, 0x0A, 0x5F, 0x95, 0xA2, 0xF3, 0xD6, 0x17, 0x2F, 0x86, 0xE7, + 0x46, 0xF4, 0x16, 0x1D, 0xAD, 0xDA, 0x58, 0x98, 0x9B, 0xF6, 0x86, 0x3D, 0xD1, 0x97, 0xB3, 0x75, + 0xF1, 0x1B, 0x73, 0x8B, 0xC5, 0xF9, 0x8E, 0x7A, 0xB5, 0x51, 0x8A, 0x17, 0xCA, 0xA1, 0xEF, 0x4C, + 0xF1, 0x71, 0x29, 0xDE, 0xB1, 0x9E, 0x1F, 0xD3, 0xFE, 0xD8, 0x61, 0x57, 0xF0, 0x6B, 0x62, 0x8A, + 0x62, 0x6C, 0xE0, 0xD0, 0x72, 0xF1, 0x79, 0x4F, 0x4D, 0x3C, 0xC6, 0x97, 0xB3, 0x73, 0xB5, 0x2E, + 0x7A, 0x44, 0xDE, 0x9B, 0x31, 0x3B, 0xBE, 0x10, 0x5C, 0xEF, 0xC5, 0x83, 0x18, 0x9E, 0x2B, 0xD6, + 0x1B, 0x8D, 0xD8, 0xE3, 0x95, 0xF9, 0x50, 0x07, 0xD3, 0x53, 0xEF, 0x76, 0x4E, 0x24, 0xC7, 0x9E, + 0x6F, 0xD7, 0x46, 0x21, 0x3C, 0x85, 0xDE, 0x0D, 0x2A, 0x2B, 0xC5, 0xC3, 0x45, 0xE6, 0x54, 0xCC, + 0xC9, 0xD0, 0x22, 0x64, 0x23, 0xB0, 0x9C, 0x1F, 0x9D, 0x1E, 0xFE, 0x32, 0x27, 0xAA, 0xBD, 0xF3, + 0xDE, 0x62, 0x78, 0xC2, 0xC5, 0xC2, 0xDB, 0xF8, 0x42, 0xFE, 0x90, 0x9D, 0xC3, 0xCF, 0x8D, 0x30, + 0x5A, 0xB6, 0xCC, 0x83, 0xE7, 0x5D, 0x1C, 0x77, 0xA2, 0x12, 0xA2, 0x18, 0x13, 0x9F, 0x3C, 0xD0, + 0xE6, 0x61, 0xC2, 0x58, 0x79, 0x3F, 0x82, 0x97, 0x44, 0x57, 0x78, 0xF5, 0xD2, 0x70, 0x20, 0x6C, + 0xC8, 0x1B, 0x74, 0x2D, 0xB4, 0x12, 0x6E, 0xA7, 0x52, 0x25, 0xB3, 0xE1, 0x34, 0xF5, 0x6D, 0x78, + 0x33, 0x98, 0x1E, 0x8A, 0x00, 0x27, 0x69, 0xEA, 0xB0, 0x2E, 0xC7, 0x75, 0x74, 0xBA, 0x60, 0x3F, + 0xB5, 0x4B, 0xE9, 0x70, 0xBC, 0xD2, 0x2C, 0x49, 0xF6, 0x7D, 0x8A, 0x33, 0xE8, 0xC0, 0x9B, 0xDE, + 0x61, 0xFC, 0x82, 0xE8, 0x49, 0xF7, 0x32, 0xBB, 0x5D, 0x4A, 0x3C, 0x77, 0x7C, 0x47, 0xB8, 0x48, + 0x02, 0xFE, 0xEC, 0xBF, 0xC9, 0xF6, 0x79, 0x79, 0xC0, 0x85, 0x99, 0xCF, 0xAE, 0x38, 0x37, 0x31, + 0x4A, 0xC0, 0x14, 0x3C, 0x83, 0x80, 0x0E, 0x9F, 0xC9, 0x3B, 0xAD, 0x47, 0x6A, 0xCA, 0x46, 0x20, + 0x4D, 0x84, 0x93, 0x02, 0xAE, 0x98, 0xBC, 0x65, 0x2C, 0x5E, 0xAC, 0x10, 0xBC, 0x33, 0x4D, 0x65, + 0x36, 0x92, 0xF4, 0x8E, 0x46, 0x7C, 0x52, 0x8A, 0xE9, 0x54, 0x6A, 0x48, 0xD6, 0xB8, 0x31, 0xC5, + 0x84, 0xCB, 0x3E, 0xFD, 0xEA, 0x78, 0xB3, 0x20, 0xC1, 0xFA, 0x4C, 0xDE, 0xB3, 0xD6, 0xBD, 0xBF, + 0xE8, 0x80, 0x2D, 0x88, 0xB3, 0x41, 0x0E, 0xC6, 0x81, 0x48, 0xF8, 0x8C, 0xB8, 0xE3, 0x5C, 0x7F, + 0xFF, 0x98, 0x51, 0xFF, 0x8E, 0x67, 0x38, 0xF6, 0x7C, 0xF0, 0x27, 0x5B, 0x8D, 0xB6, 0x7C, 0x86, + 0xBD, 0x4C, 0xDA, 0xCA, 0x81, 0x5D, 0x23, 0x27, 0x81, 0xA4, 0x44, 0x41, 0xEC, 0x16, 0xC2, 0xF7, + 0xE7, 0xCF, 0x65, 0x97, 0x47, 0x6B, 0xE4, 0x27, 0x09, 0xE4, 0xD3, 0xB7, 0xCF, 0x6D, 0x67, 0xF8, + 0x19, 0x37, 0x71, 0xD5, 0x8F, 0xCC, 0x13, 0x15, 0xF9, 0xAD, 0xD5, 0x46, 0x47, 0x07, 0x01, 0xA2, + 0xCD, 0xE9, 0x75, 0x4C, 0xD5, 0x36, 0x27, 0x67, 0x0D, 0x2F, 0x5D, 0x2F, 0x6C, 0xB5, 0xF5, 0xCB, + 0xD1, 0x4B, 0x91, 0x38, 0x7C, 0x39, 0xFC, 0x63, 0x4D, 0x59, 0x60, 0x2B, 0x80, 0x3E, 0x85, 0x5E, + 0x03, 0x27, 0xD7, 0x16, 0x07, 0x8C, 0x81, 0xC8, 0x2E, 0x10, 0xE0, 0x06, 0xED, 0x64, 0x6A, 0xFB, + 0x4E, 0xE0, 0xB9, 0x73, 0xC9, 0x4F, 0xAC, 0x5A, 0xDA, 0xA1, 0xC7, 0x9F, 0x9E, 0x46, 0x63, 0x4C, + 0x17, 0xA6, 0xB4, 0x1D, 0x3C, 0x8D, 0x47, 0x5A, 0x66, 0x03, 0x8D, 0xBB, 0xE4, 0x85, 0xFD, 0x6D, + 0x3A, 0x74, 0x60, 0x77, 0x58, 0xCD, 0x9B, 0xCE, 0xC0, 0xFE, 0x67, 0x65, 0x57, 0x3F, 0xB5, 0x4D, + 0x8E, 0x0D, 0xCC, 0x6E, 0x18, 0x8F, 0x09, 0x22, 0x67, 0x86, 0x66, 0x7A, 0xA2, 0xE5, 0x84, 0xE6, + 0xA6, 0x81, 0x80, 0x21, 0xBB, 0x23, 0x63, 0x27, 0xC4, 0xDC, 0x97, 0x01, 0x9E, 0xD6, 0x04, 0x21, + 0xB5, 0x87, 0x11, 0x2A, 0x18, 0xCF, 0x03, 0xB4, 0x32, 0xB8, 0xA4, 0x67, 0x76, 0x06, 0x2C, 0x19, + 0x5D, 0xC6, 0xD5, 0xC0, 0xAD, 0xC3, 0x56, 0x61, 0xCC, 0xD4, 0xE0, 0xBE, 0x3A, 0x9B, 0x62, 0x61, + 0x71, 0x90, 0x2C, 0x0C, 0x02, 0x42, 0x19, 0xF2, 0xD0, 0x99, 0xD0, 0xB6, 0x92, 0xA1, 0x9D, 0xED, + 0x3F, 0xC0, 0x7A, 0x48, 0x88, 0x4C, 0xAC, 0xBD, 0x82, 0xF0, 0x0E, 0x56, 0x3D, 0x68, 0xE3, 0xC7, + 0x36, 0x1E, 0xA3, 0x34, 0x5C, 0xCF, 0xA5, 0x0D, 0x35, 0xB7, 0x3B, 0xDB, 0xA7, 0x29, 0x86, 0xBC, + 0x1A, 0x7B, 0x83, 0x2F, 0x1A, 0xA8, 0x13, 0xA9, 0x47, 0x1F, 0x70, 0xB8, 0x12, 0x12, 0x5C, 0xB6, + 0x98, 0x11, 0xC5, 0x98, 0xE4, 0xCE, 0x15, 0x29, 0xE5, 0x5B, 0xD2, 0xF3, 0xBB, 0x7B, 0x39, 0xD7, + 0x7C, 0x8B, 0xAD, 0x67, 0x78, 0x62, 0xF9, 0xD5, 0x55, 0x61, 0xA3, 0xF7, 0xFB, 0x3F, 0xA1, 0x2C, + 0x71, 0x25, 0x25, 0x2C, 0x19, 0xCF, 0x53, 0x1B, 0xDE, 0xD8, 0xFC, 0xEC, 0x8C, 0xF7, 0xC6, 0x90, + 0x07, 0x81, 0x43, 0xBB, 0x1A, 0xC5, 0xB3, 0x21, 0x23, 0x58, 0x73, 0xB1, 0xF0, 0x2D, 0x33, 0xD9, + 0xA4, 0x8A, 0xBC, 0xDC, 0xB1, 0x1D, 0xE5, 0xC9, 0xBA, 0x19, 0x66, 0xA4, 0x95, 0xDC, 0xD3, 0xE2, + 0x09, 0xBB, 0x19, 0x72, 0xF6, 0xC0, 0x88, 0xEF, 0x2F, 0x45, 0xFD, 0xCB, 0xB7, 0x44, 0x7E, 0x23, + 0x66, 0x34, 0xCE, 0xC3, 0x9B, 0x1A, 0xFF, 0x6A, 0x46, 0x5E, 0x31, 0x25, 0xFD, 0x24, 0xD6, 0xF2, + 0xD9, 0x86, 0x35, 0xBE, 0xBF, 0xA6, 0x8D, 0x57, 0x34, 0x28, 0x7F, 0x82, 0xDE, 0x97, 0x11, 0xA5, + 0x5F, 0x70, 0xC4, 0xC2, 0x7E, 0xBE, 0x1B, 0xA5, 0xF4, 0x95, 0x9E, 0x70, 0x72, 0xEA, 0xEC, 0xA3, + 0x96, 0x0B, 0x56, 0xEA, 0x8C, 0xE7, 0xCF, 0x77, 0x52, 0x9B, 0x00, 0x6A, 0xD7, 0xB0, 0x4E, 0x59, + 0xFE, 0xAD, 0x19, 0xF9, 0x32, 0x3D, 0x95, 0x9A, 0x08, 0x60, 0x14, 0x04, 0xCC, 0xA2, 0x91, 0x26, + 0x8E, 0xAD, 0xE6, 0x6A, 0x93, 0x8D, 0x24, 0x76, 0xFE, 0xCE, 0x76, 0x57, 0xC0, 0x45, 0x43, 0x4F, + 0x23, 0x99, 0x20, 0xF8, 0x06, 0x8B, 0xD6, 0x7B, 0x15, 0x54, 0x21, 0x6B, 0x8E, 0x78, 0xD2, 0x7A, + 0x71, 0xCE, 0xED, 0x38, 0x69, 0xC5, 0x96, 0x3D, 0x32, 0xE9, 0x4B, 0x64, 0x85, 0x25, 0xF0, 0x09, + 0x9C, 0xC9, 0x74, 0xEC, 0x0C, 0x60, 0x92, 0x61, 0x96, 0x9A, 0x99, 0x68, 0x34, 0x29, 0xB8, 0xF3, + 0xC2, 0x02, 0x4C, 0xB2, 0x4D, 0x1D, 0xF7, 0x8E, 0xFF, 0x1E, 0x6D, 0xB3, 0xD0, 0x6F, 0xF0, 0x57, + 0xD0, 0xCE, 0xEC, 0x76, 0xF9, 0x4D, 0x5D, 0x46, 0xB7, 0xAB, 0x6D, 0x57, 0x9E, 0xE8, 0x41, 0x8B, + 0x31, 0x83, 0x72, 0x73, 0xB9, 0x09, 0x3F, 0x25, 0x54, 0xD0, 0x0D, 0xB2, 0x30, 0xEE, 0x8B, 0xC8, + 0xC7, 0x4F, 0xEE, 0x2A, 0xB1, 0x10, 0xBF, 0xE4, 0x33, 0xB1, 0x11, 0x15, 0xA6, 0x58, 0x89, 0x47, + 0xA2, 0xE4, 0x23, 0xF4, 0x8A, 0x7D, 0x84, 0xDC, 0x93, 0xE4, 0xEC, 0xA1, 0x52, 0xDD, 0x49, 0xC8, + 0xB7, 0x7A, 0xD5, 0xBC, 0x87, 0x05, 0xAB, 0x3C, 0x17, 0xF0, 0x42, 0x54, 0x5E, 0xDB, 0x0E, 0x75, + 0x87, 0x68, 0x21, 0x98, 0x5C, 0xE4, 0x59, 0x0D, 0x93, 0x73, 0x47, 0x73, 0x68, 0xB4, 0x56, 0xE0, + 0xFB, 0xAE, 0x09, 0x77, 0x4B, 0xC9, 0xBC, 0x77, 0x86, 0x8B, 0x23, 0x36, 0x30, 0xA0, 0xD1, 0xB8, + 0x3C, 0xA3, 0x98, 0x1D, 0x3D, 0x5E, 0x2E, 0xB5, 0xA6, 0x63, 0x58, 0x73, 0xE0, 0x98, 0xB1, 0xC7, + 0xB7, 0xF6, 0x5D, 0xB0, 0x12, 0xB0, 0xA8, 0x6A, 0x5C, 0x5F, 0x96, 0x62, 0xAF, 0x21, 0x41, 0x1D, + 0xBF, 0x48, 0x53, 0x4F, 0xBB, 0x6E, 0xE9, 0x55, 0x00, 0xFE, 0x03, 0x0D, 0xDB, 0x48, 0xAB, 0xA5, + 0xB0, 0x22, 0x3F, 0x05, 0xC4, 0xA9, 0x5C, 0x1C, 0xBF, 0x40, 0xD7, 0x41, 0x35, 0xF1, 0x47, 0x2B, + 0x2A, 0x5C, 0x26, 0x5D, 0xCB, 0xB2, 0x22, 0x77, 0x43, 0xDF, 0xD6, 0x86, 0x06, 0x1D, 0x5D, 0xE3, + 0xF5, 0x9B, 0x1B, 0xE6, 0xA7, 0x71, 0x31, 0x2C, 0x13, 0x67, 0x32, 0xA1, 0x43, 0x07, 0xDC, 0x0F, + 0x68, 0xAB, 0x4F, 0x59, 0x0C, 0xCB, 0x60, 0x36, 0x00, 0x87, 0x55, 0x8C, 0xF2, 0xE8, 0xE0, 0xAB, + 0xCF, 0x3F, 0xB6, 0x9A, 0xB8, 0x50, 0x7B, 0x13, 0x62, 0x10, 0xA9, 0xC6, 0xA9, 0x17, 0x0B, 0x03, + 0x06, 0x07, 0x28, 0x12, 0x98, 0xC9, 0x46, 0xEC, 0xEE, 0xE8, 0x2E, 0x19, 0xBB, 0x50, 0x0B, 0x1E, + 0xD4, 0x32, 0x61, 0xDB, 0xE3, 0x78, 0x23, 0x48, 0x71, 0xD1, 0x50, 0x23, 0xF8, 0xA5, 0x5B, 0x6D, + 0xD3, 0x19, 0x9F, 0x00, 0xB3, 0x82, 0x97, 0x04, 0x15, 0x26, 0x86, 0x46, 0xEF, 0x29, 0xA6, 0x30, + 0xC0, 0xA5, 0x60, 0x44, 0xA2, 0x1C, 0xDE, 0x66, 0xDA, 0x6D, 0x8C, 0x5A, 0x89, 0x5C, 0x4E, 0x82, + 0x51, 0x0A, 0x8F, 0x28, 0x37, 0x71, 0x88, 0xAC, 0x01, 0x48, 0x9A, 0xA9, 0x04, 0x67, 0x59, 0x74, + 0x06, 0xC6, 0x4E, 0x82, 0x51, 0xC4, 0x94, 0x90, 0x5F, 0xB4, 0x29, 0x2E, 0x7B, 0xA8, 0xA2, 0x20, + 0xBD, 0x9F, 0x9E, 0x3E, 0xCF, 0x88, 0xCE, 0x6D, 0xF0, 0x3E, 0x19, 0xEE, 0x6B, 0xB4, 0x7D, 0x16, + 0x64, 0xB8, 0x25, 0x6E, 0x3F, 0xC7, 0x9C, 0xED, 0xE4, 0x43, 0x61, 0x04, 0x20, 0xE5, 0xC2, 0xB4, + 0xF1, 0xA6, 0x05, 0x3F, 0x16, 0xF9, 0x97, 0x72, 0x86, 0xA1, 0xA9, 0x67, 0x65, 0x0E, 0x53, 0xE4, + 0x8A, 0xF8, 0x33, 0x34, 0x29, 0x9F, 0x43, 0xC3, 0xAB, 0xFD, 0xCC, 0x9E, 0x16, 0x7D, 0x94, 0xE8, + 0xB8, 0xA4, 0x3D, 0x72, 0xFF, 0x35, 0x84, 0x22, 0x37, 0x38, 0x8E, 0x38, 0x40, 0x87, 0xAE, 0x34, + 0x52, 0x7F, 0x6B, 0xEB, 0x18, 0x83, 0xA6, 0xA0, 0x65, 0x67, 0x5D, 0x2F, 0x3B, 0xEF, 0x09, 0x3E, + 0x74, 0x60, 0xE4, 0xEB, 0xA7, 0x1F, 0xDE, 0xFC, 0x22, 0x29, 0x23, 0x2B, 0x16, 0x0E, 0x0F, 0x2B, + 0x66, 0x74, 0x2D, 0x30, 0x26, 0x1B, 0x1B, 0xC0, 0xEF, 0xC9, 0x2C, 0xC0, 0xCB, 0x7A, 0xF0, 0xBF, + 0xF0, 0x16, 0xAF, 0xEC, 0x59, 0xCC, 0x9B, 0x80, 0xB2, 0xC6, 0x32, 0xCE, 0x46, 0xE3, 0xB1, 0x3D, + 0x0D, 0x28, 0xA6, 0x25, 0xE4, 0x5B, 0x46, 0xEC, 0xCC, 0x48, 0x55, 0x5F, 0x13, 0x7D, 0x3C, 0x1D, + 0x78, 0x48, 0x1E, 0x10, 0x7F, 0x31, 0x1F, 0x98, 0x6E, 0xAA, 0x0C, 0x17, 0x9B, 0xD9, 0x4C, 0x6C, + 0xCE, 0x23, 0x07, 0xA4, 0x5F, 0x56, 0x12, 0xF5, 0x78, 0x28, 0x25, 0x07, 0x1E, 0xA7, 0xD5, 0xEA, + 0x94, 0x61, 0xA3, 0x93, 0xC9, 0x45, 0xA7, 0xBE, 0x20, 0x22, 0x06, 0x60, 0xFA, 0x2A, 0xC5, 0x03, + 0xD4, 0xCB, 0x66, 0x03, 0x0A, 0xCB, 0x73, 0x22, 0x2A, 0xF5, 0xB9, 0x13, 0x04, 0x33, 0xE9, 0x80, + 0x47, 0x32, 0x1B, 0xC0, 0x44, 0x2F, 0xCF, 0x4E, 0xA2, 0xC0, 0x64, 0x8D, 0x70, 0x74, 0x47, 0x36, + 0x05, 0x6A, 0x72, 0x48, 0x93, 0xD5, 0x02, 0x1F, 0x65, 0x85, 0x95, 0xAE, 0xE0, 0x32, 0xB7, 0x22, + 0xC8, 0x6C, 0x9A, 0x07, 0xC0, 0xAD, 0x5C, 0x9A, 0x80, 0xDC, 0x56, 0x58, 0xD2, 0x3A, 0xB8, 0x6B, + 0xFC, 0xD6, 0xA1, 0xE3, 0x61, 0xB2, 0xB7, 0x8A, 0xD7, 0x32, 0xB8, 0x10, 0xC4, 0xC6, 0xC3, 0x20, + 0x09, 0xEB, 0xA9, 0x8B, 0x27, 0x16, 0xAA, 0x38, 0x20, 0x16, 0x61, 0x79, 0x41, 0xDA, 0xD1, 0x29, + 0x33, 0x52, 0x8F, 0x3C, 0x80, 0x4C, 0xE8, 0xA4, 0x4B, 0x10, 0x14, 0x03, 0xA8, 0x55, 0x85, 0xC3, + 0xAE, 0x14, 0xA0, 0xF0, 0x6B, 0x39, 0xE8, 0x37, 0x49, 0x1C, 0x72, 0x00, 0x65, 0x51, 0xC9, 0xAB, + 0x53, 0x65, 0xE3, 0x49, 0x80, 0x97, 0xA6, 0xDC, 0xEB, 0x49, 0x82, 0x92, 0x0E, 0xFB, 0x4A, 0x42, + 0x4B, 0xE1, 0xCA, 0x19, 0x02, 0xFC, 0xB3, 0x14, 0xE4, 0xCF, 0xCE, 0x5B, 0x27, 0x01, 0xBC, 0x75, + 0xAE, 0x9D, 0x72, 0x70, 0x17, 0xFB, 0xBD, 0x0F, 0x07, 0x12, 0xCF, 0xE1, 0x60, 0xFA, 0x61, 0x38, + 0x2D, 0x07, 0xCB, 0x82, 0x55, 0x25, 0xA0, 0x6C, 0x9F, 0xA0, 0x1C, 0x64, 0xFA, 0x34, 0xE3, 0x2E, + 0xC1, 0x23, 0x2D, 0x54, 0xCA, 0x61, 0xEB, 0xDF, 0x05, 0x21, 0x9D, 0x24, 0x08, 0x02, 0xFE, 0x77, + 0x29, 0xD8, 0x43, 0x35, 0xD6, 0x3C, 0x40, 0xC7, 0xD1, 0xE7, 0x4B, 0xC1, 0x9F, 0x5E, 0x48, 0xC2, + 0xC3, 0x80, 0xF4, 0xA5, 0xA0, 0xDE, 0x26, 0x7B, 0x2D, 0x08, 0x27, 0x6F, 0xBD, 0x44, 0xF0, 0xDC, + 0x6F, 0xD2, 0x27, 0x7A, 0x3E, 0x8A, 0xC5, 0x90, 0x14, 0x27, 0x37, 0x29, 0x03, 0x2A, 0x16, 0x72, + 0x71, 0xA0, 0x32, 0xBC, 0xAC, 0xCA, 0xAC, 0xF9, 0xFA, 0xB6, 0x64, 0x4A, 0x59, 0x9E, 0xD9, 0xF5, + 0x6D, 0xF4, 0xEA, 0x7D, 0x7B, 0x80, 0x17, 0xB2, 0x64, 0x53, 0xAA, 0x8E, 0xFA, 0x64, 0xA1, 0xC4, + 0x92, 0x12, 0x67, 0xD0, 0xE5, 0x86, 0xDB, 0x70, 0x15, 0x03, 0x2C, 0x79, 0x1B, 0x56, 0x2B, 0x9D, + 0x2E, 0x06, 0xCC, 0x36, 0x59, 0x73, 0x5E, 0xCA, 0x6D, 0xBA, 0xC5, 0x00, 0x4C, 0x06, 0x24, 0x92, + 0x2A, 0x92, 0xDC, 0x97, 0x43, 0xD5, 0x27, 0x07, 0x61, 0x26, 0x76, 0x78, 0xF0, 0xF1, 0x06, 0x9B, + 0x4E, 0xB6, 0xB3, 0x27, 0x93, 0x6D, 0xAB, 0x04, 0xD9, 0x14, 0xEA, 0xFD, 0xD3, 0xB3, 0xB9, 0x31, + 0xB3, 0x65, 0xB6, 0xBA, 0x19, 0x6D, 0x8C, 0x99, 0x6F, 0x72, 0xF6, 0x0D, 0x5C, 0x61, 0x84, 0xF4, + 0x93, 0xB8, 0xD1, 0x2B, 0xDB, 0x59, 0xCC, 0x41, 0x49, 0x29, 0xF6, 0xEE, 0x33, 0x99, 0x1C, 0x88, + 0x93, 0x43, 0xDA, 0x9B, 0x4E, 0xE3, 0x2C, 0x00, 0x45, 0x5C, 0x72, 0xED, 0x64, 0xC1, 0x3B, 0x83, + 0x53, 0x30, 0x1F, 0x93, 0x89, 0x1D, 0xC8, 0xA8, 0x7A, 0x3D, 0xAE, 0xAC, 0x6B, 0x96, 0xAE, 0xAC, + 0x6B, 0x96, 0xA4, 0xAC, 0x6D, 0xD2, 0xA7, 0x53, 0x3B, 0x8E, 0x1C, 0x1A, 0x30, 0x7C, 0x6D, 0xC2, + 0xF1, 0xB1, 0x97, 0x27, 0x30, 0xC5, 0x79, 0xB7, 0x74, 0x58, 0xB6, 0x71, 0x59, 0x17, 0x46, 0xE2, + 0xDB, 0x6E, 0x65, 0x9A, 0x85, 0x49, 0x29, 0x62, 0xE0, 0x7D, 0x1B, 0x54, 0xD4, 0x7F, 0xEF, 0x05, + 0xA1, 0x18, 0x7E, 0x1B, 0xA9, 0xE1, 0xB7, 0x91, 0x31, 0xFC, 0xD2, 0x8C, 0x66, 0x74, 0x76, 0x8A, + 0x1C, 0x4E, 0x21, 0x9C, 0xDC, 0x36, 0xFE, 0xD3, 0x29, 0xB2, 0x8F, 0xD5, 0x28, 0x19, 0x5A, 0x76, + 0x82, 0x26, 0xA9, 0x87, 0xD3, 0x5B, 0xA9, 0xBE, 0xAA, 0x46, 0x8F, 0xB7, 0xE3, 0x43, 0x40, 0xFD, + 0x6C, 0x69, 0xA6, 0x0B, 0xB0, 0x3E, 0x9B, 0x85, 0xC2, 0x2F, 0xDD, 0x91, 0xD7, 0x1E, 0x78, 0x13, + 0xFC, 0x0B, 0xBF, 0x92, 0x09, 0x32, 0x36, 0x0B, 0xD8, 0xF1, 0xB4, 0x03, 0xAB, 0xA7, 0x89, 0xED, + 0x8C, 0xF1, 0x39, 0x12, 0x9E, 0x72, 0x97, 0xD1, 0x8E, 0xD5, 0x55, 0xC2, 0x6F, 0xC0, 0xE1, 0xE3, + 0xBA, 0x5B, 0x98, 0xAC, 0xC4, 0x45, 0x3E, 0xDC, 0x0E, 0x12, 0xE9, 0x02, 0x02, 0x76, 0x0E, 0xD6, + 0x26, 0x9C, 0x9E, 0x7D, 0x47, 0x6E, 0x6D, 0xB0, 0xD9, 0x20, 0x87, 0x21, 0x8F, 0x75, 0xCF, 0x63, + 0xD0, 0xE3, 0x7E, 0x3D, 0x53, 0xCD, 0xB1, 0xC7, 0xB9, 0xE1, 0x7B, 0xAC, 0xB8, 0x47, 0x13, 0x6D, + 0x51, 0xB5, 0x23, 0x8A, 0xD2, 0x92, 0x19, 0xFE, 0xE2, 0x1B, 0xFC, 0xB8, 0xEB, 0xC1, 0x65, 0x94, + 0x23, 0x19, 0x49, 0x00, 0xA2, 0x15, 0xE5, 0xE0, 0x85, 0xE2, 0x74, 0x3B, 0x56, 0xA7, 0x24, 0x9C, + 0xA2, 0x05, 0x8D, 0xAB, 0xF1, 0xD0, 0xBF, 0x84, 0x61, 0xED, 0x7F, 0x79, 0x3B, 0x73, 0x3B, 0x8D, + 0xCA, 0x38, 0x7A, 0x3F, 0x57, 0xE3, 0x37, 0xEA, 0xF0, 0x90, 0x06, 0xE1, 0xFF, 0xC1, 0x1F, 0xD5, + 0x9B, 0x8C, 0x28, 0x80, 0x2C, 0x20, 0xD1, 0xE0, 0x46, 0xEA, 0xC8, 0xBA, 0x10, 0x49, 0x18, 0xDE, + 0xBD, 0xDB, 0xCB, 0xB8, 0x3A, 0x0E, 0x70, 0xF1, 0xF6, 0x30, 0x3F, 0xA7, 0x41, 0x07, 0x1B, 0x16, + 0xBF, 0xD1, 0x9B, 0x38, 0x7E, 0x6E, 0x23, 0x6A, 0x4C, 0xD8, 0x06, 0x04, 0xD6, 0x70, 0x86, 0x78, + 0xC6, 0x61, 0xFB, 0x4C, 0x07, 0x98, 0x52, 0x69, 0x21, 0x8B, 0x9E, 0x7D, 0xA7, 0x50, 0xFB, 0xB8, + 0xCD, 0x90, 0xB0, 0x92, 0x7F, 0xA2, 0xD4, 0xE4, 0x71, 0x4C, 0x9D, 0xE1, 0x7F, 0xEC, 0x6A, 0xDC, + 0x7F, 0x96, 0x37, 0x60, 0x4C, 0x5B, 0xE3, 0x12, 0x89, 0xAC, 0xFD, 0x70, 0xF3, 0x63, 0x54, 0x09, + 0x50, 0x3F, 0x47, 0x8A, 0xED, 0x89, 0xBE, 0x0F, 0x62, 0x7E, 0x4A, 0x28, 0x07, 0xA5, 0x2E, 0xDF, + 0x31, 0xEC, 0xE1, 0xEC, 0x62, 0xA5, 0xC5, 0x50, 0x3E, 0x29, 0x89, 0xB1, 0xFD, 0x8A, 0x3C, 0xA9, + 0x99, 0x74, 0x1E, 0x37, 0x3A, 0x0C, 0x5A, 0x5F, 0x2D, 0xED, 0xBB, 0xC4, 0x7E, 0x69, 0x69, 0xEA, + 0xD1, 0x5E, 0x0A, 0x45, 0x39, 0xA9, 0x25, 0xC7, 0x49, 0x25, 0x21, 0xB2, 0x6D, 0xA7, 0x22, 0xC5, + 0x9B, 0xB3, 0xB5, 0xC9, 0xC3, 0xEF, 0x3F, 0x54, 0x93, 0xCB, 0x8D, 0x97, 0xC7, 0x6A, 0x71, 0xD5, + 0xB1, 0xC2, 0x8D, 0x2F, 0x4F, 0x3F, 0xF5, 0xCB, 0x06, 0x4F, 0xEB, 0x13, 0x85, 0xBC, 0x29, 0x1E, + 0x31, 0x2A, 0xF4, 0xA2, 0x86, 0x4E, 0x2A, 0x52, 0xD1, 0xF7, 0x92, 0xAE, 0xE2, 0xE3, 0x4A, 0xB0, + 0xB8, 0x90, 0x04, 0x77, 0x73, 0x13, 0xDF, 0xF4, 0x18, 0xD7, 0x91, 0x1D, 0xBE, 0x49, 0x8A, 0xE5, + 0xB9, 0x1B, 0x83, 0x0B, 0x55, 0x48, 0x3D, 0x5E, 0xD3, 0xEF, 0x52, 0x6A, 0xD1, 0xEE, 0x72, 0xE1, + 0x04, 0xC0, 0x37, 0x78, 0xF3, 0x66, 0x80, 0x82, 0x94, 0xE5, 0x19, 0xDE, 0x4A, 0x92, 0x7E, 0xF0, + 0xF7, 0x38, 0x51, 0xC4, 0xFB, 0xF2, 0x7F, 0xA8, 0xB9, 0x42, 0x3E, 0x0C, 0xF8, 0x23, 0xCD, 0x18, + 0x65, 0xDB, 0x1D, 0x0F, 0x2F, 0x96, 0x9D, 0x4D, 0xDA, 0x76, 0x8B, 0x36, 0x2C, 0x0C, 0x2F, 0x8C, + 0x4A, 0xEE, 0x57, 0x88, 0xFD, 0x03, 0xEF, 0x2A, 0x40, 0xDB, 0xC5, 0xB2, 0x46, 0xD2, 0x81, 0xE7, + 0x0E, 0x71, 0x45, 0xBC, 0x69, 0x31, 0x6B, 0x61, 0xB0, 0x15, 0x9B, 0x2C, 0xCF, 0xDC, 0xA6, 0x7A, + 0xEC, 0xF2, 0xC6, 0x98, 0xF5, 0x33, 0x9F, 0x18, 0x8C, 0x77, 0x07, 0xFF, 0xBB, 0x37, 0x18, 0xCC, + 0x7C, 0x7B, 0x70, 0xC7, 0xF7, 0x11, 0x36, 0xDA, 0xA6, 0x33, 0xA7, 0x4E, 0x9B, 0x51, 0xDD, 0x68, + 0xE7, 0x50, 0x4D, 0xC8, 0x2A, 0x4B, 0x3E, 0xF6, 0x3C, 0xE9, 0x90, 0x45, 0xA8, 0x5F, 0x26, 0x2B, + 0x9D, 0xEE, 0x96, 0xD5, 0xB5, 0x36, 0xDB, 0x1B, 0x9B, 0x5B, 0x32, 0xA3, 0x66, 0x88, 0x8F, 0x08, + 0xB1, 0xFE, 0xA2, 0xB3, 0xB9, 0x65, 0xAD, 0xB7, 0xD7, 0xAD, 0xB5, 0x62, 0x88, 0x5F, 0x01, 0x62, + 0xDD, 0xDA, 0xDA, 0xDC, 0xDC, 0xDC, 0x68, 0xAF, 0x6F, 0xAD, 0xE7, 0x03, 0x1C, 0xDB, 0x21, 0x4B, + 0x5F, 0x88, 0x20, 0x6D, 0x6B, 0xDB, 0xEA, 0x6E, 0xAF, 0xBF, 0xD8, 0x2E, 0x00, 0xF1, 0xDC, 0x91, + 0x80, 0x59, 0xE9, 0x58, 0x20, 0xAB, 0xAD, 0x0D, 0x6B, 0xE3, 0xC5, 0x66, 0x27, 0x1F, 0x6A, 0x6F, + 0x1C, 0x3A, 0xE1, 0x6C, 0xC8, 0xB6, 0x80, 0x37, 0x36, 0x81, 0xD6, 0xD6, 0xB6, 0xB2, 0xBB, 0xA1, + 0x9D, 0xCD, 0xAB, 0x18, 0x32, 0xD4, 0x23, 0x93, 0x62, 0x7E, 0x0F, 0x43, 0x0F, 0xCA, 0x5D, 0x15, + 0x29, 0x71, 0xFE, 0xBB, 0xB4, 0x1C, 0x7D, 0xAE, 0x29, 0xDA, 0xFA, 0xE2, 0xAD, 0x24, 0xE2, 0x82, + 0x09, 0x5A, 0xD3, 0xCD, 0x17, 0x16, 0xFB, 0xB7, 0x4C, 0xE2, 0x5F, 0xE2, 0x71, 0x10, 0x95, 0xE1, + 0x20, 0x10, 0xBF, 0x16, 0x0F, 0xBF, 0x22, 0xA2, 0x1F, 0xBF, 0x07, 0xD1, 0x5F, 0x1F, 0x82, 0xE8, + 0x7D, 0xDE, 0xE3, 0xDE, 0xEA, 0xE6, 0xA0, 0x9E, 0x49, 0xA8, 0x64, 0x16, 0xD2, 0xF2, 0x4A, 0xDE, + 0xFD, 0x80, 0xB1, 0xFF, 0x89, 0xFA, 0x98, 0x91, 0x11, 0xBE, 0xAD, 0xB2, 0xA0, 0x1A, 0x49, 0x9C, + 0xC5, 0x52, 0x82, 0x96, 0xB4, 0x71, 0xA5, 0xD3, 0xB1, 0xD6, 0xD6, 0x97, 0xC9, 0xD6, 0x96, 0x72, + 0xF4, 0xC3, 0x3F, 0xA3, 0x90, 0xB1, 0xA0, 0x84, 0x51, 0xCD, 0x20, 0xA7, 0x3F, 0xBE, 0x47, 0x82, + 0x98, 0x20, 0x75, 0x43, 0xA1, 0xB5, 0xC1, 0x52, 0x8D, 0x6E, 0xD4, 0xD6, 0x1E, 0xF3, 0xC3, 0x3D, + 0xA0, 0xD5, 0xE5, 0x0E, 0x6D, 0x57, 0xF3, 0x6B, 0xF9, 0x77, 0x9E, 0x0F, 0xD5, 0x6A, 0x97, 0x56, + 0x20, 0x31, 0xD7, 0x1A, 0x8E, 0x02, 0xE2, 0x57, 0xA8, 0x75, 0x8E, 0x02, 0x38, 0x70, 0xB2, 0x45, + 0x7B, 0x69, 0x95, 0x3E, 0x8B, 0x93, 0xE1, 0x19, 0xD3, 0x56, 0x99, 0xC3, 0x00, 0x99, 0x20, 0xEE, + 0xE9, 0x46, 0x04, 0xF3, 0x8F, 0x03, 0xCA, 0xD3, 0xCA, 0x6C, 0x1D, 0xEE, 0xA6, 0x32, 0x62, 0x96, + 0xD6, 0x3A, 0x6B, 0xCE, 0xD6, 0xE5, 0x52, 0xEC, 0xFD, 0xFC, 0x58, 0x34, 0x93, 0xAD, 0xEA, 0x07, + 0xE9, 0xC3, 0x5C, 0x8A, 0x8F, 0xD7, 0x4A, 0x49, 0x53, 0x3B, 0xF5, 0x29, 0x76, 0x6A, 0x69, 0xAA, + 0x20, 0xA8, 0x6B, 0xAA, 0x95, 0xAF, 0xA9, 0x9D, 0x7A, 0x9A, 0xFA, 0x10, 0xAD, 0x2B, 0xD2, 0xD4, + 0x47, 0xA2, 0x29, 0x69, 0xEA, 0xA3, 0x53, 0x7C, 0xBC, 0x56, 0x4A, 0x9A, 0xDA, 0xAD, 0x4F, 0xB1, + 0x5B, 0x4B, 0x53, 0xBB, 0xB5, 0x34, 0xB5, 0x5B, 0x4F, 0x53, 0x1F, 0xA2, 0x75, 0x45, 0x9A, 0xFA, + 0x48, 0x34, 0x25, 0x4D, 0x7D, 0x74, 0x8A, 0x8F, 0xD7, 0x4A, 0x49, 0x53, 0xD7, 0xEA, 0x53, 0x5C, + 0xAB, 0xA5, 0xA9, 0x6B, 0xB5, 0x34, 0x75, 0xAD, 0x9E, 0xA6, 0x3E, 0x44, 0xEB, 0x8A, 0x34, 0xF5, + 0x91, 0x68, 0x4A, 0x9A, 0xFA, 0xE8, 0x14, 0x17, 0xD4, 0xCA, 0xA7, 0x7E, 0x9B, 0xC1, 0xE8, 0x2A, + 0x57, 0xBA, 0xCF, 0x60, 0xF4, 0x7D, 0x4B, 0xDD, 0x68, 0x30, 0x3A, 0xB2, 0x55, 0xEF, 0x16, 0x64, + 0xF8, 0xA6, 0x8D, 0xB2, 0x90, 0x9A, 0x87, 0xC9, 0xAF, 0x54, 0x0C, 0x6F, 0xDD, 0xF0, 0xD6, 0xED, + 0x56, 0xC7, 0x11, 0x51, 0xFF, 0xF9, 0x7C, 0xE3, 0xF6, 0xDC, 0x5B, 0x7F, 0x5F, 0x8D, 0xFF, 0xD8, + 0x03, 0x6C, 0xD4, 0x10, 0x3B, 0xF3, 0x00, 0xAA, 0xCB, 0xBC, 0x06, 0x39, 0xC9, 0xB1, 0xAA, 0x23, + 0xE6, 0x9A, 0x70, 0x55, 0x29, 0x6A, 0xAE, 0x4A, 0x1D, 0x91, 0x76, 0xEB, 0x89, 0xB4, 0x5B, 0x5B, + 0xA4, 0xDD, 0x9A, 0x22, 0xED, 0xD6, 0x16, 0x69, 0xB7, 0xA6, 0x48, 0xD7, 0x6A, 0x8A, 0x74, 0xAD, + 0x9E, 0x48, 0xD7, 0x6A, 0x8B, 0x74, 0xAD, 0xA6, 0x48, 0xD7, 0x6A, 0x8B, 0x54, 0x87, 0x8C, 0x0F, + 0x14, 0x7A, 0xD2, 0xDD, 0xF4, 0xD4, 0x7D, 0xDE, 0x5E, 0x3A, 0x4A, 0x55, 0x2B, 0xB9, 0x02, 0x8C, + 0xB2, 0x33, 0x9D, 0x45, 0x98, 0xE3, 0x51, 0x55, 0x3B, 0x8E, 0xA0, 0x32, 0x34, 0xBE, 0x79, 0x7C, + 0xC3, 0xCF, 0x00, 0x38, 0x36, 0xB6, 0xE8, 0xDE, 0xB4, 0x52, 0xDB, 0x86, 0x1D, 0x7E, 0x28, 0xB1, + 0x8C, 0x5F, 0xB5, 0x2D, 0x43, 0xF9, 0x46, 0x7D, 0xBE, 0xFB, 0xA4, 0x90, 0x3E, 0x66, 0x47, 0x3F, + 0x0B, 0x22, 0x18, 0x0B, 0x1D, 0x2F, 0xE9, 0x17, 0x5D, 0xDA, 0xC6, 0xAB, 0xFB, 0xA7, 0xD0, 0x68, + 0xCF, 0xFF, 0x72, 0x69, 0xF5, 0xFB, 0x47, 0x07, 0xA5, 0x27, 0x7E, 0xC3, 0x53, 0x00, 0xC3, 0xD5, + 0x65, 0x23, 0x9D, 0x9E, 0x1D, 0x04, 0xF0, 0xDB, 0xF0, 0x11, 0x68, 0x75, 0x1E, 0xA9, 0x4D, 0x9D, + 0x47, 0x6C, 0x53, 0xF7, 0x91, 0xDA, 0xD4, 0x7D, 0xC4, 0x36, 0xAD, 0x3D, 0x52, 0x9B, 0xD6, 0x16, + 0xD4, 0x26, 0x31, 0xC4, 0x2E, 0xF6, 0x7B, 0xAB, 0x1F, 0x0E, 0x7A, 0xD9, 0xF6, 0xE9, 0x62, 0x50, + 0xF9, 0x6A, 0xB7, 0x30, 0x10, 0x71, 0x04, 0xB0, 0xE4, 0x8A, 0xF5, 0xE6, 0xC6, 0xC6, 0x5A, 0xEA, + 0x52, 0x37, 0xFB, 0x28, 0x33, 0xAA, 0xBC, 0xB1, 0x29, 0xF0, 0xFF, 0x63, 0x22, 0xD2, 0xB5, 0xF1, + 0xF2, 0xAF, 0x36, 0x4C, 0x94, 0xEE, 0xCD, 0x42, 0xA8, 0xBA, 0xA9, 0x9D, 0x08, 0x81, 0x43, 0x2E, + 0x42, 0x08, 0x26, 0xD6, 0x3E, 0x0C, 0xEB, 0xB2, 0x36, 0x1B, 0x2E, 0x9C, 0xB5, 0xD5, 0xD5, 0x33, + 0x97, 0x44, 0x4F, 0x84, 0x96, 0x09, 0x54, 0x24, 0xBC, 0x77, 0xD8, 0x85, 0x19, 0x4E, 0x0D, 0xD3, + 0x61, 0xB0, 0x65, 0x10, 0xE0, 0xE7, 0x4D, 0x18, 0x12, 0x9B, 0x27, 0xA1, 0x09, 0xF0, 0x6A, 0x00, + 0x46, 0x3B, 0x8A, 0x4E, 0xF1, 0x67, 0x80, 0xC4, 0x73, 0x09, 0x6A, 0xEE, 0x32, 0xD6, 0xB8, 0x63, + 0xC0, 0x57, 0xB4, 0xDD, 0x8E, 0x56, 0x4A, 0xFC, 0x71, 0x8B, 0x08, 0xE8, 0x75, 0x32, 0x0B, 0xE9, + 0xB7, 0xB4, 0xE2, 0xE2, 0x23, 0x25, 0xAD, 0x1B, 0xE1, 0x53, 0x6D, 0xE6, 0xF2, 0x44, 0x21, 0xB8, + 0x62, 0x2F, 0xBD, 0xB2, 0xC7, 0x94, 0x88, 0xCB, 0x58, 0xAD, 0xBB, 0xC6, 0x00, 0x14, 0x1F, 0xF8, + 0x3A, 0x9E, 0xFB, 0xD6, 0xA7, 0xFF, 0x98, 0x51, 0x97, 0x1D, 0x14, 0x6F, 0x5B, 0x6B, 0xF0, 0xA3, + 0xFB, 0x42, 0xEA, 0x3A, 0xF8, 0xC4, 0xB6, 0x2C, 0xBA, 0x2F, 0x64, 0x7E, 0xE5, 0x27, 0x68, 0xF9, + 0xD3, 0x3B, 0x92, 0x03, 0x99, 0x38, 0xF6, 0x98, 0x5D, 0xD7, 0xB2, 0xD9, 0x8B, 0x2C, 0x11, 0x55, + 0xE1, 0x12, 0x07, 0x51, 0x27, 0x75, 0xE9, 0xA1, 0x63, 0xBA, 0xEC, 0x60, 0xA0, 0x98, 0x5C, 0x82, + 0x92, 0xE2, 0x82, 0xE4, 0xBF, 0x91, 0x4A, 0x05, 0xE3, 0x08, 0x8E, 0x9D, 0x6B, 0x2A, 0x7A, 0x63, + 0x83, 0x3D, 0x7B, 0x95, 0x18, 0xE1, 0x27, 0x68, 0x5D, 0x85, 0x8F, 0xEC, 0x27, 0x74, 0x49, 0xB7, + 0x1D, 0xB9, 0x01, 0x74, 0x04, 0x0B, 0xE6, 0x92, 0xCF, 0xCE, 0x02, 0x0F, 0xF2, 0x1E, 0xF3, 0x00, + 0x4F, 0x34, 0x93, 0xBF, 0xFF, 0xCB, 0x53, 0xCF, 0x28, 0x22, 0x66, 0x35, 0x0D, 0x9D, 0xD8, 0xDF, + 0x00, 0xF4, 0x82, 0x77, 0x0A, 0xBE, 0x45, 0xB6, 0x36, 0xB4, 0xE7, 0xC8, 0x8C, 0xC9, 0xCE, 0x32, + 0x7C, 0x5F, 0xD6, 0x9E, 0x22, 0x2B, 0x6F, 0x12, 0xF3, 0x35, 0x93, 0x93, 0x89, 0x3D, 0x4E, 0x14, + 0xC8, 0xD6, 0x56, 0x8A, 0x0A, 0x7E, 0x2B, 0x22, 0x50, 0xE2, 0x42, 0x87, 0xD2, 0xA6, 0x4D, 0x8B, + 0xFC, 0x95, 0x74, 0xB3, 0x2F, 0xAA, 0x68, 0x9C, 0xA9, 0xD5, 0x8D, 0xE7, 0xA5, 0x4A, 0xFC, 0xD1, + 0x6A, 0xD2, 0x4E, 0x40, 0xA3, 0xFB, 0x94, 0xB1, 0xFB, 0x9D, 0xF6, 0xBC, 0x17, 0x21, 0x0A, 0x33, + 0x41, 0x2B, 0xB7, 0x79, 0xA6, 0xA8, 0xA8, 0xD5, 0x9A, 0x69, 0x4B, 0x28, 0x98, 0x9D, 0x8F, 0xC2, + 0xFD, 0x27, 0x87, 0xB4, 0xE6, 0x53, 0xDA, 0xED, 0x05, 0x34, 0x39, 0x87, 0x78, 0x61, 0xBB, 0x53, + 0x39, 0x27, 0xCA, 0x3D, 0x46, 0x54, 0x52, 0x5C, 0x70, 0x17, 0xAF, 0xBB, 0xBD, 0xBE, 0xBD, 0xF9, + 0x22, 0xE5, 0xE7, 0x2D, 0xC3, 0xF7, 0x65, 0x28, 0x58, 0x40, 0x3B, 0x53, 0x54, 0xD9, 0xBD, 0x0A, + 0x4C, 0xFA, 0x2D, 0x76, 0x30, 0x4D, 0x4D, 0xAD, 0x9E, 0x4E, 0xA1, 0x94, 0x04, 0x0A, 0xB2, 0x3C, + 0xF0, 0x80, 0x0F, 0xD6, 0xFA, 0x56, 0xDA, 0xB0, 0xC0, 0xD7, 0xE5, 0xAD, 0x85, 0xA8, 0x7A, 0x31, + 0x0F, 0x79, 0x02, 0x5A, 0x5D, 0x8D, 0x5C, 0xA0, 0x58, 0x5E, 0x99, 0x8F, 0x91, 0xCC, 0xA2, 0x38, + 0xEA, 0xED, 0xF1, 0xE7, 0x76, 0xAD, 0xF8, 0x79, 0xF5, 0x11, 0x3E, 0xF3, 0x8C, 0xDB, 0xEB, 0xBA, + 0x6E, 0x5B, 0xFA, 0xBF, 0xDC, 0x64, 0xED, 0x85, 0x76, 0x86, 0x2D, 0x35, 0x50, 0x38, 0x38, 0xED, + 0x3F, 0x34, 0x89, 0x77, 0x60, 0x01, 0x6E, 0xED, 0xBB, 0x87, 0x26, 0xD3, 0x9F, 0x5D, 0xC1, 0xCF, + 0x85, 0x52, 0x89, 0x36, 0x3D, 0x44, 0xE5, 0xD3, 0x70, 0x2A, 0xBC, 0x66, 0x2B, 0xED, 0x35, 0x5B, + 0x46, 0xAF, 0xD9, 0x4C, 0x27, 0x56, 0x99, 0xD3, 0x8B, 0x5E, 0x5D, 0x6D, 0x89, 0xCF, 0xB3, 0x80, + 0xA7, 0xF1, 0xF8, 0xF0, 0xDB, 0xD4, 0x73, 0xB9, 0xDB, 0x0B, 0x4E, 0x61, 0x47, 0xB6, 0x1B, 0xCC, + 0x23, 0xEC, 0x28, 0x06, 0x23, 0x79, 0x8F, 0x5F, 0x74, 0x58, 0x36, 0x05, 0x6E, 0x06, 0x0E, 0xCB, + 0x8E, 0x05, 0xAE, 0x08, 0xBE, 0x60, 0x55, 0x7C, 0x90, 0x35, 0xD6, 0x6A, 0xAB, 0x26, 0xEE, 0x73, + 0x30, 0x3F, 0x07, 0x74, 0xCC, 0x54, 0x83, 0x79, 0x0E, 0xA9, 0x2D, 0x24, 0xEE, 0x3A, 0x18, 0xB7, + 0x90, 0xAA, 0xD2, 0x71, 0x82, 0xA9, 0x48, 0xF3, 0xF5, 0x10, 0xC4, 0x92, 0x93, 0xA9, 0xE9, 0x39, + 0xBD, 0xA6, 0x3E, 0xB8, 0xE8, 0xF4, 0x68, 0x28, 0x96, 0xA6, 0xA9, 0x95, 0x29, 0x5B, 0x98, 0x06, + 0xB9, 0x04, 0xEE, 0xA3, 0x30, 0x46, 0x22, 0x1A, 0x9C, 0x08, 0x35, 0x70, 0xCA, 0x32, 0x08, 0xA7, + 0x03, 0x1A, 0x61, 0xCC, 0x31, 0x51, 0x45, 0x0A, 0x6E, 0xAA, 0xC6, 0x37, 0xD9, 0x79, 0xA6, 0x86, + 0xC5, 0x12, 0x21, 0x13, 0x76, 0x49, 0x47, 0x09, 0x05, 0x18, 0x07, 0x26, 0x93, 0x03, 0x9B, 0xF5, + 0xC0, 0x52, 0x82, 0xE9, 0x64, 0x06, 0x93, 0x85, 0x6A, 0x92, 0x30, 0x60, 0x10, 0x39, 0xF6, 0x67, + 0x43, 0xF7, 0x91, 0x52, 0x21, 0xD2, 0xA4, 0x0A, 0x7F, 0x6E, 0x35, 0xF8, 0x15, 0x74, 0x96, 0x1E, + 0x56, 0x44, 0x61, 0x60, 0xEB, 0x86, 0xCF, 0x9F, 0x78, 0xF6, 0x54, 0x29, 0xFC, 0xA3, 0xDA, 0x7A, + 0x20, 0xF8, 0x19, 0x66, 0x18, 0x80, 0x99, 0xB6, 0xE2, 0xE4, 0x8A, 0x71, 0xE0, 0x28, 0xCD, 0xDA, + 0x6B, 0xCD, 0x7D, 0xBD, 0xB0, 0xD6, 0x06, 0x4F, 0xB2, 0xB9, 0xFF, 0x52, 0x33, 0x29, 0x94, 0xC8, + 0x75, 0x72, 0xEC, 0xD9, 0x18, 0x1C, 0xB0, 0x4D, 0x44, 0xAB, 0x6F, 0x6D, 0x27, 0x84, 0xA5, 0x76, + 0x53, 0xBE, 0x2E, 0x6E, 0xD6, 0x41, 0xF3, 0xEB, 0x82, 0xE8, 0x69, 0x41, 0xBA, 0xA1, 0x2F, 0x23, + 0xE6, 0x97, 0xA2, 0x70, 0xB2, 0xA9, 0x70, 0x7E, 0xAD, 0x94, 0x9B, 0xAD, 0x76, 0x8E, 0x1C, 0x01, + 0x30, 0x23, 0x06, 0x5F, 0xDF, 0xFE, 0x8A, 0xCD, 0x69, 0xB7, 0x95, 0xCB, 0x99, 0x5A, 0x4C, 0xC1, + 0x46, 0x92, 0xD4, 0x65, 0x39, 0x4F, 0xF0, 0xCB, 0x0A, 0x92, 0x11, 0xCD, 0x8A, 0xF8, 0x93, 0x8A, + 0x3D, 0x24, 0x07, 0x41, 0x9A, 0x27, 0xF6, 0xCF, 0xFC, 0xF1, 0x7F, 0xE6, 0x89, 0x01, 0xB4, 0x98, + 0x38, 0x40, 0xF3, 0xC7, 0x02, 0x9A, 0x2F, 0x1E, 0xD0, 0x3C, 0x31, 0x81, 0xE6, 0x8D, 0x0B, 0x34, + 0x5F, 0x6C, 0xA0, 0xC5, 0xC7, 0x07, 0xCA, 0xC5, 0x98, 0x6C, 0x85, 0x24, 0x88, 0x9C, 0xE4, 0x5B, + 0x69, 0x3C, 0x05, 0xB1, 0x86, 0x8A, 0x11, 0x94, 0x0C, 0x38, 0x54, 0x3F, 0xE8, 0xD0, 0xBC, 0x81, + 0x87, 0x0C, 0x01, 0x3D, 0xC1, 0x02, 0x71, 0x7A, 0xBF, 0x81, 0x09, 0xF8, 0x69, 0xCD, 0x8F, 0x39, + 0x6B, 0xB3, 0x6C, 0xEB, 0x6F, 0x98, 0x30, 0x4A, 0xCD, 0x08, 0xC2, 0xFF, 0x4E, 0x85, 0xDF, 0xD3, + 0x63, 0x25, 0x49, 0x41, 0x44, 0x5B, 0xDC, 0xEE, 0x4B, 0xE5, 0x97, 0xEF, 0x7A, 0x7D, 0x75, 0x8D, + 0xCB, 0x23, 0x8F, 0xC6, 0xAC, 0xFC, 0xE5, 0x2F, 0xC4, 0x04, 0xC5, 0xD3, 0xB2, 0xD4, 0x80, 0x7C, + 0x43, 0x9D, 0x03, 0x6F, 0x56, 0x87, 0xE4, 0xF1, 0xD9, 0xE9, 0x5E, 0xDF, 0xC8, 0xEC, 0x92, 0xE6, + 0x2C, 0x98, 0x22, 0xBC, 0x14, 0x4D, 0x6B, 0x92, 0x7E, 0xB0, 0xA9, 0x4B, 0x11, 0xA2, 0xAC, 0x2A, + 0x37, 0x1E, 0xDE, 0x7F, 0x82, 0x35, 0x0A, 0x51, 0xF8, 0x93, 0x75, 0x24, 0x51, 0xA2, 0x28, 0xAA, + 0x71, 0xA2, 0x18, 0x26, 0xB5, 0x68, 0xA4, 0x29, 0x1A, 0x03, 0x2B, 0x1A, 0x0F, 0xEA, 0xD5, 0x2C, + 0x06, 0x19, 0x29, 0xA7, 0x78, 0x5E, 0x3B, 0x2D, 0x3A, 0x71, 0x94, 0xEC, 0x4E, 0x07, 0x3B, 0xA0, + 0x08, 0x25, 0xDC, 0x82, 0x0B, 0xEF, 0x0B, 0x75, 0x1B, 0x4B, 0xA6, 0xB0, 0xF9, 0xEC, 0x93, 0x1C, + 0xF9, 0x38, 0xF3, 0x69, 0x47, 0x1C, 0xA2, 0x2C, 0x9F, 0x0A, 0x2C, 0xF9, 0x36, 0xF9, 0xFF, 0x93, + 0x35, 0xDF, 0x66, 0x56, 0xC4, 0xB2, 0x9E, 0xE1, 0xE1, 0x0A, 0x72, 0xE5, 0xF2, 0x93, 0x46, 0x26, + 0xFE, 0x16, 0x0B, 0x4F, 0x95, 0x4A, 0x40, 0x2A, 0xF5, 0xB5, 0x41, 0x5C, 0xD8, 0xD9, 0x17, 0x37, + 0x4E, 0x40, 0x94, 0x4B, 0x13, 0x01, 0x2F, 0x24, 0x78, 0x6C, 0xE1, 0xF8, 0x98, 0x28, 0x21, 0x24, + 0xA8, 0x11, 0x21, 0x53, 0x05, 0x76, 0xD4, 0x2F, 0x28, 0x37, 0xD2, 0x81, 0x6B, 0x0D, 0x5C, 0x17, + 0xE9, 0xA3, 0x0E, 0x29, 0x1F, 0x7F, 0x96, 0x81, 0x4D, 0xEB, 0x60, 0xC9, 0xC7, 0x53, 0x5C, 0x23, + 0x8D, 0x6A, 0x94, 0xCA, 0xAB, 0x59, 0x62, 0x2F, 0xAA, 0xB0, 0xCB, 0x1B, 0x0D, 0x3D, 0x73, 0xD7, + 0x2C, 0xF4, 0xFE, 0x46, 0xEF, 0xCE, 0xA9, 0x4B, 0x6F, 0xED, 0x71, 0x4E, 0xF2, 0xD6, 0x92, 0xFC, + 0xDE, 0xA7, 0x07, 0xD2, 0x1B, 0x27, 0x3C, 0xB1, 0xA7, 0x49, 0xE4, 0xD1, 0x89, 0xE3, 0xC2, 0x0F, + 0xFB, 0xDB, 0x32, 0xB9, 0x62, 0x25, 0x52, 0x1C, 0xEB, 0xE5, 0x78, 0x76, 0x3D, 0x3A, 0x90, 0xA6, + 0xC3, 0x68, 0xE0, 0xC4, 0x49, 0x23, 0x39, 0xAD, 0x89, 0x1D, 0x7C, 0xE1, 0x05, 0x1C, 0x91, 0x52, + 0xC8, 0x2C, 0x30, 0x87, 0x7D, 0x85, 0x24, 0xF9, 0xDB, 0xF7, 0x68, 0x68, 0x02, 0x79, 0xFE, 0xA1, + 0xC5, 0x90, 0x80, 0x0D, 0xEC, 0x90, 0x57, 0xAF, 0x38, 0xAD, 0x25, 0xA1, 0xC7, 0x9A, 0xA1, 0xCB, + 0x09, 0x80, 0x6D, 0x0E, 0xAA, 0x2D, 0xC1, 0x4A, 0xAD, 0x2A, 0x52, 0xA7, 0x3C, 0x73, 0x66, 0x9E, + 0xE7, 0xE2, 0x5C, 0x97, 0x22, 0x5D, 0x94, 0x48, 0x33, 0x72, 0x6D, 0x7A, 0xE4, 0x16, 0xB0, 0xC8, + 0xEB, 0x43, 0x3A, 0x70, 0xA6, 0xE0, 0x18, 0xB1, 0xCD, 0x48, 0xB5, 0xB3, 0xE2, 0xC7, 0x72, 0x52, + 0xAA, 0x13, 0x1E, 0x31, 0x5F, 0x79, 0xFE, 0x29, 0xA5, 0x3B, 0x89, 0x9B, 0xC6, 0xC3, 0xEA, 0xA7, + 0x16, 0x08, 0x49, 0x4E, 0xCC, 0x28, 0xB6, 0xF9, 0x5B, 0xCF, 0x9F, 0x08, 0x3C, 0x49, 0x12, 0x50, + 0x4C, 0xA1, 0x92, 0x50, 0x8C, 0x52, 0x73, 0xF3, 0x5C, 0xDA, 0xCE, 0x10, 0xB4, 0xDB, 0xB9, 0xBE, + 0x8B, 0x33, 0x76, 0xB7, 0x64, 0x65, 0x48, 0x42, 0xC4, 0xAB, 0x60, 0xBB, 0x44, 0x7D, 0xF3, 0x1A, + 0xB4, 0xF7, 0xCF, 0xCE, 0xCE, 0x0F, 0x8E, 0x4E, 0xF7, 0x2E, 0x0E, 0x2F, 0x8F, 0x4E, 0x7B, 0x1F, + 0x2E, 0x2E, 0x2F, 0x3E, 0xF6, 0xF0, 0xD7, 0x9F, 0xF6, 0x8E, 0x8F, 0x0E, 0x2E, 0x3F, 0x9C, 0xFE, + 0xED, 0xF4, 0xEC, 0xE7, 0x53, 0x3D, 0x02, 0x42, 0xDC, 0xA3, 0xC8, 0x64, 0x82, 0x11, 0x9F, 0xB7, + 0x43, 0x2B, 0xC8, 0xCC, 0xFD, 0xE2, 0x62, 0xB6, 0x95, 0x9D, 0xA7, 0xA6, 0x2B, 0x6C, 0x00, 0x0C, + 0x78, 0xAA, 0x60, 0x0C, 0xDC, 0x1F, 0x33, 0xFE, 0x8A, 0xAC, 0x74, 0xB6, 0x2C, 0xAE, 0xFE, 0xA6, + 0x72, 0xF0, 0xE5, 0xB6, 0xAC, 0xA5, 0x5C, 0x31, 0x24, 0xE7, 0x96, 0x5B, 0x7C, 0xFB, 0x6B, 0xCB, + 0x7A, 0x72, 0x02, 0xC8, 0x1C, 0x2A, 0x5C, 0x5D, 0x24, 0x9D, 0x8E, 0xDE, 0x26, 0xEF, 0x18, 0xF4, + 0x8F, 0x27, 0x5E, 0xAF, 0xAE, 0x80, 0x0C, 0xEE, 0x87, 0x06, 0xFE, 0xD0, 0xC0, 0x6C, 0x0D, 0x4C, + 0xE9, 0xCB, 0x9F, 0x76, 0x15, 0xC3, 0x97, 0xDB, 0x7E, 0x6E, 0x43, 0x03, 0x1E, 0x7F, 0x91, 0x85, + 0x56, 0x7B, 0x22, 0xCD, 0xCF, 0x35, 0xF6, 0x32, 0x1F, 0x53, 0xF0, 0x52, 0x43, 0x9C, 0x81, 0x92, + 0x41, 0x55, 0x6F, 0xB4, 0x64, 0x8A, 0xBD, 0x2E, 0x1B, 0x4A, 0x27, 0x88, 0xD4, 0x62, 0x38, 0xA1, + 0x61, 0x9A, 0x47, 0x9E, 0x86, 0x31, 0xE6, 0x33, 0x06, 0x5A, 0x8E, 0x46, 0x23, 0x96, 0xC3, 0xB2, + 0x62, 0x75, 0x8C, 0x3D, 0x1A, 0x62, 0x6F, 0xF1, 0x28, 0x3D, 0xF1, 0x34, 0xAB, 0x25, 0xA3, 0x4C, + 0x62, 0xA3, 0xAB, 0x33, 0x6C, 0x32, 0x33, 0x8A, 0x11, 0xC2, 0x48, 0xB5, 0xA2, 0x3A, 0xCB, 0x26, + 0x26, 0x92, 0xC8, 0xE6, 0x9A, 0x65, 0xCB, 0x45, 0x06, 0x95, 0xF2, 0xB0, 0xA5, 0xDF, 0xD0, 0xF3, + 0xD3, 0xF9, 0x40, 0xBC, 0x6A, 0xE1, 0xF2, 0x15, 0xCD, 0x4F, 0x7B, 0x7F, 0xA9, 0xC0, 0xF3, 0x89, + 0xFB, 0x57, 0xD3, 0xED, 0x2B, 0xE9, 0xD9, 0x09, 0x04, 0xE8, 0x59, 0x7C, 0x27, 0x57, 0x0E, 0x19, + 0x95, 0xDD, 0xA3, 0xDD, 0xCC, 0xA0, 0x59, 0xE9, 0x8C, 0x1D, 0xB5, 0x96, 0xD5, 0xF7, 0x95, 0x49, + 0xF3, 0xC8, 0x53, 0x39, 0xE4, 0xE5, 0x4B, 0x41, 0xE5, 0xC9, 0xD7, 0xB2, 0x8A, 0x59, 0xAA, 0x23, + 0xD6, 0xB3, 0x0B, 0xD6, 0x9D, 0x68, 0x29, 0xAD, 0xAB, 0x50, 0xB2, 0xC4, 0x46, 0x4D, 0x5A, 0x94, + 0xE2, 0x18, 0xFA, 0xC3, 0xF4, 0x92, 0x7C, 0x41, 0x1D, 0xA1, 0x84, 0x59, 0x95, 0x49, 0xCC, 0x01, + 0x6A, 0x55, 0xEA, 0xFF, 0x68, 0xFA, 0x2F, 0x6A, 0x73, 0xE7, 0x49, 0xB7, 0xB9, 0xF3, 0x20, 0x6D, + 0xEE, 0x3E, 0xE9, 0x36, 0x77, 0x1F, 0xA4, 0xCD, 0x6B, 0x4F, 0xBA, 0xCD, 0x6B, 0x55, 0xDB, 0xAC, + 0xA3, 0x7C, 0x68, 0x87, 0x31, 0xDF, 0x34, 0x6A, 0xF1, 0xDE, 0x17, 0x62, 0x28, 0xF9, 0xD2, 0x9E, + 0xC5, 0x7B, 0xDF, 0xE5, 0xD5, 0xDA, 0xC1, 0x74, 0xEC, 0x84, 0xAD, 0xE6, 0x72, 0xD4, 0x1A, 0x96, + 0x05, 0x95, 0x91, 0xD6, 0xAB, 0x90, 0xE6, 0x52, 0x3D, 0x73, 0x2B, 0x56, 0x04, 0x48, 0x36, 0x29, + 0xE8, 0xF0, 0xCF, 0x22, 0x0A, 0xBD, 0xF8, 0xCC, 0x8E, 0x3F, 0x9E, 0xDE, 0x0E, 0x4D, 0xE5, 0x1E, + 0x4C, 0x6E, 0x24, 0x29, 0x09, 0xDD, 0xAA, 0x77, 0x16, 0xCB, 0x70, 0xAB, 0xF5, 0x43, 0x5B, 0xE9, + 0x07, 0xAC, 0x11, 0x89, 0x0F, 0x96, 0x1A, 0xEB, 0xC9, 0x0E, 0x32, 0xDB, 0x08, 0xC3, 0xE2, 0x4F, + 0xD6, 0x67, 0xE1, 0x31, 0xB1, 0x6F, 0x4E, 0x70, 0x6A, 0x9F, 0xB6, 0xF8, 0xB1, 0x76, 0x54, 0xBE, + 0xB4, 0xC4, 0xCB, 0xA2, 0xEA, 0xAF, 0x88, 0xA5, 0x7E, 0x78, 0x8D, 0x09, 0xA5, 0x96, 0x4C, 0xC8, + 0x3B, 0x05, 0xC8, 0x3B, 0x2A, 0xF2, 0x8E, 0x8E, 0xBC, 0x93, 0x87, 0xBC, 0x5B, 0x80, 0xBC, 0xAB, + 0x22, 0xEF, 0xEA, 0xC8, 0xBB, 0x79, 0xC8, 0xD7, 0x0A, 0x90, 0xAF, 0xA9, 0xC8, 0xD7, 0x74, 0xE4, + 0x6B, 0x31, 0xF2, 0xDF, 0x81, 0xCA, 0x4A, 0x39, 0x04, 0x6E, 0xBC, 0x00, 0x54, 0x75, 0x06, 0xBF, + 0xC2, 0x4F, 0x7F, 0x5C, 0xA0, 0xC0, 0xE2, 0xD4, 0x04, 0x81, 0x84, 0xFA, 0xB6, 0x43, 0xEF, 0xD8, + 0xBB, 0x65, 0x2F, 0x39, 0x69, 0x0B, 0xDB, 0x3F, 0x18, 0xCF, 0x86, 0x34, 0x68, 0x01, 0xAE, 0xA5, + 0x8C, 0xC3, 0x13, 0x24, 0x66, 0x3C, 0x20, 0xD1, 0xED, 0x4C, 0xC7, 0x68, 0x65, 0xD6, 0xB7, 0x97, + 0x0C, 0x33, 0x11, 0x22, 0xAD, 0xD9, 0x11, 0xD5, 0x3B, 0xA3, 0xEC, 0x81, 0x41, 0xD6, 0x71, 0x01, + 0x93, 0x40, 0x99, 0x5E, 0x14, 0x15, 0xD3, 0x67, 0x96, 0xCA, 0x13, 0x18, 0x67, 0xD8, 0x59, 0x26, + 0xCE, 0xB0, 0x5B, 0xA2, 0xF3, 0xF8, 0xAE, 0x57, 0xC7, 0x70, 0x4B, 0x57, 0x9C, 0x22, 0x02, 0x9A, + 0x74, 0x61, 0x4A, 0xE5, 0x3B, 0xF5, 0x75, 0x1E, 0x08, 0x3C, 0xD9, 0x5D, 0xF8, 0x8E, 0xF9, 0x12, + 0x12, 0xCA, 0xC4, 0x78, 0x36, 0x22, 0x9F, 0xDC, 0xA0, 0xF1, 0xFF, 0x2A, 0xA7, 0x7B, 0x95, 0x8D, + 0x7C, 0x64, 0xD6, 0xC5, 0x7A, 0x3C, 0x67, 0x98, 0x62, 0x8A, 0xF8, 0xF0, 0xC2, 0x7B, 0x6B, 0xE3, + 0x8D, 0xAA, 0xBB, 0x03, 0x11, 0x71, 0x42, 0xDD, 0x64, 0x50, 0xCB, 0xD8, 0xF2, 0x53, 0x91, 0x63, + 0x23, 0x2A, 0x22, 0x7B, 0x53, 0x98, 0x46, 0xE8, 0x50, 0xB9, 0xE2, 0xC5, 0xA2, 0xBA, 0x0E, 0xA9, + 0x38, 0x9D, 0x03, 0x6A, 0x78, 0x3E, 0xCE, 0x19, 0xD3, 0xEF, 0x4A, 0xA9, 0x94, 0xD8, 0x15, 0xF7, + 0xE5, 0xCE, 0x72, 0xC3, 0xCC, 0xB2, 0xE1, 0x56, 0x4A, 0x8A, 0xFD, 0x52, 0xF9, 0x7F, 0x93, 0xCC, + 0xBB, 0x59, 0x31, 0x66, 0xF3, 0x93, 0xF5, 0x02, 0xEA, 0x6F, 0xCA, 0x75, 0x5B, 0xBE, 0x5F, 0x93, + 0xE6, 0x0F, 0xAA, 0xB7, 0xB4, 0xB6, 0xFC, 0x93, 0xFA, 0x5E, 0x94, 0x07, 0x40, 0x4A, 0x0C, 0x27, + 0x65, 0x3E, 0x60, 0x07, 0x31, 0x85, 0x89, 0x29, 0x48, 0x0B, 0x9F, 0x95, 0x19, 0x32, 0x18, 0x2C, + 0x3D, 0x7B, 0x80, 0xFC, 0x11, 0x35, 0x33, 0x21, 0x54, 0xCA, 0x82, 0x30, 0x52, 0xE3, 0xB7, 0xC7, + 0x7A, 0x6D, 0xA9, 0x2F, 0x02, 0xB9, 0xA4, 0xF4, 0x18, 0xD2, 0xCF, 0x16, 0x1E, 0x8C, 0xBA, 0x4E, + 0x68, 0xE2, 0xF2, 0x61, 0x89, 0x33, 0x1B, 0xDB, 0xB6, 0x8A, 0xDA, 0x9B, 0x84, 0x90, 0xE6, 0x27, + 0x9C, 0x0B, 0x0D, 0x46, 0xFD, 0xB4, 0x5A, 0xCD, 0xB3, 0x24, 0x62, 0x33, 0x0C, 0x03, 0x42, 0x60, + 0x82, 0xF5, 0x0D, 0xB5, 0x27, 0x89, 0x12, 0x94, 0x93, 0x07, 0xC7, 0x2A, 0x0B, 0x44, 0xC2, 0xF3, + 0xBD, 0xA5, 0x91, 0xA3, 0x00, 0xA9, 0x14, 0x01, 0x73, 0x29, 0x41, 0x1A, 0xDB, 0x77, 0x6E, 0x7A, + 0xA7, 0x9D, 0xD7, 0xF8, 0x43, 0xFE, 0x82, 0x76, 0x31, 0x6D, 0x4F, 0x21, 0xFB, 0x4E, 0x4D, 0x4F, + 0x2E, 0x53, 0xB0, 0xBB, 0x53, 0x05, 0x83, 0xBF, 0xF7, 0xF7, 0x8B, 0x93, 0xB9, 0xC7, 0x3D, 0x43, + 0xF2, 0xB4, 0x9A, 0xAB, 0x4F, 0x91, 0x38, 0x95, 0xE5, 0x4F, 0x93, 0x65, 0x12, 0x04, 0x99, 0x26, + 0xC9, 0x45, 0x4E, 0x90, 0x6A, 0x40, 0xFB, 0xA7, 0x3C, 0x49, 0xC6, 0xE1, 0xF7, 0x17, 0x31, 0x51, + 0xA6, 0x63, 0xF9, 0x3F, 0xC9, 0xC9, 0x52, 0xCF, 0x0B, 0xB2, 0x30, 0x53, 0xF9, 0x14, 0xDA, 0x5E, + 0xDA, 0x52, 0xCE, 0xDD, 0x72, 0x1D, 0xD7, 0xD3, 0x35, 0x1C, 0x62, 0x9D, 0xC0, 0x93, 0x31, 0x80, + 0x5D, 0x48, 0xAD, 0x0E, 0x54, 0xE7, 0x7B, 0xE7, 0x7B, 0x25, 0x77, 0xC3, 0x35, 0x96, 0x66, 0x94, + 0x98, 0xDF, 0xC1, 0xF3, 0xDB, 0xC5, 0x3D, 0xBC, 0x53, 0x0C, 0xD0, 0xAF, 0x0C, 0x70, 0x51, 0x15, + 0xE0, 0x27, 0x09, 0x60, 0xBD, 0x18, 0xE0, 0xFC, 0x64, 0x3F, 0x4D, 0xE1, 0xBE, 0x46, 0x0A, 0xB2, + 0x11, 0x4B, 0x65, 0xAB, 0x3A, 0xE7, 0xEF, 0x7A, 0xAA, 0x88, 0xAC, 0xF6, 0xC6, 0x4E, 0x11, 0x40, + 0xBF, 0x32, 0xC0, 0x45, 0x55, 0x00, 0x59, 0x44, 0xF1, 0xB8, 0xCC, 0x06, 0x50, 0x45, 0x14, 0x53, + 0xB8, 0x9F, 0x27, 0xEB, 0x14, 0x7B, 0x40, 0xCD, 0x3C, 0xD8, 0xC8, 0x50, 0x31, 0x62, 0x96, 0x44, + 0x68, 0x13, 0xCF, 0xE5, 0x27, 0x01, 0x1D, 0x6C, 0x58, 0x56, 0x11, 0x5C, 0x47, 0x82, 0x7B, 0x81, + 0x70, 0x00, 0xD6, 0x31, 0x35, 0x4B, 0xF2, 0x9A, 0x73, 0xB5, 0xD7, 0x50, 0xBD, 0x5F, 0xB1, 0xFA, + 0x45, 0xB5, 0xEA, 0x72, 0xA7, 0x74, 0x8B, 0xAA, 0xA7, 0xB4, 0xD6, 0x54, 0x3F, 0xED, 0x2D, 0xE3, + 0x6F, 0x1D, 0x6B, 0x6D, 0x4D, 0x86, 0xB5, 0x54, 0xC3, 0xFC, 0x20, 0x59, 0x97, 0xCA, 0xE8, 0x55, + 0x67, 0xA7, 0xD2, 0x50, 0xEA, 0x54, 0x54, 0xF3, 0x6A, 0xE3, 0xAE, 0xB0, 0xFA, 0x4F, 0x17, 0xEF, + 0x2A, 0x61, 0x3F, 0x3E, 0xAE, 0xC6, 0x8C, 0xAA, 0x3C, 0x18, 0xB4, 0x64, 0x36, 0xC5, 0xE7, 0x5C, + 0xFC, 0xC2, 0xCE, 0xEB, 0x5D, 0xF2, 0x75, 0x3D, 0x9E, 0x50, 0xF4, 0xF9, 0x44, 0x44, 0xA9, 0xF8, + 0x31, 0x9B, 0x3C, 0x81, 0xD9, 0x24, 0x0F, 0xE2, 0xFC, 0x97, 0x93, 0xCB, 0xF3, 0xBD, 0x9F, 0x7F, + 0x29, 0xCD, 0x13, 0x02, 0xF4, 0xDF, 0x9E, 0xBF, 0xF9, 0xE5, 0xF1, 0x66, 0xAC, 0x45, 0x8F, 0x9B, + 0x32, 0x66, 0x31, 0x73, 0x10, 0x6F, 0xE0, 0x40, 0x20, 0xC7, 0xCE, 0xC4, 0x61, 0xD1, 0x85, 0x3B, + 0x64, 0x4A, 0x7D, 0xB2, 0x41, 0x02, 0x9E, 0x69, 0xA8, 0xAA, 0xB5, 0xC9, 0xAA, 0xAF, 0x9B, 0xCB, + 0xCE, 0xB6, 0x04, 0xB7, 0x96, 0x3D, 0x5B, 0xEA, 0x70, 0x5D, 0xAB, 0x1E, 0xDC, 0x7A, 0xB7, 0x26, + 0xDC, 0xA6, 0x06, 0x57, 0x16, 0xF0, 0xC5, 0x7A, 0x3D, 0x82, 0x5B, 0x35, 0xE1, 0xB6, 0xEB, 0xC1, + 0x75, 0xBA, 0x26, 0xB8, 0x1F, 0xB3, 0xD6, 0x53, 0x9E, 0xB5, 0x88, 0x61, 0xDA, 0xFA, 0x31, 0xEE, + 0xA2, 0x71, 0xF7, 0x4B, 0xCD, 0x71, 0x57, 0x13, 0x6E, 0xFB, 0x97, 0x9A, 0xE3, 0xEE, 0x97, 0xE2, + 0x71, 0xF7, 0xC3, 0xFB, 0xFF, 0x0D, 0x7B, 0xFF, 0x26, 0xF0, 0xD4, 0x76, 0xB3, 0x34, 0x28, 0xB3, + 0xDE, 0xD3, 0x15, 0x83, 0xB3, 0xB1, 0x59, 0x1F, 0x9C, 0x0D, 0xD1, 0x39, 0xC0, 0x37, 0x33, 0xC0, + 0x8D, 0xDB, 0x32, 0x08, 0x63, 0xF4, 0xA1, 0xD5, 0xBD, 0xDE, 0x27, 0xE4, 0x47, 0xB3, 0xED, 0x2E, + 0x64, 0xFB, 0xB2, 0x63, 0x59, 0x1B, 0x65, 0xDD, 0x4A, 0x19, 0x4A, 0x71, 0x05, 0xCA, 0x43, 0xBD, + 0x68, 0xA4, 0x76, 0x76, 0x8B, 0xA1, 0xB6, 0x6A, 0xD1, 0xDA, 0xD2, 0x68, 0x95, 0x04, 0xDB, 0xAE, + 0x45, 0x6C, 0xBB, 0x4E, 0xC3, 0x54, 0x3F, 0xA5, 0x53, 0x1A, 0xAA, 0x0E, 0xAD, 0xEE, 0x9A, 0xA5, + 0x8C, 0xE6, 0x92, 0xF2, 0x58, 0xB7, 0x5E, 0x74, 0x15, 0x6B, 0x5B, 0x92, 0x1E, 0x83, 0xEB, 0x34, + 0x32, 0xB6, 0xF1, 0xE7, 0x5A, 0x7D, 0xC4, 0xDB, 0xB5, 0x7C, 0xA8, 0xAA, 0xEA, 0xDB, 0xCE, 0x9F, + 0xAC, 0x24, 0xB8, 0x8C, 0xBD, 0x8D, 0x62, 0x40, 0x55, 0xF3, 0xCB, 0xC3, 0x6D, 0xD5, 0x84, 0xDB, + 0xAE, 0x07, 0xA7, 0x29, 0x57, 0x7B, 0x51, 0xB3, 0x71, 0xD6, 0xA9, 0x41, 0xDD, 0x39, 0x43, 0xEF, + 0xCA, 0x6A, 0x46, 0x5B, 0x27, 0x5D, 0x03, 0xFA, 0xA4, 0x7F, 0xB2, 0x5E, 0xD5, 0xDA, 0x1F, 0x7B, + 0xB7, 0x68, 0x66, 0x6F, 0x9D, 0x61, 0x78, 0xF3, 0x5B, 0xB7, 0xF8, 0x56, 0x2D, 0x93, 0xDF, 0x7D, + 0x44, 0x93, 0xDF, 0x7D, 0x4C, 0x93, 0xDF, 0x7D, 0x44, 0x93, 0xDF, 0xFD, 0x61, 0xF2, 0xE7, 0x36, + 0xF9, 0xDD, 0xC7, 0x36, 0xF9, 0xDD, 0x9A, 0x26, 0xBF, 0x5B, 0xD3, 0xE4, 0x77, 0x6B, 0x9A, 0xFC, + 0xEE, 0x23, 0x99, 0x7C, 0x6B, 0xE3, 0xBF, 0x37, 0xCB, 0xC8, 0xB5, 0xFC, 0x8C, 0x51, 0x06, 0x58, + 0x58, 0x6D, 0xA5, 0xB1, 0xBF, 0x9B, 0x99, 0x66, 0x16, 0xB0, 0x1C, 0xE5, 0xC9, 0x8B, 0xE0, 0x20, + 0xFD, 0x54, 0x96, 0x27, 0x9B, 0x4E, 0x24, 0x40, 0xF1, 0xEF, 0x9D, 0x74, 0x9D, 0x8F, 0x5A, 0x9D, + 0x8F, 0x86, 0x3A, 0xBF, 0x6A, 0x75, 0x7E, 0xDD, 0x91, 0x0F, 0x0B, 0x80, 0x9B, 0x77, 0xD4, 0x1B, + 0xD2, 0xD0, 0x19, 0xE4, 0x72, 0x94, 0x7E, 0xBC, 0x3B, 0x12, 0x60, 0x50, 0x52, 0xFC, 0x38, 0x37, + 0xAE, 0xEC, 0xB9, 0x5A, 0xE5, 0xF7, 0x7B, 0x87, 0x7B, 0xBD, 0x7D, 0x43, 0xD5, 0xBD, 0x71, 0x28, + 0x7A, 0x5D, 0x0D, 0x15, 0x39, 0xB1, 0xFD, 0x2F, 0x4A, 0x9C, 0xC8, 0x4E, 0x41, 0x30, 0xC8, 0x02, + 0xF0, 0xAE, 0x09, 0x9C, 0x07, 0x84, 0x12, 0xF4, 0xED, 0xE1, 0x7F, 0xCD, 0x82, 0x10, 0x18, 0xD5, + 0x6F, 0xC5, 0xB2, 0x9B, 0x3C, 0xA7, 0xF4, 0xF6, 0xD8, 0x4B, 0x9E, 0x3B, 0xA7, 0xE2, 0x2A, 0x26, + 0x75, 0x0C, 0x77, 0x84, 0xE9, 0x37, 0x27, 0xD4, 0x82, 0xA4, 0xDD, 0x38, 0x43, 0x16, 0xDE, 0xDD, + 0x71, 0x7B, 0x2C, 0x38, 0x25, 0x6F, 0x04, 0x5E, 0xE3, 0xC6, 0x08, 0xD5, 0xE0, 0xA5, 0x1C, 0xB9, + 0x3D, 0xDF, 0xC3, 0x98, 0x5E, 0x71, 0xCC, 0x22, 0x9D, 0x26, 0x62, 0xDD, 0x73, 0x87, 0xF2, 0xC5, + 0x64, 0xAC, 0xC6, 0x7D, 0x1C, 0x1E, 0xC4, 0x19, 0x04, 0x9D, 0xFC, 0xD1, 0x4A, 0xD8, 0x60, 0x71, + 0xF5, 0x2D, 0xD3, 0x4D, 0xE6, 0x7D, 0x6F, 0x32, 0x1D, 0xD3, 0x30, 0x09, 0x15, 0xC5, 0xAE, 0x6B, + 0x47, 0x18, 0x64, 0xDC, 0x82, 0x9C, 0xB9, 0x21, 0xFC, 0x6B, 0xBA, 0x21, 0x5A, 0x23, 0x23, 0x6A, + 0x8D, 0xE8, 0x99, 0xFA, 0xBE, 0x3D, 0xC6, 0x34, 0x14, 0xB7, 0x37, 0x94, 0xBF, 0x54, 0x3F, 0xEC, + 0xF7, 0xD6, 0xBA, 0xE4, 0xC6, 0x0E, 0xF0, 0xE1, 0xF7, 0xB5, 0xE3, 0x4F, 0xA0, 0xD0, 0x07, 0xFD, + 0x76, 0xA6, 0x21, 0xF1, 0xAE, 0xF9, 0xA3, 0x21, 0x5C, 0xF4, 0x27, 0xC2, 0x21, 0xD7, 0xBE, 0x37, + 0x21, 0x7B, 0x3D, 0x0E, 0x30, 0x22, 0x53, 0xE0, 0x4A, 0xBA, 0xB4, 0xCE, 0xB1, 0x60, 0x08, 0xB5, + 0x73, 0x8E, 0x46, 0xBA, 0xC0, 0x75, 0x00, 0x9C, 0xF8, 0x13, 0xC7, 0xA5, 0x40, 0xDF, 0x19, 0xDC, + 0x90, 0x44, 0x03, 0x30, 0x4B, 0x02, 0xB2, 0xE3, 0xF9, 0xCE, 0x08, 0xC6, 0xCE, 0x98, 0x11, 0x8E, + 0x3D, 0xC3, 0x28, 0x28, 0x5B, 0x24, 0xF4, 0x3F, 0xED, 0x12, 0x77, 0x36, 0x1E, 0x2F, 0xE9, 0x17, + 0xED, 0x23, 0x29, 0x6A, 0xF5, 0xCB, 0x84, 0x72, 0xE3, 0xDF, 0x5E, 0x92, 0xBD, 0xF1, 0x98, 0xF4, + 0xE1, 0xFB, 0x30, 0x3F, 0xC0, 0xB7, 0xE7, 0x06, 0xDE, 0x98, 0xB6, 0xC7, 0xA0, 0xB1, 0x8D, 0x0F, + 0x3C, 0xBC, 0x06, 0x81, 0xFF, 0x83, 0x9C, 0x40, 0x68, 0x69, 0x19, 0x98, 0x83, 0x1F, 0x5D, 0xC7, + 0xC1, 0xEC, 0xC7, 0x9E, 0x3D, 0xFC, 0xD9, 0x76, 0x42, 0x25, 0xAA, 0x0E, 0x86, 0x65, 0x12, 0xF1, + 0xC0, 0x82, 0xD9, 0xD5, 0xC4, 0x09, 0xA3, 0xE0, 0xF1, 0x18, 0x47, 0x10, 0x06, 0x1B, 0x96, 0x07, + 0x9F, 0xAC, 0xCF, 0xC9, 0x13, 0x2F, 0x9C, 0xB2, 0xC4, 0x33, 0x2F, 0x97, 0xDE, 0x12, 0x0C, 0x69, + 0x20, 0xC7, 0xB2, 0x8B, 0x8A, 0xDB, 0xF6, 0x74, 0xCA, 0x07, 0x55, 0x1A, 0xED, 0x32, 0x23, 0x2B, + 0x3D, 0xE0, 0xB3, 0xFF, 0xCB, 0xFE, 0x26, 0xF0, 0xFD, 0x72, 0x72, 0xFC, 0x3E, 0xC4, 0x40, 0xC4, + 0xFF, 0x98, 0xD1, 0x20, 0x8C, 0xB0, 0x62, 0x85, 0xB6, 0x07, 0x08, 0x5B, 0x8D, 0xDE, 0x59, 0xFF, + 0x02, 0x63, 0x48, 0xAD, 0xCE, 0x58, 0x8B, 0x22, 0xC4, 0x0D, 0xB9, 0x26, 0x1B, 0x5A, 0x11, 0x27, + 0xD1, 0xC8, 0xE3, 0x66, 0x4C, 0x96, 0x86, 0xE1, 0xD9, 0xC1, 0xAB, 0x2B, 0xFF, 0x35, 0x2F, 0x74, + 0x30, 0x20, 0xC1, 0x54, 0x09, 0x2B, 0xDB, 0xD8, 0xC9, 0x11, 0x6D, 0x3F, 0xB4, 0xC3, 0x59, 0x80, + 0x2F, 0x7D, 0x54, 0x83, 0x9C, 0x4F, 0x10, 0xAA, 0xE7, 0x21, 0x4D, 0x0D, 0x64, 0x3E, 0xEC, 0xCC, + 0x95, 0x1A, 0x99, 0x83, 0x59, 0x21, 0xE0, 0xF9, 0x23, 0x1A, 0xF6, 0x6C, 0xC7, 0x87, 0x19, 0x11, + 0x8D, 0xAB, 0x3A, 0x83, 0x5C, 0x85, 0xEE, 0x5B, 0x56, 0x83, 0x97, 0x19, 0x44, 0x84, 0xDA, 0xCB, + 0xA2, 0x7D, 0x06, 0x0C, 0x97, 0x17, 0x86, 0xD4, 0x6D, 0x4B, 0x01, 0x96, 0xA6, 0x94, 0xFA, 0x27, + 0x7B, 0xFB, 0x81, 0x0E, 0x77, 0xEA, 0xB9, 0x34, 0xEB, 0x91, 0x06, 0xA3, 0x78, 0x18, 0x4C, 0x4F, + 0xBD, 0xDB, 0x1E, 0x80, 0x07, 0x06, 0xF3, 0x0B, 0x8C, 0x31, 0x23, 0xA9, 0x47, 0x8A, 0x1E, 0x45, + 0x26, 0x4A, 0x14, 0x18, 0x38, 0x66, 0x70, 0xEC, 0x1A, 0xA7, 0x08, 0xE9, 0x9B, 0xF5, 0x58, 0x44, + 0xC6, 0x93, 0xB0, 0x10, 0x5F, 0x65, 0xB3, 0x87, 0xC3, 0xC3, 0xAF, 0xF0, 0x0B, 0xBE, 0xD8, 0xA1, + 0x80, 0xBF, 0xD5, 0x38, 0x38, 0x3B, 0x01, 0x5B, 0x1C, 0xE2, 0x37, 0xE8, 0x08, 0x8A, 0x41, 0xB3, + 0x5B, 0x14, 0xAB, 0x2C, 0x91, 0xDD, 0xD7, 0xC0, 0x60, 0xAC, 0xE1, 0x42, 0x60, 0x25, 0xEE, 0xC5, + 0xA5, 0x43, 0x0F, 0x2B, 0xB7, 0xE1, 0x58, 0x60, 0x20, 0x74, 0xEA, 0xD9, 0xCB, 0x5A, 0xF8, 0x85, + 0x63, 0x8E, 0x6F, 0xC3, 0x39, 0x78, 0x45, 0xCE, 0xFE, 0x06, 0xBF, 0xA8, 0xD7, 0xE2, 0x78, 0xB5, + 0x4F, 0xCE, 0xE7, 0xB6, 0xE7, 0x0E, 0xC6, 0xCE, 0x00, 0x63, 0x96, 0xC5, 0xB2, 0x6D, 0xE9, 0xAF, + 0xD1, 0xB4, 0xA0, 0xDC, 0xFA, 0xE3, 0xB0, 0xFB, 0x64, 0x44, 0x4D, 0x60, 0x80, 0xCC, 0x7C, 0xF6, + 0x7E, 0x08, 0x1D, 0xE1, 0xF7, 0xFF, 0x04, 0xE1, 0xA7, 0xE5, 0xC4, 0xF1, 0xE1, 0xC0, 0x37, 0x92, + 0x34, 0x20, 0xEA, 0xD3, 0x81, 0xBA, 0x6D, 0x42, 0x56, 0x33, 0xE9, 0x49, 0xEF, 0x92, 0xEE, 0xE5, + 0xD1, 0x6E, 0x44, 0xB9, 0x08, 0xE6, 0x12, 0xAA, 0x79, 0xBC, 0x49, 0x4D, 0x30, 0x30, 0x87, 0xC1, + 0x86, 0x31, 0xC0, 0x09, 0xBF, 0x4B, 0x78, 0xE4, 0xD6, 0x61, 0x2D, 0x8A, 0x00, 0x69, 0xC0, 0x95, + 0x93, 0xC2, 0x22, 0xB1, 0x23, 0x81, 0xA8, 0x9F, 0x8E, 0x0F, 0x9F, 0xD8, 0x11, 0xE6, 0xF9, 0xA5, + 0x2B, 0xDC, 0x67, 0xB7, 0xE8, 0x2D, 0x42, 0x2C, 0xA2, 0x39, 0x11, 0xA2, 0x52, 0x6D, 0xC9, 0xE0, + 0x33, 0x69, 0x48, 0x76, 0x63, 0x0D, 0x6D, 0x61, 0xD8, 0x78, 0x44, 0x00, 0x39, 0x1A, 0x10, 0xAE, + 0x06, 0xE6, 0x69, 0x59, 0x3E, 0xDA, 0x52, 0xED, 0xC4, 0x75, 0x41, 0x5E, 0x33, 0x47, 0xF1, 0x12, + 0xA1, 0x7E, 0x33, 0xDF, 0xB1, 0x38, 0xAF, 0x8B, 0x6E, 0xE5, 0x3B, 0x3D, 0x7A, 0xAC, 0xA9, 0x91, + 0xBC, 0x11, 0xD9, 0x8D, 0xE4, 0x42, 0x48, 0x37, 0x52, 0xA9, 0x94, 0xB5, 0xD3, 0x97, 0x5A, 0x5F, + 0xD7, 0xD8, 0xD2, 0x53, 0xE2, 0x56, 0x1A, 0xF3, 0x5E, 0x49, 0x47, 0xA2, 0x5B, 0x6D, 0x76, 0x03, + 0x66, 0x0F, 0x9C, 0x5B, 0x98, 0x8A, 0xD1, 0x6F, 0x3B, 0xEE, 0xAC, 0x1E, 0x77, 0x15, 0x64, 0xF7, + 0xEA, 0x9B, 0xDC, 0xC2, 0xED, 0x81, 0xAF, 0xE9, 0xD0, 0x1D, 0xA5, 0xF9, 0xD9, 0x6E, 0x6F, 0x2E, + 0x90, 0x9F, 0xF4, 0x7E, 0x51, 0x15, 0x66, 0x3A, 0x9D, 0xCD, 0x85, 0x4A, 0x47, 0x4F, 0x38, 0x52, + 0x85, 0x97, 0x75, 0xDC, 0xB7, 0xA8, 0xC1, 0x4A, 0x3D, 0x6A, 0xCA, 0xE6, 0x8A, 0x8A, 0xD9, 0x30, + 0x46, 0x79, 0x82, 0xA6, 0xD3, 0x24, 0x5C, 0xC8, 0x3C, 0x43, 0xD3, 0x84, 0xAC, 0x94, 0xD9, 0x31, + 0x44, 0x3A, 0x29, 0x19, 0x63, 0x96, 0x8F, 0xE8, 0x12, 0xF0, 0x59, 0xAD, 0x8E, 0xB3, 0x79, 0x2E, + 0xA2, 0xD5, 0x65, 0x52, 0x83, 0x6A, 0xAD, 0xE6, 0x20, 0xF5, 0x5B, 0x9D, 0x0F, 0x6F, 0x68, 0xB5, + 0xF6, 0x72, 0x7A, 0xFE, 0x96, 0xA7, 0x11, 0x16, 0xB4, 0xDE, 0xF0, 0x46, 0x1B, 0x80, 0x44, 0xE6, + 0x28, 0xED, 0x85, 0x44, 0xA1, 0x28, 0x0A, 0x91, 0xA9, 0x1B, 0x77, 0x06, 0xB1, 0xE0, 0x32, 0x0E, + 0x33, 0x25, 0x60, 0x2E, 0x10, 0x97, 0x8E, 0xE7, 0x11, 0x48, 0x1A, 0x55, 0x1C, 0xA2, 0xCD, 0x32, + 0xEB, 0x40, 0x04, 0xF1, 0xC6, 0x9E, 0x0D, 0x0F, 0x7C, 0x6F, 0x8A, 0x69, 0xB6, 0xCC, 0x53, 0xAF, + 0x92, 0x60, 0xBA, 0x50, 0x5F, 0x4A, 0x70, 0xD4, 0x31, 0xCF, 0x8E, 0x65, 0x38, 0x12, 0xCE, 0x42, + 0x25, 0x8E, 0xEA, 0xD2, 0xAA, 0xD0, 0x7A, 0xA5, 0x5B, 0xCD, 0x81, 0xCB, 0x6B, 0x77, 0x6D, 0x5E, + 0x1C, 0x74, 0x21, 0x4C, 0x30, 0xF1, 0x6F, 0xC7, 0xF4, 0x1B, 0xC1, 0xAD, 0x60, 0x62, 0x68, 0xC3, + 0x14, 0x4C, 0x14, 0x5B, 0x29, 0x06, 0x6C, 0xE6, 0x3F, 0xDD, 0x2B, 0xDD, 0x8B, 0x05, 0xC4, 0xBB, + 0x12, 0xF1, 0xE3, 0x15, 0xC4, 0x4D, 0x4E, 0xF7, 0x0C, 0x1D, 0x56, 0x9D, 0x01, 0x44, 0x5B, 0x44, + 0xDD, 0xC2, 0x7D, 0x31, 0x31, 0xDE, 0xE6, 0x69, 0xB5, 0xC1, 0x56, 0xE9, 0xD9, 0xE0, 0xE7, 0xB4, + 0x54, 0x15, 0x92, 0xCB, 0xE7, 0x6A, 0xF9, 0x01, 0x0D, 0x6D, 0x67, 0x1C, 0x54, 0x54, 0xF6, 0x2A, + 0x88, 0x72, 0x64, 0xF1, 0xDE, 0xF6, 0x87, 0xB8, 0x3D, 0xC3, 0x05, 0x11, 0x67, 0xCB, 0x5C, 0x90, + 0x68, 0x32, 0xB0, 0x57, 0x92, 0x94, 0x0C, 0x3B, 0x9F, 0xA8, 0x4A, 0x61, 0x32, 0xC9, 0x8A, 0x6D, + 0xF6, 0x2C, 0x40, 0x2A, 0x11, 0x9E, 0x52, 0xED, 0x67, 0xBB, 0x20, 0xF5, 0x1A, 0x9C, 0x0F, 0x6A, + 0x9A, 0xC5, 0xA5, 0x6D, 0xB4, 0x05, 0x4C, 0xE1, 0x2A, 0x36, 0xD1, 0x5A, 0xD3, 0xBC, 0xAD, 0xED, + 0xE0, 0xCD, 0x37, 0x6F, 0xE7, 0x22, 0x2B, 0x9C, 0xB7, 0x95, 0xE4, 0xD1, 0x73, 0x0A, 0xA0, 0x38, + 0x05, 0x75, 0xD2, 0xCD, 0x98, 0x0A, 0xBA, 0x5E, 0x2F, 0xE7, 0x42, 0x1A, 0xDB, 0x56, 0x7B, 0x74, + 0x23, 0xAB, 0xEF, 0x81, 0xA8, 0x3A, 0x78, 0xA2, 0xCD, 0xB6, 0x6C, 0x5A, 0xE7, 0x47, 0xA7, 0x87, + 0xBF, 0x2C, 0x42, 0x9E, 0x0A, 0xB6, 0x72, 0xE6, 0x23, 0x05, 0x59, 0xD3, 0x78, 0x94, 0xC7, 0x63, + 0x90, 0x83, 0x92, 0x82, 0x78, 0x4E, 0x29, 0x94, 0x4D, 0x67, 0xAC, 0xCB, 0x20, 0x81, 0x9B, 0x47, + 0x02, 0x25, 0xB0, 0x98, 0xDA, 0x6F, 0xCA, 0x51, 0x3C, 0xAF, 0x1C, 0x2A, 0xE6, 0x3D, 0x4E, 0xC9, + 0x03, 0xE0, 0x27, 0x76, 0xE8, 0x0C, 0x54, 0x24, 0x73, 0x09, 0xA7, 0x22, 0xCA, 0x0C, 0x49, 0x45, + 0x59, 0x8D, 0x17, 0x20, 0xA0, 0x12, 0x09, 0x92, 0x33, 0xE5, 0xC2, 0x60, 0x17, 0x22, 0x8E, 0x7C, + 0x4C, 0x8A, 0x14, 0x4A, 0x27, 0x3C, 0xAE, 0x2D, 0x9C, 0x45, 0xA4, 0x54, 0x96, 0xF6, 0xA3, 0x73, + 0xB1, 0xD5, 0x93, 0x5E, 0x4D, 0x9C, 0xE9, 0x6D, 0xD2, 0xBD, 0x71, 0xE8, 0x84, 0xB3, 0x61, 0xAD, + 0xC1, 0xA6, 0x5C, 0x4B, 0x48, 0xA1, 0x17, 0xFB, 0x45, 0xEF, 0xA9, 0x33, 0xBA, 0x09, 0x2F, 0x27, + 0x0F, 0x46, 0x20, 0xB5, 0x21, 0xB5, 0x60, 0x32, 0xEA, 0x25, 0x91, 0x05, 0x23, 0xE7, 0xA3, 0x40, + 0x64, 0x21, 0x7B, 0x6F, 0xD7, 0x76, 0xA9, 0x5A, 0x4E, 0x10, 0xC5, 0xAD, 0x05, 0x9D, 0x73, 0x5B, + 0x8D, 0x51, 0x8C, 0x52, 0xAC, 0x82, 0x1A, 0x4B, 0x6A, 0x48, 0x41, 0x1D, 0x60, 0x3C, 0xEA, 0x6E, + 0x5B, 0xD3, 0x77, 0x6E, 0x10, 0x01, 0x04, 0x12, 0x84, 0xAE, 0xD8, 0xAA, 0x15, 0x51, 0xD8, 0x2F, + 0x18, 0x12, 0xC9, 0xB0, 0xE0, 0x97, 0x20, 0x66, 0x3E, 0xED, 0xC5, 0x2B, 0x35, 0x7D, 0x09, 0x5E, + 0x6A, 0x6F, 0x92, 0x0F, 0x88, 0x4A, 0xD8, 0x4A, 0x0C, 0x30, 0x33, 0x3E, 0x7C, 0x4A, 0x86, 0xDE, + 0x0D, 0xBE, 0x22, 0xE3, 0x8F, 0xF5, 0x3E, 0x9C, 0x6C, 0x6F, 0x59, 0x64, 0x85, 0x38, 0x6D, 0xDA, + 0x26, 0xAE, 0xE7, 0xAE, 0x1C, 0xBF, 0x03, 0x39, 0xF6, 0xB2, 0xC6, 0x5D, 0x1C, 0xFB, 0xE3, 0x8E, + 0xC7, 0xFE, 0xB8, 0x23, 0xAF, 0x88, 0x3B, 0x9B, 0xEC, 0xEB, 0x71, 0xF3, 0x02, 0x28, 0x4A, 0x47, + 0x00, 0xB9, 0x9A, 0x85, 0xA1, 0xE7, 0x8A, 0x00, 0x20, 0x2C, 0xA1, 0x24, 0x06, 0xCC, 0x7B, 0xC3, + 0xBE, 0x62, 0xD2, 0xBF, 0x3B, 0xE5, 0xA2, 0x58, 0x52, 0xDB, 0xA8, 0x54, 0x78, 0x5C, 0x9A, 0xA9, + 0x53, 0x51, 0x30, 0xBF, 0x04, 0xFF, 0x3E, 0xD6, 0x6F, 0xDD, 0xC9, 0x26, 0x45, 0xCA, 0xDD, 0xB7, + 0x24, 0x5F, 0x4A, 0xCA, 0x70, 0x01, 0xA5, 0x68, 0x97, 0xD5, 0x6E, 0x09, 0x1A, 0x5D, 0xBC, 0xEC, + 0xE5, 0x82, 0xC1, 0xAB, 0x13, 0x3C, 0x9C, 0x30, 0xEC, 0xF3, 0xB8, 0x75, 0x05, 0x88, 0x8C, 0x57, + 0x5E, 0x16, 0xC6, 0xFE, 0x02, 0x18, 0x37, 0xB1, 0xAC, 0xDC, 0x0D, 0xCC, 0x8B, 0xC8, 0x98, 0x13, + 0x2B, 0x32, 0x43, 0x87, 0xB5, 0x28, 0x36, 0xF5, 0xB5, 0x3F, 0x09, 0xF4, 0x9F, 0x1D, 0x60, 0xF2, + 0x8E, 0x45, 0x12, 0xFE, 0x66, 0xB2, 0x38, 0x65, 0x06, 0xCF, 0xB7, 0x1D, 0xD3, 0xB1, 0x87, 0x3C, + 0x88, 0x30, 0xE5, 0x88, 0xB8, 0x18, 0xC1, 0xD2, 0x7D, 0x68, 0xAC, 0x60, 0x25, 0xE4, 0xA2, 0xE0, + 0x14, 0x44, 0x8D, 0x54, 0x6A, 0x18, 0x63, 0xF8, 0x8D, 0xFF, 0x9D, 0xDC, 0xFF, 0x22, 0x47, 0xEE, + 0xC0, 0x67, 0xB7, 0x76, 0xA6, 0x22, 0x84, 0x27, 0xD8, 0x9C, 0xE0, 0xD6, 0x9E, 0xB2, 0xBB, 0x5F, + 0x3C, 0x2A, 0x1F, 0x18, 0xDD, 0x84, 0x27, 0x12, 0x30, 0x9E, 0x78, 0x88, 0x2F, 0xAC, 0xE3, 0x62, + 0xBE, 0x94, 0x1B, 0x98, 0x8B, 0x69, 0x10, 0x3E, 0x93, 0xC5, 0xC9, 0x49, 0xA5, 0x73, 0x2A, 0xFA, + 0x64, 0x62, 0x7F, 0xA1, 0x27, 0xF4, 0x3D, 0xC2, 0xF8, 0x3B, 0x86, 0x12, 0x16, 0x5F, 0x78, 0x27, + 0xDD, 0xBB, 0x95, 0xF5, 0xA2, 0x4C, 0xEF, 0x7E, 0x63, 0xBD, 0x9B, 0x96, 0x8D, 0xFC, 0x4F, 0x66, + 0x38, 0x09, 0x36, 0x6A, 0x9E, 0x4D, 0xCA, 0xD1, 0x93, 0x25, 0xB4, 0xA2, 0x85, 0x45, 0x57, 0xA9, + 0x32, 0x61, 0xE4, 0x11, 0xBD, 0x5F, 0xA0, 0xA0, 0x98, 0xC9, 0x94, 0x5B, 0x6B, 0xE2, 0xAB, 0xA0, + 0x75, 0x2B, 0xD1, 0xDB, 0xE8, 0x48, 0xB5, 0x0A, 0x84, 0x25, 0xD1, 0x64, 0x6D, 0x35, 0x91, 0x04, + 0x6C, 0xA7, 0x5E, 0x48, 0x5F, 0x2A, 0xD9, 0x8E, 0x4D, 0xC4, 0x9F, 0x03, 0xF1, 0x06, 0xCC, 0xA2, + 0xE3, 0x3B, 0x82, 0xA9, 0x26, 0x83, 0x88, 0x59, 0xF8, 0xDB, 0xB9, 0x36, 0xA1, 0xCD, 0xC1, 0xC7, + 0xF2, 0xEE, 0x39, 0x6E, 0xB8, 0x4C, 0x30, 0x6A, 0x5D, 0xC0, 0xE2, 0xF6, 0xB7, 0xC9, 0x07, 0x1C, + 0x2B, 0xB6, 0x8F, 0x29, 0x94, 0x43, 0x1C, 0x2B, 0x94, 0x12, 0xFB, 0xCA, 0xFB, 0x4A, 0xAB, 0x8A, + 0xE9, 0x79, 0x24, 0xA6, 0x03, 0x9A, 0x2B, 0xA6, 0x7B, 0x25, 0xAA, 0x18, 0x39, 0xBA, 0x26, 0xF6, + 0x18, 0xEA, 0x0F, 0xEF, 0xD8, 0xE8, 0x13, 0x03, 0x2F, 0x1E, 0xBD, 0xCB, 0x4C, 0x92, 0xC4, 0x09, + 0xC9, 0x18, 0x64, 0x29, 0x46, 0xA4, 0x66, 0xC9, 0xD9, 0xA5, 0xA8, 0xBD, 0xC9, 0x7B, 0x0E, 0xFA, + 0xB8, 0xE3, 0xCC, 0xE2, 0x3B, 0xFB, 0xC4, 0x22, 0x4E, 0x40, 0xDE, 0x4B, 0x56, 0x43, 0x41, 0x15, + 0x33, 0x97, 0xD6, 0x7B, 0xFC, 0x77, 0x05, 0xED, 0xFF, 0xF2, 0x38, 0xC3, 0x01, 0xF3, 0x7B, 0xC5, + 0xDC, 0x3C, 0xF0, 0x60, 0xC8, 0xF0, 0x43, 0x0B, 0x63, 0x1F, 0x1B, 0xDB, 0x84, 0x56, 0x85, 0x87, + 0x13, 0x49, 0xF4, 0x20, 0x5B, 0xB9, 0xAA, 0x46, 0x4D, 0x46, 0xB7, 0x6F, 0xFF, 0xF0, 0x6D, 0x3C, + 0x75, 0xCB, 0x49, 0xAE, 0xE3, 0x27, 0x4C, 0x2E, 0x4C, 0x3A, 0x78, 0x3F, 0x0F, 0x6B, 0xC6, 0xA7, + 0xF9, 0x3E, 0x9D, 0xC0, 0x60, 0x79, 0x63, 0x0F, 0x71, 0x7D, 0x19, 0xB4, 0xD2, 0x75, 0x22, 0x8F, + 0xD6, 0x94, 0x1E, 0x57, 0xAE, 0x0D, 0x2E, 0x66, 0x67, 0x99, 0xAC, 0x6F, 0x4B, 0xB9, 0x70, 0x3B, + 0x18, 0x35, 0x65, 0x7D, 0x3B, 0x23, 0x21, 0xAE, 0x9C, 0xB1, 0x64, 0x27, 0x45, 0x82, 0x27, 0xBB, + 0x92, 0x1F, 0x29, 0x2C, 0x93, 0x95, 0x17, 0x16, 0xFB, 0xB7, 0x4C, 0xE2, 0x5F, 0x92, 0x24, 0x76, + 0xE2, 0x13, 0x92, 0x14, 0xBF, 0xD6, 0x27, 0xF6, 0xF1, 0x31, 0x89, 0xFD, 0xBA, 0x48, 0x62, 0x19, + 0x69, 0xCE, 0x95, 0x29, 0x3F, 0x4A, 0x6F, 0x8A, 0x3D, 0x47, 0xEC, 0x91, 0x8D, 0x79, 0xE6, 0x79, + 0xCE, 0x35, 0x47, 0x52, 0x4C, 0x9E, 0xC3, 0x71, 0x48, 0xBF, 0xA9, 0x6F, 0xB7, 0xD8, 0x20, 0xDE, + 0x11, 0x25, 0xAF, 0xF0, 0x22, 0xBC, 0xE7, 0x0F, 0x03, 0xA6, 0x2E, 0xD1, 0x25, 0xCE, 0xE7, 0xCF, + 0x59, 0xA9, 0x3E, 0x3A, 0x11, 0x21, 0x18, 0xEA, 0x30, 0x60, 0x5A, 0x17, 0x83, 0x7D, 0x62, 0x95, + 0x3F, 0xA7, 0xF2, 0x9E, 0xE8, 0x5E, 0xB5, 0xA2, 0x6B, 0xD2, 0xE9, 0x20, 0x43, 0x89, 0x49, 0x35, + 0x0C, 0x43, 0x35, 0x4D, 0x06, 0x87, 0x67, 0x7A, 0x18, 0x3C, 0x27, 0x4D, 0x16, 0xF3, 0x3E, 0xD1, + 0xB6, 0xAC, 0x82, 0x8F, 0x59, 0x05, 0xBF, 0xEA, 0xF9, 0x14, 0x2A, 0x1A, 0x47, 0x9E, 0xCA, 0x90, + 0x89, 0x7B, 0xD7, 0x20, 0x55, 0x35, 0x55, 0xB5, 0x5C, 0x3E, 0x9D, 0x05, 0x37, 0xAD, 0x07, 0x6D, + 0xD3, 0x92, 0x21, 0x96, 0x3B, 0x12, 0xC2, 0x35, 0xA6, 0x6E, 0x88, 0x86, 0x14, 0xEF, 0x72, 0xC7, + 0xB6, 0x28, 0xBE, 0x41, 0x0C, 0x88, 0xC4, 0x45, 0x7D, 0xBC, 0x69, 0x0E, 0x35, 0xA5, 0x37, 0x40, + 0x72, 0x8F, 0x26, 0x6F, 0x5D, 0x11, 0xE2, 0x35, 0xCB, 0x17, 0xA2, 0xCE, 0x94, 0x26, 0x15, 0x82, + 0xBA, 0x66, 0x05, 0x42, 0x00, 0x94, 0x8D, 0x58, 0x0D, 0x44, 0xBA, 0xA2, 0x65, 0xE0, 0x16, 0xAF, + 0x11, 0x5A, 0x8D, 0x03, 0xC6, 0x3D, 0x4C, 0xD5, 0x03, 0xC6, 0x23, 0xC1, 0xE5, 0x42, 0x0C, 0xFE, + 0x9C, 0x34, 0xFE, 0x4D, 0xDE, 0x5C, 0xF9, 0x57, 0x66, 0x97, 0x20, 0x27, 0x03, 0x8A, 0x2D, 0x00, + 0x9B, 0x98, 0xB1, 0x76, 0xCC, 0x17, 0x23, 0x5E, 0x8C, 0x57, 0x0C, 0xFA, 0x77, 0x94, 0x61, 0xE6, + 0x5B, 0x31, 0x2E, 0xCD, 0xCE, 0xE7, 0x8C, 0xAA, 0x1F, 0x53, 0x55, 0xBB, 0x59, 0x55, 0x7F, 0x4D, + 0x55, 0x5D, 0xD3, 0xAA, 0x9A, 0x47, 0xBF, 0xD4, 0xA1, 0xA6, 0x1C, 0xDB, 0x32, 0xD7, 0x05, 0x35, + 0x3E, 0x16, 0xD6, 0xF8, 0x35, 0xAB, 0x86, 0xCA, 0x9A, 0x92, 0x46, 0x3A, 0xCE, 0x78, 0x29, 0x09, + 0x1A, 0xBC, 0x58, 0xDF, 0x06, 0xBF, 0x90, 0x2B, 0x00, 0xC1, 0xBB, 0x14, 0x13, 0xCF, 0xF5, 0x58, + 0x6A, 0x26, 0xC2, 0xEE, 0xFC, 0x33, 0x33, 0xAC, 0xAD, 0xD4, 0x13, 0x45, 0x91, 0x1E, 0x0E, 0x64, + 0xAA, 0x41, 0x94, 0xE0, 0x29, 0x9E, 0xFA, 0x51, 0x19, 0xD2, 0x46, 0x25, 0x35, 0x33, 0xF0, 0xFD, + 0x84, 0x2C, 0xB4, 0x49, 0xF3, 0xE5, 0x26, 0xE3, 0xFB, 0x3B, 0xFD, 0xA9, 0x84, 0x94, 0x0A, 0x13, + 0xA3, 0x50, 0x7B, 0x3E, 0x1D, 0x36, 0x72, 0xDE, 0x0A, 0xF1, 0x9D, 0x90, 0xB9, 0xC9, 0x8A, 0xD2, + 0x97, 0xE4, 0x97, 0xD5, 0x8F, 0xAB, 0xBF, 0x36, 0xD4, 0xD4, 0x36, 0x86, 0xD6, 0xBF, 0x22, 0x1B, + 0x4B, 0xA9, 0x23, 0xE3, 0x4C, 0x99, 0x06, 0xCE, 0x3F, 0x29, 0x31, 0x99, 0x66, 0xC5, 0x3A, 0xC6, + 0x3E, 0x6E, 0x32, 0x75, 0x56, 0x9D, 0x2B, 0x71, 0x80, 0x7A, 0x53, 0xD6, 0xF7, 0xD2, 0x83, 0x0B, + 0xF4, 0x56, 0x41, 0x0D, 0x44, 0xAE, 0x93, 0x26, 0xAF, 0x20, 0x0F, 0x53, 0xFE, 0x85, 0xED, 0x5D, + 0x18, 0x27, 0xD8, 0x54, 0xCD, 0x68, 0x0C, 0xB1, 0x62, 0x75, 0xB4, 0x65, 0x0A, 0x01, 0x13, 0xBD, + 0x70, 0x70, 0x75, 0x52, 0xF8, 0x73, 0xAB, 0xF1, 0xBF, 0xCC, 0x40, 0x82, 0x1A, 0xC0, 0x52, 0x7B, + 0x70, 0xD3, 0x32, 0xEF, 0x42, 0xCA, 0x36, 0xE9, 0xCF, 0xAD, 0xF0, 0xC6, 0x09, 0xF8, 0x26, 0x4C, + 0x6B, 0x29, 0xD7, 0xAA, 0xBB, 0xAA, 0x55, 0x6F, 0x07, 0xB3, 0x2B, 0xBE, 0x2A, 0x6C, 0x81, 0xFF, + 0xD4, 0xD9, 0x90, 0x20, 0x14, 0xA4, 0x31, 0x28, 0x4C, 0x78, 0x3C, 0xD7, 0x4D, 0x64, 0xC9, 0xE2, + 0x29, 0x30, 0xB2, 0x57, 0xDA, 0x87, 0xB5, 0xCF, 0x1C, 0x45, 0xB2, 0xC1, 0xAF, 0x39, 0xE1, 0xD1, + 0x0B, 0xD7, 0x72, 0x8E, 0x78, 0x54, 0xBB, 0xC8, 0x19, 0x57, 0xEB, 0x95, 0x71, 0xC8, 0x23, 0x88, + 0x45, 0x39, 0xE5, 0x49, 0xEE, 0xDA, 0x5C, 0x77, 0x36, 0x3E, 0x64, 0x02, 0x8F, 0xB6, 0xD3, 0xB1, + 0xD6, 0xD6, 0x97, 0xC9, 0xD6, 0x96, 0x42, 0x9D, 0x7F, 0x46, 0x16, 0xB0, 0xA0, 0xB2, 0xD3, 0xAC, + 0x9F, 0x35, 0x21, 0x9D, 0x0D, 0xEC, 0x6B, 0x85, 0xC4, 0x06, 0x8B, 0xD6, 0xB8, 0x51, 0x17, 0xBB, + 0x76, 0xD0, 0x04, 0x34, 0xBA, 0x96, 0xD5, 0xB6, 0xD8, 0x83, 0xD5, 0xB6, 0xE2, 0x99, 0xB3, 0x0F, + 0x48, 0x8C, 0xFD, 0xF2, 0xE4, 0xBC, 0xF2, 0x58, 0x6F, 0xAA, 0x7B, 0xE6, 0x11, 0x68, 0x55, 0xEF, + 0x3C, 0x56, 0xBC, 0x6A, 0x1E, 0xBA, 0x46, 0x4E, 0xF2, 0xD2, 0xB5, 0x31, 0xA2, 0xF8, 0xA8, 0xE2, + 0xA9, 0xB8, 0xB1, 0x48, 0xBC, 0x0C, 0x37, 0x95, 0x45, 0x5A, 0xAA, 0x95, 0x69, 0xBA, 0x65, 0x2E, + 0x55, 0x75, 0xE3, 0x01, 0x7C, 0x7E, 0xAD, 0xCF, 0x8C, 0x7E, 0x7F, 0x5C, 0x47, 0xF1, 0xFD, 0x7F, + 0x03, 0x92, 0x32, 0xAD, 0x24, 0x22, 0xB6, 0xB3, 0x57, 0x13, 0x29, 0xA3, 0x5A, 0xE4, 0x0C, 0xEB, + 0x4A, 0x58, 0xD9, 0x21, 0x8E, 0xD5, 0xF1, 0xE9, 0x2C, 0x2C, 0xE2, 0xDE, 0x2D, 0xBF, 0xB8, 0xC8, + 0x93, 0xAC, 0x74, 0x5A, 0x2D, 0x2F, 0xD3, 0x6E, 0x6C, 0x7A, 0x42, 0xC3, 0x1B, 0x6F, 0x98, 0xF9, + 0xD6, 0x53, 0x79, 0xE8, 0x99, 0x84, 0x38, 0x78, 0x19, 0x45, 0x34, 0x48, 0x25, 0xD5, 0x04, 0x94, + 0x89, 0xFC, 0x25, 0xFC, 0xDA, 0xFD, 0xF0, 0xF4, 0x09, 0x7C, 0xF6, 0xBD, 0x3F, 0xD3, 0xA5, 0x86, + 0xCC, 0x8B, 0x7D, 0x40, 0x12, 0xBE, 0x89, 0x4C, 0x93, 0x19, 0xC1, 0x20, 0x96, 0xC8, 0x0A, 0x69, + 0x49, 0x55, 0xD2, 0x57, 0x1A, 0x44, 0xB5, 0xE7, 0x24, 0x5D, 0xCB, 0xFC, 0x50, 0x66, 0x89, 0xAC, + 0x92, 0x0E, 0x0F, 0x70, 0x90, 0xC7, 0x76, 0x34, 0xF3, 0x03, 0x97, 0x6D, 0xBC, 0xC3, 0x04, 0xA5, + 0xAD, 0xB5, 0xBC, 0x77, 0xF5, 0xB9, 0x72, 0x4A, 0xC7, 0x10, 0xC9, 0x11, 0x93, 0x26, 0x54, 0xB3, + 0x9C, 0x74, 0x56, 0x51, 0x04, 0x8F, 0x28, 0xA9, 0x54, 0xCC, 0x0E, 0xB3, 0x9C, 0xF4, 0xA5, 0xF3, + 0x93, 0xB5, 0x18, 0xB3, 0x49, 0x4F, 0xC0, 0x31, 0x78, 0x65, 0x05, 0x11, 0x51, 0x8C, 0x2B, 0xBD, + 0xDE, 0x25, 0x9B, 0xA6, 0xA9, 0x7A, 0x6C, 0x87, 0x11, 0x96, 0xA4, 0xF2, 0x0A, 0x59, 0x47, 0x41, + 0x76, 0x0D, 0xA9, 0x9A, 0x33, 0xA7, 0x66, 0xC3, 0xF2, 0xB9, 0x20, 0x14, 0x4B, 0x7A, 0xC9, 0x1F, + 0x71, 0x1D, 0x33, 0xF5, 0x3A, 0xFD, 0xEE, 0x43, 0x59, 0x18, 0x4D, 0x60, 0x35, 0x18, 0xB1, 0xDF, + 0xD9, 0x91, 0xFE, 0x7C, 0x15, 0x37, 0x4C, 0xFA, 0x9A, 0x3E, 0x07, 0x28, 0xE4, 0xF2, 0xF9, 0xAE, + 0xE2, 0xB3, 0x27, 0x04, 0x9E, 0x13, 0x9D, 0xF1, 0xF4, 0x9E, 0xFF, 0x7D, 0x86, 0x24, 0xD2, 0x81, + 0x66, 0x84, 0x28, 0x00, 0x6B, 0xC4, 0xF6, 0xD3, 0x92, 0x8A, 0xCE, 0x71, 0x9E, 0x58, 0xB2, 0x1B, + 0x51, 0x5A, 0x42, 0x06, 0x9B, 0xC6, 0x09, 0x49, 0x1A, 0xBA, 0x66, 0x50, 0xB4, 0x0C, 0x03, 0x62, + 0x02, 0xEF, 0x66, 0x83, 0x67, 0x3E, 0x56, 0x4C, 0x21, 0xE9, 0x7C, 0xD6, 0x5E, 0xDB, 0xD6, 0x89, + 0xF9, 0x13, 0x05, 0xED, 0xA9, 0x80, 0xA7, 0x9B, 0x13, 0x3B, 0x48, 0xC1, 0xA3, 0xDC, 0x23, 0xCB, + 0xCA, 0x5F, 0x6B, 0x18, 0xD4, 0x3B, 0x99, 0x75, 0xD5, 0x51, 0x52, 0x54, 0x2F, 0xD6, 0x9B, 0x82, + 0x8A, 0x49, 0x87, 0x67, 0x57, 0x4C, 0x75, 0x6E, 0x61, 0x55, 0xBD, 0x23, 0x4B, 0x5E, 0x84, 0x51, + 0xA2, 0xCD, 0x04, 0xDC, 0xBC, 0x47, 0xA2, 0x21, 0xCC, 0x1A, 0xF3, 0x95, 0x78, 0xC6, 0xB5, 0x98, + 0xF4, 0x4E, 0x5D, 0x0C, 0x5C, 0x6B, 0xB7, 0x4E, 0xF5, 0xBC, 0x72, 0x77, 0xEC, 0x24, 0xAB, 0x9C, + 0xB7, 0x6B, 0xA7, 0x2D, 0x0B, 0x4A, 0xEF, 0xDC, 0x99, 0xF4, 0x43, 0xD7, 0x9D, 0x07, 0xDC, 0xC1, + 0xAB, 0x49, 0x3E, 0xDE, 0xC9, 0x03, 0xAD, 0x5D, 0x45, 0x8D, 0x5C, 0x05, 0x6D, 0x33, 0x6F, 0xE8, + 0xE9, 0x82, 0x29, 0xB9, 0xA9, 0x27, 0x89, 0x5D, 0xDD, 0xD8, 0xD3, 0xD7, 0xCC, 0x15, 0x37, 0xF7, + 0xCA, 0x2C, 0xB9, 0x17, 0xB9, 0xC1, 0xA7, 0x2D, 0x9C, 0xE7, 0xDB, 0xE4, 0x93, 0x84, 0x52, 0x6D, + 0xA3, 0x2F, 0x1E, 0x2D, 0xDF, 0x75, 0xB3, 0x4F, 0x51, 0x0F, 0xD9, 0xBF, 0x42, 0x4F, 0xEA, 0x85, + 0x3E, 0x63, 0x2E, 0x6C, 0x4B, 0x30, 0x35, 0x5F, 0xAA, 0x15, 0xD6, 0x75, 0x88, 0x0D, 0xFD, 0xC3, + 0x66, 0x11, 0x8A, 0x17, 0xCA, 0xB6, 0x63, 0xA1, 0x31, 0x7C, 0x90, 0xCD, 0x4E, 0x49, 0x07, 0xEE, + 0x53, 0x41, 0xDB, 0x94, 0x5D, 0x4B, 0x29, 0x86, 0x14, 0x77, 0xB9, 0xE1, 0xA7, 0xD4, 0xB3, 0xED, + 0xFF, 0xF2, 0x1C, 0xB7, 0xD5, 0x6C, 0xC6, 0x01, 0xB4, 0xB4, 0x2A, 0xCB, 0xC5, 0x55, 0xFE, 0xFD, + 0xDF, 0x53, 0x75, 0x7C, 0x1A, 0xCE, 0x7C, 0x97, 0xB9, 0xEB, 0x1A, 0x77, 0x23, 0x1A, 0x62, 0xD8, + 0x2E, 0xC5, 0x14, 0xB3, 0x88, 0x69, 0x60, 0xB2, 0x40, 0x7B, 0xA2, 0x32, 0xB4, 0xA8, 0x7C, 0x5A, + 0xD7, 0xCC, 0x9A, 0x52, 0x47, 0xAC, 0xB0, 0xA4, 0x4D, 0xBB, 0xA3, 0x6B, 0xB6, 0x49, 0x17, 0xDA, + 0x57, 0xE4, 0xD6, 0x0E, 0x08, 0xCE, 0xDD, 0x04, 0x43, 0x7D, 0xD1, 0xE1, 0x32, 0xE1, 0x43, 0x1A, + 0xCB, 0xC6, 0x94, 0xC7, 0x84, 0x0B, 0x06, 0x3E, 0xA6, 0x21, 0xD4, 0x16, 0x3A, 0x63, 0x7A, 0x62, + 0xBB, 0xF6, 0x88, 0xFA, 0x17, 0x58, 0x33, 0x15, 0xD4, 0x8B, 0xC1, 0xBF, 0x7E, 0x15, 0xFA, 0xC4, + 0x1E, 0x3B, 0x23, 0x77, 0xB7, 0x39, 0xA6, 0xD7, 0x61, 0x13, 0x3E, 0xDC, 0xBC, 0xC6, 0xFD, 0x83, + 0x57, 0xAB, 0xF0, 0x0B, 0xFE, 0xD1, 0x07, 0x43, 0x26, 0xFE, 0x18, 0xBE, 0x7E, 0xC5, 0xF3, 0x64, + 0x87, 0x77, 0x53, 0xBA, 0xCB, 0x3D, 0x8E, 0x2B, 0xEF, 0x5B, 0x93, 0x38, 0xC3, 0xDD, 0x26, 0x12, + 0xE4, 0xCB, 0xF9, 0xBD, 0xF1, 0xB8, 0x49, 0x58, 0x1A, 0x77, 0xF8, 0xEA, 0xF9, 0x93, 0x15, 0x56, + 0x71, 0x85, 0x83, 0x4A, 0x7C, 0xB1, 0x9D, 0xC9, 0x26, 0x11, 0x17, 0x17, 0x39, 0x86, 0x88, 0x65, + 0x6F, 0x34, 0xC2, 0x20, 0x4B, 0xC0, 0xCF, 0x2A, 0x92, 0x5D, 0x0D, 0xFD, 0xF8, 0x07, 0xE3, 0x5B, + 0x32, 0xDB, 0x08, 0xC6, 0x9A, 0x78, 0xC1, 0x6D, 0x58, 0xA3, 0x21, 0x89, 0xF2, 0xDB, 0x64, 0x7C, + 0x13, 0x86, 0xD3, 0xDC, 0x40, 0x6A, 0x52, 0x3D, 0x11, 0x4F, 0xED, 0xDD, 0x21, 0x0F, 0xA7, 0x86, + 0xB3, 0x30, 0x8B, 0xF6, 0xD6, 0x48, 0x7B, 0x67, 0x11, 0x04, 0x8B, 0x92, 0x25, 0xDB, 0x09, 0x71, + 0x6D, 0x6C, 0xE0, 0x4D, 0xD0, 0x8C, 0x44, 0xD5, 0x7C, 0x1A, 0x4C, 0xC1, 0x9D, 0x60, 0x4C, 0xB2, + 0x9B, 0xE0, 0x22, 0x76, 0x20, 0xD9, 0xEF, 0xFF, 0xC4, 0xA3, 0xFD, 0x39, 0x6E, 0xE8, 0xB1, 0xC9, + 0xFF, 0x59, 0xF9, 0x8E, 0x04, 0xF7, 0x5B, 0x69, 0x7E, 0xC1, 0x64, 0xAA, 0x6A, 0x5D, 0x66, 0x46, + 0x47, 0x50, 0x6E, 0x11, 0x45, 0x37, 0xA5, 0xDF, 0xDE, 0x55, 0x68, 0x3B, 0xA0, 0x86, 0x52, 0xB9, + 0x51, 0xC7, 0x8D, 0xF5, 0x74, 0x3D, 0x97, 0xC2, 0x91, 0x62, 0x05, 0x5D, 0x45, 0xA5, 0x3E, 0x16, + 0xB5, 0xA4, 0x1E, 0x8E, 0x9B, 0x85, 0x31, 0x03, 0x4F, 0x92, 0x94, 0x95, 0x68, 0xFF, 0x3F, 0x7D, + 0x36, 0x97, 0xB3, 0x0D, 0x79, 0x63, 0x85, 0xE8, 0x51, 0x4E, 0x26, 0x86, 0xA8, 0x82, 0x82, 0x62, + 0x81, 0x5A, 0x16, 0xC5, 0xE5, 0xFE, 0x8E, 0x8A, 0x96, 0xD5, 0x13, 0xCF, 0x77, 0x65, 0xF1, 0x2B, + 0x66, 0x8A, 0x9C, 0xD3, 0xA9, 0xC0, 0x6E, 0xBB, 0x77, 0x5C, 0x52, 0x51, 0x65, 0x76, 0xE4, 0x10, + 0x30, 0xDF, 0xF6, 0x2B, 0x17, 0x9A, 0x78, 0xE6, 0x80, 0x86, 0x4D, 0x7C, 0x41, 0xD7, 0x07, 0xFF, + 0xC4, 0x7C, 0x20, 0x84, 0xA7, 0x44, 0x21, 0x43, 0x11, 0x50, 0x21, 0xC8, 0xBD, 0xE1, 0x97, 0xEA, + 0xF6, 0xAC, 0xD4, 0xA7, 0xA2, 0x75, 0xA9, 0xFA, 0x9F, 0xBE, 0x7D, 0x4E, 0xD6, 0x73, 0x69, 0x25, + 0xF9, 0x24, 0x7B, 0x3D, 0xF7, 0x85, 0x6D, 0x8E, 0x4C, 0x61, 0x95, 0x46, 0xB3, 0x78, 0x0B, 0xFC, + 0x96, 0x7D, 0x82, 0x80, 0x96, 0x68, 0xB6, 0xA2, 0xAC, 0x79, 0xED, 0x66, 0x13, 0x52, 0x5A, 0x7B, + 0xC5, 0x25, 0xCD, 0x06, 0x8E, 0xC6, 0xAC, 0xE8, 0x40, 0x69, 0x42, 0x4C, 0x60, 0x59, 0x81, 0x85, + 0x73, 0xA2, 0x12, 0xE5, 0x30, 0xC0, 0x34, 0xBD, 0x36, 0x07, 0xDA, 0x4E, 0x63, 0x85, 0x9B, 0x96, + 0xD2, 0xAA, 0x4E, 0x35, 0x75, 0xE4, 0x28, 0x08, 0x66, 0xE2, 0xD6, 0xFB, 0xD1, 0xC1, 0x4B, 0xB6, + 0xA1, 0x6E, 0xE6, 0xA3, 0xCA, 0x2D, 0x7D, 0x95, 0x06, 0xAE, 0x09, 0x8B, 0x4C, 0x2A, 0xD6, 0x29, + 0x6B, 0x56, 0x79, 0xDD, 0x02, 0xD3, 0x8A, 0x95, 0xEA, 0x9B, 0xD7, 0x27, 0x63, 0x1D, 0x59, 0x33, + 0x9E, 0x84, 0x85, 0x4C, 0x09, 0xB4, 0xAA, 0x95, 0xFC, 0x61, 0x31, 0x7E, 0x17, 0x16, 0x83, 0x8D, + 0x3E, 0xE7, 0x21, 0xAC, 0x86, 0xE4, 0xF7, 0x1D, 0xC0, 0x74, 0x88, 0x07, 0x10, 0x49, 0xC4, 0x5B, + 0xF1, 0x62, 0x07, 0x9D, 0xB9, 0xF2, 0x01, 0x54, 0x11, 0xE3, 0xD1, 0x81, 0x74, 0xA8, 0xC6, 0xD9, + 0x71, 0xD9, 0x89, 0xCA, 0xD9, 0x35, 0x43, 0xD6, 0x8F, 0xDE, 0x02, 0xD5, 0x46, 0xAA, 0x6C, 0x71, + 0x60, 0x29, 0x3F, 0xB1, 0x49, 0x6E, 0x16, 0xE0, 0x28, 0x7D, 0xCB, 0x43, 0xA8, 0x62, 0x46, 0x58, + 0x8C, 0x2F, 0x8E, 0x11, 0x7E, 0xC1, 0xFA, 0x62, 0x89, 0x1A, 0xA0, 0x3C, 0xAE, 0x2A, 0xD9, 0x4B, + 0x19, 0xE7, 0xAE, 0x99, 0xFB, 0x25, 0xB1, 0x72, 0x4B, 0xCE, 0x0B, 0x67, 0xFE, 0x38, 0xF4, 0x06, + 0xF6, 0x18, 0xD7, 0x7C, 0x8D, 0x55, 0x44, 0xF1, 0x6F, 0x8C, 0x7D, 0xD6, 0x57, 0xB2, 0x34, 0x3F, + 0x25, 0xE8, 0x31, 0x33, 0x3A, 0x1E, 0xA3, 0xFE, 0xC5, 0x66, 0xDC, 0xEC, 0x0E, 0x45, 0x37, 0x08, + 0xF3, 0x28, 0x6B, 0x45, 0x8C, 0x5E, 0xC8, 0x14, 0x3C, 0x6D, 0xA8, 0xDD, 0x8E, 0x4E, 0x66, 0xDB, + 0x37, 0x3E, 0xBD, 0x06, 0xCA, 0x71, 0xB5, 0xE8, 0x3D, 0x67, 0x4C, 0xEB, 0xF9, 0xF3, 0x9D, 0xAC, + 0xDE, 0x8F, 0xD6, 0x42, 0xD2, 0xA1, 0x53, 0x32, 0xF6, 0xAB, 0xF6, 0x53, 0x56, 0xDC, 0x5C, 0xDC, + 0x34, 0x4A, 0xB0, 0x2A, 0x91, 0x73, 0xDD, 0x54, 0xDC, 0xDC, 0xA4, 0x22, 0xC6, 0xCE, 0x4D, 0xC6, + 0x57, 0xB4, 0x5C, 0x89, 0x97, 0x81, 0xC9, 0x33, 0xC5, 0x9D, 0x02, 0x0D, 0xA7, 0x6A, 0x44, 0xE7, + 0x45, 0xE9, 0xF7, 0xB3, 0xAC, 0x33, 0xF3, 0x54, 0xBF, 0x47, 0x9B, 0x3A, 0xD0, 0xDF, 0x8C, 0xB1, + 0x40, 0x1C, 0x9E, 0xA7, 0xA6, 0x60, 0x59, 0xB3, 0xF4, 0x1D, 0x3C, 0xD9, 0xEE, 0x1A, 0x90, 0xA7, + 0x4C, 0x6E, 0x35, 0xCD, 0xFC, 0x96, 0x52, 0x48, 0xD6, 0x96, 0xC6, 0x4E, 0xE9, 0x99, 0x36, 0x77, + 0xAA, 0x8D, 0x19, 0x29, 0x9E, 0x60, 0xA5, 0xB6, 0xAF, 0xAE, 0x9E, 0xD3, 0x6B, 0x98, 0x51, 0x6F, + 0x78, 0xD8, 0xF4, 0xF8, 0x5A, 0x51, 0xEE, 0x72, 0x53, 0xD9, 0x3D, 0xD9, 0xD1, 0x9E, 0x90, 0xF2, + 0x08, 0xE6, 0x9A, 0xC6, 0x4B, 0x31, 0xD9, 0xF1, 0xD7, 0xCE, 0x42, 0xC2, 0xB0, 0x73, 0x4C, 0x35, + 0x23, 0xAF, 0x73, 0x46, 0x0D, 0x4F, 0xA3, 0x61, 0xAE, 0x1F, 0xF9, 0x98, 0x15, 0x60, 0x99, 0x44, + 0xBF, 0xBE, 0x87, 0xE9, 0x7D, 0x4C, 0x7D, 0x55, 0xB0, 0x0C, 0x4B, 0x1A, 0x9C, 0x59, 0x98, 0x65, + 0xB0, 0x2E, 0x3C, 0x80, 0x79, 0x15, 0x50, 0x7E, 0x18, 0xB1, 0xCC, 0x0F, 0x25, 0xAA, 0x00, 0xDA, + 0x57, 0x9E, 0x1F, 0x02, 0x20, 0xFB, 0x6F, 0x36, 0x60, 0x46, 0xB0, 0xF9, 0x71, 0x7E, 0xA0, 0x79, + 0x29, 0x5B, 0x87, 0x26, 0x8F, 0x28, 0x2C, 0x78, 0xD2, 0xCD, 0x53, 0xEA, 0x0F, 0xF8, 0xFB, 0x58, + 0x5E, 0xD6, 0x1E, 0xB3, 0x10, 0xE2, 0x64, 0x95, 0xF0, 0x3F, 0x43, 0x2F, 0xC4, 0x7D, 0xC0, 0xBF, + 0xE2, 0xD1, 0xBE, 0x14, 0x5D, 0x5D, 0xA0, 0x7D, 0x63, 0xFB, 0xD2, 0x21, 0xDD, 0x89, 0x1D, 0xDE, + 0xB4, 0x7D, 0x6F, 0x06, 0xDC, 0x08, 0xB4, 0x4B, 0x09, 0xC8, 0x4C, 0x8A, 0x4F, 0xAF, 0x39, 0xC6, + 0x06, 0x38, 0x1C, 0x74, 0xFF, 0x5B, 0xA8, 0x26, 0x1D, 0xF2, 0xA8, 0xF7, 0xF1, 0x96, 0xB0, 0x60, + 0xF9, 0x35, 0x66, 0x88, 0xB1, 0x52, 0x89, 0xAE, 0xB2, 0xE9, 0x34, 0x7A, 0x49, 0x20, 0xFD, 0x65, + 0x72, 0x8B, 0x4F, 0xB0, 0xDC, 0x11, 0x57, 0x74, 0xF0, 0x3E, 0x99, 0x76, 0xDF, 0x41, 0x07, 0x4D, + 0x1A, 0x3B, 0xE9, 0x1C, 0xE9, 0x9A, 0x76, 0xA8, 0x82, 0x2C, 0xA2, 0xCB, 0x23, 0xE4, 0x93, 0x38, + 0x44, 0x7E, 0x91, 0x20, 0xA3, 0x83, 0xA3, 0x45, 0x0C, 0x75, 0xF6, 0x2D, 0x36, 0xE7, 0x18, 0xE0, + 0x9E, 0x1F, 0x4D, 0xBC, 0xB9, 0x3B, 0x1A, 0x56, 0xE5, 0x5A, 0x92, 0x87, 0xAC, 0xF1, 0xB5, 0x84, + 0xF1, 0xD6, 0x06, 0x26, 0x87, 0x2A, 0x52, 0x79, 0x34, 0xD4, 0x42, 0xBA, 0x77, 0xC5, 0x92, 0x06, + 0x6B, 0x29, 0x12, 0xC2, 0x81, 0x88, 0x7E, 0xFA, 0x06, 0x67, 0x50, 0xC5, 0xB5, 0x49, 0xDE, 0xF9, + 0x5F, 0x0C, 0x4A, 0x45, 0x65, 0xE5, 0x27, 0x64, 0x31, 0x46, 0xF5, 0x2E, 0xAA, 0x71, 0x1B, 0x90, + 0x1F, 0xE9, 0x65, 0x40, 0x44, 0x6D, 0x8B, 0x8B, 0x31, 0xCA, 0xA5, 0x9C, 0xC9, 0x68, 0x7B, 0x7D, + 0xCB, 0x34, 0x93, 0x43, 0x7D, 0x1E, 0xC6, 0xB6, 0xA0, 0x49, 0x65, 0xC2, 0xEB, 0xC6, 0x4D, 0x32, + 0x05, 0xC6, 0xCD, 0x6F, 0x52, 0x56, 0x28, 0xDD, 0x91, 0x5C, 0x5C, 0xB2, 0x49, 0xB3, 0xE1, 0x34, + 0xAF, 0x31, 0x1F, 0x86, 0x15, 0x1A, 0x33, 0x1B, 0xC6, 0xC1, 0x24, 0x4B, 0x37, 0x27, 0x13, 0x26, + 0xD6, 0xBF, 0xA1, 0xB9, 0x41, 0x1D, 0xAB, 0xD3, 0xB1, 0x4C, 0x2D, 0x1A, 0xDE, 0x0C, 0xA6, 0x87, + 0xB0, 0x8C, 0xF4, 0x5D, 0x1A, 0xA6, 0x5B, 0x25, 0x0A, 0x0E, 0xDE, 0xEF, 0xF7, 0xF2, 0x9B, 0x24, + 0x45, 0xC0, 0x3F, 0xEA, 0xA9, 0x2C, 0x46, 0xD8, 0x73, 0x9B, 0x27, 0x45, 0xA6, 0x2F, 0x86, 0x97, + 0xF9, 0x87, 0x02, 0x7C, 0xEC, 0xCD, 0xEE, 0x39, 0xAB, 0xDE, 0xB0, 0x76, 0x11, 0x1E, 0xBF, 0xDD, + 0x3A, 0xD7, 0xCE, 0x29, 0x07, 0x28, 0xE5, 0x40, 0x3A, 0xC3, 0xFF, 0xD8, 0x95, 0x60, 0x3E, 0x37, + 0x31, 0xCA, 0x4D, 0x5C, 0xF6, 0xE7, 0xDD, 0x7E, 0x5F, 0x77, 0x9E, 0x35, 0x7F, 0x4F, 0x26, 0x98, + 0xE5, 0xEE, 0xA1, 0xB0, 0xE5, 0x7A, 0xE8, 0xD1, 0xB1, 0x6E, 0x8B, 0x4F, 0x14, 0x89, 0xB5, 0xA4, + 0xDD, 0x40, 0x80, 0xA6, 0xE1, 0xDA, 0x40, 0xF2, 0xB8, 0xA2, 0x43, 0x29, 0x56, 0xA6, 0x79, 0x4F, + 0xAC, 0xDF, 0x4E, 0xE9, 0x6D, 0x14, 0x1E, 0x4C, 0xE9, 0x67, 0x3D, 0x6E, 0xCA, 0x9F, 0xE2, 0x00, + 0xE1, 0x18, 0xD1, 0x47, 0x13, 0x2F, 0xBB, 0x0A, 0xA0, 0xAB, 0xF2, 0x49, 0x30, 0xE2, 0x17, 0x2B, + 0x9A, 0x51, 0xB6, 0x95, 0x7D, 0x41, 0x10, 0x4A, 0x30, 0x9D, 0xCF, 0xCF, 0xCE, 0x5B, 0x87, 0x4D, + 0x0C, 0xF8, 0xF0, 0x9B, 0x4E, 0xA6, 0xE1, 0x9D, 0xAC, 0xB6, 0x06, 0xD7, 0x59, 0xC4, 0x53, 0xDC, + 0xD7, 0xF8, 0xCE, 0xBA, 0x80, 0x28, 0x98, 0xC8, 0xA4, 0x0F, 0x7A, 0xE4, 0xE2, 0xB3, 0x66, 0x98, + 0x48, 0x61, 0x0E, 0x15, 0x4D, 0x6A, 0x68, 0xF9, 0xB0, 0x50, 0x3F, 0x44, 0xF2, 0x13, 0xDC, 0xF1, + 0x91, 0x4E, 0x8C, 0x60, 0x39, 0x0A, 0xCE, 0x0B, 0x19, 0xCC, 0x7C, 0x1F, 0xA7, 0x74, 0xD6, 0x1A, + 0xEC, 0x79, 0xB6, 0x3D, 0xD3, 0xFB, 0x39, 0x48, 0x54, 0x6E, 0x1C, 0xC5, 0x3F, 0xAA, 0xA7, 0x5D, + 0x39, 0x8A, 0x24, 0xA1, 0xCE, 0xD2, 0x23, 0x89, 0xF9, 0xE7, 0xBB, 0x32, 0x40, 0xB2, 0x44, 0x58, + 0xC6, 0xE5, 0x83, 0x56, 0x12, 0x5D, 0xA8, 0x86, 0x42, 0xA5, 0x0F, 0x54, 0xCB, 0x76, 0xBE, 0x2F, + 0x75, 0x82, 0x6E, 0x07, 0x32, 0x58, 0x48, 0x81, 0x2E, 0x63, 0xED, 0x88, 0x0C, 0x1A, 0x80, 0xD2, + 0x80, 0xAC, 0xA7, 0x96, 0xA3, 0x0E, 0xD1, 0x6A, 0xEB, 0xEA, 0x8D, 0xF9, 0x68, 0xA2, 0x77, 0x2B, + 0xF2, 0x1E, 0x4D, 0x54, 0xCE, 0x36, 0x10, 0x00, 0x5E, 0xEC, 0xC9, 0xC4, 0xC8, 0x96, 0x8C, 0xA9, + 0x6E, 0x94, 0xF2, 0xE4, 0x35, 0x87, 0x44, 0xCF, 0x98, 0x7C, 0x2C, 0xC5, 0x94, 0x29, 0x05, 0x19, + 0xAB, 0x04, 0xC8, 0x4D, 0x63, 0x53, 0x49, 0xA1, 0x95, 0x41, 0x72, 0x29, 0xBD, 0xE7, 0xD0, 0xD8, + 0x47, 0x38, 0xA6, 0xEA, 0x82, 0x2D, 0x54, 0xA7, 0x0C, 0xF8, 0xF8, 0xBD, 0x48, 0xE1, 0x08, 0x12, + 0x8C, 0xC6, 0x49, 0x97, 0x08, 0x4C, 0x31, 0x01, 0xBB, 0x7E, 0xB1, 0xA3, 0x99, 0xE3, 0x98, 0xC6, + 0x4F, 0xBC, 0x46, 0xEB, 0x5A, 0xFD, 0x5B, 0x69, 0x5F, 0x26, 0x4D, 0x29, 0x11, 0xAD, 0x06, 0xCF, + 0x76, 0xFC, 0x4E, 0xCF, 0x2E, 0x8F, 0x4E, 0x2F, 0x0E, 0xCF, 0x4F, 0x61, 0x8D, 0x5A, 0xD9, 0x1C, + 0x9D, 0x7A, 0xB8, 0x95, 0xAB, 0xCC, 0x29, 0x52, 0x14, 0x6F, 0xE7, 0xEB, 0x3B, 0x1A, 0x2A, 0x46, + 0x47, 0x9D, 0x61, 0x0B, 0xED, 0x92, 0xB6, 0x9F, 0xA8, 0x9A, 0x37, 0x65, 0x4B, 0x33, 0xA3, 0x65, + 0xFD, 0xC3, 0xF3, 0x9F, 0x0E, 0xCF, 0x6B, 0xB4, 0x8B, 0xDB, 0x11, 0x02, 0xFD, 0xCD, 0x7D, 0x00, + 0x16, 0xBB, 0xC4, 0xFE, 0x0A, 0x4E, 0x2C, 0x3F, 0x22, 0x7E, 0x6A, 0x6D, 0xDD, 0xFF, 0x70, 0x7E, + 0x7E, 0x78, 0x6A, 0xEC, 0xC1, 0xCC, 0x46, 0xC6, 0x83, 0x18, 0xA6, 0x92, 0xD9, 0x14, 0xED, 0x39, + 0x0F, 0xC1, 0xF9, 0xC8, 0x6D, 0x2B, 0x35, 0x6A, 0xE0, 0xB7, 0x64, 0xC0, 0xC4, 0xFD, 0xF0, 0xA7, + 0x86, 0xB4, 0xE2, 0x04, 0x2E, 0x74, 0x36, 0xF5, 0x45, 0x03, 0xBB, 0x0C, 0x08, 0xED, 0xFC, 0xDA, + 0x60, 0x4F, 0x65, 0x14, 0x31, 0xE6, 0x23, 0x32, 0x37, 0x46, 0x4D, 0xB6, 0x86, 0xD8, 0x7B, 0x59, + 0x0B, 0x3C, 0xF3, 0x38, 0x55, 0x81, 0xA4, 0xD1, 0x2A, 0xB2, 0x00, 0x98, 0x24, 0xAF, 0x9D, 0x7C, + 0xE9, 0x06, 0xEF, 0xE9, 0x78, 0x23, 0x8F, 0xA7, 0x3D, 0x25, 0x7A, 0x2D, 0x71, 0x71, 0x4A, 0x59, + 0xCB, 0x94, 0x3E, 0xA6, 0x7B, 0x0A, 0xDA, 0xFF, 0x4E, 0x64, 0x78, 0x73, 0x25, 0xED, 0x6C, 0xFC, + 0xF0, 0x82, 0x52, 0x5E, 0x90, 0xC1, 0xD3, 0x50, 0x35, 0xF7, 0xA1, 0xFD, 0x0C, 0x95, 0x9A, 0xD1, + 0xCB, 0xD0, 0x18, 0x32, 0xF9, 0x18, 0x23, 0x8E, 0x57, 0x1E, 0x71, 0xD2, 0xAD, 0xB9, 0xE8, 0xD9, + 0x09, 0x9A, 0xE3, 0x4E, 0x23, 0x33, 0x85, 0xA7, 0x91, 0x95, 0x25, 0xA3, 0xA1, 0x8F, 0xB0, 0x1D, + 0x9E, 0x9F, 0x9F, 0xA9, 0x93, 0xD8, 0x03, 0x0D, 0xAD, 0x22, 0x2B, 0xCC, 0xAC, 0x41, 0x24, 0x06, + 0x55, 0xEB, 0x95, 0x8C, 0xBA, 0xEA, 0xBA, 0xD2, 0x0B, 0xED, 0x88, 0xBA, 0xC8, 0x57, 0x29, 0xB6, + 0xF4, 0xA2, 0xAD, 0x26, 0xA3, 0x9F, 0x96, 0x25, 0xA7, 0xF2, 0xC3, 0x53, 0xA3, 0xC2, 0xF7, 0x18, + 0xF5, 0xBC, 0x95, 0x65, 0x4D, 0xB8, 0x86, 0x4C, 0x3A, 0xF9, 0xD0, 0xC9, 0xEC, 0xA6, 0xF6, 0x29, + 0xB5, 0xF4, 0xB8, 0x4A, 0xAC, 0x89, 0x77, 0xCE, 0x57, 0xEA, 0x12, 0x1B, 0xF3, 0x2C, 0xFB, 0xCD, + 0x40, 0x84, 0x47, 0x43, 0x61, 0xDE, 0xE1, 0x44, 0x05, 0xDD, 0xEC, 0x86, 0xCE, 0x35, 0x0F, 0x52, + 0x86, 0x97, 0x02, 0x99, 0x89, 0x10, 0x0B, 0x54, 0xFC, 0x96, 0xDC, 0xF7, 0x06, 0x47, 0x8C, 0x1C, + 0x1C, 0xB4, 0x87, 0xD1, 0x3F, 0xB6, 0x1B, 0x6F, 0x4B, 0x77, 0xDC, 0x23, 0x5C, 0x47, 0x68, 0x2B, + 0x30, 0x35, 0x5A, 0x0B, 0x69, 0x1E, 0xBA, 0x40, 0x4A, 0x5D, 0xEC, 0x47, 0x18, 0xE3, 0x8A, 0xD0, + 0x7C, 0x35, 0xA9, 0x5A, 0xD0, 0xDE, 0x3F, 0x3B, 0x3B, 0x3F, 0x38, 0x3A, 0xDD, 0xBB, 0x38, 0x04, + 0xEF, 0xB1, 0xF7, 0xE1, 0xE2, 0xF2, 0xE2, 0x63, 0x0F, 0x7F, 0xFD, 0x69, 0xEF, 0xF8, 0xE8, 0xE0, + 0xF2, 0xC3, 0xE9, 0xDF, 0x4E, 0xCF, 0x7E, 0x3E, 0x4D, 0x76, 0xFC, 0x87, 0x76, 0x70, 0x23, 0x3D, + 0xA7, 0x8F, 0xCD, 0x23, 0xDE, 0xC7, 0x37, 0x7C, 0x1F, 0xD2, 0x81, 0x33, 0xB1, 0xC7, 0x86, 0x12, + 0x6E, 0xAA, 0xCE, 0xAE, 0x8F, 0x29, 0x4B, 0x96, 0xAA, 0x1F, 0x7D, 0x82, 0xF1, 0x00, 0x67, 0x2D, + 0xC4, 0x9C, 0x7C, 0xB1, 0x5C, 0x78, 0xEA, 0x2B, 0x7C, 0xA8, 0x8D, 0xEA, 0x45, 0x6E, 0x6F, 0x6C, + 0x36, 0x5D, 0x8D, 0x98, 0xE0, 0x41, 0xC6, 0xB3, 0x20, 0xB6, 0xCA, 0x03, 0xDB, 0x25, 0x14, 0x05, + 0xC2, 0x4C, 0xA6, 0xE3, 0x42, 0xE7, 0x3B, 0x43, 0xF6, 0xE4, 0x3E, 0x10, 0x55, 0xF6, 0x08, 0xFF, + 0xC6, 0x6B, 0x61, 0x76, 0x61, 0x16, 0x24, 0x8F, 0x1F, 0x92, 0x06, 0xCB, 0x64, 0x65, 0x19, 0x2F, + 0xE3, 0x2E, 0xB3, 0x6E, 0x6A, 0xAB, 0x07, 0x81, 0x92, 0xF1, 0x8D, 0x05, 0xAF, 0x9B, 0x5E, 0xF5, + 0x8D, 0x71, 0x30, 0x74, 0x46, 0x4E, 0x98, 0x74, 0x13, 0x9E, 0x70, 0x67, 0xBD, 0x37, 0x45, 0x00, + 0x55, 0x6C, 0xEC, 0xA9, 0x81, 0x51, 0x5E, 0xCF, 0x9F, 0xE7, 0x25, 0x96, 0x91, 0xC9, 0x21, 0x96, + 0xE6, 0x4A, 0x73, 0x29, 0xE9, 0xC0, 0xE7, 0xCF, 0x59, 0xCA, 0xB2, 0xF1, 0x98, 0x8C, 0x3C, 0x6F, + 0x58, 0x02, 0x9A, 0x00, 0x74, 0xD2, 0xCF, 0x95, 0xC1, 0xDB, 0x48, 0x5C, 0x6A, 0x57, 0x1E, 0x82, + 0x68, 0xE3, 0xA6, 0x96, 0xB2, 0x8A, 0xC3, 0x72, 0xB6, 0xDE, 0x03, 0x35, 0xC2, 0x6B, 0x40, 0x81, + 0xA2, 0x02, 0x2C, 0xEA, 0x82, 0x7A, 0x32, 0x07, 0x8B, 0x03, 0x54, 0xA2, 0xA9, 0x17, 0x04, 0x0E, + 0x5E, 0x16, 0xE6, 0x5A, 0x81, 0xE3, 0x34, 0xD2, 0x97, 0x64, 0x48, 0x26, 0x1F, 0x4E, 0x4E, 0xDA, + 0x13, 0xFE, 0x2F, 0xF9, 0x46, 0x4C, 0x1F, 0x57, 0x4C, 0x1F, 0x4F, 0x4E, 0xFA, 0xFD, 0x76, 0xC0, + 0xFE, 0x29, 0xE0, 0xC4, 0xF0, 0x19, 0x10, 0xAC, 0x24, 0x9F, 0x9F, 0x19, 0xF5, 0x84, 0x3D, 0x71, + 0x9B, 0x5F, 0x72, 0xFF, 0x17, 0x6F, 0x50, 0xBB, 0x5E, 0x9B, 0xAC, 0xC3, 0x68, 0xDB, 0xB6, 0xD6, + 0xD6, 0xD6, 0x5F, 0xB0, 0xE0, 0x84, 0x4C, 0x7E, 0xED, 0xE4, 0xFA, 0x76, 0x32, 0xE2, 0x5F, 0x63, + 0x7E, 0xA2, 0xF9, 0x09, 0x9F, 0xE1, 0xF8, 0xB3, 0x58, 0xC0, 0x0C, 0x18, 0x69, 0x5D, 0x62, 0x8F, + 0x31, 0x64, 0xE3, 0x10, 0x19, 0x21, 0xD6, 0x06, 0xE9, 0x6E, 0xB4, 0xBB, 0xD6, 0xFA, 0xB6, 0x81, + 0x95, 0xC4, 0x26, 0xBD, 0x26, 0x6B, 0x0B, 0xE6, 0xA4, 0xCB, 0x98, 0x59, 0x4B, 0x98, 0x59, 0xE9, + 0x58, 0x1B, 0x2B, 0x9D, 0xCE, 0x8A, 0xB5, 0xD1, 0xEE, 0x6C, 0x76, 0x4D, 0xEC, 0x98, 0x2D, 0xDB, + 0x6B, 0x7C, 0x01, 0xB1, 0x20, 0xD6, 0x5E, 0x20, 0x4F, 0xD7, 0xF4, 0x96, 0xFA, 0x9C, 0x9F, 0x4E, + 0x07, 0xB9, 0xD9, 0xDA, 0xDA, 0xDE, 0xEE, 0x92, 0xD6, 0x01, 0xD7, 0x2C, 0xAC, 0xC2, 0x7F, 0x5B, + 0x8A, 0x79, 0x4C, 0xDC, 0x59, 0x97, 0x8E, 0xEC, 0x10, 0xEC, 0x66, 0xDF, 0x19, 0xB9, 0xAA, 0xF7, + 0xA0, 0x8E, 0x5D, 0x2B, 0x31, 0x1C, 0x89, 0x95, 0x8A, 0x8B, 0xB9, 0xDF, 0x85, 0xAF, 0x0E, 0xF6, + 0x24, 0xE3, 0xB6, 0x8C, 0xA2, 0xC3, 0x87, 0x01, 0xEC, 0x18, 0x0C, 0x9F, 0x26, 0x80, 0xF1, 0x62, + 0xA2, 0xE0, 0xE6, 0x23, 0x79, 0x88, 0xA4, 0x32, 0xA1, 0xDE, 0x7A, 0x8A, 0x3B, 0x75, 0x65, 0x05, + 0x11, 0x61, 0x94, 0xD1, 0xA4, 0x9F, 0xC1, 0x5A, 0xE3, 0x9C, 0xC9, 0x77, 0x2C, 0x58, 0x2A, 0xF6, + 0xE0, 0x86, 0x72, 0x0B, 0xCE, 0x83, 0x93, 0xB2, 0xB8, 0x1D, 0x82, 0x68, 0x44, 0x86, 0x04, 0x40, + 0x47, 0xDF, 0xCD, 0x93, 0xF5, 0x98, 0x1B, 0x5A, 0x5C, 0x53, 0x49, 0xB3, 0x5C, 0xFC, 0x2D, 0xA3, + 0x5F, 0x77, 0xD9, 0xD3, 0x16, 0xCC, 0x04, 0x9A, 0x59, 0xBE, 0xB9, 0x04, 0x0B, 0xB2, 0xD5, 0xD5, + 0xF4, 0x88, 0x97, 0xB3, 0xB5, 0xD7, 0x9F, 0xAB, 0x39, 0x5E, 0xE9, 0xCA, 0x02, 0x8F, 0x51, 0xC2, + 0x4E, 0xA4, 0xF8, 0x1B, 0x27, 0x76, 0x4E, 0x0B, 0xE2, 0x75, 0x07, 0xD1, 0xD3, 0xF1, 0xC4, 0x61, + 0x60, 0xDD, 0x04, 0xCE, 0x27, 0x11, 0x7A, 0xA3, 0x60, 0x11, 0xF6, 0x45, 0x45, 0x21, 0xA1, 0xE6, + 0x0F, 0xC7, 0x2D, 0x19, 0x47, 0x32, 0xF1, 0x25, 0xD5, 0x56, 0x76, 0x63, 0x53, 0xC5, 0x0F, 0xA4, + 0x95, 0xC7, 0xE6, 0x2C, 0xCE, 0x31, 0xCF, 0xA7, 0x90, 0x4F, 0x28, 0x26, 0x73, 0x72, 0x22, 0x5F, + 0x1A, 0x7C, 0xEB, 0xC0, 0x14, 0x0D, 0xD3, 0x8B, 0x32, 0xE5, 0x26, 0x13, 0x33, 0x7B, 0x79, 0x75, + 0x76, 0xDD, 0x62, 0x13, 0x10, 0xF4, 0xC6, 0x4A, 0x47, 0x3F, 0x38, 0x98, 0x57, 0xF4, 0x97, 0xA7, + 0x67, 0x97, 0x07, 0x87, 0xFB, 0x47, 0x27, 0x7B, 0xC7, 0x5A, 0x2F, 0x04, 0x14, 0x26, 0xA0, 0x21, + 0x36, 0x2B, 0xE6, 0x47, 0x13, 0xB7, 0xAC, 0x0E, 0x7C, 0x71, 0xC5, 0x21, 0x8C, 0x22, 0x4B, 0x06, + 0x94, 0x2C, 0x68, 0x19, 0x24, 0x92, 0xE3, 0x5F, 0x63, 0x79, 0x09, 0x00, 0x10, 0x99, 0x74, 0x47, + 0xCF, 0xE0, 0x5A, 0x45, 0xC4, 0x9E, 0x27, 0x48, 0x56, 0xC9, 0x26, 0x4C, 0x01, 0x2C, 0xE2, 0x40, + 0x44, 0x63, 0x95, 0xAC, 0x6D, 0x62, 0xA8, 0x9D, 0x25, 0xED, 0xC9, 0xBC, 0x32, 0x92, 0xCD, 0x7E, + 0x8D, 0x89, 0xEC, 0x5F, 0xB1, 0x3B, 0xE4, 0x74, 0xA6, 0xF7, 0xA6, 0xD5, 0x93, 0x36, 0x44, 0x71, + 0x34, 0xAA, 0x03, 0x94, 0x8D, 0xCF, 0xCC, 0xE1, 0xB7, 0x81, 0xA3, 0x33, 0xB3, 0x74, 0x3D, 0x1E, + 0x9B, 0xCA, 0x0C, 0xBD, 0xB8, 0xA1, 0x59, 0x72, 0x60, 0x26, 0x23, 0x52, 0xD1, 0x90, 0x8C, 0xE1, + 0xA8, 0x0F, 0x8D, 0xAA, 0x03, 0x30, 0x73, 0xF8, 0x99, 0xF5, 0x54, 0x11, 0x0D, 0xBB, 0x06, 0x2D, + 0x00, 0x0C, 0x88, 0xCD, 0x4A, 0x5A, 0x55, 0xE9, 0x1E, 0x58, 0xBF, 0x54, 0x05, 0x53, 0xB4, 0xA9, + 0xC3, 0xF5, 0x61, 0xE5, 0x81, 0x14, 0xE2, 0xF2, 0xE4, 0xE4, 0xF2, 0x60, 0xAF, 0xFF, 0x5E, 0x53, + 0x0B, 0x71, 0x19, 0x2B, 0x31, 0x5B, 0xE2, 0xA9, 0xDD, 0x8A, 0xFE, 0x14, 0x33, 0xD1, 0x01, 0x61, + 0xCA, 0x11, 0x12, 0x83, 0x3B, 0x25, 0x1D, 0x96, 0xD1, 0xB5, 0x72, 0xFD, 0xCE, 0x67, 0xC9, 0x98, + 0xA6, 0x7A, 0xF7, 0x89, 0x75, 0x56, 0x76, 0x5F, 0x75, 0xE3, 0xBE, 0x8A, 0xBC, 0xE3, 0x85, 0xF7, + 0x15, 0x98, 0xF7, 0x27, 0xD6, 0x5D, 0x4F, 0x66, 0xEE, 0x93, 0xC4, 0x53, 0x66, 0x0A, 0x94, 0x1B, + 0xD4, 0x4D, 0x1A, 0x94, 0x9E, 0x03, 0x7F, 0xEB, 0x13, 0x14, 0x57, 0xCA, 0x64, 0x03, 0x67, 0xA1, + 0x3A, 0xB9, 0x53, 0x20, 0xA6, 0xC4, 0x80, 0x7F, 0x37, 0x01, 0x08, 0x0B, 0x4A, 0x1E, 0xCE, 0x82, + 0x96, 0x1C, 0x8D, 0xE4, 0x87, 0xF1, 0xCC, 0xEB, 0xA7, 0x6E, 0xDC, 0x4F, 0xE4, 0x61, 0xD6, 0x25, + 0xDC, 0x40, 0x3C, 0xA1, 0xCE, 0x7A, 0x6A, 0xA6, 0xF3, 0x8F, 0x66, 0x35, 0xC5, 0x86, 0x96, 0x72, + 0x32, 0x64, 0x40, 0xC0, 0x0F, 0x87, 0x0C, 0x05, 0x71, 0xE8, 0xB1, 0xED, 0x25, 0x2D, 0xEE, 0x80, + 0xA1, 0x3B, 0xF8, 0x99, 0x4F, 0xB2, 0x31, 0x2F, 0xED, 0xB0, 0xE3, 0xA6, 0x6E, 0xF2, 0x3E, 0x7F, + 0x99, 0x78, 0xB3, 0x10, 0xFF, 0xB0, 0xC5, 0xAE, 0x3D, 0x00, 0xF5, 0x3D, 0x75, 0x0F, 0x1E, 0x37, + 0x94, 0xAF, 0x40, 0x5A, 0x13, 0x4A, 0x9A, 0xDA, 0x90, 0x69, 0x2E, 0x13, 0x1A, 0x0E, 0xE4, 0x1B, + 0xC7, 0x8C, 0x6F, 0xC6, 0x87, 0xC4, 0xD7, 0xB2, 0x49, 0x65, 0xCC, 0xFB, 0xF5, 0x62, 0xF3, 0x52, + 0x3A, 0x68, 0xE4, 0x0F, 0x33, 0x0C, 0x1A, 0x57, 0x5E, 0xE5, 0x96, 0x8C, 0xC3, 0x3A, 0xD1, 0xB0, + 0xE4, 0xDB, 0x92, 0x24, 0x66, 0xFD, 0xB4, 0x56, 0x66, 0xC3, 0x7C, 0xD6, 0x35, 0x27, 0x9B, 0x97, + 0xD2, 0x9A, 0x07, 0xD6, 0x6D, 0x73, 0x62, 0x5B, 0x28, 0xB2, 0xC8, 0x75, 0x5F, 0x30, 0xCA, 0xFE, + 0xC7, 0x93, 0x37, 0x67, 0xC7, 0x0C, 0xA9, 0xFE, 0xE2, 0x65, 0xEC, 0xB9, 0x23, 0x16, 0xE4, 0xE9, + 0x80, 0x8E, 0x7C, 0xAA, 0xEF, 0x8F, 0xA4, 0x7A, 0x42, 0xEB, 0x5A, 0x58, 0x9C, 0xE9, 0x08, 0x8C, + 0xF5, 0x60, 0xB8, 0x6E, 0x5A, 0x3B, 0x5A, 0xE0, 0xCC, 0xB8, 0xF4, 0x15, 0xC9, 0xB4, 0x7C, 0x7C, + 0xA0, 0x4B, 0xA6, 0x4B, 0xD1, 0xAB, 0x41, 0x7A, 0xD8, 0xBE, 0x58, 0x4A, 0x05, 0xE8, 0x9C, 0xB3, + 0x7B, 0xB3, 0x58, 0x8B, 0x87, 0x50, 0x4A, 0x84, 0xCF, 0x61, 0x54, 0x31, 0xEB, 0x12, 0x55, 0xDD, + 0x49, 0x1F, 0x5E, 0x2C, 0x48, 0x51, 0x6A, 0x31, 0xB7, 0xF2, 0x18, 0xDC, 0x71, 0x9D, 0xAB, 0xC5, + 0xDF, 0xFF, 0xFB, 0x1F, 0x95, 0x41, 0xFC, 0xD6, 0x6C, 0xA8, 0x6C, 0xD6, 0xC1, 0x4B, 0x4C, 0xED, + 0xD6, 0x6C, 0xCB, 0x42, 0x9A, 0xDE, 0x5F, 0x92, 0x07, 0xF0, 0xFC, 0x2A, 0xB8, 0x60, 0x84, 0xD2, + 0xAA, 0xEA, 0x21, 0xF0, 0xEA, 0x3D, 0xBF, 0x20, 0x11, 0x48, 0xAE, 0xCC, 0x43, 0x70, 0xFD, 0xB0, + 0xD8, 0xB5, 0x15, 0xEC, 0xD2, 0x6F, 0xDD, 0x0C, 0x2B, 0x3C, 0x9F, 0x98, 0xB6, 0xD6, 0xAB, 0xF0, + 0x2C, 0x10, 0xE4, 0xF1, 0x5C, 0x7A, 0x02, 0xD8, 0x5C, 0xF8, 0x04, 0x20, 0x8F, 0xBE, 0x8A, 0x53, + 0x40, 0x4A, 0x44, 0x8F, 0x34, 0x35, 0xA4, 0x46, 0x77, 0xD5, 0xD9, 0xC1, 0xC4, 0xF8, 0xCA, 0x23, + 0x71, 0x3E, 0xF7, 0xCC, 0x61, 0x62, 0xBE, 0x99, 0x9E, 0x52, 0xFE, 0xBD, 0xD1, 0x78, 0xA8, 0x36, + 0x2C, 0xD5, 0x9E, 0x9E, 0x4C, 0xBC, 0x93, 0x87, 0x16, 0x7C, 0xA6, 0x79, 0x5D, 0x90, 0xBA, 0x4B, + 0xAF, 0x38, 0x8D, 0x66, 0x61, 0xC1, 0x0A, 0x34, 0x67, 0x4B, 0xF2, 0xFB, 0xE1, 0x91, 0xDB, 0xA2, + 0x4F, 0x1C, 0x8B, 0x1F, 0xD1, 0x79, 0x0D, 0x4A, 0xBD, 0x72, 0x52, 0xE9, 0x69, 0x77, 0x1E, 0xA3, + 0x4B, 0x48, 0x03, 0xCC, 0x38, 0x29, 0x60, 0x56, 0xFF, 0x7D, 0xB8, 0xDA, 0x0E, 0xF1, 0xBD, 0xF6, + 0x60, 0x69, 0x87, 0xA8, 0xF1, 0x24, 0xA2, 0x73, 0x7D, 0x58, 0x12, 0x2F, 0xF3, 0xF0, 0x95, 0xB0, + 0x82, 0xBD, 0xF1, 0xE5, 0x4B, 0x92, 0x3C, 0xF6, 0xE6, 0x6B, 0x5C, 0x35, 0x47, 0xEF, 0xB2, 0x56, + 0xA4, 0x4B, 0x28, 0xF0, 0x59, 0x59, 0xA4, 0x63, 0x35, 0x25, 0x6A, 0xA4, 0x88, 0xCC, 0xF9, 0x1C, + 0xF1, 0xE2, 0x6D, 0x50, 0xA5, 0x9C, 0x23, 0x7F, 0xCE, 0x62, 0xEC, 0xCB, 0xEB, 0x78, 0x57, 0x59, + 0xB9, 0x0B, 0xD4, 0x36, 0x26, 0xFC, 0x74, 0x79, 0xA0, 0x3F, 0xB1, 0x86, 0x97, 0x9E, 0x52, 0x8B, + 0x92, 0xE4, 0xBE, 0x5C, 0xCE, 0x4A, 0x3C, 0xB8, 0x75, 0xC2, 0xC1, 0x0D, 0xC9, 0xAB, 0xC2, 0xAE, + 0x27, 0xD0, 0x6B, 0x7B, 0x36, 0x0E, 0x5F, 0x6A, 0xA9, 0x02, 0x78, 0x4F, 0x34, 0x3E, 0xB8, 0x5F, + 0x5C, 0xEF, 0xD6, 0xD5, 0xE3, 0xED, 0x6A, 0x69, 0x29, 0x06, 0xF8, 0xA6, 0xB9, 0x55, 0x7A, 0xFD, + 0x9E, 0x41, 0x4B, 0xDE, 0xA6, 0x58, 0x28, 0x41, 0x58, 0x5C, 0x65, 0x92, 0x4C, 0xF6, 0x3D, 0x17, + 0x4A, 0xF2, 0x32, 0x8F, 0x26, 0x79, 0x38, 0xA2, 0x7C, 0x3E, 0xCE, 0xA4, 0xBC, 0xF2, 0x40, 0x94, + 0x99, 0xF7, 0x92, 0x23, 0xE3, 0x78, 0x8B, 0x69, 0xE1, 0xED, 0xCD, 0xA3, 0xAB, 0x6C, 0x6E, 0x3D, + 0x00, 0xE5, 0x62, 0x61, 0xAF, 0x3C, 0x0C, 0x79, 0x7D, 0x22, 0xCD, 0x95, 0xFC, 0x43, 0x34, 0xBC, + 0x0C, 0x6D, 0x2E, 0xFD, 0x87, 0x12, 0x7B, 0x29, 0x16, 0x78, 0x0F, 0xE4, 0xB0, 0x70, 0xFF, 0x2C, + 0xCB, 0xDA, 0xDD, 0x3F, 0xFB, 0xFF, 0x93, 0xBE, 0xD8, 0x19, 0x92, 0xCE, 0x00 }; ///main_js //To convert AP-Config\index.html to index_html[], run the Python index_html_zipper.py script in the Tools folder: @@ -1074,1108 +1145,1113 @@ static const uint8_t main_js[] PROGMEM = { // python index_html_zipper.py static const uint8_t index_html[] PROGMEM = { - 0x1F, 0x8B, 0x08, 0x08, 0x11, 0xE6, 0x77, 0x68, 0x02, 0xFF, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x2E, - 0x68, 0x74, 0x6D, 0x6C, 0x2E, 0x67, 0x7A, 0x69, 0x70, 0x00, 0xED, 0x7D, 0xD9, 0x76, 0xDB, 0xC8, - 0x92, 0xE0, 0x7B, 0x7D, 0x45, 0x36, 0x7B, 0xA6, 0x2D, 0xF7, 0x88, 0x14, 0x17, 0x49, 0x96, 0x75, - 0x6D, 0x9D, 0x43, 0x2D, 0xB6, 0x35, 0x57, 0x96, 0xD9, 0xA2, 0x7C, 0x6B, 0x99, 0x33, 0x53, 0x07, - 0x02, 0x92, 0x24, 0xAE, 0x41, 0x00, 0x85, 0x45, 0xB2, 0xAA, 0x4F, 0xF7, 0xE9, 0xCF, 0x98, 0xF9, - 0x90, 0xF9, 0x81, 0xF9, 0x94, 0xFE, 0x92, 0x89, 0x88, 0x4C, 0x80, 0x00, 0x88, 0x95, 0x04, 0x29, - 0x52, 0x96, 0xEF, 0x2D, 0x49, 0x04, 0x91, 0x5B, 0x64, 0x44, 0x64, 0x44, 0x64, 0x2C, 0xEF, 0xFE, - 0xE1, 0xFC, 0xCB, 0xD9, 0xED, 0xAF, 0x83, 0x0B, 0x36, 0xF1, 0xA6, 0xC6, 0xC9, 0x4F, 0xEF, 0xF0, - 0x17, 0x33, 0x14, 0x73, 0xFC, 0xBE, 0xC1, 0xCD, 0xC6, 0xC9, 0x4F, 0xF0, 0x84, 0x2B, 0xDA, 0xC9, - 0x4F, 0x0C, 0xFE, 0xBD, 0x9B, 0x72, 0x4F, 0x61, 0xEA, 0x44, 0x71, 0x5C, 0xEE, 0xBD, 0x6F, 0xF8, - 0xDE, 0xA8, 0x79, 0xD4, 0x60, 0x7B, 0xD1, 0x2F, 0x27, 0x9E, 0x67, 0x37, 0xF9, 0x1F, 0xBE, 0x7E, - 0xFF, 0xBE, 0xF1, 0x4B, 0xF3, 0x6B, 0xBF, 0x79, 0x66, 0x4D, 0x6D, 0xC5, 0xD3, 0xEF, 0x0C, 0xDE, - 0x60, 0xAA, 0x65, 0x7A, 0xDC, 0x84, 0x96, 0x97, 0x17, 0xEF, 0xB9, 0x36, 0xE6, 0xBB, 0xEA, 0xC4, - 0xB1, 0xA6, 0xFC, 0x7D, 0x67, 0xD6, 0x89, 0xA7, 0x7B, 0x06, 0x3F, 0x19, 0xDA, 0x8A, 0xF3, 0xED, - 0x83, 0x6F, 0xB2, 0x9B, 0xDB, 0xBF, 0xB2, 0x21, 0xF7, 0x7C, 0xFB, 0xDD, 0x9E, 0xF8, 0x26, 0x32, - 0x94, 0xA9, 0x40, 0xD3, 0xC6, 0xBD, 0xCE, 0x1F, 0x6C, 0xCB, 0xF1, 0x1A, 0xF4, 0x0D, 0xFE, 0x0B, - 0x47, 0x79, 0xD0, 0x35, 0x6F, 0xF2, 0x5E, 0xE3, 0xF7, 0xBA, 0xCA, 0x9B, 0xF4, 0x61, 0x97, 0xE9, - 0xA6, 0xEE, 0xE9, 0x8A, 0xD1, 0x74, 0x55, 0xC5, 0x80, 0x81, 0x77, 0xD9, 0x54, 0xF9, 0xAE, 0x4F, - 0xFD, 0xE9, 0xEC, 0x81, 0xEF, 0x72, 0x87, 0x3E, 0x29, 0x30, 0xE7, 0xF7, 0xED, 0x5D, 0xE6, 0x4E, - 0x1C, 0xDD, 0xFC, 0xD6, 0xF4, 0xAC, 0xE6, 0x48, 0xF7, 0xDE, 0x3F, 0x72, 0x77, 0x36, 0x5B, 0x03, - 0xBE, 0x60, 0x0E, 0x37, 0xDE, 0x37, 0x5C, 0xEF, 0xD1, 0xE0, 0xEE, 0x84, 0x73, 0xAF, 0xC1, 0x26, - 0x0E, 0x1F, 0xC1, 0x13, 0x47, 0xDD, 0xBB, 0xB3, 0x2C, 0xCF, 0xF5, 0x1C, 0xC5, 0x6E, 0x4D, 0x75, - 0xB3, 0xA5, 0xBA, 0x6E, 0xA3, 0x64, 0x43, 0x7A, 0x1A, 0x6D, 0xE0, 0xAA, 0x8E, 0x6E, 0x7B, 0x0C, - 0xBE, 0x13, 0x2F, 0xFC, 0xFD, 0x0F, 0x9F, 0x3B, 0x8F, 0xCD, 0x5E, 0xEB, 0xB0, 0xD5, 0xA6, 0xCE, - 0xFF, 0x0E, 0xAF, 0xBE, 0xDB, 0x13, 0xAF, 0x65, 0xB4, 0x89, 0xCF, 0xA6, 0x52, 0x83, 0x3B, 0xDF, - 0xD4, 0x60, 0x42, 0xF3, 0xED, 0xA2, 0x0D, 0x4F, 0xC2, 0x2D, 0xF8, 0x2F, 0x3B, 0x9A, 0xA5, 0xFA, - 0x53, 0xD8, 0x85, 0xD7, 0x2D, 0xCB, 0xDC, 0x79, 0xA5, 0x1A, 0xBA, 0xFA, 0xED, 0xD5, 0x2E, 0x7B, - 0xD5, 0xF2, 0xAC, 0xF1, 0xD8, 0xE0, 0xCD, 0x3B, 0xCF, 0x84, 0x8F, 0x23, 0xDF, 0x54, 0x3D, 0xDD, - 0x32, 0xD9, 0x0E, 0x7F, 0xCD, 0xFE, 0x35, 0x6C, 0x2D, 0x7A, 0x80, 0xE5, 0xFB, 0x8E, 0x03, 0x5D, - 0xDC, 0x2A, 0xCE, 0x98, 0x7B, 0x2D, 0x75, 0xA2, 0x1B, 0x1A, 0x7C, 0xFE, 0x1F, 0xED, 0xFF, 0xF9, - 0x5A, 0x76, 0x73, 0x66, 0x28, 0xAE, 0xBB, 0xF3, 0x4A, 0x87, 0x1D, 0x6F, 0xAA, 0x8A, 0xC3, 0xBD, - 0xA6, 0x66, 0x3D, 0x98, 0x2C, 0xF2, 0xD9, 0xB7, 0x5F, 0xBD, 0xFE, 0x4B, 0xD8, 0xF1, 0xBF, 0xBD, - 0x16, 0xD3, 0x4D, 0xCE, 0x1E, 0x81, 0x3D, 0x9B, 0x7C, 0xCB, 0xF5, 0x00, 0x61, 0xD5, 0xE6, 0xD8, - 0xB1, 0x7C, 0x3B, 0x31, 0xAD, 0x09, 0xD7, 0xC7, 0x13, 0xEF, 0x98, 0xB5, 0xFF, 0x12, 0x7B, 0x6C, - 0xDD, 0x73, 0x67, 0x64, 0x58, 0x0F, 0xC7, 0x6C, 0xA2, 0x6B, 0x1A, 0x37, 0xE3, 0xDF, 0x02, 0x04, - 0x4D, 0x57, 0xC7, 0x85, 0x1E, 0xCB, 0x0E, 0x58, 0xBB, 0xB5, 0xEF, 0x32, 0xAE, 0xB8, 0x3C, 0xFE, - 0xE6, 0x9D, 0xE5, 0x68, 0x80, 0x7D, 0x77, 0x96, 0xE7, 0x59, 0xD3, 0x63, 0xE6, 0x5A, 0x86, 0xAE, - 0xB1, 0x8E, 0xFD, 0x9D, 0xFD, 0xA3, 0xDA, 0xC6, 0xFF, 0x45, 0x96, 0xF2, 0xD3, 0x6C, 0xBE, 0x86, - 0xEE, 0x7A, 0x9B, 0x3D, 0x5B, 0xFC, 0x67, 0x2B, 0x9A, 0xA6, 0x9B, 0xE3, 0xA6, 0x23, 0xE6, 0x74, - 0xD0, 0xB6, 0xBF, 0xA7, 0x2F, 0x47, 0x74, 0x0B, 0x44, 0xE1, 0x32, 0x4F, 0xDB, 0x4D, 0x7F, 0x3E, - 0x49, 0xAC, 0x54, 0x7C, 0x77, 0xCC, 0x4C, 0xCB, 0x4C, 0x4C, 0x72, 0x0A, 0xD8, 0xA3, 0x9B, 0x4D, - 0x83, 0x8F, 0x10, 0x10, 0x19, 0x63, 0xDE, 0xF9, 0xB0, 0x04, 0xF3, 0x78, 0x04, 0x48, 0xEB, 0x26, - 0x7A, 0xB6, 0x7C, 0x0F, 0x88, 0x95, 0xC7, 0x80, 0x18, 0x9D, 0xAD, 0x6E, 0xE2, 0xD7, 0x17, 0x8E, - 0x63, 0x39, 0x89, 0x96, 0x9A, 0xEE, 0xDA, 0x86, 0xF2, 0x78, 0xCC, 0xC4, 0x2B, 0xF1, 0x69, 0xA9, - 0x96, 0x61, 0xC1, 0x7C, 0x1D, 0xAE, 0xC5, 0x9F, 0x8F, 0x80, 0x79, 0x35, 0x5D, 0xFD, 0x4F, 0x18, - 0xD0, 0x9D, 0x2A, 0x86, 0xC1, 0x9D, 0xBC, 0x61, 0x87, 0xBE, 0xAA, 0x22, 0x3C, 0xAA, 0x0F, 0x3C, - 0x76, 0x78, 0x72, 0xE3, 0xF3, 0x86, 0x0E, 0xBF, 0x7F, 0x90, 0x28, 0x75, 0x67, 0x19, 0x5A, 0xD6, - 0xF6, 0x7D, 0x6F, 0x52, 0xFB, 0xC4, 0xAC, 0xB2, 0x37, 0x02, 0xFF, 0x11, 0x7B, 0x3E, 0x66, 0xBD, - 0xF6, 0x7F, 0xCD, 0xEE, 0x55, 0xF4, 0xD0, 0x6D, 0xE7, 0x75, 0xDC, 0xCD, 0x41, 0xAB, 0xA0, 0x87, - 0xFD, 0xDC, 0x1E, 0xF6, 0xB3, 0x7B, 0x50, 0x3C, 0x0F, 0x98, 0x6E, 0xA2, 0xB1, 0x6D, 0x05, 0xD4, - 0xA2, 0xDC, 0x01, 0x09, 0xF8, 0x5E, 0x02, 0xE0, 0x7F, 0x36, 0x75, 0x53, 0xE3, 0xDF, 0x8F, 0x59, - 0xA7, 0xDD, 0x4E, 0x90, 0x84, 0x24, 0x85, 0xCE, 0x1C, 0x34, 0xE0, 0x50, 0x6A, 0x4A, 0x88, 0x1C, - 0xB6, 0x53, 0xBE, 0xA5, 0xE9, 0x7A, 0x96, 0x0D, 0x64, 0x14, 0x9F, 0xAC, 0x64, 0x6F, 0x82, 0xA1, - 0xBD, 0xDB, 0x13, 0x47, 0xF7, 0x4F, 0xEF, 0xEE, 0x2C, 0xED, 0x51, 0xF2, 0x78, 0x4D, 0xBF, 0x67, - 0x2A, 0xF2, 0xCD, 0xF7, 0x0D, 0x3C, 0x28, 0x15, 0x40, 0x10, 0xA7, 0xC1, 0x74, 0xED, 0x7D, 0x43, - 0x2E, 0xEF, 0x12, 0x1E, 0x37, 0x66, 0xDC, 0x90, 0x1A, 0x28, 0x86, 0x3E, 0x36, 0xDF, 0x37, 0x68, - 0xBE, 0x8D, 0xA0, 0xB9, 0x7C, 0x3F, 0xF2, 0x2E, 0xBD, 0xAF, 0x4F, 0xC7, 0xC9, 0xEE, 0x3E, 0xE8, - 0x06, 0xBF, 0x86, 0xD3, 0xBA, 0x31, 0x3B, 0x5A, 0x4E, 0xC5, 0xB7, 0xA7, 0x20, 0x69, 0x7C, 0x6B, - 0xD9, 0xE6, 0xB8, 0x01, 0x63, 0xC0, 0x91, 0x2D, 0x1F, 0x33, 0x83, 0xDF, 0x73, 0xA3, 0x71, 0x02, - 0xBC, 0xD9, 0x56, 0xCC, 0x68, 0x77, 0x03, 0xEE, 0xA8, 0x70, 0x26, 0x34, 0x62, 0x63, 0x12, 0x5E, - 0x8B, 0x49, 0x11, 0xE6, 0xC1, 0x38, 0x08, 0x81, 0xF7, 0x8D, 0x80, 0x12, 0x24, 0x21, 0xD0, 0xC1, - 0x05, 0x1D, 0x46, 0x56, 0xB7, 0x07, 0xCB, 0x93, 0x90, 0x11, 0x7F, 0xE6, 0x41, 0x29, 0xD1, 0x2B, - 0x31, 0x9B, 0xE8, 0x6E, 0x10, 0xF2, 0xCD, 0xF6, 0x4E, 0x6C, 0x9D, 0x00, 0xAE, 0xC3, 0x41, 0x64, - 0xBA, 0x34, 0x07, 0x8E, 0x85, 0x04, 0x1B, 0x85, 0xEF, 0xDD, 0xC9, 0x0D, 0x7E, 0xE7, 0x01, 0x6F, - 0x7C, 0xB7, 0x77, 0x77, 0xF2, 0xEE, 0xCE, 0xA1, 0xFF, 0x50, 0xF2, 0x11, 0xA2, 0x0B, 0xD3, 0x5D, - 0xE0, 0x13, 0x78, 0x16, 0xC3, 0x2B, 0x2D, 0x36, 0x30, 0x90, 0x13, 0xB3, 0x07, 0x45, 0xF7, 0x5A, - 0xAD, 0xD6, 0xBA, 0xA6, 0x8E, 0x62, 0x9C, 0xC1, 0x3D, 0x9E, 0x32, 0x73, 0x76, 0x0E, 0x9D, 0x65, - 0x4C, 0x7D, 0xA2, 0xB8, 0xC0, 0x93, 0x1F, 0x18, 0xF5, 0xB1, 0x8E, 0xC9, 0x8E, 0x74, 0x67, 0xFA, - 0x00, 0x47, 0xFF, 0x57, 0xDB, 0xB0, 0x14, 0x2D, 0x7D, 0xD6, 0xC9, 0xF9, 0x7E, 0x90, 0x6D, 0x98, - 0x6F, 0x6B, 0x8A, 0xC7, 0x81, 0x45, 0x8A, 0x56, 0x2D, 0x16, 0xDF, 0x04, 0xB1, 0x90, 0x60, 0x23, - 0x4A, 0x2E, 0xE6, 0xE4, 0xA7, 0x54, 0x52, 0x42, 0x24, 0xC6, 0xA5, 0x86, 0xEF, 0x83, 0x48, 0x3A, - 0x6D, 0x76, 0xBA, 0x80, 0xA2, 0x48, 0x40, 0x21, 0x9D, 0x38, 0xDE, 0xB7, 0xA6, 0x8B, 0x02, 0x70, - 0x84, 0x48, 0x62, 0xD2, 0xF1, 0xCF, 0xFA, 0x07, 0x5D, 0x88, 0xC8, 0x88, 0xDD, 0x91, 0xD9, 0x94, - 0x06, 0x73, 0x04, 0xB0, 0x9D, 0x6C, 0xC0, 0x4E, 0xA1, 0xD1, 0x40, 0x19, 0xF3, 0x92, 0x0B, 0x72, - 0xAC, 0x87, 0xB9, 0x7D, 0xBC, 0x33, 0x2C, 0xF5, 0xDB, 0x5F, 0xA2, 0x1D, 0x14, 0x74, 0x22, 0x8E, - 0x11, 0x64, 0xCB, 0x09, 0x26, 0x83, 0xFF, 0x70, 0xF1, 0x17, 0x20, 0xC9, 0x3C, 0x3E, 0x4C, 0x38, - 0xEC, 0x5D, 0xB0, 0x89, 0xC7, 0x11, 0x9E, 0x01, 0xC0, 0x0B, 0x1E, 0xFF, 0x8D, 0x3B, 0x2E, 0x30, - 0xE9, 0x6C, 0xCE, 0x70, 0xDF, 0x6E, 0xB5, 0x25, 0x77, 0x40, 0x9C, 0x98, 0x1B, 0x6E, 0xD6, 0xEB, - 0xD8, 0x74, 0xDD, 0xD2, 0xDD, 0x7E, 0xBC, 0x1E, 0x0E, 0x23, 0x73, 0x8B, 0x8C, 0xC2, 0x0A, 0x86, - 0x11, 0x78, 0x77, 0x7A, 0x7B, 0x79, 0x9E, 0xDD, 0xFB, 0xB9, 0xC0, 0xCD, 0x53, 0xC3, 0xE7, 0x1E, - 0xA0, 0xE5, 0x84, 0x5D, 0x9E, 0xC3, 0xD9, 0x0A, 0xFF, 0x4A, 0x8E, 0xA1, 0x5A, 0x20, 0x37, 0xE9, - 0x26, 0x20, 0xBD, 0x7B, 0x75, 0xF5, 0x29, 0x7B, 0x9C, 0xAB, 0xAB, 0xC9, 0xF1, 0x5C, 0x37, 0x09, - 0xA8, 0x70, 0x4B, 0xE3, 0x20, 0x36, 0x5F, 0x29, 0x5E, 0x76, 0x3F, 0xFB, 0xB0, 0xFC, 0xB7, 0xED, - 0xEE, 0xDB, 0xFD, 0x37, 0x6F, 0xE5, 0x0C, 0x77, 0xCB, 0x76, 0x9B, 0x07, 0xE4, 0x66, 0xA7, 0x7D, - 0xD0, 0xEA, 0x1C, 0x1D, 0xB4, 0x0F, 0xDE, 0x1C, 0x76, 0x2A, 0x76, 0xDC, 0x37, 0x72, 0xE6, 0xDB, - 0x39, 0x38, 0x84, 0x19, 0x1F, 0x05, 0x93, 0x65, 0x3B, 0xFD, 0xC1, 0xD9, 0xEB, 0x79, 0x78, 0x96, - 0x42, 0x9B, 0x08, 0xAC, 0x2F, 0xCE, 0x2E, 0x3E, 0x64, 0x0F, 0x8A, 0xDF, 0x16, 0x41, 0x9B, 0xAB, - 0x7C, 0xF4, 0x4B, 0x1E, 0x40, 0xBA, 0x47, 0xED, 0x6E, 0xFB, 0xB0, 0x75, 0x70, 0x78, 0x54, 0x12, - 0x1E, 0xD8, 0xE3, 0xAF, 0x39, 0x3D, 0xEE, 0xBF, 0xE9, 0x1C, 0x1E, 0xB5, 0xF7, 0x5B, 0xFB, 0xED, - 0x5E, 0x85, 0x1E, 0x7F, 0xCB, 0xC3, 0x85, 0xA3, 0xC3, 0xC3, 0xC3, 0x83, 0xD6, 0xFE, 0xD1, 0x7E, - 0xF2, 0x54, 0x2E, 0x02, 0x6C, 0x94, 0xB7, 0xA5, 0x7E, 0x9E, 0x38, 0x01, 0x0B, 0x99, 0x7A, 0xCD, - 0x76, 0x52, 0x9A, 0x99, 0xE7, 0x7B, 0x74, 0xA0, 0xCC, 0x31, 0xA6, 0x7F, 0x68, 0x36, 0x59, 0x33, - 0xF8, 0xC7, 0xE0, 0xE8, 0x1E, 0x81, 0x1C, 0xC3, 0xCE, 0x2C, 0x73, 0xA4, 0x8F, 0x23, 0x5F, 0x34, - 0x9B, 0x27, 0xF3, 0x0C, 0x4D, 0x0E, 0xAF, 0x81, 0x5E, 0x06, 0x4A, 0xD1, 0x58, 0xB1, 0x9B, 0xDD, - 0x14, 0x1E, 0xF6, 0x4E, 0x28, 0x1E, 0xA1, 0x44, 0xE5, 0x99, 0x0C, 0xFE, 0x6B, 0xDA, 0x8E, 0x0E, - 0x93, 0x7B, 0x64, 0x33, 0x65, 0x59, 0xF0, 0x60, 0x5B, 0x4C, 0x41, 0xCC, 0xA0, 0xC1, 0xBC, 0x47, - 0x1B, 0x96, 0x21, 0xBA, 0x68, 0x30, 0x38, 0xBA, 0x94, 0xA6, 0x68, 0x41, 0xE7, 0x89, 0xA1, 0xD8, - 0x2E, 0x6F, 0xA4, 0xEE, 0x91, 0x78, 0x95, 0xD4, 0xEA, 0xF7, 0x8D, 0x7F, 0x0C, 0xDE, 0x1D, 0xC4, - 0x7B, 0x57, 0x1C, 0x5D, 0x69, 0xF2, 0xEF, 0xB0, 0x01, 0x1A, 0xC7, 0x83, 0x55, 0x31, 0xA0, 0x3B, - 0xF1, 0x14, 0xCF, 0x10, 0xC7, 0x32, 0xDC, 0xD9, 0x38, 0xF1, 0xB6, 0x27, 0xA9, 0xA3, 0xC6, 0x01, - 0xE8, 0x3B, 0x0A, 0xA9, 0xFE, 0xEF, 0xF4, 0xD8, 0xD2, 0x50, 0x6B, 0x9F, 0x9D, 0x8A, 0xA4, 0xC3, - 0xA3, 0x3A, 0xCF, 0xEE, 0x74, 0x96, 0x50, 0xF3, 0xF1, 0xB8, 0xD3, 0xD3, 0x70, 0x46, 0x00, 0x24, - 0x15, 0x63, 0xB2, 0xB6, 0x29, 0x58, 0x06, 0x9B, 0xDE, 0xC1, 0x3E, 0x49, 0x72, 0x2D, 0xB7, 0x32, - 0xC2, 0x92, 0xD4, 0xBE, 0xDC, 0x09, 0xC8, 0x0B, 0x85, 0x1D, 0xCE, 0xA1, 0xCF, 0xDC, 0xDC, 0x14, - 0x47, 0x63, 0xF8, 0xA3, 0x89, 0x52, 0x7C, 0x12, 0x49, 0xD3, 0x5A, 0x8C, 0x2C, 0x67, 0x2A, 0xED, - 0x01, 0x80, 0xFE, 0xDD, 0x8C, 0xED, 0x88, 0x6C, 0xC9, 0x71, 0xE6, 0x0B, 0x82, 0x9A, 0x65, 0xBF, - 0x9E, 0x27, 0xB1, 0xEC, 0xCE, 0x6D, 0x02, 0x2D, 0xAB, 0x7C, 0x4A, 0x66, 0x36, 0xA1, 0x15, 0x64, - 0x76, 0x41, 0x36, 0x05, 0xB4, 0xDD, 0x81, 0xE0, 0xC2, 0x0D, 0xAE, 0x7A, 0x4C, 0x61, 0x72, 0xB7, - 0x19, 0xE0, 0x16, 0xE8, 0xF2, 0xDC, 0x64, 0xD0, 0x3F, 0x08, 0x00, 0x4C, 0xCA, 0xC1, 0xA0, 0xE0, - 0x5B, 0xF0, 0x5C, 0xF1, 0x82, 0x17, 0x5B, 0xAC, 0xEF, 0x09, 0x19, 0x72, 0x37, 0x2A, 0x93, 0x3D, - 0xE8, 0x20, 0x1E, 0xF8, 0x08, 0x6A, 0xEA, 0x98, 0x6B, 0xB3, 0xF7, 0x03, 0x64, 0x53, 0x27, 0x8A, - 0x39, 0xE6, 0x2E, 0x43, 0xF1, 0xCE, 0x55, 0xEE, 0xE1, 0x95, 0x07, 0x1A, 0x0F, 0x94, 0xE4, 0xD1, - 0x88, 0xA3, 0x79, 0x29, 0x9C, 0x0C, 0x48, 0x78, 0x61, 0x3F, 0xA0, 0xCC, 0xD3, 0x7B, 0xAF, 0x86, - 0xD0, 0x26, 0x8E, 0xB1, 0xAF, 0xF0, 0x45, 0x1B, 0x26, 0xE3, 0x72, 0xAD, 0x95, 0x03, 0xDB, 0x39, - 0xF0, 0x11, 0xFE, 0xEA, 0xE6, 0xC8, 0x6A, 0xAA, 0xBA, 0xA3, 0xC2, 0x80, 0x1E, 0xFF, 0xEE, 0x85, - 0xB4, 0x3E, 0x75, 0x71, 0xA7, 0xB2, 0x38, 0x61, 0x82, 0x23, 0xA6, 0xA3, 0x40, 0x82, 0x0B, 0x96, - 0x40, 0x0F, 0x94, 0xD2, 0x4E, 0x0A, 0x36, 0x3F, 0x9D, 0x7F, 0xC7, 0x74, 0xE6, 0x80, 0x7D, 0xE6, - 0x82, 0x42, 0x37, 0x6D, 0xDF, 0x93, 0x3C, 0xCB, 0x51, 0x34, 0xDD, 0x6A, 0x48, 0x0B, 0xAE, 0x84, - 0xFF, 0x8D, 0x78, 0x76, 0xAF, 0x80, 0x30, 0xF3, 0xBE, 0xD1, 0x2E, 0xEA, 0xCE, 0x50, 0xEE, 0xB8, - 0x11, 0x65, 0x1D, 0x6D, 0xD2, 0x30, 0x4F, 0xE4, 0xC6, 0x83, 0x18, 0x40, 0x6F, 0x2C, 0x05, 0xCA, - 0x67, 0x01, 0xC9, 0x4E, 0x65, 0x48, 0x76, 0x04, 0x24, 0x3B, 0xDD, 0xDE, 0xFE, 0xC1, 0xE1, 0x9B, - 0xA3, 0xB7, 0xED, 0xD9, 0x5F, 0x2F, 0x50, 0x95, 0x50, 0xED, 0x56, 0x86, 0x6A, 0x57, 0x40, 0xF5, - 0x05, 0x82, 0x12, 0x82, 0xBD, 0xCA, 0x10, 0xEC, 0xBD, 0x40, 0x30, 0x06, 0xC1, 0xFD, 0xCA, 0x10, - 0xDC, 0x7F, 0x81, 0x60, 0x0C, 0x82, 0x07, 0x95, 0x21, 0x78, 0xF0, 0x02, 0xC1, 0x18, 0x04, 0x0F, - 0x2B, 0x43, 0xF0, 0xF0, 0x05, 0x82, 0x31, 0x08, 0xBE, 0xA9, 0x0C, 0xC1, 0x37, 0xF5, 0x41, 0xB0, - 0x46, 0x10, 0x8A, 0x69, 0xC2, 0xFB, 0xE1, 0x3C, 0x85, 0xC9, 0x3F, 0xD0, 0x6D, 0xA3, 0x17, 0x38, - 0xD2, 0xDC, 0xD9, 0xA3, 0x3F, 0xF6, 0xE9, 0x27, 0x0D, 0x44, 0x7D, 0x84, 0x32, 0x5C, 0x2E, 0x58, - 0xB0, 0xF3, 0xE3, 0x62, 0x10, 0xC4, 0x15, 0x33, 0x1C, 0xF4, 0x88, 0x86, 0x7B, 0x53, 0x65, 0x13, - 0x51, 0x50, 0x6F, 0xC4, 0x20, 0x22, 0x35, 0xE0, 0x98, 0x5A, 0x2E, 0x76, 0x25, 0xBF, 0x57, 0x3B, - 0xD9, 0x80, 0x2E, 0x0E, 0xC3, 0xBE, 0x23, 0x97, 0x89, 0xB8, 0xBF, 0x76, 0xDE, 0xDE, 0x66, 0x52, - 0xC0, 0xFC, 0x40, 0x67, 0xA4, 0x04, 0x7D, 0x06, 0x95, 0x05, 0x0D, 0xB8, 0xF1, 0xC1, 0xE4, 0x15, - 0x62, 0xCE, 0x70, 0xF5, 0xA3, 0xCA, 0xBC, 0x11, 0x46, 0xDE, 0x21, 0x1F, 0x94, 0xA0, 0x2E, 0x69, - 0x32, 0x89, 0x1B, 0x3F, 0xE8, 0x86, 0xC8, 0x33, 0xE9, 0x3E, 0x42, 0x62, 0x4F, 0x23, 0xCB, 0xAA, - 0x92, 0x8A, 0x89, 0xF9, 0xFA, 0x2B, 0x5D, 0x04, 0x9B, 0x67, 0xE8, 0xC5, 0x30, 0x37, 0xCE, 0xCE, - 0xEB, 0x86, 0xBC, 0x07, 0x91, 0x0F, 0xD2, 0x2D, 0x10, 0x2B, 0xD2, 0xAC, 0x23, 0xDA, 0xB5, 0x98, - 0x44, 0x52, 0x15, 0x46, 0x55, 0x7A, 0xA4, 0xA8, 0x9E, 0x05, 0x2B, 0xD7, 0xF8, 0x48, 0xF1, 0x0D, - 0xCF, 0x2D, 0x52, 0x5B, 0x57, 0xA2, 0xBA, 0x16, 0x71, 0xA4, 0xF2, 0x58, 0xED, 0x44, 0xA0, 0xFF, - 0xD9, 0x1D, 0xD7, 0x86, 0xD0, 0x69, 0x46, 0xA2, 0x94, 0x57, 0x13, 0x76, 0x41, 0xB2, 0xF0, 0xAF, - 0xD1, 0x28, 0x38, 0xF5, 0x80, 0x6F, 0x46, 0x2D, 0x83, 0x35, 0x9B, 0x01, 0x71, 0x3D, 0x0B, 0xD9, - 0x00, 0x23, 0x0D, 0xD3, 0xE1, 0x1E, 0x81, 0x54, 0xC2, 0xFA, 0x87, 0x57, 0x2A, 0x4F, 0x6C, 0xFA, - 0x8B, 0x1B, 0xE9, 0x72, 0xD7, 0x92, 0x6D, 0x9D, 0x63, 0xB6, 0xD7, 0xEC, 0xE4, 0x9A, 0xE8, 0xE8, - 0x2A, 0x8D, 0x2B, 0xAE, 0xEF, 0x10, 0x8D, 0xDF, 0x28, 0x1E, 0xBF, 0xC4, 0x93, 0x26, 0x87, 0x22, - 0x3F, 0xCF, 0x5E, 0x67, 0xF8, 0xFE, 0x71, 0xA9, 0xD3, 0x2E, 0x9F, 0x05, 0x67, 0x9C, 0x8D, 0x5D, - 0xE2, 0x87, 0x9D, 0x2E, 0x92, 0x74, 0x8F, 0xCD, 0x18, 0x7A, 0x19, 0x7E, 0x11, 0x39, 0xFF, 0x13, - 0x0B, 0xFC, 0xF4, 0x67, 0xEC, 0x9E, 0x33, 0x7A, 0xD2, 0x5F, 0x9A, 0x85, 0x1D, 0xE3, 0xBF, 0x4F, - 0x7F, 0x1E, 0x97, 0x7A, 0xAF, 0x46, 0xA6, 0x9A, 0x60, 0xAE, 0xB7, 0x13, 0xCE, 0x4C, 0x7F, 0x7A, - 0xC7, 0x1D, 0x66, 0x8D, 0x18, 0xF9, 0x79, 0x00, 0xFE, 0xBA, 0x68, 0x28, 0x34, 0x2C, 0x55, 0x20, - 0xF3, 0x7F, 0xFE, 0xC7, 0xFF, 0x1E, 0xE9, 0xDF, 0xB9, 0xFB, 0x9F, 0xFF, 0xF1, 0x7F, 0x98, 0x0D, - 0x2F, 0xBA, 0x1C, 0xD0, 0x56, 0x6B, 0xB1, 0xBE, 0xF9, 0xE8, 0x4D, 0x74, 0x73, 0xCC, 0x94, 0x3B, - 0xEB, 0x9E, 0xB3, 0xFD, 0x4F, 0x7F, 0x82, 0x4C, 0xF9, 0x08, 0x58, 0x83, 0xA6, 0xCB, 0xD9, 0xDD, - 0x1D, 0xBC, 0x3C, 0xE6, 0x2E, 0xF5, 0x04, 0xF4, 0xB6, 0x47, 0x3D, 0x8F, 0xC7, 0xD8, 0x0E, 0x24, - 0x52, 0xD5, 0xE1, 0xB0, 0x34, 0x55, 0xE7, 0x6E, 0x8B, 0x5D, 0x5B, 0x80, 0x04, 0x0C, 0x67, 0x14, - 0x01, 0x34, 0x73, 0xF0, 0xEA, 0x5A, 0x77, 0xC9, 0xBB, 0xCB, 0x21, 0xBF, 0x2E, 0x64, 0xFD, 0x1D, - 0x18, 0x8C, 0x2C, 0x99, 0xBA, 0xC9, 0x4E, 0xD1, 0x6F, 0x60, 0x6A, 0x69, 0xBC, 0xC5, 0xCE, 0xC5, - 0x49, 0x70, 0x8C, 0x93, 0x69, 0xB1, 0x2B, 0x7D, 0xAA, 0x7B, 0xEE, 0x31, 0x6B, 0xB7, 0xDA, 0xED, - 0x76, 0xA7, 0xDB, 0xA5, 0x86, 0x6D, 0xF8, 0xA6, 0xC4, 0xBE, 0xAF, 0xF4, 0xBC, 0x28, 0x7B, 0x6E, - 0xCC, 0xDE, 0x2B, 0x90, 0x07, 0x4B, 0x1C, 0x32, 0x19, 0xA4, 0x21, 0xA4, 0xD4, 0x83, 0x45, 0x28, - 0x23, 0x2A, 0x4A, 0x0A, 0x1C, 0x4A, 0x15, 0x26, 0x23, 0x77, 0x05, 0xF3, 0x04, 0x54, 0x62, 0x18, - 0x3B, 0xBD, 0xE9, 0xA2, 0x12, 0x66, 0x91, 0xE8, 0x17, 0x19, 0x37, 0x76, 0x5D, 0x4F, 0x00, 0xC2, - 0x6B, 0x37, 0x5C, 0x4F, 0x1B, 0x06, 0xE1, 0xD3, 0x13, 0xCB, 0x79, 0xB7, 0x07, 0xBF, 0x68, 0xBC, - 0xCD, 0xE0, 0x49, 0x43, 0xAE, 0x36, 0x4E, 0x86, 0x44, 0xA0, 0x2E, 0xBB, 0xE3, 0xDE, 0x03, 0x07, - 0x1A, 0x89, 0xBC, 0xE3, 0x6E, 0x18, 0xC3, 0xC9, 0x99, 0x69, 0x0B, 0x58, 0x01, 0xD0, 0xBD, 0xC0, - 0x32, 0x1D, 0x9D, 0x23, 0x81, 0x0F, 0x98, 0xC0, 0x05, 0x80, 0xDA, 0xA1, 0xA9, 0x97, 0xC6, 0x27, - 0xF0, 0xE2, 0x05, 0x5E, 0x05, 0x06, 0x34, 0xF2, 0x0D, 0xC1, 0x20, 0x3C, 0xE5, 0x1B, 0xF1, 0xA8, - 0xD8, 0xCB, 0x1C, 0x1D, 0x2C, 0xD8, 0x88, 0x3F, 0x84, 0x33, 0x50, 0x54, 0xC7, 0x72, 0xE1, 0x17, - 0x30, 0x27, 0x78, 0x1B, 0x5E, 0xBC, 0xE7, 0x8F, 0x6C, 0xA7, 0xBB, 0xFF, 0xDF, 0xD8, 0xC4, 0xF2, - 0x1D, 0xF7, 0x75, 0x1D, 0xEC, 0x69, 0xC6, 0x8F, 0x3A, 0xF8, 0xD2, 0x51, 0xE7, 0xED, 0x61, 0x30, - 0x3E, 0xB0, 0x24, 0x82, 0x79, 0x69, 0x70, 0x46, 0x7C, 0xC3, 0x5E, 0xB8, 0x52, 0xAD, 0x5C, 0x89, - 0x48, 0x68, 0x41, 0xB6, 0x04, 0x6D, 0x6B, 0xE0, 0x4B, 0x0B, 0x7C, 0xBD, 0xA0, 0x32, 0x2B, 0x3C, - 0x72, 0x1E, 0x4D, 0x65, 0xAA, 0xAB, 0x9F, 0x01, 0x45, 0x8D, 0x73, 0xC7, 0xB2, 0x85, 0x28, 0x5A, - 0xCA, 0x22, 0x12, 0x6D, 0xDA, 0x48, 0xDD, 0xC3, 0xC3, 0x39, 0x2B, 0xC8, 0xB9, 0x68, 0xC3, 0xA8, - 0xD1, 0xF1, 0x9A, 0x95, 0xC9, 0xBE, 0xF6, 0x77, 0xDF, 0xF5, 0x02, 0x66, 0xE2, 0x71, 0xC7, 0x54, - 0x0C, 0xA6, 0x18, 0x63, 0xCB, 0xD1, 0xBD, 0xC9, 0x14, 0xA9, 0x72, 0xAA, 0x78, 0xEA, 0x84, 0xBE, - 0x07, 0x05, 0x41, 0xA8, 0x9C, 0x8A, 0x6D, 0x83, 0x8A, 0x2C, 0x84, 0x21, 0x6E, 0xDE, 0xEB, 0x8E, - 0x65, 0xE2, 0xD8, 0x92, 0x41, 0xC9, 0xCB, 0x5D, 0xA6, 0x4F, 0x41, 0x35, 0xBD, 0xE7, 0xA2, 0x6F, - 0x87, 0xAB, 0x5C, 0x07, 0x96, 0xF0, 0xCA, 0x15, 0xC3, 0xD8, 0x20, 0xE3, 0x8B, 0x0E, 0x80, 0x75, - 0x45, 0xB9, 0x9C, 0xBC, 0x2B, 0xF6, 0xF1, 0xEE, 0xD5, 0xBA, 0xD7, 0x35, 0xBC, 0xD3, 0x05, 0x6E, - 0xE1, 0x00, 0x2F, 0x53, 0x55, 0x9F, 0xB8, 0x4B, 0xE0, 0x89, 0x8B, 0x3E, 0xDB, 0x80, 0xDB, 0x2D, - 0x74, 0x8B, 0xA3, 0x11, 0xA3, 0x03, 0xE1, 0xD4, 0x01, 0x56, 0xBE, 0xE9, 0xFA, 0xBA, 0x87, 0x21, - 0x1E, 0x0C, 0x60, 0xE4, 0x21, 0xDC, 0x89, 0xF7, 0xD0, 0x7E, 0x51, 0x83, 0x31, 0xBC, 0x6D, 0x66, - 0x2D, 0x09, 0x39, 0x99, 0xA1, 0x7F, 0xE3, 0x06, 0x3A, 0x69, 0xE0, 0xCD, 0x34, 0x08, 0x53, 0xC8, - 0xC3, 0x90, 0x2D, 0x02, 0x77, 0x84, 0xB9, 0x87, 0xE3, 0x81, 0x24, 0x88, 0xBD, 0x83, 0xF0, 0x26, - 0xD8, 0x6E, 0x38, 0x4B, 0x31, 0x6F, 0xF5, 0x71, 0x73, 0x95, 0xF1, 0xEA, 0xC6, 0x35, 0x89, 0xCB, - 0x85, 0xD7, 0xE2, 0xC2, 0x11, 0x40, 0x58, 0x45, 0xE3, 0xB4, 0x91, 0x24, 0xB4, 0x38, 0x53, 0xD2, - 0x24, 0xD9, 0x09, 0xAE, 0x54, 0xB8, 0x3E, 0x1A, 0x66, 0xED, 0x7C, 0x62, 0xAA, 0x9B, 0x17, 0x06, - 0xBF, 0xCF, 0xD5, 0x85, 0x17, 0x36, 0x9E, 0xCD, 0xC9, 0x35, 0x62, 0xB0, 0xB2, 0x4C, 0xE5, 0x33, - 0x20, 0xE9, 0xF0, 0x6F, 0x0C, 0x9B, 0x10, 0x52, 0x1F, 0xFF, 0xB4, 0x66, 0x11, 0x47, 0xF2, 0x17, - 0x98, 0x07, 0x86, 0x5D, 0x31, 0x1E, 0x4C, 0x04, 0xA9, 0x47, 0xE3, 0x18, 0x96, 0xE0, 0x12, 0x09, - 0x2A, 0xC2, 0x5C, 0xE0, 0x02, 0x61, 0x1B, 0x86, 0xEE, 0x91, 0x1D, 0xEB, 0x8E, 0xA3, 0xC4, 0xA2, - 0x09, 0x42, 0x03, 0x55, 0xAB, 0xAC, 0x7E, 0xB2, 0x32, 0xDD, 0xA4, 0x1C, 0x99, 0x95, 0x39, 0xFD, - 0x17, 0x25, 0xA5, 0x2A, 0x47, 0x79, 0x0C, 0x3B, 0x2B, 0x1C, 0xDD, 0xA2, 0xC1, 0xF6, 0x9D, 0xD7, - 0x30, 0xF1, 0xB3, 0xEB, 0x2F, 0x6B, 0x23, 0x43, 0x18, 0xAB, 0x0A, 0x15, 0x9E, 0xED, 0x5D, 0xB7, - 0x9F, 0x9A, 0xFA, 0x66, 0xD4, 0x85, 0xEE, 0x57, 0x8A, 0x21, 0xE2, 0x2E, 0x52, 0x49, 0x6D, 0x66, - 0x32, 0x38, 0xD4, 0x4E, 0x41, 0x6A, 0x47, 0x1A, 0xFD, 0xED, 0xE2, 0xBC, 0xF9, 0xE1, 0xED, 0x80, - 0x8E, 0xB5, 0x4E, 0x3B, 0x7C, 0xFC, 0xF5, 0xF3, 0xDB, 0xA3, 0xF6, 0x0B, 0x6D, 0x2E, 0x46, 0x9B, - 0x88, 0x45, 0x55, 0x48, 0x13, 0xDE, 0xDF, 0x1A, 0xCA, 0x44, 0xD3, 0x75, 0x60, 0x67, 0x35, 0x5D, - 0x44, 0x3D, 0x62, 0xFD, 0x67, 0x13, 0xAE, 0x7E, 0x3B, 0xB5, 0xBE, 0x73, 0xB7, 0xA4, 0x34, 0x4D, - 0xE6, 0xE2, 0x68, 0x0F, 0xD0, 0x30, 0xFE, 0xB9, 0xC4, 0xCD, 0x60, 0xAD, 0x9E, 0x8D, 0xB7, 0x51, - 0x09, 0x13, 0x64, 0x43, 0x55, 0xB1, 0x49, 0xB6, 0x04, 0x41, 0x10, 0x96, 0x2A, 0x03, 0x59, 0x41, - 0x58, 0x14, 0xEF, 0xA0, 0x4C, 0x2A, 0x08, 0x0E, 0xCE, 0x3A, 0xC7, 0x02, 0xC9, 0x13, 0x08, 0x4B, - 0xB7, 0x0D, 0x3E, 0x23, 0xC8, 0x50, 0xD1, 0x0E, 0xBF, 0x8A, 0x81, 0x0C, 0x94, 0xFE, 0xA1, 0x35, - 0xE5, 0x51, 0xF1, 0xD4, 0x65, 0x9A, 0xAE, 0x7A, 0x28, 0x07, 0xA3, 0xF4, 0x6A, 0x72, 0x20, 0x5E, - 0xF4, 0xA2, 0xF4, 0x1D, 0x14, 0xA5, 0x61, 0x1A, 0xDC, 0xC1, 0xB8, 0x8F, 0x78, 0x37, 0x34, 0x1F, - 0x1B, 0xFF, 0x42, 0xFA, 0x16, 0xE2, 0x92, 0x30, 0x02, 0x08, 0xE9, 0x37, 0xFE, 0x32, 0xB9, 0x5B, - 0x0A, 0xAB, 0x65, 0x52, 0xA2, 0x86, 0xC5, 0xA0, 0x28, 0xEE, 0x4D, 0x2C, 0x97, 0x87, 0x4B, 0x03, - 0x59, 0x1E, 0x3A, 0x09, 0x24, 0xF0, 0xA9, 0x58, 0xEA, 0x1D, 0xC7, 0xCF, 0xC4, 0x5B, 0x34, 0xDF, - 0xC1, 0xBF, 0x43, 0x81, 0x58, 0x55, 0x0C, 0xD5, 0x0F, 0xD7, 0x17, 0xF2, 0x9B, 0x3E, 0x8C, 0xCA, - 0x4D, 0x04, 0xE7, 0x66, 0xF9, 0x5B, 0xC6, 0x6C, 0xFA, 0x31, 0x48, 0x9D, 0x72, 0xFD, 0xDC, 0xF2, - 0x13, 0x74, 0x8E, 0x48, 0x2E, 0x2E, 0x6F, 0xA2, 0x17, 0x90, 0xE5, 0x8E, 0x98, 0xB9, 0x8E, 0xE4, - 0x41, 0x22, 0xC8, 0x21, 0x36, 0xF6, 0xEF, 0x72, 0xF0, 0x13, 0xF1, 0xBB, 0x1C, 0x87, 0x13, 0x4C, - 0x6A, 0x7E, 0x14, 0x7A, 0x1E, 0xDC, 0x30, 0xD1, 0x23, 0x98, 0x7B, 0xE8, 0xB9, 0x90, 0x42, 0xCA, - 0xE1, 0xE8, 0x0B, 0x5F, 0xF1, 0xA5, 0x02, 0xF4, 0xA3, 0x62, 0xE8, 0x06, 0xB7, 0x9E, 0x08, 0xA2, - 0xC1, 0xE8, 0x27, 0xF2, 0x8F, 0x75, 0xC3, 0x34, 0x1C, 0xBF, 0x66, 0xA0, 0x1A, 0x96, 0x09, 0x93, - 0x7B, 0x2A, 0xA0, 0x5E, 0x7D, 0xB9, 0xEE, 0x0F, 0x87, 0x00, 0x54, 0xF1, 0xC7, 0xDA, 0x81, 0x1A, - 0x8C, 0x5F, 0x33, 0x50, 0xED, 0x27, 0x03, 0xE8, 0x00, 0x81, 0x39, 0x58, 0x3F, 0x20, 0x07, 0xB5, - 0x03, 0xF1, 0x5A, 0xB9, 0xD7, 0xD5, 0x27, 0x02, 0x23, 0x8C, 0x7D, 0x79, 0xD6, 0x38, 0xB9, 0xEE, - 0xFF, 0xED, 0xF2, 0x6C, 0xDD, 0xA0, 0x94, 0x63, 0xD7, 0x0B, 0xCC, 0x7F, 0xF9, 0xF3, 0xC9, 0x68, - 0xFC, 0x5F, 0x7E, 0x43, 0x02, 0xC3, 0x9F, 0xEB, 0x86, 0xA4, 0x18, 0xB9, 0x5E, 0x40, 0x0E, 0xEF, - 0x94, 0xA7, 0x02, 0xE4, 0xF0, 0xB4, 0x0F, 0xCB, 0xC1, 0x9F, 0xEB, 0x06, 0xA4, 0x18, 0x79, 0x29, - 0x40, 0x2E, 0xA4, 0x5A, 0xDB, 0x33, 0xBF, 0x90, 0x98, 0xDC, 0xBB, 0x02, 0x7F, 0xB9, 0x42, 0x45, - 0x86, 0x66, 0x22, 0xCE, 0xE0, 0x4F, 0x8A, 0x2B, 0x8D, 0xCA, 0x55, 0x0C, 0x0A, 0x33, 0x3C, 0xA9, - 0x03, 0x35, 0x84, 0x2C, 0xFC, 0x31, 0x9C, 0x50, 0xE3, 0xE4, 0x82, 0x9E, 0x30, 0xF9, 0x88, 0x7D, - 0xEA, 0x0F, 0xF7, 0x2E, 0x0E, 0x0B, 0x75, 0xC8, 0x33, 0x0B, 0xB4, 0x12, 0xCA, 0xBF, 0xE3, 0xAE, - 0x1E, 0xAB, 0xE6, 0x27, 0xBD, 0xE6, 0x0B, 0x8D, 0xAF, 0xA0, 0x98, 0x7C, 0x82, 0x16, 0xAC, 0x2F, - 0xCD, 0xEE, 0x6C, 0xC8, 0x1D, 0x8A, 0x22, 0x53, 0x67, 0x70, 0x08, 0xEE, 0x16, 0x34, 0xBA, 0xA6, - 0x24, 0x2D, 0x27, 0x00, 0x6A, 0x8C, 0x2C, 0x22, 0xDA, 0xC9, 0x45, 0x39, 0xCD, 0x64, 0x13, 0x5D, - 0xEA, 0x2A, 0x69, 0xF0, 0xA5, 0x70, 0xB8, 0x02, 0xFE, 0x5E, 0x7B, 0x8E, 0x6E, 0x9F, 0x19, 0x3A, - 0x26, 0xF3, 0x08, 0x10, 0xF8, 0xFA, 0xF6, 0xE6, 0x72, 0xC0, 0xC4, 0xC3, 0x62, 0x05, 0x7E, 0x79, - 0x74, 0x8C, 0xCD, 0x61, 0x4D, 0x96, 0x82, 0xAF, 0xA4, 0x3D, 0xEB, 0xAE, 0x5C, 0xAC, 0x4A, 0xA3, - 0xA3, 0x0A, 0x8D, 0xD7, 0x1A, 0x98, 0xB3, 0x22, 0x82, 0x8F, 0x34, 0x92, 0x50, 0x9B, 0x15, 0xD0, - 0x8E, 0x5D, 0x52, 0xA5, 0x5D, 0x81, 0xB6, 0x2D, 0xF6, 0xAB, 0xE5, 0x3B, 0x41, 0x24, 0xE4, 0xD4, - 0x77, 0x3D, 0xB4, 0xD9, 0x3D, 0xE8, 0xE8, 0x69, 0x24, 0x92, 0x42, 0x38, 0xE8, 0xF4, 0xCB, 0x14, - 0x8F, 0xA1, 0x57, 0x86, 0xA7, 0x4F, 0x79, 0x54, 0xA9, 0x3E, 0xD7, 0xDD, 0xCD, 0xD3, 0xA8, 0x4B, - 0x71, 0x62, 0x73, 0xB6, 0x69, 0x81, 0x9B, 0x62, 0x6A, 0x14, 0xEF, 0x8A, 0x0D, 0xBE, 0xD1, 0x69, - 0xC0, 0xCE, 0x70, 0xE7, 0x93, 0xE5, 0x7A, 0x25, 0xBC, 0xDD, 0x0F, 0xE6, 0x8C, 0xC1, 0xA2, 0x79, - 0x21, 0xF7, 0xC0, 0xFE, 0x8F, 0x17, 0x35, 0x58, 0x1E, 0x2D, 0x66, 0xB0, 0x2C, 0x70, 0x7C, 0x4F, - 0x87, 0x41, 0x69, 0xEB, 0x65, 0x6A, 0xF3, 0xD5, 0x1B, 0x33, 0xD7, 0x8C, 0x17, 0x03, 0x4C, 0x4E, - 0xB8, 0x42, 0xBC, 0xC0, 0xFE, 0xD7, 0x8D, 0x17, 0x85, 0x86, 0xEC, 0x74, 0x28, 0x2C, 0x8E, 0x19, - 0xD8, 0xFC, 0xD9, 0x61, 0x06, 0x1C, 0x05, 0xCE, 0x2A, 0x31, 0x03, 0xFB, 0xDF, 0x74, 0x8E, 0x41, - 0x30, 0x58, 0x1C, 0x2F, 0xB0, 0xF9, 0xB3, 0xC4, 0x8B, 0xC1, 0xCF, 0xC5, 0x92, 0x6D, 0x0E, 0xE6, - 0x64, 0x5D, 0x3C, 0x56, 0xC0, 0x1C, 0x36, 0xF8, 0x79, 0x61, 0xE4, 0x79, 0x23, 0x10, 0x77, 0x1D, - 0xC8, 0x03, 0x80, 0x5A, 0x0E, 0x7D, 0x06, 0x3F, 0x3F, 0x23, 0x04, 0xFA, 0x6C, 0xF9, 0xA6, 0x37, - 0xB0, 0x74, 0x73, 0xB1, 0x23, 0x87, 0x9A, 0x97, 0x38, 0x71, 0xA0, 0xFF, 0xCD, 0x65, 0x2C, 0x11, - 0x18, 0x2C, 0x82, 0x19, 0xB3, 0xE6, 0xCF, 0x12, 0x2F, 0x56, 0xC4, 0x58, 0x2A, 0x60, 0x4E, 0xF1, - 0x5B, 0x1B, 0xCC, 0x78, 0x62, 0x80, 0x5C, 0x0E, 0xBD, 0x36, 0x8B, 0xF1, 0x84, 0xFA, 0x7D, 0xA7, - 0x76, 0x5B, 0x66, 0x64, 0xF5, 0xB7, 0x98, 0x5C, 0x78, 0xAA, 0x7B, 0x1F, 0x3F, 0xF6, 0x1B, 0x27, - 0xC1, 0x07, 0x06, 0x9F, 0x50, 0x03, 0x16, 0x3C, 0x79, 0xF5, 0xB6, 0xA8, 0x8C, 0xF9, 0x14, 0x6E, - 0xA6, 0x6F, 0x52, 0x87, 0x5C, 0x5B, 0xB7, 0xED, 0x8A, 0xAE, 0xFA, 0x55, 0x82, 0x0E, 0xA6, 0x02, - 0xFD, 0xC3, 0xD7, 0xD1, 0xED, 0x15, 0xFE, 0x1A, 0xFB, 0x86, 0xE2, 0xCC, 0x2E, 0xD0, 0x65, 0xFE, - 0x4A, 0x32, 0x18, 0xD0, 0x0D, 0x3D, 0x59, 0xB1, 0x76, 0x10, 0xBC, 0x53, 0x11, 0xFC, 0xFB, 0x9A, - 0xB9, 0x32, 0xB3, 0x12, 0x7E, 0x2F, 0xBA, 0x84, 0x5F, 0x26, 0x53, 0x7C, 0xCF, 0x9A, 0x62, 0xDA, - 0x6B, 0xC5, 0x30, 0x1E, 0x65, 0x10, 0xA9, 0x74, 0x24, 0x50, 0x1C, 0xEE, 0x7A, 0x4C, 0xB9, 0x57, - 0x74, 0x4A, 0x89, 0x9E, 0xB4, 0x4F, 0xA4, 0x18, 0x15, 0x9E, 0xA3, 0x2D, 0x4C, 0x38, 0xB1, 0x13, - 0x10, 0xD1, 0x81, 0xFD, 0x54, 0x84, 0x5B, 0xE6, 0x8C, 0x25, 0xA3, 0x38, 0xC3, 0xB0, 0xE1, 0x31, - 0xF7, 0x64, 0x04, 0xF6, 0x95, 0xEE, 0x7A, 0x3B, 0xAF, 0xE7, 0xE2, 0x93, 0xA7, 0x1A, 0xFD, 0x92, - 0x09, 0xA7, 0x33, 0xE3, 0x3D, 0xF3, 0x8D, 0x4C, 0x25, 0x62, 0x41, 0x0B, 0xE3, 0x3E, 0x31, 0xA6, - 0x36, 0x77, 0x94, 0x05, 0xC3, 0x42, 0xB1, 0xDF, 0xFC, 0x0D, 0x94, 0x00, 0xA2, 0x30, 0x47, 0x37, - 0x1A, 0x1C, 0x0A, 0x4D, 0x97, 0x8F, 0x0F, 0x9D, 0xED, 0x75, 0x51, 0x80, 0x76, 0x79, 0x12, 0x4E, - 0xE2, 0xC5, 0x25, 0x60, 0xF1, 0x2D, 0x9E, 0x26, 0x65, 0x6C, 0x81, 0xD7, 0x9F, 0x2F, 0xFA, 0xE4, - 0x3C, 0x77, 0xD3, 0xFF, 0xF9, 0x17, 0x4A, 0x51, 0x86, 0x14, 0xE7, 0x3D, 0x58, 0x6C, 0x6A, 0x01, - 0xC9, 0xA9, 0xD6, 0x74, 0x6A, 0x99, 0xE4, 0x35, 0x84, 0x15, 0x0E, 0xD0, 0xA1, 0x07, 0xB6, 0xD7, - 0x15, 0x9E, 0xF1, 0x02, 0x50, 0x77, 0xBE, 0x17, 0xF7, 0xC5, 0x71, 0x7D, 0x1B, 0xDF, 0x75, 0x85, - 0x6B, 0x3C, 0x50, 0xBA, 0xC9, 0xDE, 0xB4, 0x23, 0xC9, 0xCE, 0x64, 0x43, 0xB7, 0xC5, 0x2E, 0x14, - 0x75, 0x12, 0xF6, 0x23, 0xA2, 0x73, 0x04, 0x4F, 0x95, 0x3B, 0xC8, 0x1E, 0x26, 0xFA, 0xEC, 0x0D, - 0x91, 0x41, 0x4D, 0x93, 0x04, 0xCE, 0x76, 0xDA, 0xAF, 0x69, 0xE2, 0x98, 0xE2, 0xCE, 0x1A, 0x79, - 0x18, 0xCC, 0x43, 0xF1, 0x3E, 0xA2, 0x37, 0x4A, 0x58, 0x2C, 0xA7, 0xBC, 0xD3, 0x61, 0xEF, 0x81, - 0x08, 0x66, 0x5F, 0x86, 0xDF, 0x60, 0x88, 0x64, 0x07, 0x7D, 0x0B, 0x77, 0xD9, 0x81, 0x7C, 0x47, - 0x7C, 0x27, 0xA3, 0x8E, 0x0E, 0x18, 0x45, 0x53, 0xBE, 0x8E, 0x30, 0x18, 0x02, 0x18, 0xB0, 0xB3, - 0x5D, 0xF6, 0x71, 0x48, 0x3F, 0x6E, 0xF1, 0xC7, 0xDF, 0x76, 0x05, 0x10, 0x3F, 0x9F, 0x45, 0x42, - 0x19, 0xF1, 0x40, 0xE9, 0xB6, 0xB7, 0x32, 0x41, 0x5B, 0x51, 0x48, 0x72, 0x3E, 0x1D, 0xE5, 0xE4, - 0x0E, 0x4C, 0xC9, 0x7C, 0x79, 0x90, 0x92, 0xF8, 0x32, 0xB5, 0xC7, 0x45, 0xF3, 0x35, 0x44, 0x79, - 0xE1, 0x7C, 0xCE, 0x06, 0x73, 0xCA, 0x15, 0xB9, 0xBB, 0x6E, 0x56, 0xC2, 0x86, 0x72, 0x9E, 0xAD, - 0x21, 0x9F, 0xA5, 0xEC, 0x00, 0xB7, 0xD6, 0x90, 0x22, 0xD3, 0x74, 0x73, 0x1C, 0x74, 0x3F, 0xCB, - 0xD3, 0x00, 0x98, 0x11, 0x7E, 0x1B, 0xE0, 0x96, 0x5B, 0x32, 0x6B, 0x43, 0xC9, 0x28, 0xAD, 0xD5, - 0x40, 0x4B, 0xC6, 0x03, 0xAF, 0x06, 0x60, 0x57, 0xF1, 0xCE, 0x63, 0xE0, 0x92, 0xDF, 0xAD, 0x00, - 0x58, 0x69, 0x39, 0x73, 0xD3, 0xCF, 0x5E, 0xCB, 0x55, 0x74, 0x15, 0x19, 0xC0, 0xD0, 0x73, 0xB8, - 0x32, 0x0D, 0x02, 0xB0, 0xDC, 0x32, 0x10, 0xCD, 0xEA, 0xA4, 0x53, 0x22, 0x8C, 0x2B, 0x4B, 0xBB, - 0x72, 0xA9, 0x87, 0x4B, 0x0C, 0x5A, 0x02, 0xE9, 0x12, 0xFB, 0xFC, 0x1D, 0xA4, 0x65, 0xE2, 0x50, - 0xB2, 0x73, 0x11, 0xD1, 0x04, 0x5F, 0x1E, 0x97, 0x73, 0x34, 0x9E, 0x31, 0xA5, 0x68, 0x78, 0x4C, - 0xEA, 0x38, 0xB4, 0x9A, 0xD4, 0x6F, 0x4A, 0x07, 0x46, 0x2E, 0x1A, 0x56, 0x13, 0x9B, 0xA9, 0x45, - 0xCE, 0xA3, 0x91, 0xA4, 0x8D, 0x9D, 0xF6, 0x14, 0xB0, 0x43, 0x3C, 0x5E, 0xB8, 0x9F, 0x4E, 0xE3, - 0xA4, 0x5B, 0x47, 0x3F, 0x5D, 0xCC, 0x32, 0x5C, 0x43, 0x3F, 0xBD, 0xC6, 0xC9, 0x41, 0x1D, 0xFD, - 0xEC, 0x23, 0x7C, 0xEA, 0xE8, 0xE8, 0x00, 0x01, 0x54, 0x47, 0x47, 0x87, 0xB8, 0xB2, 0x3A, 0x3A, - 0x7A, 0x03, 0x4B, 0x5B, 0xBE, 0x97, 0x23, 0x58, 0xD7, 0xF2, 0xBD, 0xBC, 0x85, 0x45, 0xD5, 0x80, - 0x84, 0x84, 0xCD, 0x35, 0xF4, 0xD3, 0xC1, 0x3C, 0xE2, 0x35, 0xF4, 0x03, 0xD8, 0xDC, 0xAB, 0x63, - 0x3E, 0x80, 0xCD, 0x87, 0x75, 0xF4, 0x03, 0xD8, 0xDC, 0x9D, 0xEA, 0xE6, 0xF2, 0x1D, 0x01, 0x36, - 0x1F, 0xD4, 0xD2, 0xD1, 0x21, 0xF1, 0x9F, 0x3A, 0x7A, 0x42, 0x74, 0xAE, 0x67, 0x4E, 0x47, 0xB8, - 0x6B, 0xB5, 0xF4, 0xF4, 0x16, 0xF7, 0xAD, 0x72, 0x4F, 0xC5, 0x51, 0x90, 0x2B, 0xB2, 0x5D, 0x24, - 0x6D, 0x18, 0x33, 0x93, 0x42, 0x70, 0x2C, 0x52, 0xB0, 0x50, 0xF4, 0xC0, 0xDC, 0xB6, 0x74, 0x23, - 0xA5, 0x24, 0x98, 0x92, 0x92, 0x50, 0xAE, 0x9C, 0xD2, 0xAD, 0x57, 0x4E, 0xE9, 0xC4, 0xE4, 0x94, - 0xEE, 0xCA, 0xE4, 0x94, 0x4E, 0xA6, 0x9C, 0xD2, 0x79, 0x91, 0x53, 0x5E, 0xE4, 0x94, 0x17, 0x39, - 0xE5, 0x45, 0x4E, 0x79, 0x91, 0x53, 0x5E, 0xE4, 0x94, 0x6D, 0x93, 0x53, 0xBA, 0xDB, 0x97, 0x16, - 0xAD, 0xD8, 0x10, 0x53, 0xD2, 0xB0, 0x15, 0x31, 0x77, 0xE3, 0x35, 0x06, 0x9A, 0x0E, 0x57, 0x1B, - 0x5F, 0x5C, 0xE2, 0x71, 0x60, 0x57, 0xCD, 0xCB, 0xD2, 0x49, 0xC9, 0xA5, 0x9E, 0x32, 0x4B, 0xA7, - 0xA8, 0x61, 0xE8, 0xAE, 0xAA, 0x78, 0xCF, 0x69, 0xA4, 0xEB, 0x4A, 0xD7, 0x33, 0x91, 0x86, 0x19, - 0xFB, 0x80, 0x80, 0x4C, 0xA9, 0xC8, 0x97, 0x51, 0xBA, 0x06, 0xFF, 0x45, 0x80, 0x9D, 0x48, 0xF4, - 0x49, 0x10, 0xD8, 0xA4, 0x44, 0x9F, 0xB9, 0xCB, 0x5F, 0xB0, 0x0C, 0x0F, 0xC9, 0xBC, 0x64, 0x60, - 0xBE, 0x34, 0x45, 0xAE, 0xEF, 0x42, 0x2F, 0xF6, 0x58, 0xB2, 0xF0, 0x00, 0x50, 0xB7, 0xF0, 0x70, - 0x28, 0xFB, 0x09, 0x52, 0x88, 0x07, 0xCF, 0xE3, 0xDE, 0x0A, 0xB2, 0x61, 0xE1, 0xF5, 0x74, 0x54, - 0x2F, 0x98, 0x1B, 0xE1, 0x44, 0xFC, 0xD5, 0xBC, 0x34, 0xD7, 0x1C, 0x3C, 0x7F, 0x29, 0x92, 0xD4, - 0xD9, 0x0E, 0x57, 0x75, 0x40, 0x9C, 0x30, 0x9F, 0xA6, 0x35, 0x62, 0x0A, 0xC3, 0x69, 0x32, 0x57, - 0xE6, 0x84, 0xA2, 0x22, 0x8C, 0x1E, 0xFB, 0x66, 0x52, 0x99, 0x67, 0x8F, 0xD2, 0x68, 0xDE, 0x71, - 0x66, 0xDD, 0x51, 0x49, 0x43, 0x8D, 0xDD, 0x3D, 0x62, 0x12, 0x4E, 0x37, 0x30, 0xEE, 0x63, 0x22, - 0x4E, 0xEC, 0x39, 0xE8, 0xB1, 0x45, 0x59, 0xE9, 0xA8, 0x47, 0xE8, 0x09, 0x6F, 0x97, 0x28, 0xC1, - 0x05, 0xDE, 0x3C, 0xD1, 0xC4, 0x45, 0x8E, 0x29, 0xE5, 0x1B, 0xDE, 0x76, 0xD9, 0xB6, 0x63, 0x7D, - 0x07, 0x5A, 0xF6, 0x30, 0xC7, 0xD3, 0x61, 0x3B, 0xCC, 0x7F, 0xF7, 0x60, 0x39, 0xDE, 0x44, 0x24, - 0x78, 0x52, 0xB4, 0xA0, 0x56, 0x91, 0x98, 0x00, 0xCE, 0x16, 0xAF, 0xCA, 0x47, 0x30, 0xB3, 0x70, - 0x11, 0x38, 0x9A, 0xC6, 0x2C, 0x33, 0x99, 0x87, 0x2F, 0x48, 0xDB, 0x37, 0xE5, 0xDE, 0xC4, 0xD2, - 0x98, 0xA2, 0x4E, 0x74, 0x8E, 0x49, 0xB1, 0xFE, 0xBD, 0xD7, 0x56, 0xA7, 0x29, 0x39, 0xAD, 0xF0, - 0xA6, 0x0F, 0x2F, 0xEA, 0xEF, 0x81, 0xBB, 0xB4, 0xD8, 0xA5, 0xA9, 0xC2, 0xF8, 0x6E, 0x90, 0xDC, - 0x2A, 0xC8, 0xE7, 0xF1, 0xE5, 0x0E, 0xA3, 0x03, 0xC4, 0xC0, 0xB7, 0xFA, 0x94, 0x07, 0x89, 0x44, - 0x6F, 0x84, 0xCF, 0x80, 0x86, 0xB9, 0x64, 0x4D, 0x86, 0x55, 0x03, 0x23, 0x11, 0xFD, 0xBA, 0xE8, - 0x8B, 0x87, 0x09, 0xA9, 0x68, 0x2C, 0xBA, 0x78, 0xC4, 0x5C, 0x59, 0x30, 0x05, 0x1D, 0x73, 0x78, - 0x9D, 0x72, 0x2C, 0xC0, 0x3A, 0x7B, 0x49, 0x77, 0x83, 0x49, 0x6B, 0x14, 0x76, 0x40, 0x09, 0x01, - 0x9B, 0xF0, 0xCA, 0x34, 0xCC, 0x5B, 0x2A, 0xD3, 0x5D, 0x51, 0x89, 0x25, 0xCC, 0xC9, 0x4C, 0xF5, - 0x4B, 0x67, 0x79, 0x44, 0xDA, 0x22, 0xA9, 0xD7, 0x41, 0xAB, 0x3D, 0x9D, 0x5D, 0xDC, 0x1D, 0xD2, - 0xCD, 0xDD, 0x61, 0xBB, 0xED, 0xEE, 0xB2, 0x4E, 0x8B, 0x3E, 0xD0, 0x0B, 0x5B, 0x17, 0xA7, 0x10, - 0x70, 0x00, 0x19, 0x2F, 0xE6, 0x36, 0x4A, 0xC4, 0x1B, 0x06, 0x6D, 0x16, 0x0C, 0x6C, 0x58, 0xCA, - 0x73, 0x2C, 0xC9, 0x1F, 0xAC, 0x19, 0x2E, 0xC9, 0x3C, 0x99, 0xB9, 0x2E, 0x85, 0x9D, 0x6E, 0x5A, - 0x96, 0x1B, 0xC4, 0xCA, 0x72, 0xB7, 0x51, 0x11, 0xCC, 0xC5, 0x58, 0x15, 0xB6, 0xE3, 0xBE, 0x3E, - 0x2E, 0x6D, 0x8D, 0x28, 0xCA, 0x8C, 0x58, 0xC1, 0x5C, 0x50, 0xCD, 0xCF, 0x3D, 0x05, 0x48, 0x25, - 0x87, 0xB1, 0x33, 0xDA, 0x2F, 0xE3, 0x13, 0x56, 0x4D, 0xD6, 0x5B, 0x3B, 0x1A, 0x0D, 0x24, 0x2F, - 0x0B, 0x22, 0xF0, 0xCA, 0xC9, 0xE6, 0xD5, 0x70, 0x2E, 0xE0, 0x74, 0xA5, 0xBA, 0x26, 0x6E, 0xD8, - 0x3B, 0x07, 0xB1, 0x1E, 0xF8, 0x10, 0x9E, 0xEF, 0x21, 0x67, 0x2C, 0xD5, 0x7C, 0x67, 0xBA, 0x2C, - 0x8A, 0x12, 0x72, 0x4A, 0x3C, 0xBD, 0x2B, 0x8C, 0x0E, 0x5D, 0x1A, 0x45, 0xE7, 0x36, 0x60, 0x51, - 0x5C, 0x4D, 0x76, 0xB4, 0x3E, 0xA4, 0x5D, 0x95, 0x6B, 0x17, 0x09, 0x03, 0xCB, 0x0A, 0x6B, 0x1F, - 0xB0, 0x93, 0x79, 0x49, 0x2D, 0xB4, 0x16, 0xA6, 0xC8, 0x6C, 0xD5, 0x64, 0x35, 0x31, 0xC0, 0x09, - 0xFD, 0x8A, 0x9D, 0x78, 0xA2, 0xEC, 0xF9, 0x09, 0xDB, 0x39, 0x9B, 0x58, 0x98, 0x82, 0x07, 0x6B, - 0xC8, 0x32, 0xAB, 0xD8, 0xD1, 0xFF, 0xA3, 0xAC, 0x82, 0xFB, 0x3A, 0x28, 0xB5, 0xFA, 0x24, 0x92, - 0x5F, 0x54, 0xE2, 0xF3, 0x22, 0x12, 0x5A, 0x28, 0xE7, 0xA1, 0xE0, 0x03, 0x72, 0x1E, 0x55, 0x87, - 0x16, 0x32, 0x1B, 0x07, 0x89, 0x03, 0xA4, 0x11, 0xB9, 0xCE, 0x70, 0x1D, 0x2C, 0x52, 0x65, 0x17, - 0xA5, 0x24, 0x11, 0x6A, 0x89, 0x89, 0x3D, 0xE3, 0x6E, 0x52, 0x42, 0xF0, 0x99, 0x4E, 0xB9, 0xA6, - 0x0B, 0x09, 0xEF, 0x8E, 0x8F, 0xF5, 0x20, 0x71, 0x28, 0x85, 0x59, 0xDE, 0xDC, 0x9E, 0x7D, 0x9E, - 0x77, 0x75, 0xEC, 0x4B, 0xA9, 0x31, 0x14, 0xCB, 0x74, 0x57, 0xC8, 0x7C, 0xA1, 0x08, 0x4A, 0xA2, - 0xD0, 0x60, 0x30, 0x60, 0x3B, 0xB6, 0x28, 0xD4, 0xEE, 0x72, 0x10, 0x50, 0x7D, 0x87, 0x79, 0xBE, - 0x67, 0x81, 0x0A, 0x66, 0xBC, 0xA6, 0xE2, 0x92, 0xF8, 0x56, 0x42, 0x34, 0x62, 0xCA, 0x18, 0xBA, - 0x40, 0x57, 0x4B, 0x98, 0x27, 0xB9, 0x6B, 0xA9, 0xA1, 0xE4, 0x1B, 0x11, 0x9B, 0x82, 0xEA, 0xDF, - 0xAF, 0xDC, 0x19, 0xDC, 0x30, 0x7B, 0xB2, 0xE5, 0x1B, 0x1A, 0x77, 0x76, 0x41, 0xEF, 0x32, 0x2C, - 0xC0, 0x2D, 0x6B, 0xFB, 0x24, 0x26, 0x02, 0x6D, 0x0D, 0x31, 0x9D, 0x65, 0x02, 0xED, 0x33, 0x28, - 0x99, 0xA6, 0x20, 0x74, 0xC2, 0x00, 0x8F, 0x90, 0xEE, 0x44, 0xC1, 0x66, 0x59, 0xC4, 0x49, 0x6E, - 0x7D, 0x8C, 0xB6, 0xDB, 0xA5, 0x9D, 0xEA, 0x67, 0xB4, 0xBF, 0x80, 0x9F, 0x35, 0x31, 0x83, 0xBC, - 0x39, 0x52, 0xF1, 0x68, 0x36, 0xFB, 0x22, 0x8C, 0xEC, 0xCF, 0xBD, 0xA6, 0x2A, 0xE5, 0x2C, 0x1E, - 0x94, 0x74, 0x2E, 0xD8, 0xA0, 0x15, 0x4A, 0x15, 0x91, 0xC6, 0x33, 0xD0, 0xED, 0x87, 0xD2, 0x80, - 0x08, 0x2C, 0x39, 0x9A, 0x13, 0x09, 0x4A, 0x5E, 0xE3, 0x65, 0x39, 0x5D, 0xF9, 0x2E, 0x81, 0x36, - 0x02, 0xD3, 0x52, 0x95, 0x85, 0xCA, 0x1B, 0x1E, 0x43, 0x47, 0xAC, 0xF9, 0x91, 0xD0, 0x09, 0xEB, - 0x0A, 0x63, 0xC2, 0x69, 0x5B, 0x3F, 0xA0, 0x5F, 0x37, 0xBA, 0x01, 0x96, 0x73, 0xBF, 0x5A, 0xBD, - 0xAD, 0x74, 0xE0, 0xCB, 0x0C, 0xD1, 0x32, 0xC1, 0x9D, 0x98, 0x66, 0x84, 0x05, 0xA3, 0x09, 0xD5, - 0xA2, 0x37, 0x04, 0xDB, 0xFC, 0x65, 0xEF, 0xD7, 0xBD, 0xDF, 0x10, 0x4C, 0xDC, 0x6D, 0x3D, 0x5F, - 0x23, 0xEA, 0x7A, 0x48, 0x20, 0x56, 0x1E, 0xA1, 0xB7, 0xC0, 0xC5, 0x30, 0x6D, 0xC9, 0x85, 0x28, - 0x24, 0x9F, 0x45, 0x56, 0x51, 0x3A, 0xFA, 0xA5, 0x82, 0xB0, 0x5B, 0xE1, 0xBE, 0x3B, 0x4D, 0x6D, - 0x3B, 0x5A, 0x89, 0x24, 0x1C, 0x59, 0x70, 0x25, 0xC1, 0x77, 0xD6, 0xEE, 0x59, 0x28, 0x67, 0x2B, - 0xC1, 0xA1, 0x5F, 0xCB, 0xE1, 0xD0, 0xAF, 0xCF, 0x06, 0x87, 0x7E, 0x5D, 0x10, 0x87, 0x7E, 0x7D, - 0xC1, 0xA1, 0x2C, 0x1C, 0xFA, 0xAD, 0x1C, 0x0E, 0xFD, 0xF6, 0x6C, 0x70, 0xE8, 0xB7, 0x05, 0x71, - 0xE8, 0xB7, 0x17, 0x1C, 0x4A, 0xE0, 0x90, 0x09, 0x02, 0x14, 0x8A, 0xE7, 0x42, 0x50, 0x2F, 0x83, - 0x45, 0xE5, 0xEA, 0x87, 0x3E, 0x29, 0x22, 0x15, 0x45, 0xA5, 0x46, 0xD7, 0x5C, 0x09, 0x91, 0xA2, - 0x2D, 0x9F, 0x8F, 0xBD, 0xF1, 0xE4, 0x2C, 0x88, 0x97, 0xFA, 0x8A, 0x57, 0x2E, 0x11, 0x31, 0xFA, - 0xC9, 0x4B, 0x39, 0x51, 0xB5, 0x10, 0xB4, 0x12, 0x8C, 0x62, 0xD2, 0xB1, 0x34, 0x6B, 0x50, 0x32, - 0x64, 0x90, 0x93, 0xFF, 0xF0, 0x61, 0x5F, 0x60, 0xFA, 0xAA, 0x65, 0x3F, 0xEE, 0xD9, 0x18, 0x9B, - 0x29, 0x2D, 0x20, 0x73, 0x12, 0xF5, 0x76, 0xCB, 0xD1, 0xE5, 0xAB, 0x21, 0xAD, 0x96, 0xFB, 0x54, - 0x51, 0x9F, 0x92, 0x64, 0x43, 0x31, 0x7E, 0x19, 0x15, 0xA3, 0x81, 0xB9, 0xC8, 0x37, 0x8F, 0xC5, - 0x4E, 0x49, 0xD0, 0x94, 0xF3, 0x15, 0x15, 0x63, 0x46, 0x3D, 0x2B, 0x87, 0xC2, 0x06, 0x14, 0x41, - 0x68, 0xC1, 0xE6, 0x70, 0x4E, 0x59, 0xDF, 0xB9, 0xFA, 0x9F, 0xE4, 0x7F, 0x57, 0x1A, 0x37, 0xC2, - 0x88, 0xA5, 0xEF, 0xCD, 0x07, 0x5D, 0xF3, 0x26, 0xC7, 0xBD, 0x83, 0x76, 0xB9, 0x78, 0xA5, 0x2C, - 0x3F, 0x20, 0x54, 0x5D, 0x85, 0x7D, 0xAA, 0xCF, 0x9A, 0x9D, 0xEE, 0x51, 0xBB, 0xDB, 0x3E, 0x6C, - 0x1D, 0x1C, 0x1E, 0xB1, 0xE6, 0xFE, 0x9B, 0xCE, 0xE1, 0x51, 0x7B, 0xBF, 0xB5, 0xDF, 0xEE, 0xB1, - 0xFD, 0xF6, 0xD1, 0xE1, 0xE1, 0xE1, 0x41, 0x6B, 0xFF, 0x68, 0xBF, 0x0E, 0x3F, 0xCA, 0x60, 0xC8, - 0xD3, 0x35, 0x0D, 0xD9, 0xA3, 0x21, 0xCF, 0xD6, 0x34, 0xDA, 0x7E, 0xE3, 0xA4, 0x8F, 0x07, 0xD7, - 0xED, 0x44, 0xF1, 0x2E, 0xDD, 0x5B, 0xCB, 0xBA, 0xB2, 0xCC, 0xF1, 0xAD, 0x75, 0xCA, 0xCF, 0x05, - 0x06, 0x02, 0x1F, 0xC9, 0x9C, 0x48, 0xA5, 0x8A, 0x69, 0x0B, 0x4F, 0xBA, 0xBC, 0x1B, 0xD7, 0xA6, - 0xC9, 0x20, 0x73, 0x17, 0x4C, 0x35, 0xDA, 0x90, 0x14, 0x4D, 0x8B, 0x4B, 0x26, 0xF5, 0x1A, 0x8E, - 0x64, 0xF7, 0x68, 0x2D, 0xEA, 0x6B, 0x5A, 0x45, 0xEB, 0x50, 0x4E, 0xB4, 0xA1, 0xB2, 0xD2, 0x59, - 0x07, 0xFD, 0x07, 0x46, 0xAE, 0xBA, 0xE6, 0xAD, 0x01, 0x02, 0x7A, 0x7C, 0x95, 0x33, 0x9F, 0x8D, - 0x80, 0x73, 0x3F, 0xA7, 0x4F, 0x9B, 0x62, 0x93, 0x03, 0x04, 0x00, 0x59, 0x62, 0x57, 0x14, 0xA6, - 0x55, 0x34, 0x4A, 0x06, 0xB1, 0x4B, 0x26, 0xB8, 0xB0, 0x32, 0xB8, 0xC3, 0x55, 0x38, 0x2D, 0x22, - 0x92, 0x04, 0xBD, 0x2D, 0x16, 0xC5, 0x74, 0xAF, 0xF5, 0xE3, 0xB9, 0x37, 0x56, 0xC9, 0x96, 0x52, - 0xFF, 0xED, 0xC2, 0x47, 0xAC, 0x6C, 0x90, 0x73, 0xB9, 0xD0, 0x79, 0xFA, 0xCB, 0x85, 0x8F, 0x54, - 0xFE, 0x40, 0x5E, 0xB2, 0xD5, 0x7B, 0xA7, 0x30, 0x96, 0xBD, 0x3E, 0x99, 0xCF, 0xCB, 0x93, 0x5D, - 0x2B, 0x7C, 0x0C, 0x57, 0x3E, 0xBB, 0x5A, 0xA8, 0x1A, 0x16, 0x93, 0xCB, 0xD9, 0x62, 0x57, 0x0B, - 0x29, 0xA3, 0x85, 0xD7, 0x0B, 0x57, 0x57, 0x93, 0xD2, 0x03, 0x6F, 0xFE, 0x2D, 0x04, 0xAC, 0x26, - 0x79, 0xF1, 0x80, 0x8F, 0x5E, 0xAE, 0x1D, 0xEA, 0xF0, 0xE7, 0x21, 0x78, 0x5E, 0x29, 0x5E, 0x71, - 0x92, 0x93, 0x4C, 0x07, 0x9E, 0xFD, 0x44, 0x1E, 0xBA, 0xFD, 0x39, 0xDA, 0x82, 0xFE, 0x75, 0xCF, - 0xD7, 0x78, 0x0D, 0x1E, 0x60, 0x87, 0x2B, 0xB0, 0xBC, 0xC4, 0x60, 0x50, 0xDD, 0x84, 0x27, 0x5B, - 0x3E, 0x37, 0x4F, 0x2F, 0xB1, 0x36, 0x54, 0x48, 0x56, 0x8A, 0x1A, 0x30, 0xC0, 0xE6, 0xE3, 0x46, - 0x00, 0x85, 0x05, 0x90, 0x43, 0x36, 0x7D, 0x36, 0x26, 0x5E, 0x21, 0x92, 0x7B, 0x24, 0x7A, 0x7E, - 0xC0, 0x42, 0xB8, 0x5E, 0xAA, 0x81, 0xB6, 0x9A, 0xD1, 0x37, 0x2B, 0xE1, 0x1C, 0x08, 0xE3, 0x62, - 0x24, 0x26, 0x86, 0x3A, 0xAE, 0x18, 0xD0, 0x1A, 0x98, 0x7A, 0xE2, 0x13, 0xCE, 0x37, 0xF6, 0x6C, - 0xEB, 0x05, 0x72, 0xE5, 0xC6, 0xA9, 0x04, 0xDF, 0x37, 0x04, 0xAB, 0x6E, 0x14, 0x13, 0xF3, 0x7C, - 0xD6, 0xC8, 0x4F, 0xFD, 0x8B, 0xD2, 0xA7, 0xF1, 0x67, 0xC5, 0xF9, 0xB6, 0x07, 0xA3, 0xA1, 0xD7, - 0xE5, 0x62, 0x47, 0x78, 0x3D, 0x52, 0x47, 0x44, 0xF2, 0xF8, 0xC4, 0xB1, 0x29, 0xEB, 0xDF, 0x59, - 0xF7, 0x9C, 0x5D, 0x18, 0x86, 0x6E, 0xBB, 0x96, 0xAE, 0x05, 0x5E, 0x6C, 0x00, 0x84, 0x6F, 0xD2, - 0xC9, 0x5F, 0x97, 0x02, 0x4A, 0x28, 0x7A, 0xA1, 0xC2, 0xA5, 0x48, 0xC8, 0x45, 0xDF, 0xC7, 0xE7, - 0x53, 0xCB, 0xF4, 0xA9, 0xC6, 0xB4, 0x0C, 0x1A, 0xC0, 0x2D, 0x32, 0xB5, 0x2A, 0x82, 0xCB, 0xCA, - 0x85, 0x97, 0x2A, 0x02, 0x4C, 0x69, 0x9B, 0x6F, 0x21, 0xBB, 0xDE, 0xAF, 0x22, 0xBB, 0x55, 0xBF, - 0x91, 0x0B, 0x31, 0xB9, 0xEC, 0x9A, 0xCA, 0x5D, 0x09, 0x95, 0x7C, 0xCD, 0x9E, 0x9F, 0x48, 0x0D, - 0xE9, 0x41, 0x57, 0xC8, 0x49, 0x08, 0xBF, 0xD2, 0x79, 0x22, 0x93, 0x79, 0xAF, 0x0C, 0x3E, 0xF2, - 0x8E, 0xF7, 0x2B, 0x98, 0x91, 0xD3, 0x14, 0x67, 0xA1, 0x18, 0x23, 0x71, 0x08, 0xF7, 0xDC, 0x88, - 0x3B, 0x6D, 0xC4, 0x00, 0x86, 0xD5, 0xEA, 0x81, 0x9B, 0xA0, 0x46, 0x53, 0x85, 0x8F, 0x51, 0x28, - 0x98, 0x62, 0xA8, 0xD0, 0x14, 0xF9, 0x0B, 0x26, 0xC8, 0x16, 0x35, 0x28, 0x39, 0x83, 0x47, 0xC4, - 0x73, 0x16, 0x38, 0x41, 0x56, 0xA1, 0xE5, 0x5C, 0x8E, 0x82, 0x22, 0x98, 0xBB, 0xE1, 0xD4, 0x44, - 0xA5, 0x51, 0x39, 0x61, 0x8A, 0x7E, 0xFA, 0x67, 0xD7, 0xBF, 0xF3, 0x1C, 0x85, 0xAA, 0x78, 0xFE, - 0x33, 0x71, 0x8F, 0xC0, 0x67, 0xB6, 0x0F, 0xBF, 0x4D, 0x53, 0x61, 0x92, 0x67, 0x61, 0xE0, 0x4D, - 0xFF, 0x66, 0x30, 0xCB, 0x15, 0x1A, 0x72, 0xA3, 0x30, 0x3F, 0x1F, 0x74, 0x47, 0x05, 0x70, 0xB0, - 0x0C, 0x77, 0xE0, 0x38, 0x3B, 0xE3, 0x67, 0x13, 0xE8, 0xE1, 0x91, 0x3D, 0x4C, 0xB8, 0x29, 0xA3, - 0x9A, 0x44, 0xDD, 0x50, 0x62, 0x62, 0xE4, 0xDD, 0xAA, 0xC8, 0xCB, 0x2B, 0xDB, 0x02, 0x7E, 0x33, - 0x89, 0x8D, 0xBA, 0x4B, 0x11, 0x46, 0xBE, 0x29, 0x5E, 0xA0, 0x26, 0x61, 0x1D, 0xF0, 0x16, 0xBB, - 0xB6, 0x3C, 0x7E, 0x4C, 0x91, 0x5A, 0xE1, 0x3A, 0x69, 0xCB, 0x29, 0xE2, 0xC8, 0x78, 0x50, 0x1E, - 0x5D, 0x69, 0xC1, 0x92, 0x15, 0x4E, 0x27, 0x18, 0x6B, 0x98, 0x71, 0xF3, 0xC7, 0x3C, 0x04, 0xD9, - 0x16, 0x2A, 0x7D, 0x65, 0x92, 0x9D, 0x96, 0x8B, 0xD8, 0xDD, 0x5A, 0x02, 0xEF, 0x66, 0x10, 0x38, - 0x2B, 0x95, 0x85, 0x37, 0x9D, 0xD0, 0x0D, 0xE8, 0xA2, 0x3F, 0x38, 0x4B, 0xD2, 0x39, 0x3C, 0xDA, - 0x50, 0x32, 0x87, 0x99, 0xA5, 0x50, 0xB9, 0xA2, 0x69, 0x65, 0x09, 0x5C, 0x52, 0x48, 0x59, 0xF2, - 0x7E, 0x21, 0xBE, 0x2A, 0xC4, 0xB7, 0x46, 0xC5, 0x5A, 0x22, 0x6E, 0xB1, 0x94, 0x7D, 0x90, 0x26, - 0x65, 0x23, 0x1E, 0x95, 0x16, 0x9C, 0x57, 0x87, 0xDD, 0xF9, 0x02, 0x73, 0x80, 0xC1, 0x83, 0x09, - 0xC5, 0x8F, 0x13, 0x62, 0xC7, 0x05, 0x68, 0xD7, 0x9F, 0x06, 0x2F, 0x2B, 0xF2, 0x65, 0x71, 0xB2, - 0xEC, 0x32, 0x9B, 0x1A, 0xA9, 0xD4, 0x48, 0xE4, 0x83, 0xA5, 0x73, 0x45, 0x7C, 0x4D, 0x78, 0x8D, - 0x7E, 0x16, 0x0E, 0xE3, 0x9A, 0x4E, 0x68, 0xB9, 0xCB, 0xDC, 0x09, 0x9E, 0x3E, 0x98, 0xDB, 0x01, - 0x91, 0x0C, 0xF5, 0x3C, 0x0A, 0x41, 0x01, 0x4C, 0x7E, 0x9E, 0x3E, 0x15, 0xB9, 0xB2, 0xF5, 0xC1, - 0xEA, 0x3C, 0xDD, 0x02, 0xCC, 0x0D, 0x92, 0x07, 0x57, 0xB7, 0x89, 0x88, 0x1E, 0xD6, 0x66, 0x11, - 0xA1, 0x7B, 0x8D, 0xF5, 0x90, 0x76, 0xE0, 0x52, 0x12, 0x18, 0xE7, 0x1B, 0x8B, 0x98, 0xC4, 0xC8, - 0x95, 0xED, 0x89, 0x29, 0xFB, 0x23, 0x1C, 0x1F, 0x22, 0xD8, 0x8A, 0xC2, 0xC5, 0x41, 0xFA, 0x0B, - 0x96, 0xC6, 0xEE, 0xF8, 0x08, 0x73, 0x51, 0x8B, 0x33, 0x0B, 0xA3, 0xB9, 0xE4, 0xB9, 0x11, 0xA6, - 0xB7, 0x26, 0xFF, 0xA7, 0xA8, 0x8F, 0x13, 0xFA, 0x4A, 0xFD, 0x80, 0x34, 0x78, 0xB8, 0x42, 0x27, - 0xC1, 0x10, 0xC1, 0x16, 0x72, 0x14, 0x0C, 0x5A, 0xBF, 0x38, 0x0B, 0xAE, 0x9C, 0x90, 0xEA, 0x77, - 0x16, 0xBC, 0x52, 0xBC, 0x3D, 0xB4, 0x2A, 0xA3, 0xF1, 0xEC, 0xC5, 0x67, 0xF0, 0x89, 0x7C, 0x06, - 0x03, 0x0A, 0x2A, 0xE9, 0x37, 0x58, 0x7A, 0x7B, 0xA2, 0x9B, 0x5B, 0xBB, 0x9B, 0xE1, 0xEC, 0x54, - 0x4A, 0x77, 0x35, 0x9C, 0x7D, 0xBF, 0x61, 0xEE, 0x86, 0xFB, 0xED, 0x56, 0xFB, 0x6D, 0xBB, 0xFB, - 0x76, 0xFF, 0xCD, 0x5B, 0xD6, 0xEC, 0xB4, 0x0F, 0x5A, 0x9D, 0xA3, 0x83, 0xF6, 0xC1, 0x9B, 0xC3, - 0x0E, 0xEB, 0x1C, 0x1C, 0xC2, 0x77, 0x47, 0x6F, 0xEB, 0xF5, 0x35, 0x5C, 0xC3, 0x78, 0x81, 0xA3, - 0xE1, 0x1A, 0x86, 0x2A, 0xE1, 0x65, 0x98, 0x39, 0x8B, 0x4A, 0x36, 0xEA, 0xC5, 0x66, 0xFC, 0xE2, - 0x62, 0x98, 0xE1, 0x62, 0x38, 0x2F, 0x44, 0xD6, 0xEE, 0x66, 0x18, 0x0C, 0xB1, 0x02, 0x57, 0xC3, - 0x55, 0xCF, 0x3E, 0x3A, 0xC6, 0x6A, 0x5C, 0x0E, 0x57, 0xBD, 0x82, 0xF8, 0x28, 0x5B, 0xEF, 0x7A, - 0x18, 0x3D, 0xBA, 0x7E, 0x18, 0x0F, 0xC4, 0xED, 0xAC, 0xD3, 0x3E, 0xE4, 0xCE, 0x3D, 0xD6, 0x69, - 0x8D, 0xD5, 0x69, 0x17, 0x0F, 0xD7, 0x56, 0xA7, 0x3D, 0x98, 0xC3, 0xD3, 0xD4, 0x69, 0x77, 0x69, - 0x74, 0x14, 0xBC, 0x7D, 0x9B, 0x90, 0x3B, 0xC8, 0x53, 0xF2, 0xCA, 0x9D, 0x2B, 0xD8, 0x4E, 0x59, - 0xD3, 0xE6, 0xCA, 0xB5, 0x7F, 0xA1, 0x84, 0x25, 0xA2, 0x5E, 0xBB, 0x90, 0xE6, 0x3D, 0xBC, 0x3C, - 0x51, 0x54, 0x4C, 0xFF, 0x21, 0x15, 0xE2, 0x78, 0x3F, 0xBE, 0xC8, 0x0A, 0x62, 0xC6, 0x4A, 0xC5, - 0x3F, 0x9F, 0x1A, 0xEE, 0x62, 0x43, 0x17, 0x4D, 0x27, 0xF1, 0xAE, 0x44, 0x6D, 0x99, 0xD4, 0x0C, - 0x9D, 0x25, 0xCB, 0xAC, 0xC5, 0xB9, 0x7C, 0x21, 0x07, 0x28, 0x55, 0x6A, 0x6D, 0x6E, 0xD9, 0xED, - 0x8C, 0x64, 0x9D, 0x85, 0xC3, 0x25, 0x92, 0x79, 0xA6, 0x74, 0x5C, 0xCC, 0xB4, 0xA2, 0x54, 0xCC, - 0x3A, 0x98, 0xA1, 0xB3, 0x86, 0xDA, 0x6A, 0x02, 0x05, 0x0A, 0xEB, 0xAB, 0x55, 0xF0, 0xB7, 0x8E, - 0xE7, 0xED, 0xAC, 0xBC, 0xD2, 0xFA, 0xCB, 0x61, 0xD5, 0xEE, 0x47, 0x13, 0x5D, 0x13, 0x55, 0x64, - 0xFC, 0x64, 0xB9, 0xDE, 0x02, 0xA5, 0x7C, 0x56, 0x50, 0x42, 0x3C, 0xF8, 0x87, 0x33, 0x3A, 0x5E, - 0xD6, 0x8B, 0xE3, 0xA8, 0x92, 0x95, 0xAB, 0xB2, 0xA5, 0x2B, 0x03, 0x8A, 0x15, 0x46, 0xB3, 0xF3, - 0x3A, 0x5A, 0xD6, 0xF6, 0x55, 0xDD, 0x67, 0xE4, 0x89, 0xB1, 0x70, 0x60, 0x39, 0x1B, 0x86, 0x85, - 0x38, 0xA3, 0xA7, 0xC6, 0xC2, 0xC2, 0x3B, 0x8F, 0x2C, 0x38, 0x2E, 0x8F, 0x87, 0xA2, 0xA3, 0x1F, - 0x0E, 0x0F, 0xB1, 0x48, 0xFB, 0x66, 0xE1, 0x21, 0xCE, 0x68, 0xDB, 0xB8, 0xA1, 0x84, 0xE2, 0xF2, - 0x58, 0x28, 0x3A, 0xFA, 0x21, 0xB1, 0x70, 0xF0, 0x73, 0x4D, 0x78, 0x98, 0x55, 0x45, 0x7D, 0x01, - 0x3C, 0x2C, 0x5D, 0x2D, 0x3D, 0x07, 0x15, 0xDF, 0x54, 0xBA, 0x02, 0xAE, 0x05, 0x15, 0x09, 0x94, - 0xF5, 0x20, 0x23, 0x76, 0xF5, 0x03, 0xA1, 0xE3, 0xAC, 0x80, 0xFC, 0x8A, 0x99, 0x22, 0x0D, 0x54, - 0xE1, 0x6C, 0x86, 0x19, 0x6D, 0x0F, 0x53, 0x8C, 0x41, 0x71, 0x19, 0x3C, 0x8C, 0x76, 0xF4, 0x43, - 0x62, 0xE1, 0xCA, 0x99, 0xE2, 0x02, 0x78, 0xB8, 0x55, 0x4C, 0x31, 0x01, 0xCA, 0x7A, 0x90, 0xF1, - 0x69, 0x98, 0xE2, 0x12, 0xAF, 0x94, 0x31, 0x09, 0x6C, 0xBD, 0xBD, 0xA7, 0xB3, 0x2A, 0x7B, 0x4F, - 0xA7, 0xAA, 0xBD, 0xA7, 0xBB, 0xAD, 0xF6, 0x9E, 0xCE, 0x73, 0xB5, 0xF7, 0x74, 0x5E, 0xEC, 0x3D, - 0x35, 0xD8, 0x7B, 0x3A, 0x75, 0xD9, 0x7B, 0x3A, 0x3F, 0xA6, 0xBD, 0xA7, 0xF3, 0x62, 0xEF, 0xA9, - 0xC5, 0xDE, 0xD3, 0xA9, 0xCB, 0xDE, 0xD3, 0xF9, 0x31, 0xED, 0x3D, 0x9D, 0x17, 0x7B, 0x4F, 0x0D, - 0xF6, 0x9E, 0x4E, 0x5D, 0xF6, 0x9E, 0xCE, 0x8F, 0x6A, 0xEF, 0xE9, 0xBC, 0xD8, 0x7B, 0xEA, 0xB2, - 0xF7, 0x74, 0xEA, 0xB3, 0xF7, 0x74, 0x7E, 0x4C, 0x7B, 0x4F, 0xE7, 0xC5, 0xDE, 0x53, 0x83, 0xBD, - 0xA7, 0x53, 0x97, 0xBD, 0xA7, 0xF3, 0xA3, 0xDA, 0x7B, 0x3A, 0x2F, 0xF6, 0x9E, 0xBA, 0xEC, 0x3D, - 0x9D, 0xFA, 0xEC, 0x3D, 0x9D, 0x17, 0x7B, 0xCF, 0xA6, 0xD9, 0x7B, 0xBA, 0xAB, 0xB2, 0xF7, 0x74, - 0xAB, 0xDA, 0x7B, 0x7A, 0xDB, 0x6A, 0xEF, 0xE9, 0x3E, 0x57, 0x7B, 0x4F, 0xF7, 0xC5, 0xDE, 0x53, - 0x83, 0xBD, 0xA7, 0x5B, 0x97, 0xBD, 0xA7, 0xFB, 0x63, 0xDA, 0x7B, 0xBA, 0x2F, 0xF6, 0x9E, 0x5A, - 0xEC, 0x3D, 0xDD, 0xBA, 0xEC, 0x3D, 0xDD, 0x1F, 0xD3, 0xDE, 0xD3, 0x7D, 0xB1, 0xF7, 0xD4, 0x60, - 0xEF, 0xE9, 0xD6, 0x65, 0xEF, 0xE9, 0xFE, 0xA8, 0xF6, 0x9E, 0xEE, 0x8B, 0xBD, 0xA7, 0x2E, 0x7B, - 0x4F, 0xB7, 0x3E, 0x7B, 0x4F, 0xF7, 0xC7, 0xB4, 0xF7, 0x74, 0x5F, 0xEC, 0x3D, 0x35, 0xD8, 0x7B, - 0xBA, 0x75, 0xD9, 0x7B, 0xBA, 0x3F, 0xAA, 0xBD, 0xA7, 0xFB, 0x62, 0xEF, 0xA9, 0xCB, 0xDE, 0xD3, - 0xAD, 0xCF, 0xDE, 0xD3, 0x7D, 0xB1, 0xF7, 0x6C, 0x9A, 0xBD, 0xA7, 0xB7, 0x2A, 0x7B, 0x4F, 0xAF, - 0xAA, 0xBD, 0x67, 0x7F, 0x5B, 0xED, 0x3D, 0xBD, 0xE7, 0x6A, 0xEF, 0xE9, 0xBD, 0xD8, 0x7B, 0x6A, - 0xB0, 0xF7, 0xF4, 0xEA, 0xB2, 0xF7, 0xF4, 0x7E, 0x4C, 0x7B, 0x4F, 0xEF, 0xC5, 0xDE, 0x53, 0x8B, - 0xBD, 0xA7, 0x57, 0x97, 0xBD, 0xA7, 0xF7, 0x63, 0xDA, 0x7B, 0x7A, 0x2F, 0xF6, 0x9E, 0x1A, 0xEC, - 0x3D, 0xBD, 0xBA, 0xEC, 0x3D, 0xBD, 0x1F, 0xD5, 0xDE, 0xD3, 0x7B, 0xB1, 0xF7, 0xD4, 0x65, 0xEF, - 0xE9, 0xD5, 0x67, 0xEF, 0xE9, 0xFD, 0x98, 0xF6, 0x9E, 0xDE, 0x8B, 0xBD, 0xA7, 0x06, 0x7B, 0x4F, - 0xAF, 0x2E, 0x7B, 0x4F, 0xEF, 0x47, 0xB5, 0xF7, 0xF4, 0x5E, 0xEC, 0x3D, 0x75, 0xD9, 0x7B, 0x7A, - 0xF5, 0xD9, 0x7B, 0x7A, 0xCF, 0xC6, 0xDE, 0x53, 0x94, 0x23, 0x28, 0xA7, 0x57, 0x69, 0x03, 0x0A, - 0x73, 0xA2, 0x8D, 0xB9, 0xF7, 0x99, 0xBB, 0xAE, 0x32, 0xE6, 0x57, 0xBA, 0xEB, 0x61, 0xE1, 0x4A, - 0xAA, 0x10, 0xB0, 0x90, 0x89, 0x28, 0x3F, 0x2D, 0x54, 0x2C, 0xE9, 0x5B, 0x29, 0xF3, 0x50, 0xF0, - 0x1C, 0x53, 0xEC, 0x0B, 0xE3, 0xC6, 0x67, 0x77, 0x8C, 0x53, 0xCC, 0x1F, 0x29, 0xD5, 0x82, 0x94, - 0xB4, 0x10, 0x65, 0xF7, 0x9D, 0xBF, 0x6B, 0x37, 0xB7, 0x67, 0x9F, 0xD9, 0x0D, 0x25, 0x87, 0x7D, - 0xA7, 0x13, 0xBA, 0x61, 0x12, 0x2B, 0x68, 0x7B, 0x86, 0x16, 0xA1, 0x46, 0x1D, 0x26, 0xA3, 0x12, - 0xE6, 0xA2, 0xD2, 0x99, 0xBA, 0x68, 0x86, 0x8E, 0xA7, 0x4E, 0x71, 0xCA, 0x97, 0xE6, 0xC8, 0x2A, - 0xAE, 0x2D, 0x27, 0xF3, 0x77, 0xD1, 0x42, 0x31, 0x6D, 0xBC, 0xA3, 0x98, 0xEE, 0x54, 0xF7, 0x22, - 0x25, 0x0F, 0x70, 0xC5, 0x4C, 0xC1, 0x1C, 0xD5, 0x9A, 0x48, 0xA5, 0x85, 0xA9, 0x76, 0x3B, 0x9F, - 0xFE, 0xA4, 0x5C, 0xF0, 0x53, 0x81, 0x4D, 0x2E, 0xEB, 0xB4, 0xDB, 0x07, 0xBB, 0xF0, 0xF3, 0xCD, - 0x3E, 0xFE, 0x3C, 0xA2, 0x9F, 0x6F, 0xF1, 0x67, 0xA7, 0xBB, 0x2F, 0x12, 0xCC, 0xB7, 0x5B, 0x41, - 0xA3, 0x4E, 0xB7, 0xD7, 0x96, 0x99, 0xEA, 0x65, 0x9A, 0x5E, 0xC3, 0x7A, 0xA0, 0xAA, 0x0C, 0xF8, - 0x2D, 0xD5, 0xB9, 0x70, 0x45, 0x55, 0x14, 0x78, 0x0E, 0xE3, 0x9B, 0x1A, 0x25, 0x3D, 0xC5, 0xA4, - 0x77, 0x9E, 0xA2, 0x1B, 0x96, 0x23, 0xAB, 0x29, 0xC8, 0xB9, 0x42, 0xEF, 0x8F, 0x7B, 0x8A, 0x61, - 0x88, 0xDD, 0x0A, 0x66, 0xD4, 0x62, 0x57, 0x3A, 0x7C, 0xE9, 0x1E, 0xB3, 0x36, 0xBE, 0xDC, 0x6D, - 0x47, 0xAB, 0x35, 0x88, 0x1A, 0x2C, 0x04, 0x3B, 0x18, 0xCF, 0xA3, 0x7A, 0x0D, 0x16, 0x70, 0x10, - 0x47, 0xD7, 0x34, 0x6E, 0xE2, 0xFB, 0x38, 0x57, 0x2A, 0xD7, 0xA2, 0x9B, 0x0C, 0x11, 0x85, 0x4D, - 0x2D, 0x8D, 0x6F, 0x57, 0xEA, 0xB0, 0x54, 0x0B, 0xE2, 0x22, 0x94, 0x50, 0xBF, 0x11, 0x91, 0x7A, - 0x8C, 0x37, 0xBD, 0xB3, 0x80, 0x0A, 0xA6, 0x41, 0xEB, 0x42, 0x8E, 0x9B, 0x9A, 0x5C, 0x32, 0x3D, - 0x91, 0x64, 0xA4, 0x30, 0x8A, 0xC3, 0x5D, 0xEE, 0xDD, 0x5A, 0x88, 0x28, 0x32, 0x2F, 0x1C, 0x55, - 0x75, 0xBD, 0xC1, 0xC7, 0xB0, 0xEB, 0xA5, 0xCE, 0x84, 0xA0, 0x61, 0xB9, 0x3C, 0x92, 0x65, 0xEB, - 0xCE, 0x3C, 0x2D, 0x30, 0xAE, 0xAC, 0x87, 0xD3, 0x80, 0xCC, 0x42, 0x80, 0x94, 0x82, 0x06, 0x66, - 0xA6, 0x04, 0x22, 0x0D, 0x5B, 0x03, 0xD5, 0x99, 0xDF, 0x2A, 0x81, 0xA6, 0x18, 0x36, 0x88, 0xB7, - 0xD3, 0xF8, 0xB1, 0xD5, 0x58, 0x75, 0xFA, 0xC8, 0x12, 0x8F, 0xD3, 0x06, 0x79, 0xF7, 0x0F, 0xCD, - 0x26, 0x6B, 0x06, 0xFF, 0x02, 0x71, 0x8C, 0x3B, 0x23, 0x4C, 0x1C, 0x2D, 0xE8, 0x2D, 0xF2, 0x75, - 0xB3, 0x99, 0xE8, 0x31, 0x42, 0x68, 0x1A, 0xC8, 0xAA, 0xBA, 0xC6, 0xC6, 0x8A, 0x9D, 0x5A, 0xD0, - 0x39, 0xE3, 0x7A, 0x27, 0xF3, 0x3E, 0x07, 0x61, 0x68, 0xDB, 0x41, 0xFA, 0xC0, 0x32, 0xC7, 0xF3, - 0x4F, 0xD9, 0x17, 0x3D, 0xC9, 0x23, 0x7B, 0x30, 0x08, 0x3A, 0xAE, 0x74, 0x1A, 0x87, 0xCD, 0x52, - 0x87, 0x8A, 0x67, 0xFD, 0xCE, 0xD8, 0x70, 0x21, 0xED, 0xC5, 0xE0, 0xEB, 0x3B, 0xA2, 0x34, 0x89, - 0x3C, 0xB0, 0xED, 0xC8, 0x1B, 0xCB, 0x9F, 0xDA, 0xE9, 0x98, 0x9D, 0x86, 0x1C, 0x85, 0x1C, 0x38, - 0x5C, 0x7D, 0xCA, 0x28, 0xD9, 0x0C, 0x77, 0x21, 0x39, 0xF0, 0x9C, 0xD2, 0x68, 0xB2, 0xCB, 0xF3, - 0xE3, 0x40, 0x6A, 0x9E, 0x40, 0x87, 0x0F, 0xB0, 0xD8, 0xCB, 0xF3, 0x9C, 0xF4, 0xEA, 0x7B, 0x7D, - 0x14, 0x94, 0x33, 0xF3, 0xA3, 0x97, 0xCA, 0x5D, 0x19, 0x05, 0xFF, 0x50, 0x24, 0xF7, 0x3C, 0x77, - 0x2C, 0x5B, 0x80, 0xB8, 0x28, 0xE3, 0x2A, 0xA9, 0x5D, 0x29, 0x3D, 0x34, 0x4E, 0x62, 0xFB, 0x2E, - 0x9F, 0x16, 0xEB, 0x3C, 0xF1, 0x0C, 0xEE, 0x69, 0x1D, 0x67, 0xCD, 0x39, 0xAE, 0xCB, 0x68, 0x72, - 0x05, 0x45, 0xD5, 0xD6, 0x8B, 0x73, 0x6F, 0xD7, 0x9B, 0x85, 0x15, 0x45, 0x1B, 0x91, 0x32, 0x15, - 0xC4, 0x27, 0x10, 0x88, 0x14, 0x90, 0xE3, 0xA6, 0x36, 0x95, 0x10, 0xF1, 0x41, 0x84, 0x89, 0x01, - 0x0D, 0x45, 0xAD, 0x59, 0x0A, 0x55, 0xB7, 0xC5, 0x22, 0x8D, 0xA7, 0xBE, 0xEB, 0xA1, 0x58, 0xE6, - 0xF0, 0xB1, 0xEE, 0x8A, 0x7A, 0x59, 0xDE, 0x04, 0x34, 0xE7, 0xF1, 0x84, 0x0D, 0x6D, 0xC5, 0xF9, - 0xF6, 0xC1, 0xC7, 0xC2, 0x73, 0x78, 0x81, 0xBA, 0x47, 0x32, 0x97, 0xCC, 0xDA, 0x0A, 0xEF, 0xFF, - 0xE1, 0xEB, 0x70, 0xAC, 0xB0, 0x9F, 0xF5, 0x0F, 0x7A, 0x4A, 0xEA, 0xD5, 0x4D, 0x12, 0x9F, 0x22, - 0x2A, 0x64, 0xCA, 0x7E, 0x2F, 0xA2, 0x3C, 0x96, 0xA3, 0x07, 0xD0, 0x55, 0x3D, 0x4C, 0x75, 0xEB, - 0x5E, 0xE1, 0x99, 0x79, 0xDD, 0xCF, 0x64, 0x02, 0xE5, 0xAF, 0xFA, 0xCF, 0xB1, 0xCE, 0x18, 0xA8, - 0xBE, 0xBA, 0xC1, 0xBE, 0x71, 0xF8, 0x13, 0xF8, 0x2F, 0xEC, 0x42, 0x48, 0xEB, 0x1A, 0x7C, 0x7D, - 0xC3, 0xA7, 0x8A, 0x6E, 0xC2, 0xB0, 0x39, 0xE4, 0x6E, 0xB1, 0xBF, 0x42, 0xEB, 0x5C, 0xDD, 0xB8, - 0xCA, 0xCD, 0x75, 0xF9, 0xFC, 0xCA, 0x11, 0x8A, 0xCF, 0xCF, 0xB1, 0x8C, 0xF8, 0xC5, 0x5D, 0x0F, - 0xA6, 0xF9, 0xD5, 0x06, 0x42, 0x29, 0xE1, 0x29, 0x90, 0xDC, 0xDE, 0xB0, 0xE9, 0x95, 0xB0, 0xAE, - 0xDC, 0x88, 0x1E, 0x71, 0xE5, 0x4C, 0x7C, 0x51, 0xAE, 0x78, 0xC6, 0x32, 0x59, 0x9A, 0xE7, 0x56, - 0x51, 0x81, 0x2A, 0x96, 0xCB, 0x40, 0x2E, 0xD9, 0xC4, 0xCF, 0xA8, 0xD7, 0xC8, 0xB2, 0x80, 0x22, - 0xE3, 0x78, 0x8C, 0x33, 0x10, 0x0E, 0x11, 0xFF, 0xB8, 0x13, 0x24, 0x0D, 0x93, 0x05, 0x0E, 0x80, - 0x3A, 0x9C, 0x4F, 0x13, 0xD6, 0x50, 0x1D, 0xC4, 0x66, 0x26, 0x90, 0x24, 0xB3, 0x6C, 0x2C, 0x91, - 0xE7, 0x9B, 0xBA, 0xF7, 0x58, 0x9D, 0xE4, 0x57, 0x42, 0xF6, 0xA5, 0x48, 0xBF, 0x0C, 0x26, 0xE3, - 0x6E, 0x8D, 0xB9, 0x35, 0x76, 0x14, 0x7B, 0xA2, 0xAB, 0x37, 0xC0, 0x0D, 0x2D, 0xB3, 0xC4, 0xE9, - 0x95, 0x3C, 0xC1, 0x92, 0x5D, 0x34, 0x4E, 0x3E, 0x86, 0x4F, 0x98, 0x78, 0x54, 0xCE, 0x5E, 0x17, - 0x3F, 0xBF, 0xE6, 0xBA, 0x4D, 0x9D, 0xEF, 0x62, 0x27, 0x57, 0x38, 0x62, 0xBC, 0xD6, 0x45, 0xBB, - 0x71, 0xF2, 0x75, 0x58, 0xBE, 0xFE, 0xC4, 0x7C, 0xD1, 0x91, 0x8B, 0xAF, 0x0B, 0xB7, 0x86, 0xE9, - 0xF6, 0x17, 0x6F, 0x0D, 0xFC, 0xE7, 0xAF, 0x37, 0x0B, 0xB7, 0xDE, 0x6F, 0x9C, 0xFC, 0x77, 0x05, - 0xF0, 0xA9, 0x5C, 0x07, 0xE5, 0x4A, 0x6E, 0xD4, 0x4F, 0xD7, 0x43, 0x81, 0x1D, 0x8F, 0x96, 0xEF, - 0xB0, 0x19, 0x1A, 0xD0, 0x29, 0x8E, 0x95, 0x62, 0xC9, 0xE0, 0xA2, 0xF1, 0x11, 0xB0, 0x7B, 0x91, - 0x41, 0xFD, 0xAA, 0x89, 0x47, 0x10, 0x1B, 0x11, 0x8D, 0x9B, 0xEA, 0x23, 0x91, 0xB8, 0xC0, 0x1A, - 0xC5, 0x00, 0x69, 0x3A, 0xCC, 0xAF, 0x0E, 0x6A, 0xBD, 0xAE, 0x46, 0x88, 0xFB, 0xEB, 0x70, 0x53, - 0xC9, 0x5A, 0xA8, 0x46, 0xCE, 0xC6, 0x9E, 0x60, 0x8A, 0xEF, 0x59, 0xC0, 0xF8, 0x6F, 0xB8, 0xC9, - 0x1F, 0x14, 0x38, 0x7F, 0xFA, 0xF0, 0x99, 0x0E, 0x1F, 0xF9, 0x84, 0xAD, 0xFE, 0xF8, 0x49, 0x4E, - 0xE1, 0x29, 0x0E, 0x1F, 0x3A, 0x62, 0x90, 0x17, 0xC1, 0x11, 0x83, 0x36, 0xBE, 0xEE, 0x11, 0x43, - 0x29, 0x05, 0x05, 0x55, 0x12, 0x5E, 0x1E, 0x77, 0x19, 0x4E, 0x13, 0x8B, 0x4C, 0x62, 0x19, 0xDA, - 0xC7, 0xA8, 0x24, 0x0B, 0x98, 0x64, 0x22, 0x9A, 0xC3, 0x9F, 0xAF, 0x3E, 0x59, 0x53, 0xFE, 0x0A, - 0x8E, 0x21, 0xEF, 0xC1, 0x72, 0xBE, 0xED, 0x32, 0xCB, 0x04, 0x21, 0x54, 0xC1, 0xAE, 0x76, 0xF1, - 0x6B, 0x07, 0x97, 0x48, 0x63, 0x45, 0x70, 0x57, 0x14, 0x65, 0xD8, 0xEE, 0x73, 0x69, 0x91, 0x1B, - 0xAD, 0x2C, 0x95, 0x4A, 0xE8, 0x86, 0x03, 0xC7, 0x1A, 0xE9, 0x06, 0xBF, 0xB5, 0xBE, 0xF1, 0x12, - 0xEE, 0x9E, 0x85, 0xD7, 0xA9, 0xF3, 0x55, 0x17, 0xA5, 0x0A, 0x2A, 0xC7, 0x61, 0x34, 0xD0, 0x71, - 0xB5, 0x2D, 0x58, 0xBE, 0xFA, 0xCA, 0xAC, 0x6A, 0x30, 0xF1, 0x48, 0xCB, 0x19, 0x2B, 0xA6, 0xFE, - 0xA7, 0x30, 0x17, 0x4C, 0x14, 0x17, 0xEB, 0x50, 0x58, 0x0E, 0x48, 0x33, 0x68, 0x11, 0x06, 0x6E, - 0x69, 0x8E, 0x87, 0x9E, 0xC3, 0x95, 0x29, 0xF1, 0xC5, 0x98, 0x88, 0xA4, 0xA8, 0x2A, 0xDE, 0x35, - 0xED, 0x8A, 0x9A, 0x17, 0xF0, 0xFF, 0x87, 0x09, 0x68, 0x49, 0xD8, 0x2B, 0x43, 0xC2, 0xA4, 0xDE, - 0x55, 0x50, 0xA2, 0xAC, 0x69, 0xA0, 0x52, 0xD9, 0x72, 0xE1, 0x1E, 0x2E, 0x3C, 0x8A, 0x8E, 0x80, - 0xD5, 0x8F, 0xAC, 0xC9, 0x44, 0x01, 0x0D, 0x1E, 0xEA, 0x57, 0x02, 0x42, 0x8D, 0x05, 0x8A, 0xD4, - 0xD4, 0x59, 0xD5, 0xA5, 0x1C, 0x46, 0x97, 0xE1, 0x58, 0x59, 0x97, 0xDD, 0x6F, 0xCA, 0x10, 0x62, - 0x85, 0x9B, 0xC5, 0x02, 0xD4, 0x2E, 0x31, 0x98, 0x5D, 0xA2, 0x9F, 0x65, 0xEE, 0x16, 0x6B, 0xF0, - 0xFC, 0xA6, 0x19, 0x82, 0x46, 0xDF, 0x77, 0x5D, 0xD0, 0xCF, 0xAF, 0xAD, 0x87, 0xB3, 0x80, 0xD5, - 0x57, 0xAC, 0x70, 0x5E, 0xFA, 0x70, 0x2B, 0x7D, 0xC0, 0x45, 0x67, 0x05, 0xC7, 0x5B, 0xF0, 0x67, - 0x85, 0x7A, 0x9F, 0xCB, 0x9C, 0x6D, 0xF1, 0xD1, 0x9F, 0x88, 0xBD, 0xD0, 0x09, 0x17, 0x96, 0x25, - 0x9F, 0x81, 0xE0, 0xF3, 0xC7, 0xBE, 0xA8, 0x54, 0x33, 0xAF, 0x5B, 0xC1, 0x61, 0xA5, 0x4F, 0x81, - 0x45, 0xDC, 0xCB, 0x0A, 0xE3, 0x8A, 0xFA, 0x87, 0xAF, 0xBB, 0x3A, 0x31, 0x26, 0x1B, 0x90, 0x10, - 0xEB, 0x2D, 0x9B, 0x58, 0x16, 0x67, 0x11, 0xFD, 0x6A, 0x03, 0x38, 0x44, 0x6D, 0x18, 0x8F, 0x45, - 0x04, 0x0D, 0xFD, 0x4F, 0xAE, 0xC1, 0xFA, 0x3D, 0x47, 0xBF, 0xF3, 0xA9, 0xC6, 0xE2, 0x26, 0x61, - 0x7F, 0xEA, 0x0C, 0x45, 0xF5, 0x43, 0x7A, 0xCC, 0xA2, 0xCF, 0x6B, 0x2C, 0x93, 0xBB, 0x24, 0xD9, - 0x64, 0x4C, 0x7B, 0x23, 0x48, 0xC8, 0x08, 0x61, 0x17, 0x31, 0x58, 0x92, 0x01, 0x93, 0x0E, 0x5A, - 0x43, 0x16, 0x96, 0x0C, 0xE9, 0x8A, 0x8A, 0xBE, 0xEA, 0x26, 0x50, 0x96, 0x12, 0x56, 0x4B, 0xC7, - 0x43, 0x02, 0x98, 0xB4, 0xE9, 0x81, 0x8C, 0x1D, 0x33, 0x7B, 0x6E, 0x33, 0x45, 0x95, 0xBB, 0x3A, - 0x33, 0xD2, 0xB6, 0xF6, 0x16, 0x8E, 0xB2, 0x2B, 0x7E, 0xCF, 0x8D, 0x92, 0xF6, 0x8C, 0xA4, 0x08, - 0x99, 0xDF, 0x69, 0x16, 0xBE, 0x33, 0x7C, 0x83, 0xD1, 0x2B, 0xE5, 0x3D, 0x94, 0xE2, 0x56, 0x8F, - 0x82, 0x81, 0x4B, 0xAC, 0xB8, 0x1C, 0x26, 0x2E, 0x63, 0x35, 0x49, 0xB7, 0x9C, 0x74, 0xDA, 0xED, - 0x36, 0xFB, 0x8E, 0x9E, 0x12, 0xED, 0x6F, 0x53, 0x12, 0xF4, 0x5C, 0x5E, 0xB1, 0x96, 0xE7, 0x9C, - 0x3D, 0xE5, 0x80, 0xBA, 0x3C, 0xA8, 0xAB, 0x47, 0x58, 0x5C, 0xF7, 0x00, 0x7B, 0x84, 0x9F, 0xF5, - 0xF4, 0xD8, 0x4B, 0xAE, 0xFB, 0x13, 0x30, 0x03, 0x20, 0x3A, 0x13, 0x4E, 0xB7, 0xC7, 0xA5, 0x7A, - 0xDE, 0x8F, 0xAF, 0xBE, 0xB6, 0x7E, 0x0F, 0xE2, 0x30, 0x58, 0xAC, 0xDF, 0x0A, 0x55, 0x57, 0x57, - 0xC2, 0x40, 0xA5, 0x29, 0x08, 0x39, 0xDF, 0x8C, 0x7B, 0x6A, 0x51, 0x4A, 0xF4, 0x90, 0x12, 0x0D, - 0xA4, 0x87, 0x56, 0x6C, 0x8D, 0xA8, 0xCD, 0x60, 0xDD, 0xC9, 0x29, 0x0C, 0xAD, 0x71, 0xAD, 0x25, - 0x91, 0x80, 0x4D, 0x95, 0x47, 0xE4, 0xAD, 0x1A, 0xB7, 0xE1, 0x5B, 0x34, 0x02, 0x47, 0x58, 0x67, - 0x16, 0xBC, 0xB6, 0x81, 0x95, 0x16, 0x5A, 0x8C, 0x2A, 0x48, 0x30, 0xEB, 0x70, 0x28, 0x70, 0x3C, - 0xF7, 0xE9, 0x1D, 0x09, 0x70, 0x16, 0xAB, 0xF2, 0x25, 0x88, 0xF6, 0x5D, 0xCD, 0x9D, 0x20, 0xD2, - 0x32, 0xCB, 0x5B, 0x60, 0x06, 0xBD, 0x39, 0x37, 0x01, 0x6C, 0xBC, 0x51, 0xFE, 0x01, 0xB9, 0xCB, - 0x59, 0xCC, 0x45, 0x20, 0xC5, 0x72, 0x04, 0x1B, 0x9C, 0x5F, 0x39, 0x12, 0x11, 0xF0, 0x83, 0xE5, - 0xCC, 0x2E, 0x96, 0xBD, 0x09, 0x56, 0xD9, 0x04, 0xAA, 0xE4, 0x0E, 0xDA, 0x89, 0xCF, 0xFB, 0xB7, - 0x7D, 0x86, 0xE0, 0xDB, 0x65, 0xEE, 0x04, 0xD4, 0x9C, 0x91, 0x0F, 0x52, 0x98, 0x64, 0xA9, 0xE8, - 0x56, 0x95, 0xC4, 0xCD, 0x54, 0x19, 0x25, 0xE8, 0x0D, 0x17, 0xFD, 0x85, 0xDA, 0xBA, 0x65, 0xA4, - 0x79, 0xBA, 0x4E, 0x43, 0x7F, 0x41, 0x6C, 0x77, 0x36, 0x51, 0x4C, 0x33, 0x22, 0xD0, 0x04, 0x8B, - 0x2D, 0x7B, 0xD5, 0x11, 0x91, 0x6E, 0xC2, 0x3E, 0x4F, 0x15, 0x1F, 0x04, 0xC2, 0x1B, 0xFC, 0x48, - 0xD8, 0xC3, 0xF0, 0x01, 0x79, 0x84, 0x1E, 0xB3, 0x05, 0x05, 0x98, 0x78, 0xDF, 0xF1, 0x25, 0x88, - 0x47, 0x69, 0xA2, 0x47, 0x59, 0x56, 0x8A, 0xBB, 0x75, 0x3B, 0xE1, 0xE8, 0xB2, 0xE9, 0x70, 0x29, - 0xF9, 0x4E, 0x6D, 0x40, 0x75, 0xAC, 0x44, 0x2B, 0x76, 0x45, 0x88, 0xCE, 0xBF, 0x5D, 0x9C, 0x37, - 0x3F, 0xBC, 0x1D, 0x90, 0x6D, 0x6B, 0x6A, 0xB9, 0x8A, 0xAE, 0xE6, 0xEE, 0x54, 0xDE, 0x41, 0x7C, - 0xD4, 0x06, 0xE9, 0x06, 0x7F, 0x2E, 0x75, 0xEE, 0xBE, 0x3D, 0xC4, 0x6E, 0xF0, 0xE7, 0x72, 0x42, - 0xD1, 0xDB, 0x2E, 0xF6, 0x43, 0xBF, 0x96, 0x93, 0x5C, 0x8E, 0xF6, 0xB1, 0x23, 0xFA, 0xB5, 0x9C, - 0x40, 0xF1, 0x86, 0x56, 0x46, 0xBF, 0x96, 0x5B, 0x5A, 0xE7, 0x40, 0xAC, 0x8D, 0x7E, 0x2F, 0x27, - 0xE8, 0xF5, 0xDA, 0xB4, 0x3A, 0xF1, 0x7B, 0x39, 0x39, 0xEC, 0xB0, 0x2D, 0x10, 0x80, 0x7E, 0x2F, - 0x87, 0x02, 0xDD, 0x8E, 0x40, 0x02, 0xFA, 0xBD, 0x3D, 0xD2, 0xD6, 0x2D, 0xB9, 0x49, 0x03, 0x63, - 0x20, 0xCB, 0x31, 0x52, 0x17, 0x12, 0xDE, 0x4D, 0xFF, 0xFC, 0xF2, 0x0B, 0x71, 0xC6, 0xC0, 0xCD, - 0x59, 0x05, 0x0E, 0x35, 0x16, 0xE6, 0x9E, 0xA9, 0xE2, 0xA9, 0xC0, 0x47, 0x51, 0x57, 0x75, 0xB0, - 0x28, 0xF2, 0xC4, 0x42, 0xE6, 0x0A, 0xCA, 0x2A, 0xF1, 0x82, 0x88, 0x6C, 0x45, 0x68, 0x73, 0x67, - 0xBB, 0xE8, 0xFD, 0x2C, 0x36, 0x1E, 0x3E, 0x3C, 0x37, 0xC1, 0xAA, 0x1C, 0xA7, 0xC7, 0xBD, 0xAA, - 0x99, 0xD1, 0x27, 0xBA, 0x6C, 0x9C, 0x7C, 0xF6, 0xBF, 0x33, 0xF9, 0x61, 0x61, 0x0E, 0x9F, 0xEC, - 0x34, 0x6D, 0xF2, 0xCB, 0x71, 0xF9, 0x39, 0xDD, 0xF2, 0xFA, 0xF3, 0x45, 0x7F, 0x59, 0x5D, 0x72, - 0x30, 0x18, 0xEE, 0x5D, 0xDC, 0xA3, 0x4B, 0xFC, 0x2D, 0x90, 0xC0, 0x18, 0x8B, 0x95, 0x2F, 0xA5, - 0x4A, 0x0A, 0xBF, 0x5D, 0xFF, 0xBB, 0x5C, 0x31, 0x6C, 0xCD, 0x65, 0xF7, 0x6C, 0x59, 0x65, 0xB2, - 0x7F, 0x7E, 0xB6, 0x77, 0xDE, 0x3F, 0xDB, 0x2E, 0xDE, 0x10, 0x8A, 0x48, 0x21, 0x23, 0x90, 0x22, - 0xA8, 0x0C, 0x79, 0xD0, 0xF4, 0xD1, 0x88, 0x3B, 0x08, 0x79, 0xC5, 0xB6, 0x0D, 0x5D, 0x98, 0xB3, - 0xDC, 0x16, 0xC3, 0x5D, 0x45, 0x7D, 0x8C, 0x0C, 0x5A, 0xF8, 0x22, 0x30, 0x0B, 0x1D, 0x44, 0xAE, - 0xDB, 0x5F, 0xF6, 0x6E, 0x7E, 0x41, 0x66, 0x11, 0x9A, 0xBE, 0x90, 0xAE, 0x9D, 0x29, 0xFD, 0xDD, - 0x62, 0xB8, 0x91, 0x72, 0x0B, 0x63, 0xAD, 0x6D, 0x1F, 0xC4, 0x67, 0xB4, 0x27, 0x43, 0x3F, 0x30, - 0x03, 0x8D, 0x59, 0xBE, 0x87, 0x46, 0x43, 0x14, 0x01, 0x0E, 0x40, 0x2C, 0x50, 0x54, 0xD5, 0x27, - 0x0E, 0xE6, 0x05, 0x8D, 0xD1, 0x76, 0x08, 0xF3, 0x80, 0x7D, 0x0B, 0x3B, 0xC2, 0x6B, 0x32, 0x93, - 0x29, 0x9A, 0x46, 0xD6, 0x69, 0x98, 0xCC, 0xF0, 0xBC, 0xBF, 0x37, 0x3C, 0xBB, 0x12, 0xA6, 0x6D, - 0x55, 0xEC, 0x75, 0x8B, 0xFD, 0x3C, 0xE1, 0xDC, 0xD8, 0x3B, 0xD7, 0x1D, 0x76, 0xAB, 0xAB, 0xDF, - 0x62, 0xD3, 0xA0, 0x9B, 0x5D, 0xCB, 0xD3, 0xEF, 0x39, 0x0C, 0x00, 0x62, 0xDF, 0x48, 0x51, 0x75, - 0x73, 0xDC, 0x62, 0x72, 0x6B, 0x63, 0xEF, 0xCA, 0x4B, 0xB4, 0x91, 0xEE, 0x4C, 0xD1, 0x5D, 0x35, - 0x01, 0x9F, 0x90, 0x49, 0x22, 0xA0, 0x9E, 0x9D, 0xDD, 0x2E, 0xE0, 0x18, 0x28, 0x14, 0xD6, 0xC9, - 0xEB, 0x84, 0x4C, 0x7B, 0x8E, 0xDB, 0x55, 0x93, 0x48, 0x1B, 0xEB, 0x79, 0x6E, 0xEE, 0x75, 0xB2, - 0xBA, 0x17, 0x59, 0xF3, 0x45, 0xD6, 0xFC, 0xB1, 0x65, 0xCD, 0x4B, 0x53, 0x1C, 0x0B, 0x18, 0x8F, - 0xB6, 0x2B, 0x03, 0xF4, 0x92, 0x92, 0xE7, 0xFC, 0x79, 0x93, 0x29, 0x78, 0x46, 0x18, 0x6A, 0x84, - 0x9F, 0x0A, 0xF8, 0x6E, 0x89, 0xA0, 0x59, 0x89, 0xA9, 0x86, 0x86, 0x06, 0x3C, 0x0B, 0x03, 0x33, - 0x53, 0xC2, 0x0E, 0x53, 0xDA, 0x39, 0x72, 0xA9, 0x0B, 0xC5, 0xD2, 0x97, 0x8A, 0xE2, 0x1E, 0xEC, - 0x22, 0x3A, 0xF1, 0xC6, 0x89, 0x70, 0x63, 0x62, 0xC1, 0xD3, 0xF2, 0x01, 0xE2, 0xD8, 0xBC, 0x5A, - 0x70, 0xF8, 0x32, 0x37, 0x8B, 0xA9, 0x73, 0xAF, 0x8E, 0x52, 0xCB, 0x53, 0x4F, 0x84, 0x82, 0x3E, - 0x72, 0x93, 0x13, 0xB9, 0x28, 0x02, 0x1A, 0x18, 0x9F, 0xC5, 0x86, 0x52, 0x22, 0x02, 0xF1, 0x04, - 0xDE, 0x9B, 0xCA, 0xB0, 0xD7, 0xA9, 0x0F, 0xB4, 0x32, 0xA2, 0x5C, 0x1B, 0xBB, 0xC2, 0xF2, 0x05, - 0xF8, 0x83, 0x71, 0xA3, 0x52, 0x56, 0x52, 0x1F, 0x5B, 0xEC, 0x26, 0x08, 0x7A, 0xA0, 0x9B, 0x7B, - 0x87, 0xAB, 0xDC, 0x4E, 0x50, 0x93, 0x74, 0x39, 0x13, 0x1D, 0x74, 0xDA, 0xED, 0xDD, 0x76, 0xBB, - 0xED, 0xBB, 0x52, 0x1C, 0x33, 0xB8, 0x39, 0x26, 0x8B, 0x9A, 0xC6, 0xDE, 0x86, 0x5F, 0x89, 0x19, - 0x70, 0xEF, 0x81, 0x73, 0x53, 0xBC, 0xE7, 0xB6, 0xAA, 0x84, 0xC6, 0xAF, 0x8A, 0x1C, 0x2B, 0xE9, - 0x7E, 0x55, 0x72, 0x34, 0x64, 0x90, 0xE6, 0x39, 0xC7, 0x80, 0x5F, 0x77, 0x61, 0x0A, 0x5D, 0xCA, - 0x63, 0x2E, 0x4B, 0x8E, 0x8A, 0xCD, 0xF3, 0x16, 0x76, 0xEA, 0x54, 0x6C, 0x94, 0xC0, 0xEE, 0xD2, - 0x5D, 0x2E, 0xE8, 0x48, 0x77, 0x3B, 0x8F, 0x1A, 0x6C, 0xE7, 0xFF, 0xFD, 0x5F, 0xF7, 0xF5, 0x71, - 0xF9, 0xC5, 0x54, 0x21, 0xFF, 0xA5, 0xBD, 0xB7, 0x32, 0x3D, 0xB9, 0xF2, 0x72, 0x89, 0x55, 0xEA, - 0x15, 0xFF, 0xCD, 0x21, 0xD0, 0xDC, 0xC6, 0x54, 0x9C, 0xA9, 0x5D, 0xDC, 0x65, 0x1D, 0x19, 0x26, - 0x4A, 0xDC, 0x2E, 0x2D, 0x42, 0x54, 0xAB, 0x47, 0xFC, 0x2B, 0xE2, 0x5B, 0x2B, 0x47, 0xF7, 0x41, - 0x84, 0x49, 0x56, 0x1A, 0x4B, 0xD0, 0xC4, 0x16, 0xA0, 0xFA, 0x3C, 0x9E, 0x49, 0xD0, 0x2E, 0x8F, - 0xB0, 0xA2, 0xA3, 0x6D, 0x40, 0x53, 0xBA, 0x82, 0x23, 0x9A, 0xD2, 0xC6, 0x7C, 0x51, 0x65, 0xB7, - 0x10, 0x67, 0x07, 0x96, 0xA1, 0x38, 0x78, 0x2F, 0xBD, 0x1E, 0xAC, 0x0D, 0x86, 0x3B, 0x5E, 0x80, - 0xE3, 0xC6, 0xF4, 0xEB, 0xF4, 0x45, 0xCC, 0xEF, 0xF7, 0x52, 0xEB, 0x5B, 0x44, 0x3B, 0xCF, 0x36, - 0x48, 0xDE, 0xE8, 0xAE, 0x6E, 0x8E, 0x19, 0x6E, 0x67, 0x35, 0x35, 0x2D, 0xDB, 0x3E, 0xF9, 0x41, - 0x31, 0x8C, 0xC5, 0xFB, 0x2C, 0xAF, 0xB7, 0xAD, 0x50, 0x02, 0x4D, 0xD8, 0x05, 0x85, 0x04, 0xE8, - 0xEA, 0x63, 0xB4, 0xA3, 0x05, 0xDE, 0x6B, 0x13, 0x74, 0xA0, 0xA0, 0xD4, 0x23, 0x8A, 0x4A, 0x46, - 0xB2, 0x1D, 0x47, 0xC0, 0x92, 0xC3, 0xBA, 0x5F, 0xA3, 0x84, 0x8A, 0x11, 0x13, 0xB1, 0x17, 0x46, - 0x12, 0x32, 0xF4, 0x46, 0x44, 0xF0, 0x8C, 0x6C, 0x42, 0xD5, 0x0D, 0x5D, 0xA5, 0x04, 0x59, 0x45, - 0x8A, 0xAC, 0xC0, 0x78, 0x16, 0x4E, 0x0A, 0xB6, 0x0E, 0xB5, 0xED, 0x93, 0x0C, 0xB8, 0x27, 0x03, - 0xFB, 0x95, 0x35, 0x1E, 0x63, 0x2C, 0xAE, 0xD4, 0xE2, 0x4A, 0x03, 0xAD, 0xB2, 0xB6, 0x27, 0xCC, - 0xF9, 0x72, 0xB8, 0xB5, 0x68, 0x7D, 0xA5, 0xA7, 0x36, 0xAF, 0x1D, 0xA6, 0x83, 0xE8, 0x89, 0x95, - 0x45, 0x98, 0xC7, 0xCC, 0xD5, 0x21, 0x10, 0xB7, 0x39, 0xCE, 0xD0, 0x7D, 0x2D, 0x14, 0xBA, 0x5E, - 0x3B, 0x34, 0x9D, 0xAB, 0x8F, 0xEC, 0xE6, 0xF3, 0xB0, 0x85, 0xC1, 0x1C, 0x23, 0xDF, 0x90, 0xE6, - 0x18, 0x8C, 0xF5, 0x66, 0x86, 0xFE, 0x0D, 0x74, 0x46, 0x1F, 0xDD, 0x08, 0x3C, 0x47, 0x57, 0xCC, - 0xB1, 0x6F, 0x48, 0x9B, 0xCB, 0x90, 0x8B, 0x6B, 0x7A, 0x14, 0x2E, 0x81, 0x9E, 0xBE, 0xA1, 0x6D, - 0x9E, 0x18, 0x9F, 0x74, 0x5C, 0x0D, 0xEE, 0xE9, 0x2F, 0x4D, 0x8F, 0x8F, 0xA5, 0xCF, 0xCA, 0x67, - 0xC5, 0xF4, 0x15, 0xD1, 0xFF, 0xD4, 0x72, 0x78, 0xDC, 0xFA, 0x5F, 0xAC, 0x8F, 0x56, 0xF4, 0x74, - 0xDD, 0x7E, 0x8D, 0x32, 0x8A, 0x51, 0xB5, 0xA9, 0x94, 0x34, 0x00, 0x76, 0xBC, 0x2A, 0x91, 0x85, - 0x66, 0xBD, 0x36, 0x91, 0x45, 0xB0, 0x8A, 0xDA, 0x45, 0x96, 0xF8, 0x22, 0xE6, 0x77, 0x65, 0x83, - 0x44, 0x16, 0xCC, 0x63, 0xE4, 0x59, 0xE4, 0xC0, 0x58, 0x97, 0xC8, 0x42, 0xCE, 0x90, 0x22, 0x45, - 0xD2, 0xF3, 0x90, 0x58, 0x42, 0x56, 0x48, 0x98, 0x1F, 0xCA, 0x2C, 0x06, 0xD0, 0x16, 0xD7, 0x18, - 0xBA, 0x95, 0x4E, 0x82, 0x2C, 0x72, 0x7A, 0x82, 0xEB, 0x44, 0xC0, 0xFB, 0x22, 0x8C, 0x54, 0x37, - 0x5C, 0xFB, 0xA0, 0x1B, 0x05, 0xC7, 0x25, 0x86, 0x66, 0x93, 0x4F, 0xDA, 0x06, 0x1A, 0xA9, 0x23, - 0x73, 0x4B, 0xD8, 0xA8, 0x19, 0x3D, 0x2E, 0xBD, 0x29, 0xB3, 0xF8, 0x73, 0xF7, 0x09, 0xEC, 0xD5, - 0x55, 0x40, 0x5C, 0x8D, 0xF4, 0x32, 0xC6, 0x29, 0x97, 0xAE, 0x31, 0x85, 0x2C, 0x25, 0x94, 0x43, - 0xCA, 0x24, 0x07, 0xA2, 0x68, 0x8C, 0xCB, 0x31, 0x25, 0x46, 0xDC, 0xFB, 0x7A, 0xFA, 0xCB, 0xDE, - 0x70, 0xD0, 0xBF, 0xB9, 0xBD, 0x46, 0x3A, 0x0D, 0xC4, 0x8A, 0xAF, 0xF0, 0xA0, 0x1B, 0xA1, 0xD2, - 0x0F, 0x4A, 0x35, 0x5B, 0xD9, 0xD6, 0x0A, 0x06, 0x21, 0xE0, 0x05, 0x4C, 0x86, 0x96, 0xEF, 0xA8, - 0x29, 0xC7, 0x78, 0x65, 0x32, 0x09, 0x8E, 0xF0, 0xD4, 0xFE, 0x81, 0x26, 0x82, 0x6D, 0x92, 0x5B, - 0x21, 0x9E, 0x57, 0x3C, 0x6E, 0xE7, 0x8E, 0xDA, 0xD4, 0xC1, 0x6E, 0x01, 0xD1, 0x1B, 0xB9, 0xCB, - 0xAD, 0x9C, 0xB8, 0x78, 0xD1, 0x03, 0x77, 0xFE, 0x64, 0x14, 0xB9, 0x27, 0x16, 0x38, 0x14, 0xE7, - 0x8E, 0xED, 0xCB, 0x41, 0xC5, 0x7B, 0xE0, 0x4A, 0xC7, 0xEA, 0xEA, 0x34, 0x0B, 0x8A, 0x71, 0x93, - 0x58, 0x10, 0x8D, 0x6B, 0x43, 0x37, 0x17, 0x0C, 0x05, 0xD5, 0x35, 0x71, 0xA2, 0x12, 0x85, 0xCA, - 0x48, 0xF3, 0x68, 0xF6, 0x0E, 0x97, 0xB6, 0xB0, 0x45, 0xBE, 0xD9, 0xD7, 0x17, 0x5F, 0x9A, 0xE7, - 0x6F, 0xCF, 0x8E, 0x99, 0x44, 0x0C, 0x01, 0xDD, 0x08, 0x59, 0x5F, 0x0E, 0x9E, 0xF7, 0xFD, 0xD1, - 0xBA, 0x0E, 0xB8, 0xEB, 0x29, 0x57, 0xBE, 0x98, 0xF1, 0xF3, 0x8D, 0xAE, 0xE3, 0xA5, 0x2B, 0x55, - 0x89, 0x90, 0xCE, 0xE0, 0x1F, 0x75, 0xB2, 0xEE, 0x93, 0x2D, 0x36, 0xFF, 0xD5, 0x1D, 0x6C, 0x91, - 0x61, 0x96, 0x3D, 0xD7, 0xE2, 0xD0, 0x4D, 0x1C, 0x73, 0x11, 0x0C, 0xBF, 0x75, 0xFC, 0x6D, 0x3D, - 0xB7, 0x96, 0x78, 0xA5, 0x30, 0x76, 0x1A, 0xE3, 0x01, 0xFA, 0xC6, 0x03, 0x26, 0x57, 0xA1, 0xE8, - 0x0C, 0x09, 0x55, 0xB2, 0x0D, 0x04, 0x50, 0xC5, 0x0A, 0x68, 0x5F, 0x87, 0xA7, 0xC5, 0x91, 0x1A, - 0xAB, 0xCB, 0x8B, 0x23, 0xD0, 0xE6, 0xA3, 0xE9, 0xBA, 0xB7, 0xD6, 0x57, 0xF7, 0x6E, 0x48, 0x7E, - 0x8E, 0x21, 0x85, 0x25, 0x67, 0x5B, 0x08, 0x58, 0x58, 0xCD, 0xEA, 0x13, 0xE9, 0x64, 0xCC, 0x79, - 0xCD, 0xF9, 0x74, 0xBE, 0x08, 0xB0, 0x10, 0x88, 0xA4, 0x7B, 0x28, 0x79, 0x62, 0xEE, 0xE8, 0x7C, - 0x57, 0x10, 0x0F, 0x65, 0x75, 0x02, 0x09, 0xF0, 0xB5, 0xD8, 0x69, 0x3C, 0x3B, 0x70, 0xB7, 0xC9, - 0x3F, 0x28, 0x12, 0x25, 0xED, 0x7A, 0x8A, 0xE7, 0xBB, 0x91, 0xFC, 0xD9, 0x95, 0x65, 0xC2, 0xA7, - 0x4C, 0x98, 0x53, 0xE1, 0xAB, 0xEC, 0xC8, 0xBB, 0x2C, 0xAA, 0x4A, 0x04, 0xE1, 0x61, 0x76, 0xCB, - 0xFC, 0x18, 0xBC, 0x92, 0xF1, 0x77, 0x55, 0x63, 0xEF, 0x16, 0x0A, 0xB5, 0x4B, 0x0F, 0xB3, 0xC3, - 0x35, 0x2C, 0x14, 0x65, 0x17, 0x69, 0x38, 0x0F, 0xDA, 0x08, 0x64, 0x12, 0xF1, 0x75, 0x0F, 0xFA, - 0x48, 0x5F, 0x2E, 0xBC, 0x6E, 0x3E, 0xB4, 0x2E, 0xB9, 0x6B, 0x85, 0x21, 0x75, 0x99, 0x73, 0xAF, - 0x16, 0x4D, 0x97, 0x1F, 0x49, 0x97, 0x86, 0x89, 0xD7, 0x22, 0x43, 0x95, 0x9B, 0xEE, 0xA3, 0x51, - 0x03, 0x53, 0x08, 0xCF, 0x4C, 0x38, 0x1D, 0x99, 0xEA, 0x70, 0x0D, 0x1A, 0x01, 0x2B, 0x10, 0xA1, - 0x5E, 0x30, 0x37, 0xCF, 0x62, 0xFB, 0x62, 0x77, 0x64, 0xB2, 0x2C, 0xA0, 0xEF, 0xBE, 0x61, 0x84, - 0x9F, 0x42, 0x4B, 0x8E, 0xE7, 0xE8, 0x32, 0xD7, 0x23, 0xB9, 0x16, 0x62, 0x6E, 0x4C, 0xF9, 0x0E, - 0x53, 0xEE, 0x15, 0xDD, 0x20, 0x7E, 0x1C, 0x4D, 0xB4, 0x90, 0x27, 0x57, 0xD6, 0xCA, 0x10, 0xB2, - 0xBE, 0xCB, 0x3A, 0x02, 0x2B, 0xBB, 0x3F, 0x44, 0x15, 0x38, 0x44, 0x57, 0xB9, 0x69, 0xBF, 0xB7, - 0x87, 0x43, 0x4C, 0x93, 0x1C, 0x71, 0x0A, 0xE8, 0xCD, 0x59, 0x4F, 0xF1, 0x15, 0xD6, 0xC9, 0x77, - 0x37, 0x58, 0xC8, 0xB5, 0xA0, 0x4A, 0xEE, 0xA3, 0x94, 0x49, 0xCB, 0x03, 0xCB, 0x83, 0x7D, 0x6C, - 0x14, 0xE6, 0xC1, 0x9D, 0x6B, 0xBF, 0x44, 0x16, 0xDC, 0xF5, 0xEF, 0xD2, 0x00, 0xFA, 0x80, 0xBF, - 0xB4, 0x82, 0x9D, 0x1A, 0xFC, 0x9C, 0x09, 0x86, 0x8D, 0xDA, 0xBF, 0x70, 0x39, 0xD5, 0xB6, 0x2D, - 0x68, 0xB6, 0x4D, 0x5B, 0xD7, 0x29, 0x4B, 0x60, 0xDD, 0x0D, 0xDA, 0x20, 0x31, 0xE9, 0x4A, 0x9B, - 0xD3, 0xD9, 0x36, 0x9A, 0xEA, 0x2C, 0x4F, 0x53, 0x1B, 0xB5, 0x65, 0x8B, 0xD1, 0x54, 0x67, 0x1B, - 0x69, 0xAA, 0x5B, 0x96, 0xA6, 0x7A, 0x1B, 0xB4, 0x41, 0xDD, 0xEA, 0x34, 0xD5, 0xDD, 0x36, 0x9A, - 0xEA, 0x2E, 0x4F, 0x53, 0x1B, 0xB5, 0x65, 0x8B, 0xD1, 0x54, 0x77, 0x1B, 0x69, 0xAA, 0x57, 0x96, - 0xA6, 0xF6, 0x37, 0x68, 0x83, 0x7A, 0xD5, 0x69, 0xAA, 0xB7, 0x6D, 0x34, 0xD5, 0x5B, 0x9E, 0xA6, - 0x36, 0x6A, 0xCB, 0x16, 0xA3, 0xA9, 0xDE, 0xBA, 0x69, 0x2A, 0xD4, 0xEB, 0x49, 0xA5, 0xC6, 0xEB, - 0xA6, 0x2A, 0xF7, 0x67, 0xC9, 0xCD, 0x14, 0xBD, 0x7C, 0xB9, 0xE7, 0x4E, 0x7F, 0xD0, 0x38, 0x09, - 0x8C, 0x08, 0x9C, 0x7D, 0xB6, 0xB4, 0xA2, 0xFB, 0xB1, 0xF8, 0x7D, 0x58, 0x7C, 0x4A, 0x8D, 0xC4, - 0x34, 0xE5, 0x00, 0x55, 0x6F, 0xB4, 0xE6, 0x6F, 0xB0, 0xFA, 0x25, 0xEE, 0x9D, 0xE6, 0x6F, 0xAB, - 0x50, 0x07, 0xCF, 0x6F, 0x97, 0x7F, 0x3F, 0x55, 0x9F, 0xAD, 0xE0, 0xD2, 0x64, 0xFD, 0x41, 0x24, - 0x8C, 0x30, 0x5A, 0x38, 0xE6, 0xCE, 0xB1, 0x14, 0x4D, 0x55, 0x40, 0xF9, 0x97, 0xE1, 0xDE, 0xAA, - 0xCA, 0x5D, 0x97, 0x51, 0x52, 0x5C, 0x86, 0x19, 0xB9, 0x39, 0x9A, 0x14, 0xFF, 0xDA, 0x14, 0x20, - 0x6D, 0x31, 0xE8, 0x8B, 0x8C, 0x0B, 0xE9, 0xBD, 0x45, 0x32, 0x76, 0x53, 0x32, 0x32, 0xF1, 0x2E, - 0xDA, 0x18, 0x22, 0xA1, 0xF0, 0x64, 0x58, 0x20, 0x07, 0x12, 0xCE, 0x64, 0x6D, 0x12, 0x18, 0xE4, - 0x72, 0x80, 0xA1, 0xE6, 0x0E, 0x0C, 0xBE, 0x91, 0x76, 0x86, 0x6A, 0x76, 0xC3, 0xDB, 0xB3, 0x01, - 0xDB, 0x63, 0x5F, 0xCF, 0x07, 0xDB, 0x6E, 0x3C, 0x84, 0x85, 0xC0, 0x2A, 0x16, 0x32, 0x1F, 0xC6, - 0x9A, 0xCE, 0x03, 0x39, 0x09, 0xA2, 0x84, 0x15, 0xD1, 0x53, 0xED, 0xAF, 0x9A, 0xFD, 0xE4, 0x76, - 0xC4, 0x9C, 0x45, 0x2C, 0x69, 0x49, 0x2C, 0xBC, 0x55, 0xA9, 0x70, 0x9B, 0x72, 0xAB, 0xDA, 0x67, - 0x86, 0x0E, 0x1C, 0xA1, 0x71, 0x82, 0x60, 0x15, 0x7F, 0xE7, 0xF3, 0xD1, 0xE5, 0xAF, 0x43, 0x66, - 0x83, 0x66, 0x52, 0x6B, 0x58, 0x80, 0xD0, 0x0B, 0xDE, 0x3D, 0xB5, 0xBE, 0x73, 0x2A, 0xC4, 0xB8, - 0x6A, 0x96, 0x37, 0x9A, 0x25, 0x95, 0xCD, 0x60, 0x50, 0x21, 0x6B, 0xB2, 0x7D, 0x77, 0x22, 0xEE, - 0x4F, 0xB0, 0xD4, 0x28, 0x30, 0xA5, 0xB1, 0x7E, 0xCF, 0x4D, 0x42, 0x50, 0x97, 0xAA, 0x0D, 0xCF, - 0x6E, 0x53, 0xC4, 0x37, 0x78, 0x9F, 0xB2, 0x29, 0x4C, 0x2A, 0xF3, 0xB8, 0x0E, 0x41, 0x9E, 0x9B, - 0x27, 0x6F, 0xA1, 0xC8, 0xB1, 0xE8, 0x79, 0x1E, 0x0E, 0x83, 0x39, 0x20, 0x1A, 0x0B, 0x45, 0xD0, - 0x40, 0xC3, 0xE3, 0x9A, 0xAE, 0xD2, 0x42, 0x07, 0x46, 0xD8, 0x3B, 0xBA, 0xF5, 0x12, 0xF5, 0xD0, - 0xA2, 0x09, 0x2C, 0xDF, 0xEE, 0x1F, 0x6D, 0xEE, 0x05, 0x57, 0x51, 0x55, 0xBB, 0x45, 0x43, 0xD6, - 0xAA, 0xC8, 0xA7, 0xF1, 0x1D, 0x2D, 0xE8, 0xD7, 0x9E, 0x6F, 0xB2, 0x68, 0x10, 0x5A, 0xF5, 0xEB, - 0xBD, 0x7A, 0x11, 0xF8, 0x93, 0xE5, 0x2E, 0x86, 0xC0, 0xD8, 0x10, 0xFB, 0xCA, 0x85, 0xD4, 0x8C, - 0x2F, 0x1F, 0xAF, 0xF9, 0xDA, 0x18, 0x9D, 0x79, 0x51, 0x5C, 0xA6, 0x88, 0x77, 0x21, 0x61, 0x05, - 0x11, 0x07, 0x13, 0x9C, 0xF9, 0xC3, 0x44, 0x57, 0x27, 0x22, 0x30, 0x01, 0xE6, 0xA8, 0xD2, 0x1C, - 0xE3, 0xD9, 0xEB, 0x91, 0x41, 0x52, 0x4A, 0x89, 0xD6, 0x0B, 0xE5, 0x94, 0xA2, 0x1C, 0x81, 0x4A, - 0xE5, 0x6E, 0x64, 0xD2, 0xC8, 0x08, 0xDB, 0xAF, 0x8F, 0x8C, 0xF2, 0x4E, 0x92, 0x4A, 0x3A, 0xBB, - 0x9D, 0x26, 0x1D, 0x54, 0x5D, 0x47, 0x69, 0x13, 0x42, 0xCD, 0x02, 0xD4, 0x90, 0x8E, 0x7A, 0x21, - 0x40, 0x89, 0xBF, 0xD7, 0x20, 0x40, 0xC9, 0x41, 0x4B, 0x09, 0x50, 0xE2, 0xDD, 0xA7, 0x16, 0xA0, - 0x40, 0x23, 0xB4, 0x1E, 0x98, 0x6E, 0xDE, 0x59, 0x3E, 0x88, 0x4E, 0xC4, 0x31, 0x84, 0x48, 0x25, - 0x3C, 0x1A, 0x63, 0xE2, 0x54, 0x8A, 0xD8, 0x24, 0xA3, 0x19, 0x03, 0x36, 0x83, 0x75, 0xE1, 0x45, - 0xF3, 0xCD, 0xB9, 0x5E, 0xCE, 0x93, 0xA8, 0xC4, 0x1E, 0xAC, 0x5C, 0xA2, 0x12, 0xC3, 0xBC, 0x48, - 0x54, 0xCF, 0xE7, 0x5C, 0x88, 0xEC, 0x68, 0xD9, 0xA3, 0x60, 0xD6, 0x64, 0x75, 0x47, 0x41, 0x39, - 0x0C, 0x2E, 0xE5, 0x00, 0x18, 0x03, 0x48, 0xBE, 0x67, 0xAA, 0xE7, 0xE8, 0xA0, 0xD9, 0x63, 0xAA, - 0x9D, 0x46, 0x65, 0x0E, 0x37, 0xE7, 0x7F, 0x3F, 0xD7, 0xE5, 0x09, 0x95, 0x2B, 0x66, 0xE2, 0x53, - 0x89, 0x42, 0xD1, 0x75, 0x96, 0x65, 0xCE, 0xE2, 0x9A, 0x7C, 0x8A, 0x51, 0xA0, 0x1C, 0x0D, 0x6C, - 0x62, 0x76, 0xAA, 0xCC, 0x34, 0x44, 0xEC, 0x14, 0x23, 0xB7, 0x03, 0x8E, 0x2A, 0x27, 0x4F, 0xEC, - 0xD1, 0x8D, 0x16, 0xC1, 0x43, 0xD6, 0x3A, 0xE6, 0x1E, 0xF9, 0xF7, 0x55, 0x55, 0x48, 0x57, 0x42, - 0x7F, 0xF9, 0x2C, 0x76, 0xAD, 0x92, 0x86, 0x40, 0x9C, 0xAD, 0x90, 0x34, 0xBE, 0x6A, 0xA1, 0xA4, - 0x81, 0xB6, 0xAF, 0xF5, 0x48, 0x1A, 0xB3, 0x41, 0x67, 0xF4, 0xE6, 0x6B, 0xF6, 0x53, 0xCB, 0x12, - 0x33, 0xDB, 0x33, 0x89, 0x0B, 0x2E, 0x74, 0xC9, 0x4D, 0x95, 0xBB, 0xD2, 0x4F, 0xF9, 0x7C, 0xB0, - 0xE9, 0x12, 0x81, 0xAF, 0x85, 0x35, 0xBE, 0x57, 0x2B, 0x13, 0xF8, 0xDA, 0x26, 0xCA, 0x04, 0x88, - 0xC0, 0xE9, 0x32, 0x41, 0xA7, 0xDD, 0xE9, 0xB4, 0x5F, 0x84, 0x82, 0x3C, 0xA1, 0x20, 0xBE, 0xA5, - 0xA5, 0x84, 0x82, 0x58, 0x93, 0x2D, 0xD7, 0x0F, 0x43, 0x96, 0x54, 0x2B, 0xD7, 0x9E, 0xDD, 0x1C, - 0xA0, 0x75, 0x77, 0x99, 0x7B, 0x4A, 0xD1, 0x0B, 0x5E, 0x21, 0x62, 0x4F, 0x43, 0x4F, 0x11, 0x55, - 0xD2, 0x40, 0x0C, 0xDE, 0x9B, 0xF1, 0x6D, 0xBC, 0xBA, 0x90, 0xBA, 0x4F, 0xA5, 0x7B, 0xCB, 0xF8, - 0x14, 0x1B, 0x91, 0x69, 0x27, 0x07, 0x5C, 0xFE, 0xF2, 0xB2, 0xF8, 0x1A, 0x32, 0xFD, 0xFA, 0xB2, - 0xE8, 0xD2, 0x73, 0x8D, 0x97, 0x97, 0x39, 0x17, 0x8E, 0xE9, 0xD5, 0x82, 0x23, 0x77, 0x8F, 0xF0, - 0x69, 0x76, 0xCC, 0x04, 0xBB, 0x67, 0x2B, 0xEA, 0x37, 0x4E, 0xE9, 0xAE, 0xF3, 0x6E, 0x46, 0xB1, - 0x34, 0x12, 0x89, 0x6C, 0x7D, 0x71, 0x27, 0x4A, 0x75, 0x61, 0xE1, 0x35, 0xC5, 0x93, 0xEF, 0xB9, - 0x94, 0x74, 0x35, 0x32, 0x2E, 0x9D, 0x5B, 0x38, 0xEC, 0x33, 0xB8, 0xC2, 0x14, 0x95, 0x50, 0xB6, - 0xFC, 0xFA, 0x92, 0x16, 0xB1, 0xD0, 0xED, 0x65, 0xB4, 0xE5, 0x3C, 0x78, 0xA3, 0xC0, 0x49, 0x5C, - 0x5C, 0x52, 0xB4, 0xDA, 0x93, 0xDF, 0x5B, 0x66, 0x4F, 0x7F, 0x83, 0xAE, 0x2D, 0x2F, 0x5C, 0x9B, - 0xAA, 0xB7, 0x5E, 0x0C, 0x07, 0xCD, 0xEB, 0x2F, 0x3F, 0xAF, 0x5A, 0x0A, 0x0E, 0x86, 0x5B, 0x31, - 0xC3, 0x42, 0x7B, 0x3B, 0x65, 0xBB, 0xC7, 0xD8, 0x45, 0x58, 0x5A, 0xAF, 0x1B, 0xE4, 0x66, 0x0E, - 0xB3, 0xEA, 0x0B, 0xF7, 0x0A, 0xC0, 0xEA, 0x26, 0xFD, 0xB1, 0x8B, 0xA6, 0xF9, 0xF0, 0x11, 0xA8, - 0x8A, 0x9E, 0x2E, 0xFC, 0x2F, 0x44, 0x80, 0x3F, 0x06, 0x76, 0x90, 0xD6, 0x47, 0xC9, 0x36, 0xA6, - 0xBA, 0xEB, 0xC6, 0xD3, 0x6D, 0x7C, 0x19, 0x8D, 0x36, 0x3A, 0x32, 0x23, 0xA4, 0x8A, 0x45, 0x12, - 0xF2, 0xA4, 0x23, 0x60, 0xCE, 0x7A, 0x05, 0x69, 0x7E, 0xEE, 0x9F, 0x1D, 0x07, 0x02, 0x07, 0x8D, - 0x0D, 0x0F, 0x1A, 0xCC, 0xF5, 0x1E, 0x71, 0x87, 0xA4, 0xD3, 0xC9, 0xB1, 0x10, 0x36, 0xFE, 0x02, - 0x67, 0x5D, 0xFF, 0xF8, 0xF4, 0xF4, 0xF8, 0xEC, 0xEC, 0xF8, 0xFC, 0xFC, 0xF8, 0xE2, 0xE2, 0xF8, - 0xC3, 0x87, 0xAA, 0xCE, 0x53, 0x0B, 0xCD, 0x74, 0xA0, 0xE8, 0x58, 0x16, 0x82, 0x26, 0xEC, 0x1E, - 0x57, 0x8C, 0xC7, 0x2C, 0x27, 0x31, 0xDA, 0x9C, 0x3B, 0xB0, 0x72, 0x37, 0x7B, 0xE9, 0xD7, 0x96, - 0xC9, 0xD7, 0x62, 0x44, 0x2A, 0xA5, 0xF2, 0x60, 0x23, 0x39, 0x53, 0xA1, 0xD8, 0x00, 0x63, 0x02, - 0x4E, 0x38, 0x3D, 0x3E, 0xB0, 0xBF, 0xFF, 0xA5, 0x68, 0xC9, 0xF2, 0x98, 0x89, 0x1F, 0x1F, 0x08, - 0x05, 0x38, 0x55, 0x10, 0xD6, 0x02, 0xD0, 0x8D, 0xAC, 0x73, 0x28, 0x55, 0x9B, 0x2A, 0xBE, 0x65, - 0x0B, 0x15, 0x6A, 0x3B, 0x1C, 0x02, 0x54, 0x6A, 0x74, 0x6C, 0x22, 0x8D, 0x17, 0x98, 0x09, 0x85, - 0x2B, 0xE3, 0x04, 0xE4, 0x56, 0xA7, 0x57, 0x8E, 0x5B, 0xC3, 0x45, 0x60, 0x44, 0x46, 0x7A, 0xB0, - 0x02, 0x19, 0x66, 0x97, 0xF1, 0xEF, 0xBA, 0x87, 0x62, 0x90, 0x3C, 0xEB, 0x85, 0x34, 0x44, 0x96, - 0x7C, 0xBA, 0x2B, 0x74, 0xB9, 0x07, 0x1B, 0x27, 0x81, 0xEB, 0x9B, 0x9E, 0x6E, 0xB0, 0x57, 0xB8, - 0x9A, 0x57, 0x68, 0xBD, 0x77, 0x39, 0xD6, 0xB8, 0xFF, 0x6A, 0xEA, 0x9E, 0x0C, 0x2C, 0x73, 0x1F, - 0x14, 0x1B, 0xA9, 0x2F, 0xB8, 0x6A, 0xE4, 0xAE, 0x74, 0xFF, 0x02, 0xB8, 0x62, 0x81, 0xB2, 0xA9, - 0x6F, 0x52, 0x12, 0x7A, 0x73, 0x0C, 0xB2, 0x1B, 0x33, 0x81, 0xFD, 0x00, 0xE7, 0x7B, 0x40, 0x1F, - 0x0B, 0xB3, 0xB5, 0xBD, 0x81, 0xA7, 0xF5, 0x30, 0x84, 0xB5, 0x44, 0x5E, 0x7F, 0xB0, 0x50, 0x46, - 0x92, 0xB4, 0x10, 0x84, 0x5D, 0x8B, 0x87, 0x18, 0x27, 0x58, 0xB8, 0x03, 0x01, 0x0E, 0xAF, 0x27, - 0xE6, 0x3A, 0x36, 0x5B, 0xC0, 0x3E, 0x7A, 0x99, 0x6B, 0x4F, 0x40, 0x3A, 0x40, 0x0C, 0x94, 0x08, - 0x4B, 0x51, 0x55, 0x5D, 0x13, 0xD5, 0xA5, 0x35, 0x50, 0x80, 0x82, 0x04, 0x7E, 0xB6, 0x60, 0xE6, - 0x74, 0xD6, 0x88, 0xAC, 0x1D, 0xC1, 0xBA, 0xD8, 0xD4, 0x47, 0xFF, 0x00, 0xDD, 0x81, 0x9F, 0x77, - 0xF2, 0x31, 0x47, 0x8A, 0x18, 0x59, 0xB2, 0x6E, 0x9F, 0xA4, 0x2D, 0x20, 0x27, 0xA2, 0xB8, 0xFC, - 0xAB, 0xB0, 0x4D, 0xA5, 0x84, 0xC5, 0x8F, 0xAA, 0x3C, 0xBE, 0x1D, 0xDF, 0xFF, 0x74, 0xCE, 0x5D, - 0x81, 0x47, 0x8F, 0xA8, 0x3B, 0x71, 0xF0, 0xCE, 0xF3, 0xEA, 0x93, 0x19, 0x19, 0x54, 0x63, 0xD5, - 0x76, 0xDA, 0x74, 0x3F, 0xBB, 0xE3, 0x84, 0x59, 0x63, 0xE8, 0x93, 0x22, 0xB9, 0x2A, 0x03, 0x4D, - 0xB6, 0xF4, 0x65, 0x58, 0x8E, 0x92, 0x5B, 0x01, 0x23, 0x29, 0x1E, 0x98, 0x20, 0x15, 0x54, 0x12, - 0xC8, 0x0A, 0x6F, 0x87, 0xCA, 0x33, 0xA8, 0x2B, 0x98, 0x2C, 0xA6, 0xE8, 0xBB, 0x51, 0x8A, 0x0D, - 0x75, 0xCB, 0x33, 0x18, 0x31, 0xDA, 0x9A, 0xAE, 0x87, 0x62, 0xAA, 0x01, 0xAE, 0x50, 0x4A, 0xAB, - 0x4F, 0xA9, 0x1F, 0x3C, 0xD5, 0xDD, 0x50, 0x36, 0x72, 0x05, 0x18, 0xBB, 0x68, 0xFE, 0xCE, 0x85, - 0xB8, 0xD0, 0x99, 0x65, 0x39, 0x9A, 0x6E, 0x0A, 0x55, 0xFE, 0x83, 0xC3, 0xFF, 0xF0, 0xB9, 0xA9, - 0x3E, 0xB2, 0x9D, 0xCF, 0x9F, 0xFE, 0x7C, 0xFD, 0x14, 0x1E, 0x5B, 0x54, 0x94, 0x64, 0x14, 0xCE, - 0x83, 0x50, 0x43, 0x18, 0xB9, 0xD0, 0x50, 0xC1, 0x26, 0x96, 0x6D, 0xA3, 0x0C, 0x15, 0x94, 0x87, - 0x90, 0xD5, 0xD8, 0xDC, 0x96, 0x64, 0x5C, 0xC2, 0x4C, 0x65, 0x72, 0xD1, 0x6A, 0xC2, 0x15, 0x87, - 0x71, 0x45, 0x9D, 0x30, 0x0B, 0xCE, 0x1B, 0x47, 0x9C, 0x48, 0xD0, 0xA5, 0xC8, 0x2E, 0x85, 0xBE, - 0x61, 0x6A, 0x74, 0xF9, 0xE1, 0xB0, 0x11, 0x24, 0x7A, 0xDB, 0x69, 0x03, 0x28, 0x5A, 0xEC, 0x4A, - 0x9F, 0x82, 0xAC, 0x07, 0x9F, 0xDB, 0x68, 0xB4, 0x61, 0x6F, 0xBB, 0x6F, 0xF0, 0xF1, 0x33, 0x38, - 0xAF, 0xA4, 0xC4, 0x2F, 0x6E, 0x4E, 0x0E, 0x70, 0x0E, 0x3D, 0x36, 0x53, 0x5C, 0xAA, 0x18, 0xFE, - 0x73, 0x4A, 0x00, 0x48, 0x6E, 0x3B, 0xE3, 0xC9, 0x33, 0xA8, 0x87, 0x38, 0x57, 0x4E, 0xB3, 0xCB, - 0x6C, 0xBE, 0xE4, 0xBD, 0x40, 0xBD, 0x54, 0x25, 0x6A, 0xED, 0xB8, 0x81, 0xB0, 0xA3, 0x71, 0x4D, - 0xA7, 0x8A, 0xF2, 0xCC, 0xD0, 0x5D, 0x8F, 0x9B, 0x88, 0xC1, 0xA8, 0x6E, 0xAC, 0x9B, 0xC0, 0xFA, - 0x23, 0x8F, 0xEE, 0xCF, 0x41, 0xE2, 0x12, 0x9B, 0x45, 0x59, 0x71, 0xC4, 0x5C, 0x77, 0x81, 0x43, - 0x83, 0x9E, 0x82, 0x53, 0x93, 0x49, 0x76, 0xC2, 0xAC, 0x49, 0xF0, 0xBA, 0x3E, 0x36, 0x2D, 0x94, - 0xF3, 0x5C, 0x4B, 0x50, 0x18, 0x31, 0x71, 0xF9, 0x1E, 0x72, 0xF1, 0x11, 0x7A, 0x47, 0x05, 0x44, - 0x29, 0x35, 0x2C, 0x4C, 0xD4, 0x8C, 0xE5, 0xB1, 0x23, 0x06, 0x66, 0xA0, 0x1C, 0x87, 0x37, 0xC5, - 0x09, 0x94, 0x1C, 0x26, 0x42, 0x74, 0xBD, 0xB6, 0x3B, 0xA3, 0xB8, 0x4E, 0x1B, 0x9B, 0x1D, 0xB6, - 0xDB, 0xEE, 0x0B, 0xB9, 0x2D, 0x46, 0x6E, 0x22, 0x6F, 0x13, 0xA6, 0xD7, 0x76, 0x14, 0xBA, 0xB4, - 0xC1, 0x4C, 0xDC, 0x96, 0xEF, 0xFD, 0xEE, 0x96, 0xA7, 0xB9, 0xEC, 0x3E, 0x56, 0x41, 0x78, 0x15, - 0x04, 0xBE, 0x6A, 0xD6, 0xFD, 0x48, 0xCA, 0x55, 0x36, 0x70, 0x74, 0x0B, 0x13, 0x33, 0x6F, 0xBB, - 0xB1, 0x3F, 0xB2, 0xA6, 0x60, 0x49, 0xB9, 0xA6, 0xFF, 0xB9, 0x6E, 0x33, 0xAE, 0x02, 0xB2, 0xFB, - 0x9D, 0xDF, 0x99, 0x28, 0x5C, 0x53, 0xAF, 0x07, 0x22, 0xF9, 0x1F, 0x57, 0x74, 0x49, 0x50, 0xE1, - 0x96, 0xA0, 0xEC, 0xCA, 0x6A, 0x49, 0x9A, 0x54, 0x2E, 0xD8, 0x37, 0x02, 0x1F, 0x91, 0xB9, 0xD4, - 0xBD, 0xD2, 0x47, 0x1C, 0xAB, 0xA4, 0x65, 0x73, 0xF7, 0x39, 0x77, 0x88, 0xFD, 0xD0, 0x80, 0x77, - 0x48, 0x7F, 0x1C, 0xCE, 0xB9, 0x43, 0x44, 0xF7, 0x49, 0x8C, 0xC3, 0x82, 0x71, 0x8E, 0xD7, 0xA4, - 0x0C, 0xF4, 0x23, 0xB9, 0x40, 0x65, 0x8A, 0x4F, 0x06, 0x28, 0x4A, 0x09, 0xFD, 0xF5, 0x11, 0x33, - 0x2D, 0xE1, 0x84, 0x0F, 0x87, 0x0E, 0x66, 0xF6, 0xD7, 0xEF, 0x65, 0x9D, 0x5C, 0x3A, 0xB5, 0xA6, - 0x8A, 0xF9, 0x18, 0x1C, 0x58, 0xAD, 0x19, 0x01, 0x07, 0x0E, 0xFB, 0xC2, 0x2B, 0x4C, 0x46, 0x33, - 0x91, 0x8D, 0x0D, 0x4B, 0x8D, 0x60, 0x86, 0xA7, 0x20, 0x95, 0x68, 0x70, 0xA8, 0x1C, 0xE0, 0x5B, - 0x9D, 0x6E, 0x3B, 0xEC, 0x6C, 0xB3, 0x34, 0x85, 0x72, 0x71, 0xDA, 0xAF, 0x62, 0x87, 0xC9, 0xFE, - 0xAB, 0x72, 0x4E, 0x8A, 0xAF, 0xC4, 0xC1, 0xF1, 0x2A, 0xE8, 0x24, 0x7A, 0x70, 0xBC, 0x4A, 0xD2, - 0x6A, 0x12, 0x17, 0xAB, 0xDF, 0x0E, 0xD8, 0x05, 0x5D, 0xAE, 0xCC, 0x7B, 0xAD, 0x30, 0x65, 0xD9, - 0x3C, 0x2D, 0xCC, 0xCE, 0x84, 0x55, 0xA7, 0x31, 0xEB, 0xBB, 0x58, 0x13, 0x87, 0xF0, 0xD4, 0x0E, - 0xB0, 0x18, 0x64, 0x31, 0xD2, 0x55, 0xA2, 0xA9, 0x72, 0x03, 0xBC, 0x25, 0x3B, 0x0E, 0x06, 0x0F, - 0x2B, 0x01, 0xC9, 0x00, 0xFE, 0x82, 0xC0, 0xE6, 0x70, 0xD4, 0x97, 0xD0, 0x0A, 0x1D, 0x74, 0x13, - 0xBC, 0x4B, 0x71, 0x2E, 0x12, 0xFB, 0xA9, 0x28, 0xEA, 0x37, 0x7C, 0x8F, 0x1E, 0x83, 0xAC, 0x06, - 0x4F, 0x5B, 0x54, 0x05, 0x7E, 0xCC, 0x45, 0x3E, 0x5E, 0x57, 0x41, 0x42, 0x23, 0x2F, 0xF5, 0x57, - 0x43, 0xF8, 0x3B, 0xCE, 0xC5, 0x5F, 0x95, 0x34, 0xD2, 0x6D, 0x4C, 0x3A, 0xB4, 0xE8, 0x49, 0x2D, - 0x59, 0xE1, 0xF4, 0x7B, 0x13, 0xEB, 0x72, 0x0B, 0x8C, 0x48, 0x22, 0x65, 0xB0, 0xEF, 0x57, 0x7A, - 0x66, 0xD0, 0x4A, 0xBA, 0xBD, 0x2E, 0xC3, 0x34, 0x17, 0xF6, 0x8F, 0x1D, 0x9F, 0xD2, 0xBB, 0xED, - 0xC6, 0x49, 0x3B, 0xDF, 0xAE, 0xB6, 0xEC, 0x08, 0x9D, 0xC6, 0x49, 0x67, 0xB5, 0x23, 0xC0, 0x8E, - 0x75, 0x57, 0x3B, 0x42, 0xAF, 0x71, 0xD2, 0x5B, 0xED, 0x08, 0xFB, 0x8D, 0x93, 0xFD, 0xD5, 0x8E, - 0x70, 0xD0, 0x38, 0x39, 0x58, 0xED, 0x08, 0x87, 0x8D, 0x93, 0xC3, 0xD5, 0x8E, 0xF0, 0xA6, 0x71, - 0xF2, 0xA6, 0x68, 0x04, 0xA7, 0xCA, 0xD0, 0x19, 0x04, 0x27, 0x75, 0xBE, 0x05, 0x8C, 0xDC, 0xA1, - 0x71, 0xDB, 0x41, 0x2D, 0xF3, 0xD6, 0x3A, 0xCB, 0xEE, 0x1C, 0x7D, 0x7D, 0xA5, 0x2E, 0x6A, 0x05, - 0x5A, 0x66, 0x8E, 0x8D, 0x7B, 0xE9, 0xF4, 0xA9, 0x97, 0xA6, 0xEB, 0x39, 0x3E, 0x9E, 0x07, 0x4F, - 0xA2, 0x5B, 0x20, 0xA8, 0xF5, 0x70, 0x0A, 0x81, 0x2E, 0x50, 0xA3, 0xC6, 0x71, 0x39, 0xD7, 0x79, - 0x25, 0x1F, 0xA3, 0xB9, 0xE6, 0xF3, 0x5B, 0x30, 0x07, 0xC1, 0x84, 0x3A, 0x11, 0x59, 0xDE, 0x53, - 0xBB, 0x1C, 0x15, 0xAC, 0x66, 0x01, 0x1D, 0x82, 0xDC, 0x22, 0x75, 0xA3, 0x62, 0x04, 0x7B, 0xDD, - 0xF7, 0x11, 0xB7, 0x34, 0x83, 0xA9, 0xCD, 0x4D, 0x57, 0x3A, 0x81, 0xCA, 0x4B, 0x53, 0xFC, 0xA2, - 0xC0, 0xA6, 0x3C, 0x6B, 0xB5, 0x8E, 0xBB, 0x8C, 0xF9, 0x99, 0xAE, 0x4B, 0x95, 0xA1, 0xA0, 0x40, - 0xDC, 0x2A, 0xBC, 0xE2, 0x0F, 0xC7, 0x27, 0xDB, 0x1E, 0x79, 0x60, 0x82, 0x66, 0x83, 0x16, 0x13, - 0xAE, 0xCD, 0xD7, 0xCA, 0x6E, 0x6D, 0xD5, 0xDD, 0xC4, 0x6A, 0x10, 0x4D, 0x24, 0x3C, 0xBF, 0xD5, - 0xED, 0xBE, 0x01, 0x10, 0xF5, 0x35, 0xD0, 0x2F, 0x64, 0xB2, 0x6F, 0x78, 0xC6, 0x82, 0x87, 0xAB, - 0x45, 0xA1, 0x94, 0x39, 0xAC, 0x09, 0x7B, 0xE4, 0x52, 0x6D, 0x0B, 0xF7, 0x13, 0xD6, 0xAB, 0xC8, - 0x09, 0x44, 0x53, 0x96, 0x2B, 0x18, 0x1A, 0x62, 0x2A, 0xE1, 0x77, 0x29, 0x35, 0xEE, 0xB6, 0x28, - 0x00, 0x2A, 0x9B, 0xDD, 0xC9, 0x75, 0x0E, 0x26, 0xA0, 0xCE, 0x9C, 0x11, 0xCD, 0xFC, 0x3E, 0x9D, - 0xAE, 0x36, 0xB6, 0x24, 0x75, 0xC8, 0x46, 0xAA, 0x9D, 0x76, 0xDE, 0x8E, 0xD2, 0x97, 0xFB, 0x42, - 0xAD, 0xF3, 0x99, 0x21, 0x75, 0xCD, 0x76, 0xA6, 0xD3, 0xB5, 0xDF, 0xA7, 0xF5, 0x07, 0x67, 0xA8, - 0xB7, 0xC9, 0x7C, 0x53, 0x9E, 0x62, 0xAA, 0x78, 0xB5, 0x66, 0x4D, 0x85, 0xF3, 0x05, 0x2A, 0x8E, - 0x32, 0x1F, 0x42, 0x80, 0x65, 0xD2, 0x72, 0x12, 0x7C, 0xB4, 0x71, 0x71, 0x4C, 0xA5, 0x05, 0xB4, - 0xD8, 0x2D, 0x1A, 0x60, 0xE0, 0xFF, 0xBE, 0xEB, 0x2B, 0x86, 0xF1, 0x88, 0x0A, 0xA7, 0xE9, 0x05, - 0x25, 0xD1, 0xB0, 0xC6, 0xAB, 0x36, 0xD7, 0x1F, 0x7A, 0x40, 0x61, 0xA8, 0xB3, 0x62, 0xA8, 0x14, - 0x07, 0xA8, 0x31, 0xCD, 0x77, 0xC8, 0x05, 0x4A, 0xBE, 0x00, 0xDF, 0xE8, 0x77, 0x8E, 0x2C, 0xEB, - 0xD8, 0x9F, 0x5A, 0xBE, 0x88, 0x8D, 0x56, 0x34, 0x4D, 0x5C, 0xE0, 0x7D, 0xEA, 0x5F, 0x04, 0x77, - 0x28, 0x30, 0x7F, 0x87, 0xDC, 0xA7, 0x46, 0xFA, 0x77, 0x74, 0x23, 0x51, 0x30, 0xF0, 0x06, 0xB8, - 0xFE, 0xD4, 0x42, 0x5F, 0xF6, 0x33, 0xF7, 0x98, 0xDD, 0x5A, 0x8E, 0x3A, 0xD9, 0xE9, 0x74, 0xDE, - 0x00, 0xA8, 0xD9, 0xC5, 0xDF, 0xFE, 0xBA, 0xB3, 0xDF, 0xC5, 0xBF, 0x3E, 0x00, 0xF4, 0x3C, 0x60, - 0xC9, 0xAE, 0xA2, 0xAB, 0x3B, 0x87, 0x6F, 0x67, 0x8F, 0x44, 0x09, 0x19, 0x76, 0xDF, 0x8D, 0x3D, - 0x85, 0x8F, 0x6F, 0xDA, 0xF0, 0xF1, 0x39, 0x45, 0xF1, 0x48, 0x2C, 0xAE, 0xE9, 0x76, 0xA1, 0x91, - 0x4D, 0xB1, 0xE5, 0xEE, 0x13, 0x52, 0x9B, 0xAE, 0x3D, 0xAE, 0xA7, 0x90, 0x19, 0x7D, 0xE2, 0x48, - 0x6D, 0xBF, 0xAF, 0x87, 0x0D, 0x05, 0x83, 0x55, 0x65, 0x40, 0xA2, 0x1D, 0xDB, 0x51, 0x5A, 0xDF, - 0x5A, 0x4A, 0x2B, 0x17, 0xFA, 0x03, 0x3C, 0x68, 0x44, 0xC1, 0xF4, 0xD7, 0xC0, 0x8F, 0x9E, 0xE0, - 0x7A, 0x5F, 0x30, 0x10, 0x32, 0x41, 0xD1, 0x34, 0x02, 0x7E, 0x01, 0x54, 0xE2, 0x4E, 0xC5, 0x41, - 0x88, 0x14, 0x89, 0x46, 0x5E, 0xDD, 0x54, 0x0D, 0x1F, 0xB9, 0x00, 0x96, 0xC3, 0x31, 0xD1, 0xB3, - 0xC3, 0x6D, 0xB1, 0x6B, 0x0B, 0x59, 0x03, 0x95, 0x5D, 0x54, 0x0C, 0xD6, 0xBF, 0x19, 0x60, 0xC5, - 0x17, 0xDF, 0xA0, 0x2C, 0x7B, 0x41, 0x83, 0x68, 0x34, 0x5E, 0xEB, 0x68, 0xFA, 0x42, 0xC6, 0xA5, - 0xC8, 0x38, 0x44, 0xBF, 0x2A, 0x04, 0x1C, 0x34, 0x7A, 0x5A, 0xD2, 0xCD, 0x50, 0xCD, 0xB3, 0x74, - 0xF3, 0xE1, 0x23, 0x08, 0x57, 0xD3, 0x6D, 0xBF, 0xF3, 0x13, 0xAB, 0x58, 0x48, 0xFB, 0x8E, 0x35, - 0x9D, 0x07, 0x71, 0x0C, 0x3E, 0x09, 0xAD, 0xDB, 0x15, 0x4D, 0x9F, 0xFC, 0xFE, 0x2E, 0x67, 0x09, - 0x0B, 0xAA, 0xDB, 0xBE, 0x6D, 0x58, 0x8A, 0x76, 0xCD, 0x1F, 0x3E, 0xE8, 0xCE, 0x14, 0x4B, 0x74, - 0x9F, 0xEB, 0xF7, 0x65, 0x2A, 0x1D, 0x97, 0x52, 0x73, 0xE6, 0x3A, 0x6F, 0x9C, 0x48, 0x28, 0x07, - 0x0F, 0x0A, 0x52, 0xF3, 0x12, 0x83, 0xA2, 0x90, 0x0E, 0xEF, 0x5B, 0xD0, 0xE4, 0x6F, 0xDC, 0x41, - 0xAE, 0xF8, 0xD5, 0x1E, 0x3B, 0x0A, 0x28, 0x2D, 0x99, 0x81, 0x0E, 0xF7, 0xED, 0x56, 0x7B, 0x11, - 0x4B, 0x7A, 0xF6, 0x71, 0x97, 0x43, 0xD0, 0x79, 0x2E, 0xAD, 0x67, 0x08, 0x97, 0x28, 0x10, 0x16, - 0x72, 0x6B, 0x0D, 0xAD, 0x7E, 0x6A, 0xA2, 0x3B, 0xB4, 0xF1, 0xD1, 0x10, 0x74, 0x5B, 0x08, 0x5F, - 0x84, 0xC0, 0x9D, 0x61, 0xDC, 0x9A, 0x14, 0x3B, 0x31, 0x8D, 0xA1, 0xAD, 0x38, 0xDF, 0x3E, 0xF8, - 0x74, 0x1F, 0xE9, 0x72, 0x4E, 0x77, 0x9B, 0x30, 0xAB, 0x91, 0x9C, 0x15, 0xC9, 0xB9, 0x61, 0xBD, - 0x99, 0xF0, 0x86, 0x53, 0x38, 0xCA, 0x6C, 0x94, 0x4E, 0x17, 0x61, 0xFC, 0xC1, 0xE4, 0x83, 0xBD, - 0x44, 0x5F, 0x5F, 0xC1, 0xE3, 0x9F, 0xD6, 0xB9, 0xFF, 0xE6, 0x6C, 0x46, 0x5A, 0xC2, 0x28, 0x73, - 0xCA, 0x3D, 0x25, 0x82, 0x01, 0xEB, 0xF1, 0xDA, 0x8F, 0x4E, 0x63, 0xCD, 0xC2, 0x15, 0xAD, 0x37, - 0xC4, 0x2D, 0xE4, 0xFA, 0x8A, 0x6E, 0xBA, 0xF2, 0x22, 0x1C, 0xAF, 0xFB, 0xD8, 0x88, 0x2B, 0x9E, - 0x8F, 0x97, 0xEC, 0x40, 0x0D, 0x6C, 0xAA, 0x3C, 0x32, 0xD3, 0x22, 0xC7, 0x7C, 0x50, 0xAC, 0x60, - 0xEA, 0x28, 0x5C, 0x79, 0x78, 0xE3, 0x0E, 0x1A, 0x15, 0xC7, 0x63, 0x84, 0x50, 0x72, 0xA4, 0x73, - 0x90, 0xAE, 0x30, 0xF7, 0xF6, 0xA6, 0xFB, 0x5E, 0x3D, 0x2D, 0xFE, 0xF5, 0x7D, 0xCF, 0x0A, 0xB6, - 0xFE, 0xAB, 0x0D, 0x9B, 0xC9, 0x43, 0x6B, 0x29, 0x7E, 0x35, 0x85, 0x53, 0x54, 0x0D, 0xB1, 0xB1, - 0xB8, 0xB6, 0x1F, 0xF5, 0xB0, 0xB6, 0x58, 0x93, 0xB4, 0xC9, 0xAF, 0x19, 0x7B, 0xB3, 0x32, 0xA5, - 0xD8, 0xDC, 0xD1, 0x2D, 0xF4, 0x9D, 0x44, 0x83, 0x83, 0x1A, 0x72, 0xF7, 0x28, 0x1F, 0x6D, 0x31, - 0x68, 0xAC, 0xD0, 0x23, 0xDB, 0xB1, 0x34, 0x5F, 0xF8, 0x95, 0xDC, 0x8B, 0xD3, 0x31, 0x9D, 0xDB, - 0xEE, 0xE2, 0x45, 0x78, 0xE0, 0x33, 0x82, 0xC6, 0x36, 0x91, 0xEE, 0x5B, 0x09, 0x76, 0x0A, 0x47, - 0xDB, 0x6E, 0x7C, 0x8F, 0x6F, 0x2E, 0x2D, 0x2A, 0xBE, 0xC3, 0x8B, 0xFA, 0x98, 0x2F, 0xAC, 0xF2, - 0xA6, 0xAA, 0xBE, 0x11, 0xC4, 0xA3, 0x13, 0xE5, 0xB3, 0x6E, 0xFA, 0x80, 0xF8, 0xE5, 0x0A, 0xA9, - 0xE6, 0x78, 0x3F, 0x89, 0x64, 0x30, 0x6F, 0xE6, 0x94, 0x66, 0xD9, 0x7F, 0xC4, 0x7B, 0x1C, 0x06, - 0x75, 0x8F, 0x9F, 0xB8, 0x4C, 0x32, 0xE2, 0x6F, 0xC8, 0x24, 0x42, 0x84, 0xF5, 0x69, 0x9F, 0x10, - 0x6F, 0x43, 0xCA, 0x98, 0xCB, 0x3A, 0x9F, 0x4A, 0x10, 0x4C, 0x99, 0x79, 0xF9, 0x92, 0xBF, 0xD4, - 0x54, 0xAE, 0x7A, 0x82, 0x6E, 0x1D, 0x9C, 0xB6, 0x39, 0xA6, 0x25, 0xEF, 0x03, 0xE0, 0x76, 0x3A, - 0xB0, 0x9E, 0xC7, 0xD7, 0xDB, 0x57, 0x5E, 0xB6, 0x64, 0x71, 0xE1, 0xD2, 0x9E, 0xB3, 0x88, 0x4E, - 0xEE, 0x14, 0x38, 0x80, 0x54, 0x8F, 0xB3, 0x50, 0xB4, 0xC4, 0x90, 0x76, 0x6E, 0x0F, 0x8B, 0x2A, - 0xCD, 0x65, 0xFC, 0x8D, 0xAB, 0x7B, 0xD6, 0x86, 0x17, 0xFA, 0xD9, 0x46, 0x2E, 0xC5, 0xD0, 0xC7, - 0x26, 0x70, 0x0A, 0x32, 0xD8, 0x09, 0xE8, 0xC0, 0xE3, 0x8F, 0xDC, 0x8B, 0xC9, 0xF4, 0xE5, 0x03, - 0xAA, 0x0A, 0x15, 0x86, 0x64, 0xD7, 0x25, 0xE2, 0x97, 0x4B, 0xEA, 0x0E, 0xE3, 0x58, 0xCF, 0xA8, - 0x39, 0x08, 0xAE, 0x88, 0xA2, 0xFA, 0x7D, 0xAF, 0xD5, 0xD9, 0x6F, 0x75, 0x0E, 0xCA, 0x68, 0x0D, - 0x02, 0x16, 0x27, 0xEF, 0xE0, 0xE0, 0x19, 0x53, 0xCC, 0x70, 0x54, 0x46, 0x16, 0x5D, 0x0E, 0xE4, - 0x57, 0xA7, 0x8A, 0x13, 0x1E, 0xBE, 0x9D, 0x6E, 0x03, 0x28, 0xF3, 0x3B, 0xFC, 0xD1, 0x6E, 0x17, - 0x73, 0x0B, 0x09, 0xD1, 0x07, 0x5D, 0xF3, 0x26, 0xC7, 0xBD, 0x76, 0x9B, 0x22, 0xC2, 0x01, 0x45, - 0x64, 0xC7, 0xA5, 0x0C, 0x36, 0xE9, 0x73, 0xCA, 0x89, 0xD4, 0xEB, 0xBD, 0xF9, 0xAF, 0x05, 0xA6, - 0x1B, 0xB9, 0xF6, 0xBA, 0x0C, 0xAF, 0x65, 0xD4, 0xEB, 0xA4, 0xA2, 0x58, 0x32, 0x29, 0xE3, 0x48, - 0x37, 0x00, 0x7B, 0x44, 0x06, 0xA2, 0x3B, 0x60, 0x52, 0xF4, 0x91, 0xCC, 0x19, 0xFE, 0xDD, 0x54, - 0xF7, 0x02, 0x34, 0xF8, 0x40, 0xCF, 0x2D, 0x53, 0x25, 0xAF, 0xB8, 0x28, 0xCC, 0x50, 0x7B, 0xFF, - 0x59, 0xD1, 0x3D, 0x8C, 0x99, 0xDC, 0xCB, 0x1E, 0x54, 0xBC, 0xC8, 0x4E, 0x2F, 0xAF, 0x17, 0xF0, - 0xEA, 0xAC, 0xCD, 0xB3, 0x30, 0xC0, 0x64, 0x38, 0x2B, 0x7C, 0x53, 0xF7, 0x5E, 0xB9, 0xB3, 0x83, - 0xE1, 0xEE, 0x91, 0x09, 0x53, 0x04, 0x5D, 0xC1, 0x30, 0x80, 0x05, 0xD2, 0x0F, 0xC2, 0x63, 0x76, - 0x2D, 0x14, 0xA6, 0xA5, 0x65, 0xF6, 0x04, 0x68, 0x17, 0x23, 0xF0, 0x06, 0x67, 0xEB, 0x76, 0xF9, - 0xCB, 0x76, 0x2D, 0x4A, 0xA2, 0x33, 0xAE, 0xA6, 0x6A, 0xC0, 0x69, 0x16, 0x76, 0xA6, 0xB2, 0xBF, - 0x59, 0x64, 0x9E, 0xE2, 0x7A, 0x98, 0x9D, 0x2A, 0x25, 0xB3, 0x56, 0xA1, 0x79, 0x88, 0xA4, 0x9D, - 0xB0, 0x83, 0xD0, 0xFA, 0x73, 0x09, 0xFB, 0x83, 0x11, 0x30, 0xF4, 0xB4, 0x52, 0x22, 0xAD, 0x59, - 0x5F, 0xF1, 0xB9, 0x2D, 0x9B, 0x37, 0xAB, 0xDD, 0x38, 0xB9, 0xB1, 0x28, 0x31, 0x63, 0xC5, 0xC4, - 0x59, 0x9D, 0xC6, 0xC9, 0xA9, 0xE2, 0xF2, 0xCA, 0xED, 0xBA, 0x98, 0xB6, 0xB4, 0x7A, 0x99, 0xA1, - 0x9E, 0x18, 0x0E, 0x73, 0x9D, 0x6E, 0x46, 0xB6, 0xAE, 0x81, 0x2F, 0x5C, 0x6B, 0x85, 0x85, 0x14, - 0x83, 0x5D, 0xC5, 0x55, 0xAA, 0x18, 0x1D, 0xA8, 0x89, 0x5C, 0x42, 0x82, 0xCC, 0x0F, 0x03, 0xCA, - 0xFC, 0xF0, 0xC5, 0x44, 0xEA, 0x22, 0xBF, 0xB4, 0xD6, 0xC6, 0x27, 0xB2, 0x31, 0xAC, 0xF1, 0xAD, - 0x35, 0x3C, 0x3F, 0x53, 0x32, 0x6B, 0x76, 0xAD, 0x21, 0x40, 0x7A, 0x0C, 0x87, 0xFC, 0x18, 0x63, - 0xA4, 0xC7, 0x78, 0x52, 0x0F, 0xCF, 0x19, 0x4E, 0x67, 0x3D, 0xD1, 0xD2, 0x72, 0xE8, 0xF5, 0xE5, - 0xD3, 0x55, 0x40, 0x6E, 0x57, 0x1D, 0x00, 0x39, 0x59, 0xB0, 0x19, 0x99, 0x06, 0x3D, 0xC2, 0x25, - 0xCA, 0x9E, 0x1B, 0x56, 0xB1, 0x0F, 0x15, 0x59, 0xD8, 0xA1, 0x71, 0x9A, 0xA3, 0xD1, 0xD6, 0xC5, - 0x40, 0xC7, 0x40, 0x5E, 0xA4, 0xA8, 0x96, 0xB7, 0xFB, 0x94, 0xD5, 0x52, 0xA3, 0x3C, 0x1B, 0xA4, - 0x34, 0x98, 0x07, 0x86, 0xBA, 0x35, 0x16, 0xD2, 0x37, 0x95, 0xEF, 0x4C, 0xAE, 0xA3, 0x50, 0xCC, - 0xC3, 0x41, 0xD8, 0x0E, 0xE8, 0x6A, 0xAF, 0x8F, 0xAB, 0x19, 0x1E, 0x96, 0xD7, 0x45, 0x03, 0x7F, - 0x24, 0xF4, 0x0F, 0x41, 0xA6, 0x05, 0xAB, 0x46, 0x6C, 0x62, 0x18, 0x9E, 0x41, 0x86, 0x13, 0x75, - 0xA2, 0xF3, 0x7B, 0x44, 0x3C, 0x43, 0x2C, 0x46, 0xAA, 0x9F, 0x9C, 0x7C, 0x30, 0x66, 0x7E, 0x21, - 0x7C, 0xE4, 0x13, 0xDC, 0x98, 0x81, 0x51, 0x36, 0xF8, 0x9E, 0x61, 0xC1, 0x0F, 0x10, 0x13, 0xA7, - 0xBB, 0x14, 0xE6, 0x69, 0xE2, 0x9C, 0x76, 0xD1, 0xE2, 0x88, 0xAA, 0xAE, 0xEB, 0x3B, 0xF7, 0xFC, - 0x91, 0x92, 0x3D, 0x2B, 0xD0, 0x99, 0x83, 0x16, 0xCB, 0xE8, 0xC5, 0x30, 0x8C, 0x9E, 0x54, 0x53, - 0xA5, 0x2A, 0x1B, 0x09, 0x0E, 0xC5, 0xD6, 0xDD, 0xA3, 0xA3, 0xD9, 0x57, 0x25, 0x55, 0xD8, 0x95, - 0xA9, 0xAF, 0xE5, 0x6C, 0x3C, 0xE5, 0x2D, 0x7B, 0x95, 0x55, 0xD6, 0x08, 0xCE, 0x96, 0xD2, 0x0D, - 0x66, 0xEF, 0xAF, 0x2D, 0x84, 0x7A, 0x71, 0x52, 0x14, 0xEE, 0x0B, 0xCB, 0x10, 0x63, 0xE1, 0x06, - 0xA2, 0x1E, 0x20, 0xDD, 0x24, 0x24, 0x3D, 0xAE, 0x94, 0xDC, 0x80, 0x72, 0xE2, 0x38, 0x1F, 0xA7, - 0x38, 0x61, 0xD9, 0x44, 0x6A, 0x0C, 0xF8, 0x3C, 0xC6, 0xFC, 0x60, 0xD9, 0x88, 0x34, 0xC2, 0xA3, - 0xEF, 0x28, 0xBA, 0x9C, 0x92, 0x65, 0x18, 0x74, 0x2A, 0xC8, 0xBC, 0xD2, 0x8A, 0xA0, 0x46, 0x41, - 0x75, 0xCF, 0x9D, 0xB0, 0x56, 0x48, 0x59, 0x12, 0x05, 0x2B, 0xD0, 0x96, 0x68, 0xB1, 0x52, 0xEA, - 0x92, 0x22, 0x9A, 0xD0, 0x61, 0xE5, 0x10, 0x25, 0xE8, 0x2B, 0x42, 0x98, 0x25, 0x0C, 0xBF, 0x73, - 0x1A, 0x4D, 0x62, 0xC0, 0x08, 0x6D, 0xC7, 0x8C, 0x32, 0x24, 0xB0, 0x91, 0x9A, 0x89, 0xDA, 0xCB, - 0xB1, 0x40, 0x91, 0xD2, 0x86, 0xC6, 0xC8, 0xD2, 0xAE, 0x95, 0x69, 0xCE, 0x4D, 0xF7, 0xF0, 0xC3, - 0xC5, 0xEF, 0x30, 0x52, 0xCB, 0xBF, 0xFB, 0x5E, 0xAB, 0xFD, 0x70, 0x09, 0x6B, 0xDB, 0x72, 0xDC, - 0x6F, 0x99, 0xAC, 0x80, 0xF9, 0xD6, 0x35, 0x72, 0xA6, 0xBC, 0xE6, 0x0F, 0x00, 0xAE, 0x1A, 0xEC, - 0x6A, 0x73, 0xF6, 0xB5, 0x48, 0xF7, 0x68, 0x5C, 0x1B, 0xE2, 0x47, 0xBA, 0x92, 0x87, 0x07, 0xE5, - 0x52, 0x4B, 0xAD, 0x4E, 0xCA, 0x39, 0x33, 0x2C, 0x4C, 0xCE, 0x47, 0xB6, 0x0E, 0xDF, 0x71, 0x30, - 0xC2, 0x04, 0xB9, 0x2B, 0xFA, 0x9D, 0xD1, 0xB4, 0x5D, 0xC9, 0x72, 0x2D, 0x93, 0x6F, 0x09, 0xCB, - 0xAB, 0x17, 0x3B, 0x43, 0xAD, 0xAD, 0x93, 0x20, 0xE2, 0xDA, 0xEE, 0x4A, 0x6F, 0x06, 0xA1, 0x3A, - 0x15, 0xDC, 0x91, 0xDE, 0x0C, 0x02, 0x39, 0x79, 0x6D, 0x97, 0x9E, 0xB3, 0x59, 0x3C, 0x5D, 0x7A, - 0xBD, 0xE8, 0xB5, 0x27, 0x22, 0x64, 0xE0, 0xD4, 0x79, 0xC3, 0x47, 0xDC, 0xC1, 0x92, 0x10, 0x6C, - 0x60, 0xB9, 0xBA, 0xCC, 0x4D, 0x64, 0x4D, 0x45, 0xB6, 0xAB, 0x4E, 0xBB, 0x7D, 0xB0, 0x07, 0x3F, - 0x0E, 0x43, 0x89, 0x20, 0x74, 0x97, 0x16, 0xC1, 0xBD, 0xE3, 0x67, 0x73, 0x77, 0x19, 0xEE, 0xD1, - 0x46, 0x5C, 0x57, 0xCE, 0xA6, 0x43, 0x69, 0x50, 0x00, 0xA9, 0x16, 0x92, 0x43, 0xA1, 0x9B, 0x52, - 0x5C, 0x45, 0x8E, 0xC5, 0x82, 0xC1, 0xD8, 0x8E, 0xFB, 0x7A, 0x03, 0xAE, 0x2A, 0x91, 0x56, 0x03, - 0x35, 0x30, 0x79, 0x39, 0x99, 0x83, 0xBF, 0x71, 0x2B, 0x05, 0x5A, 0xC2, 0x74, 0xB9, 0x2E, 0x59, - 0x95, 0x31, 0x99, 0xDD, 0xE1, 0xE5, 0x2A, 0x32, 0x21, 0x7D, 0xA6, 0xA0, 0x5F, 0xE9, 0x4B, 0xC8, - 0xF9, 0xB6, 0xAB, 0xBF, 0x7E, 0xAC, 0xD5, 0xFE, 0xF3, 0x99, 0xC2, 0x37, 0x6A, 0xB0, 0x02, 0xC9, - 0xE3, 0x0D, 0x9A, 0x09, 0xFF, 0xDC, 0xD5, 0x9C, 0x71, 0x72, 0xF2, 0x37, 0x97, 0xD7, 0x17, 0xBF, - 0x84, 0xA7, 0x1C, 0x7D, 0x5A, 0xF7, 0x39, 0x17, 0x9B, 0xC9, 0x66, 0x9C, 0x74, 0x02, 0x0E, 0xB1, - 0x4A, 0xAB, 0x92, 0x2B, 0x08, 0xA3, 0xEE, 0x83, 0xEE, 0x4D, 0x64, 0x26, 0x59, 0x10, 0xD5, 0xCC, - 0x90, 0x51, 0x90, 0x8C, 0x46, 0x6A, 0x84, 0x26, 0xFD, 0x92, 0x9F, 0xCB, 0x41, 0x17, 0xDD, 0xA4, - 0xA5, 0x8F, 0x3A, 0xF2, 0x13, 0x06, 0x6A, 0xFE, 0x8E, 0x1A, 0xD3, 0xB9, 0x84, 0x54, 0xEA, 0xA5, - 0x55, 0x19, 0x27, 0xB8, 0xE4, 0x21, 0x48, 0x73, 0x8C, 0xF6, 0xBC, 0x50, 0x55, 0x26, 0xEA, 0xA5, - 0x14, 0xFB, 0x8D, 0xED, 0xF7, 0x71, 0x05, 0x2E, 0x1B, 0xBB, 0x2F, 0x4B, 0x99, 0x35, 0x82, 0x29, - 0x7B, 0x31, 0x65, 0xEF, 0xCF, 0xF2, 0xEF, 0xD2, 0x3A, 0xEC, 0x93, 0xE5, 0x97, 0xB8, 0x4C, 0xCB, - 0xBF, 0x58, 0x3B, 0xA4, 0x5E, 0xDC, 0xA5, 0xBA, 0xC1, 0xC4, 0x1D, 0xFB, 0x35, 0xF4, 0x03, 0xE8, - 0xD2, 0x39, 0x60, 0xD2, 0x85, 0xA5, 0x7C, 0x4F, 0xF9, 0xD7, 0x70, 0xAB, 0x57, 0xFA, 0xB2, 0x59, - 0x4E, 0x3C, 0xB5, 0x54, 0xE0, 0x2A, 0xB5, 0xC7, 0x26, 0x08, 0xAA, 0x20, 0xF6, 0x50, 0x91, 0x0E, - 0x56, 0x06, 0x19, 0xE7, 0x2C, 0x9B, 0x9B, 0xB1, 0x8B, 0x96, 0x00, 0xB2, 0xDB, 0xA4, 0x2F, 0x56, - 0xE0, 0x23, 0x5F, 0xEE, 0x5C, 0xE4, 0xBF, 0xB8, 0xD3, 0x81, 0xF4, 0x50, 0x2F, 0x3B, 0x81, 0x01, - 0x72, 0x24, 0xEA, 0x3A, 0xB9, 0x89, 0x35, 0x5B, 0x4A, 0x78, 0xAC, 0x2C, 0xC7, 0x54, 0x62, 0x73, - 0x0F, 0x79, 0x4A, 0xDA, 0x8A, 0x6A, 0x62, 0x29, 0xEE, 0xB2, 0xEC, 0xA4, 0xBB, 0x34, 0x27, 0x39, - 0x58, 0x9E, 0x87, 0xB4, 0x97, 0xEB, 0x62, 0x1F, 0xD9, 0xD0, 0x72, 0x5D, 0x1C, 0x34, 0x4E, 0x7A, - 0x4B, 0xCE, 0x02, 0xB3, 0xF0, 0xB4, 0x9F, 0x05, 0x17, 0xE4, 0xF7, 0x1C, 0x98, 0x4D, 0x4A, 0x8A, - 0xBD, 0x58, 0x4A, 0xD6, 0xE7, 0x63, 0x0E, 0xAB, 0xC9, 0x69, 0x4D, 0x78, 0x2A, 0x02, 0x2E, 0x78, - 0x96, 0xE5, 0x4D, 0x28, 0x03, 0x75, 0x7A, 0xED, 0xBD, 0x02, 0xEE, 0x18, 0xE5, 0x88, 0xF3, 0xDD, - 0x35, 0x4E, 0x4E, 0x83, 0x67, 0x6C, 0xE0, 0x58, 0x9E, 0x05, 0xFC, 0xAF, 0x92, 0xB7, 0x50, 0x4A, - 0x97, 0x19, 0x33, 0xAF, 0xC1, 0x7F, 0x68, 0x38, 0x18, 0x2C, 0xE4, 0x3D, 0x74, 0x75, 0xB1, 0x88, - 0xF3, 0x10, 0x8C, 0xC6, 0xFE, 0x89, 0x2D, 0xD2, 0x18, 0xF6, 0xE2, 0xCB, 0x68, 0xB4, 0x19, 0xDE, - 0x43, 0x67, 0x61, 0x7D, 0x18, 0x4C, 0x86, 0x8F, 0x96, 0x95, 0x33, 0xEC, 0x55, 0x57, 0xD9, 0x6C, - 0xE7, 0x45, 0x02, 0x5E, 0x86, 0x25, 0x30, 0x11, 0x0B, 0x48, 0x18, 0xD9, 0x81, 0xE5, 0xBF, 0xDE, - 0x8D, 0xBC, 0x74, 0x65, 0x3D, 0x34, 0x2F, 0x4C, 0xEE, 0x8C, 0x1F, 0xD9, 0x0E, 0x00, 0xE5, 0x35, - 0x65, 0xD0, 0xF7, 0x7C, 0xC7, 0x8C, 0xBC, 0x63, 0x8D, 0x46, 0x11, 0xBA, 0x0E, 0x01, 0xB8, 0xF9, - 0x2E, 0x48, 0x77, 0x9C, 0xDB, 0x54, 0x84, 0x5E, 0x44, 0x2F, 0xAF, 0xAA, 0x3A, 0xDB, 0x29, 0x0D, - 0x13, 0x89, 0xDF, 0xD1, 0x74, 0xFC, 0x2D, 0x1E, 0xAF, 0xBA, 0x56, 0x5B, 0x30, 0xF8, 0xAA, 0xD3, - 0x4F, 0x52, 0x8C, 0x5C, 0x58, 0x92, 0xE1, 0xCE, 0xFF, 0xF3, 0x4F, 0x0C, 0x19, 0xB0, 0x28, 0x83, - 0x2A, 0x53, 0x7C, 0x2A, 0xAF, 0xC0, 0xB9, 0x76, 0xA7, 0x60, 0x26, 0x49, 0x61, 0x58, 0xF6, 0x5D, - 0xCC, 0x02, 0x52, 0xC1, 0xBB, 0x68, 0x33, 0xB0, 0x66, 0xCA, 0x15, 0xD7, 0x77, 0x08, 0x3A, 0x43, - 0x55, 0x31, 0x96, 0x63, 0xCE, 0xC9, 0xCE, 0x1A, 0x27, 0x54, 0x02, 0xAA, 0x12, 0x37, 0x9E, 0xEB, - 0x23, 0x75, 0x9A, 0x35, 0x70, 0xE2, 0xCF, 0x1C, 0xB6, 0xD7, 0x5D, 0x84, 0x19, 0x7F, 0xE0, 0xDC, - 0xDB, 0xBB, 0x44, 0x5B, 0x91, 0xBB, 0x19, 0x0C, 0xF2, 0x5C, 0xDC, 0xF5, 0xCA, 0xEA, 0x5C, 0x58, - 0x02, 0xC4, 0xA7, 0xD2, 0x5B, 0xBA, 0xC9, 0xA6, 0xB4, 0x4A, 0xE4, 0x73, 0x80, 0xB0, 0x9E, 0xF4, - 0x8A, 0xD0, 0x2C, 0x50, 0xE2, 0x30, 0xBE, 0x51, 0x19, 0x8D, 0x10, 0xF2, 0x54, 0x67, 0x5B, 0x64, - 0x7A, 0x02, 0x96, 0x68, 0x1A, 0x8F, 0x33, 0xDC, 0x97, 0x01, 0x35, 0xD4, 0xAB, 0xA8, 0xD9, 0x25, - 0x2F, 0x96, 0xA3, 0xD2, 0x8F, 0x00, 0xE5, 0x36, 0x24, 0x3E, 0xAD, 0x9D, 0x1D, 0x62, 0x00, 0x19, - 0xF9, 0xA8, 0xA6, 0x44, 0x34, 0x9E, 0x0B, 0xD8, 0xC1, 0xD7, 0x78, 0x73, 0xBA, 0x6A, 0xDE, 0x18, - 0x99, 0xC9, 0x13, 0x15, 0x6E, 0x8F, 0x85, 0x23, 0x3A, 0x62, 0xD5, 0x33, 0x3F, 0x9C, 0x09, 0x37, - 0x6C, 0x74, 0xC4, 0xA1, 0x24, 0xBA, 0x1A, 0xB7, 0x0D, 0xEB, 0x51, 0x38, 0xDA, 0xCB, 0x2E, 0x74, - 0xCC, 0xDE, 0x0B, 0x24, 0x6E, 0x79, 0x9C, 0x2A, 0xF5, 0x7A, 0xF1, 0x72, 0x35, 0x41, 0x3E, 0xAF, - 0x8D, 0xE7, 0xA8, 0x89, 0xC0, 0x42, 0xDA, 0x92, 0x5A, 0x4A, 0x5C, 0x56, 0x4D, 0x9D, 0xE3, 0xF0, - 0x3B, 0x90, 0x68, 0x82, 0x88, 0xAC, 0x1A, 0x02, 0x02, 0x73, 0x35, 0x0B, 0xB9, 0xDF, 0xEE, 0xF1, - 0xFA, 0x4D, 0xE7, 0xB3, 0xF0, 0x40, 0x39, 0x89, 0xDC, 0xB0, 0x40, 0xCA, 0x87, 0x5A, 0x2A, 0x0A, - 0x70, 0x7B, 0x93, 0xE3, 0x2C, 0x78, 0x87, 0x16, 0xC7, 0x98, 0xC2, 0x74, 0x07, 0xB1, 0xD7, 0x17, - 0xB9, 0x31, 0x5B, 0x54, 0xA7, 0x74, 0x27, 0xBE, 0x87, 0xE7, 0xFD, 0xB5, 0x75, 0x36, 0xC1, 0xD4, - 0x2F, 0xB2, 0xD8, 0x86, 0x9C, 0xC9, 0x99, 0xE4, 0x92, 0x82, 0xE8, 0xD6, 0xEF, 0x8E, 0x9F, 0x3F, - 0x3B, 0x50, 0xCA, 0xE4, 0xF7, 0x18, 0x99, 0x7D, 0x6D, 0x15, 0xE4, 0x0A, 0x9D, 0x10, 0xA9, 0x8E, - 0x57, 0xE6, 0xC5, 0xFF, 0x53, 0x91, 0x6F, 0x59, 0x39, 0x58, 0xAF, 0xD3, 0xF5, 0x3F, 0xF5, 0xEC, - 0x21, 0x2D, 0x0E, 0x74, 0x37, 0x59, 0x23, 0x01, 0xD3, 0x62, 0x91, 0xFC, 0xA2, 0xD2, 0xA4, 0x9D, - 0x20, 0x41, 0x3B, 0x8C, 0x56, 0x78, 0x22, 0xA1, 0xD4, 0x84, 0x1E, 0xA6, 0x26, 0x1A, 0x7D, 0x40, - 0x70, 0x82, 0xAF, 0xC9, 0xC8, 0x8D, 0x12, 0x3E, 0x65, 0x86, 0x10, 0xE5, 0x02, 0x49, 0xF0, 0xC7, - 0x51, 0x23, 0x0C, 0x26, 0xAE, 0x3C, 0x96, 0x38, 0xB2, 0x56, 0xC2, 0x43, 0x56, 0x91, 0x81, 0x32, - 0x1F, 0x0D, 0x9E, 0xE4, 0x7C, 0x2B, 0xA0, 0xB3, 0x5C, 0x98, 0x2F, 0x75, 0x18, 0xE2, 0xA5, 0x47, - 0x6E, 0xEF, 0xC1, 0xCC, 0x9E, 0xE0, 0x2C, 0x0C, 0x86, 0xCE, 0x3D, 0x02, 0x43, 0x62, 0xC9, 0x3A, - 0x05, 0xB3, 0x89, 0x28, 0x88, 0xB2, 0x99, 0xB9, 0x42, 0xB7, 0xD9, 0x4E, 0x50, 0x29, 0xF3, 0x35, - 0x95, 0x0D, 0x69, 0xEF, 0xB6, 0x8F, 0xDA, 0xAD, 0x1F, 0xEE, 0xF0, 0x2C, 0x62, 0xFB, 0x45, 0xA7, - 0x69, 0x7E, 0xFB, 0x15, 0x1C, 0xAF, 0xEB, 0x55, 0x94, 0x3E, 0x28, 0xAA, 0x67, 0x39, 0xB3, 0x84, - 0xF6, 0x61, 0x8D, 0x61, 0xF1, 0x3C, 0x92, 0x77, 0x7E, 0xB5, 0x6A, 0x52, 0x72, 0x1E, 0x45, 0x4E, - 0x1F, 0xF5, 0xA9, 0x4D, 0xC9, 0x95, 0x0A, 0x5A, 0xE4, 0x0E, 0x66, 0x91, 0x45, 0xE2, 0xA3, 0xF3, - 0x05, 0x64, 0x53, 0x8C, 0x50, 0x10, 0xAA, 0xB6, 0x13, 0x16, 0x88, 0x0B, 0xF5, 0x71, 0x59, 0xF4, - 0x87, 0xAC, 0x51, 0xAE, 0x67, 0xC1, 0xF6, 0x04, 0x2D, 0x5A, 0xAC, 0x0F, 0x9D, 0x88, 0x80, 0x06, - 0x13, 0x1D, 0x45, 0x30, 0xA6, 0x79, 0xAA, 0xE8, 0x94, 0xEA, 0x88, 0x02, 0x22, 0x52, 0xAB, 0x15, - 0xCF, 0xC6, 0x58, 0x51, 0x65, 0xE2, 0x75, 0x6A, 0x65, 0xE5, 0x30, 0xBA, 0x51, 0xB5, 0x30, 0xC3, - 0x28, 0x89, 0x33, 0xCB, 0x16, 0x63, 0x48, 0x20, 0x61, 0xAC, 0xDA, 0x70, 0x58, 0x89, 0x61, 0x9E, - 0x32, 0x72, 0xEB, 0x4D, 0xD8, 0x69, 0x53, 0xAD, 0x21, 0xF8, 0xBB, 0x5A, 0x6D, 0x87, 0x0B, 0xAC, - 0x24, 0x6A, 0xF2, 0xA7, 0xAB, 0xEC, 0xC0, 0xE5, 0x04, 0x56, 0x50, 0xD7, 0xE1, 0x22, 0xD1, 0x75, - 0xA5, 0xBC, 0x92, 0x89, 0xC6, 0x73, 0x43, 0x96, 0xCB, 0x0C, 0x92, 0x00, 0x6F, 0x22, 0x01, 0x65, - 0xB8, 0xF6, 0xA7, 0x2E, 0xFA, 0x90, 0x58, 0x6C, 0xAD, 0x65, 0xE3, 0x6A, 0x3A, 0x94, 0xE4, 0x0C, - 0xCF, 0x3F, 0x9D, 0x0D, 0xE0, 0x2C, 0x0A, 0xC0, 0xEA, 0x63, 0xF0, 0x03, 0x3E, 0x5B, 0xE1, 0x31, - 0x14, 0x1D, 0x79, 0xC6, 0x19, 0xB4, 0x89, 0x6A, 0x07, 0xD3, 0x00, 0x7E, 0x90, 0x5D, 0xD5, 0x6E, - 0x3D, 0x87, 0x55, 0x54, 0xCF, 0x0A, 0xA1, 0x43, 0x07, 0x16, 0x16, 0x08, 0xC6, 0xB9, 0xB7, 0x02, - 0xFD, 0x06, 0x79, 0x15, 0x3E, 0x54, 0x64, 0xEE, 0xF1, 0xCB, 0x01, 0xEB, 0x6B, 0x1A, 0x1E, 0x0C, - 0xBB, 0xEC, 0xFC, 0x7A, 0xB8, 0xCB, 0x3E, 0x2A, 0x1E, 0x7F, 0x90, 0xE6, 0xE9, 0xA1, 0x7F, 0x87, - 0x3D, 0x7D, 0x56, 0xDC, 0x6F, 0x5B, 0x74, 0x5B, 0x92, 0x9F, 0xFB, 0x82, 0x96, 0x7D, 0x39, 0x18, - 0xCA, 0x83, 0x58, 0x20, 0x7D, 0x00, 0xB4, 0x55, 0x69, 0x3F, 0x01, 0x1A, 0x5D, 0x0E, 0x62, 0x39, - 0xB1, 0x0F, 0xE6, 0xF4, 0x96, 0x0F, 0x89, 0x4D, 0x79, 0x02, 0xA5, 0x04, 0xD1, 0x85, 0x94, 0x07, - 0x79, 0xC6, 0xA5, 0xA1, 0x14, 0x29, 0x21, 0x49, 0x04, 0x7A, 0x4E, 0xE9, 0xA9, 0x0F, 0xAA, 0x24, - 0xA6, 0xC6, 0x79, 0xE7, 0xA4, 0xA5, 0x8E, 0x6C, 0x7E, 0xA9, 0x40, 0xCB, 0xD9, 0xFB, 0xEB, 0x4B, - 0x46, 0x5D, 0x2B, 0x96, 0x03, 0x1F, 0x29, 0x40, 0x73, 0x78, 0x63, 0x93, 0x31, 0x1B, 0x17, 0xF0, - 0x82, 0xCC, 0xB9, 0xC8, 0x5C, 0x0C, 0xA2, 0x04, 0x36, 0x43, 0x83, 0x2D, 0x45, 0x67, 0x79, 0x22, - 0x16, 0xA0, 0xB4, 0x7C, 0x6B, 0x93, 0xD1, 0x3A, 0x58, 0xC8, 0x0B, 0x6A, 0xE7, 0xA2, 0x76, 0x39, - 0x30, 0x25, 0xD0, 0x5B, 0x36, 0xDA, 0x52, 0x14, 0x17, 0x82, 0x5E, 0x01, 0x86, 0x47, 0xA4, 0xC1, - 0x4D, 0xC6, 0x72, 0x57, 0x4C, 0x73, 0x0A, 0xD3, 0x7C, 0xC1, 0xF4, 0x7C, 0x4C, 0x97, 0xDB, 0x5E, - 0x09, 0xD1, 0x45, 0x9B, 0x0D, 0xA8, 0x70, 0x93, 0x2D, 0xE6, 0x2F, 0x5A, 0xB7, 0x3C, 0x58, 0xE2, - 0xB5, 0x67, 0xA3, 0x6B, 0x62, 0x01, 0x39, 0x84, 0xE8, 0x77, 0x7D, 0x3B, 0x20, 0x57, 0xC6, 0x3A, - 0x8A, 0x8E, 0x07, 0x08, 0x3F, 0xD7, 0x79, 0xA8, 0x7F, 0x21, 0x0D, 0x74, 0xBA, 0xBD, 0x6D, 0xAC, - 0xF1, 0x5D, 0x06, 0x95, 0xAB, 0x55, 0x7C, 0x49, 0xEE, 0x58, 0xA1, 0xDD, 0x3E, 0xD1, 0x60, 0xC5, - 0xF7, 0xE0, 0xD5, 0xAC, 0x71, 0xB8, 0xD5, 0x4F, 0x65, 0x88, 0x33, 0x3D, 0x7B, 0x05, 0x36, 0x38, - 0x58, 0xD1, 0x42, 0xE6, 0xB7, 0x59, 0xBB, 0x05, 0x2D, 0x6F, 0x33, 0x50, 0x4A, 0xA3, 0x9B, 0xB4, - 0xB9, 0xE1, 0x32, 0x9F, 0xDA, 0xDC, 0x36, 0x5B, 0x5C, 0xAD, 0x96, 0xB6, 0x2A, 0x8C, 0xCE, 0x44, - 0xEC, 0x37, 0x8C, 0x8B, 0xEF, 0x36, 0x80, 0xCF, 0x2C, 0x62, 0x74, 0xF8, 0x2A, 0x0B, 0xDE, 0x3D, - 0x5E, 0x93, 0xEB, 0x80, 0xB8, 0xF6, 0x37, 0x35, 0x72, 0x24, 0x77, 0x83, 0x54, 0x6E, 0xFA, 0xD4, - 0x9F, 0xCE, 0x62, 0x68, 0x83, 0xD4, 0xE7, 0xAE, 0xB0, 0x92, 0xA3, 0xBB, 0x6F, 0x90, 0x49, 0xB0, - 0xC5, 0x2E, 0x5A, 0xE3, 0x96, 0xBC, 0x4B, 0x15, 0x7C, 0x93, 0xEC, 0x7A, 0x18, 0x9F, 0x7F, 0x88, - 0xB7, 0x30, 0xEE, 0xEC, 0xA6, 0x06, 0xBB, 0xC2, 0x04, 0x51, 0xFF, 0xEB, 0x90, 0xBD, 0x67, 0x87, - 0xFB, 0xEE, 0x0B, 0x6B, 0x95, 0xA4, 0x12, 0xC3, 0x91, 0x42, 0xD6, 0x9A, 0x68, 0x50, 0x3F, 0x6B, - 0xAD, 0x9D, 0x04, 0x1C, 0xAE, 0xEA, 0x6E, 0x34, 0x52, 0x36, 0x03, 0xFF, 0x83, 0xF7, 0x9E, 0x10, - 0xF7, 0xED, 0x60, 0x0E, 0x41, 0x99, 0x39, 0x99, 0x9C, 0x55, 0x35, 0x2C, 0xF5, 0x5B, 0x1E, 0xB2, - 0x37, 0xBB, 0xED, 0x19, 0xBA, 0xCF, 0x7A, 0x21, 0x7C, 0xC7, 0xEF, 0xDE, 0xB3, 0x7F, 0xEF, 0xF8, - 0x2F, 0x28, 0x1F, 0x62, 0x70, 0x88, 0x13, 0xA5, 0xF0, 0x3D, 0x78, 0x7B, 0xF3, 0x91, 0xFD, 0xC6, - 0xB2, 0xBC, 0x73, 0x6E, 0x14, 0x9A, 0x31, 0xF0, 0x3D, 0x46, 0x2F, 0x3E, 0x21, 0xB6, 0x7B, 0x16, - 0x5D, 0x76, 0x5B, 0xBE, 0xA9, 0x35, 0x3D, 0x47, 0xB7, 0x01, 0xAD, 0xD1, 0x63, 0x5E, 0x06, 0x6F, - 0x38, 0x61, 0x46, 0x16, 0xC2, 0x7E, 0x74, 0x01, 0xF3, 0xA3, 0x0E, 0xEE, 0xED, 0x17, 0x6C, 0x96, - 0xF8, 0x39, 0xDB, 0xF4, 0x32, 0xD8, 0x1C, 0xBE, 0xBD, 0x25, 0xD8, 0x0C, 0x22, 0xA0, 0xA8, 0x8C, - 0x53, 0x0A, 0xA5, 0xC3, 0xB7, 0x37, 0x40, 0x82, 0xE1, 0x08, 0x4C, 0xC0, 0x63, 0x03, 0x64, 0xD3, - 0x7B, 0x5E, 0x16, 0xAF, 0x3B, 0xED, 0xF6, 0x0B, 0x6A, 0xC7, 0x90, 0x75, 0x86, 0x01, 0xA5, 0xF1, - 0x3B, 0x6C, 0xB2, 0x05, 0x48, 0x1E, 0xE0, 0xC3, 0xA5, 0x56, 0x84, 0xE1, 0x21, 0xE6, 0x5C, 0x9E, - 0xAF, 0x15, 0xBD, 0x55, 0xCC, 0x04, 0x4F, 0xCE, 0x49, 0xFA, 0x48, 0x97, 0x48, 0x9E, 0x40, 0xE3, - 0x08, 0x02, 0x7F, 0x1C, 0x0C, 0x23, 0x49, 0x59, 0x31, 0xF9, 0xC1, 0x44, 0x71, 0x14, 0xB5, 0x20, - 0x1C, 0xE9, 0xF9, 0xE0, 0x75, 0x81, 0x55, 0x2E, 0xB1, 0xE5, 0xA5, 0x50, 0x7A, 0xF6, 0xFE, 0x46, - 0x99, 0x32, 0x28, 0xEF, 0xF0, 0x67, 0xC5, 0x54, 0xD0, 0x11, 0xB5, 0x16, 0x63, 0x86, 0x65, 0xAA, - 0x61, 0xBD, 0x1B, 0xEC, 0xFD, 0x4A, 0x77, 0xA9, 0x86, 0x89, 0xB8, 0xD2, 0x37, 0xB8, 0x1C, 0xAC, - 0xB1, 0x58, 0x01, 0xDB, 0x0C, 0x7B, 0x46, 0xD2, 0xEC, 0x91, 0x61, 0xE6, 0xF8, 0x10, 0x1D, 0x3F, - 0xD5, 0xD0, 0x31, 0xD7, 0x7F, 0x86, 0xE1, 0x23, 0xD6, 0x53, 0x39, 0x53, 0x47, 0x0C, 0xD4, 0xD2, - 0xCC, 0x11, 0x01, 0xC8, 0x93, 0x9B, 0x3B, 0xA2, 0x4B, 0x5A, 0xDA, 0xE0, 0x11, 0xAF, 0xDB, 0x94, - 0x8E, 0xD4, 0xC3, 0x73, 0x36, 0xD4, 0xFF, 0xC4, 0xD4, 0xBC, 0xD2, 0x55, 0x57, 0xC3, 0x8F, 0xD9, - 0xA9, 0x76, 0xDB, 0xEC, 0xF3, 0x29, 0x52, 0x08, 0xDB, 0x63, 0x1F, 0x1C, 0x1E, 0x6D, 0x87, 0x1F, - 0x87, 0x36, 0xF0, 0xC6, 0x6C, 0x86, 0x58, 0xD4, 0x69, 0x79, 0x73, 0x36, 0x55, 0xAE, 0x4C, 0xEE, - 0xDE, 0x2D, 0x3E, 0xCC, 0x3A, 0x2D, 0x3C, 0x47, 0xC2, 0xE3, 0x95, 0xC1, 0x47, 0xDE, 0xAB, 0x1C, - 0x7E, 0xE1, 0x4D, 0x4E, 0x30, 0xDD, 0xF0, 0xBB, 0x3D, 0xF8, 0x23, 0xF7, 0x2D, 0x84, 0x54, 0xD1, - 0x5B, 0xDA, 0x49, 0x8C, 0xA9, 0xCD, 0x1C, 0xA7, 0x82, 0xB9, 0x0F, 0x29, 0x8C, 0xB6, 0x6F, 0xA4, - 0xC5, 0xB5, 0x4B, 0xA7, 0xAB, 0xC2, 0x6B, 0x99, 0xD0, 0xD3, 0x2A, 0x0A, 0x0C, 0x22, 0x47, 0x4C, - 0xC2, 0x0B, 0x53, 0xCC, 0xF2, 0xA9, 0xDA, 0xF3, 0x9C, 0xE5, 0xC1, 0xA5, 0x51, 0xFE, 0xE5, 0x8B, - 0xEF, 0xE4, 0x30, 0xFB, 0x7B, 0xE0, 0x2A, 0xF4, 0x7B, 0xBB, 0xE5, 0x7D, 0xF7, 0xB2, 0xC7, 0x0E, - 0xDA, 0x1E, 0xD0, 0xDE, 0x17, 0xBD, 0x95, 0x01, 0x44, 0x11, 0x57, 0x8D, 0xAB, 0xBE, 0x3C, 0x17, - 0x20, 0xCD, 0x9E, 0x4A, 0x31, 0x18, 0x33, 0xE0, 0xCF, 0xA2, 0x0C, 0x22, 0xC7, 0xC9, 0x56, 0x42, - 0x74, 0x8D, 0xB0, 0xEE, 0x76, 0x3B, 0xED, 0x5E, 0xE7, 0xF7, 0x76, 0xB7, 0xDD, 0x69, 0x1F, 0x8A, - 0xEC, 0xD7, 0x45, 0x80, 0x84, 0x26, 0xEC, 0xAF, 0xAB, 0x02, 0xF8, 0xDC, 0x7C, 0x9E, 0x35, 0xCC, - 0xBB, 0xED, 0xB7, 0xE5, 0x60, 0xBE, 0xDF, 0x3E, 0x5A, 0x07, 0xCC, 0xE5, 0x7C, 0x36, 0x12, 0xE6, - 0xF0, 0x14, 0x99, 0xF3, 0x49, 0x06, 0x27, 0x2F, 0xDC, 0x24, 0x71, 0x86, 0x15, 0x6C, 0x53, 0xFE, - 0x55, 0x4E, 0x63, 0x26, 0x15, 0x45, 0x16, 0x0A, 0x2A, 0x3C, 0xF7, 0x88, 0x4D, 0x8A, 0xBF, 0x8A, - 0x93, 0x94, 0x97, 0xD8, 0xC7, 0x3A, 0xDE, 0x58, 0x64, 0x2D, 0x20, 0x96, 0x60, 0x59, 0x34, 0x5A, - 0x8D, 0xFC, 0x7B, 0x99, 0xF5, 0x14, 0x6C, 0x65, 0xFA, 0x25, 0x73, 0xBE, 0xCB, 0x72, 0xB9, 0x42, - 0x7E, 0x99, 0x45, 0xFC, 0xF0, 0xEF, 0xCE, 0xEC, 0xEC, 0xEC, 0x44, 0xAB, 0xF6, 0x89, 0x02, 0x77, - 0x28, 0x40, 0xE5, 0x54, 0xEB, 0x13, 0x75, 0xE3, 0x7E, 0x2A, 0xAD, 0xC4, 0xA4, 0x17, 0x7A, 0xB4, - 0x53, 0x4A, 0x3B, 0xB6, 0x23, 0x95, 0x1D, 0x0B, 0x2B, 0x37, 0x66, 0x17, 0x51, 0x94, 0xE2, 0x94, - 0x58, 0x0C, 0x56, 0x76, 0xF3, 0xDD, 0xB4, 0x3A, 0xEB, 0x15, 0x23, 0x17, 0x4C, 0x2D, 0xA1, 0x57, - 0xCC, 0xDE, 0x9C, 0x38, 0xE9, 0xF2, 0xE9, 0xBC, 0xE2, 0x9D, 0x56, 0x0B, 0x34, 0xA1, 0xDB, 0x61, - 0xE4, 0x9D, 0x0B, 0x02, 0x32, 0xFC, 0xDD, 0x21, 0xBD, 0xBB, 0xD3, 0x0D, 0x1E, 0xB5, 0xB3, 0x02, - 0x26, 0x73, 0x6A, 0x15, 0x28, 0xF7, 0xFC, 0xD4, 0x33, 0xE7, 0xB4, 0x14, 0x91, 0xA3, 0x2C, 0x4E, - 0x06, 0xF8, 0xAE, 0xB8, 0x28, 0xA4, 0xBA, 0x03, 0xF0, 0x29, 0x75, 0xFF, 0x13, 0xB1, 0x05, 0x73, - 0x8A, 0x32, 0x76, 0x83, 0x4A, 0x71, 0x27, 0x54, 0x8A, 0xB3, 0x09, 0x28, 0x90, 0x7C, 0xC5, 0x2C, - 0xAB, 0x6A, 0x94, 0xF1, 0xD6, 0x41, 0xE8, 0x4A, 0xD9, 0x80, 0x96, 0xB4, 0x60, 0x96, 0x12, 0xDB, - 0x23, 0xB6, 0xA4, 0xD2, 0x26, 0xF0, 0xEF, 0xBA, 0x97, 0xB6, 0x09, 0x96, 0xEF, 0xE1, 0x14, 0x53, - 0x37, 0x03, 0xDB, 0xCC, 0x36, 0xE3, 0x02, 0x3E, 0xA1, 0x83, 0x7C, 0xEA, 0x86, 0x50, 0x48, 0xD0, - 0xFC, 0x3E, 0x60, 0xB2, 0x8C, 0x7B, 0x69, 0xAB, 0x08, 0x47, 0xA8, 0xB8, 0x31, 0x72, 0xE6, 0x69, - 0x1B, 0x53, 0x10, 0x29, 0x64, 0x9F, 0xFC, 0x93, 0x79, 0xE7, 0xDA, 0x7F, 0x29, 0x02, 0x7B, 0xE4, - 0x63, 0xF4, 0x4F, 0x57, 0x75, 0x74, 0xDB, 0x63, 0xAE, 0xA3, 0xC2, 0xFE, 0x3A, 0xEA, 0x1E, 0x46, - 0xAA, 0xB5, 0xFE, 0x4E, 0xA3, 0x89, 0xAF, 0xB2, 0x9A, 0xCC, 0x7A, 0x86, 0x15, 0xBB, 0x18, 0x29, - 0x65, 0x61, 0x31, 0x1F, 0x97, 0xBD, 0x67, 0x9A, 0xA5, 0xFA, 0x68, 0x74, 0x6A, 0xFD, 0xE1, 0x73, - 0xE7, 0x51, 0x28, 0x0D, 0x96, 0x03, 0x6A, 0xC3, 0xCE, 0xAB, 0x96, 0xE7, 0xBD, 0x7A, 0x1D, 0xB6, - 0x0C, 0xDA, 0xB4, 0xE0, 0x78, 0xBF, 0x50, 0xD4, 0xC9, 0x8E, 0xC7, 0xDE, 0x9F, 0xB0, 0x7F, 0x8D, - 0x2D, 0x03, 0x73, 0x9A, 0x62, 0x7E, 0x03, 0xD7, 0x73, 0x14, 0xBB, 0x75, 0x2B, 0x5A, 0xEC, 0x78, - 0xB3, 0x4E, 0xFE, 0xED, 0xB5, 0x9C, 0x61, 0x30, 0x2F, 0x00, 0x36, 0x68, 0x9A, 0xC0, 0x37, 0xDE, - 0xED, 0x4D, 0xBC, 0xA9, 0x71, 0xF2, 0xFF, 0x01, 0xEF, 0xA3, 0xB1, 0x22, 0x2D, 0x60, 0x00 + 0x1F, 0x8B, 0x08, 0x08, 0xAE, 0x0F, 0x15, 0x69, 0x02, 0xFF, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x2E, + 0x68, 0x74, 0x6D, 0x6C, 0x2E, 0x67, 0x7A, 0x69, 0x70, 0x00, 0xED, 0x7D, 0xD9, 0x76, 0xDB, 0x4A, + 0x92, 0xE0, 0xFB, 0xFD, 0x8A, 0x6C, 0xF6, 0x74, 0x5B, 0xEE, 0x91, 0x28, 0x90, 0x94, 0x64, 0x59, + 0x65, 0xF3, 0x1C, 0xAD, 0xB6, 0xA6, 0x24, 0x99, 0x2D, 0xCA, 0x75, 0x97, 0x39, 0x33, 0xF7, 0x40, + 0x40, 0x92, 0x44, 0x19, 0x04, 0x50, 0x58, 0x24, 0xEB, 0xF6, 0xE9, 0x3E, 0xF5, 0x19, 0x3D, 0x1F, + 0x32, 0x3F, 0x30, 0x9F, 0xD2, 0x5F, 0x32, 0x11, 0x91, 0x09, 0x10, 0x20, 0xB1, 0x92, 0x20, 0x45, + 0xCA, 0x72, 0xD5, 0x95, 0x44, 0x10, 0xB9, 0x45, 0x46, 0x44, 0xC6, 0x96, 0x11, 0x1F, 0xFE, 0xE1, + 0xEC, 0xCB, 0xE9, 0xDD, 0xAF, 0xBD, 0x73, 0x36, 0xF2, 0xC7, 0x66, 0xF7, 0xA7, 0x0F, 0xF8, 0x8B, + 0x99, 0xAA, 0x35, 0xFC, 0xD8, 0xE0, 0x56, 0xA3, 0xFB, 0x13, 0x3C, 0xE1, 0xAA, 0xDE, 0xFD, 0x89, + 0xC1, 0xBF, 0x0F, 0x63, 0xEE, 0xAB, 0x4C, 0x1B, 0xA9, 0xAE, 0xC7, 0xFD, 0x8F, 0x8D, 0xC0, 0x1F, + 0xEC, 0x1C, 0x36, 0xD8, 0x6E, 0xFC, 0xCB, 0x91, 0xEF, 0x3B, 0x3B, 0xFC, 0x6F, 0x81, 0xF1, 0xF0, + 0xB1, 0xF1, 0xCB, 0xCE, 0xD7, 0xE3, 0x9D, 0x53, 0x7B, 0xEC, 0xA8, 0xBE, 0x71, 0x6F, 0xF2, 0x06, + 0xD3, 0x6C, 0xCB, 0xE7, 0x16, 0xB4, 0xBC, 0x3C, 0xFF, 0xC8, 0xF5, 0x21, 0xDF, 0xD6, 0x46, 0xAE, + 0x3D, 0xE6, 0x1F, 0x5B, 0x93, 0x4E, 0x7C, 0xC3, 0x37, 0x79, 0xB7, 0xEF, 0xA8, 0xEE, 0xB7, 0x8B, + 0xC0, 0x62, 0xB7, 0x77, 0x7F, 0x66, 0x7D, 0xEE, 0x07, 0xCE, 0x87, 0x5D, 0xF1, 0x4D, 0x6C, 0x28, + 0x4B, 0x85, 0xA6, 0x8D, 0x07, 0x83, 0x3F, 0x3A, 0xB6, 0xEB, 0x37, 0xE8, 0x1B, 0xFC, 0x17, 0x8D, + 0xF2, 0x68, 0xE8, 0xFE, 0xE8, 0xA3, 0xCE, 0x1F, 0x0C, 0x8D, 0xEF, 0xD0, 0x87, 0x6D, 0x66, 0x58, + 0x86, 0x6F, 0xA8, 0xE6, 0x8E, 0xA7, 0xA9, 0x26, 0x0C, 0xBC, 0xCD, 0xC6, 0xEA, 0x77, 0x63, 0x1C, + 0x8C, 0x27, 0x0F, 0x02, 0x8F, 0xBB, 0xF4, 0x49, 0x85, 0x39, 0x7F, 0x54, 0xB6, 0x99, 0x37, 0x72, + 0x0D, 0xEB, 0xDB, 0x8E, 0x6F, 0xEF, 0x0C, 0x0C, 0xFF, 0xE3, 0x13, 0xF7, 0x26, 0xB3, 0x35, 0xE1, + 0x0B, 0xE6, 0x72, 0xF3, 0x63, 0xC3, 0xF3, 0x9F, 0x4C, 0xEE, 0x8D, 0x38, 0xF7, 0x1B, 0x6C, 0xE4, + 0xF2, 0x01, 0x3C, 0x71, 0xB5, 0xDD, 0x7B, 0xDB, 0xF6, 0x3D, 0xDF, 0x55, 0x9D, 0xE6, 0xD8, 0xB0, + 0x9A, 0x9A, 0xE7, 0x35, 0x4A, 0x36, 0xA4, 0xA7, 0xF1, 0x06, 0x9E, 0xE6, 0x1A, 0x8E, 0xCF, 0xE0, + 0x3B, 0xF1, 0xC2, 0x5F, 0xFF, 0x16, 0x70, 0xF7, 0x69, 0xA7, 0xD3, 0x3C, 0x68, 0x2A, 0xD4, 0xF9, + 0x5F, 0xE1, 0xD5, 0x0F, 0xBB, 0xE2, 0xB5, 0x8C, 0x36, 0xC9, 0xD9, 0x54, 0x6A, 0x70, 0x1F, 0x58, + 0x3A, 0x4C, 0x68, 0xB6, 0x5D, 0xBC, 0x61, 0x37, 0xDA, 0x82, 0xFF, 0xB6, 0xA5, 0xDB, 0x5A, 0x30, + 0x86, 0x5D, 0x78, 0xDB, 0xB4, 0xAD, 0xAD, 0x37, 0x9A, 0x69, 0x68, 0xDF, 0xDE, 0x6C, 0xB3, 0x37, + 0x4D, 0xDF, 0x1E, 0x0E, 0x4D, 0xBE, 0x73, 0xEF, 0x5B, 0xF0, 0x71, 0x10, 0x58, 0x9A, 0x6F, 0xD8, + 0x16, 0xDB, 0xE2, 0x6F, 0xD9, 0xBF, 0x45, 0xAD, 0x45, 0x0F, 0xB0, 0xFC, 0xC0, 0x75, 0xA1, 0x8B, + 0x3B, 0xD5, 0x1D, 0x72, 0xBF, 0xA9, 0x8D, 0x0C, 0x53, 0x87, 0xCF, 0xFF, 0x53, 0xF9, 0x5F, 0x6F, + 0x65, 0x37, 0xA7, 0xA6, 0xEA, 0x79, 0x5B, 0x6F, 0x0C, 0xD8, 0xF1, 0x1D, 0x4D, 0x75, 0xB9, 0xBF, + 0xA3, 0xDB, 0x8F, 0x16, 0x8B, 0x7D, 0x0E, 0x9C, 0x37, 0x6F, 0xFF, 0x14, 0x75, 0xFC, 0xEF, 0x6F, + 0xC5, 0x74, 0xA7, 0x67, 0x8F, 0xC0, 0x9E, 0x4C, 0xBE, 0xE9, 0xF9, 0x80, 0xB0, 0xDA, 0xCE, 0xD0, + 0xB5, 0x03, 0x67, 0x6A, 0x5A, 0x23, 0x6E, 0x0C, 0x47, 0xFE, 0x11, 0x53, 0xFE, 0x94, 0x78, 0x6C, + 0x3F, 0x70, 0x77, 0x60, 0xDA, 0x8F, 0x47, 0x6C, 0x64, 0xE8, 0x3A, 0xB7, 0x92, 0xDF, 0x02, 0x04, + 0x2D, 0xCF, 0xC0, 0x85, 0x1E, 0xC9, 0x0E, 0x98, 0xD2, 0xDC, 0xF3, 0x18, 0x57, 0x3D, 0x9E, 0x7C, + 0xF3, 0xDE, 0x76, 0x75, 0xC0, 0xBE, 0x7B, 0xDB, 0xF7, 0xED, 0xF1, 0x11, 0xF3, 0x6C, 0xD3, 0xD0, + 0x59, 0xCB, 0xF9, 0xCE, 0xFE, 0x51, 0x53, 0xF0, 0x7F, 0xB1, 0xA5, 0xFC, 0x34, 0x99, 0xAF, 0x69, + 0x78, 0xFE, 0x7A, 0xCF, 0x16, 0xFF, 0x39, 0xAA, 0xAE, 0x1B, 0xD6, 0x70, 0xC7, 0x15, 0x73, 0xDA, + 0x57, 0x9C, 0xEF, 0xE9, 0xCB, 0x11, 0xDD, 0x02, 0x51, 0x78, 0xCC, 0xD7, 0xB7, 0xD3, 0x9F, 0x8F, + 0xA6, 0x56, 0x2A, 0xBE, 0x3B, 0x62, 0x96, 0x6D, 0x4D, 0x4D, 0x72, 0x0C, 0xD8, 0x63, 0x58, 0x3B, + 0x26, 0x1F, 0x20, 0x20, 0x32, 0xC6, 0xBC, 0x0F, 0x60, 0x09, 0xD6, 0xD1, 0x00, 0x90, 0xD6, 0x9B, + 0xEA, 0xD9, 0x0E, 0x7C, 0x20, 0x56, 0x9E, 0x00, 0x62, 0x7C, 0xB6, 0x86, 0x85, 0x5F, 0x9F, 0xBB, + 0xAE, 0xED, 0x4E, 0xB5, 0xD4, 0x0D, 0xCF, 0x31, 0xD5, 0xA7, 0x23, 0x26, 0x5E, 0x49, 0x4E, 0x4B, + 0xB3, 0x4D, 0x1B, 0xE6, 0xEB, 0x72, 0x3D, 0xF9, 0x7C, 0x00, 0xCC, 0x6B, 0xC7, 0x33, 0xFE, 0x80, + 0x01, 0xBD, 0xB1, 0x6A, 0x9A, 0xDC, 0xCD, 0x1B, 0xB6, 0x1F, 0x68, 0x1A, 0xC2, 0xA3, 0xFA, 0xC0, + 0x43, 0x97, 0x4F, 0x6F, 0x7C, 0xDE, 0xD0, 0xD1, 0xF7, 0x8F, 0x12, 0xA5, 0xEE, 0x6D, 0x53, 0xCF, + 0xDA, 0xBE, 0xEF, 0x3B, 0xD4, 0x7E, 0x6A, 0x56, 0xD9, 0x1B, 0x81, 0xFF, 0x88, 0x3D, 0x1F, 0xB1, + 0x8E, 0xF2, 0x4F, 0xD9, 0xBD, 0x8A, 0x1E, 0xDA, 0x4A, 0x5E, 0xC7, 0xED, 0x1C, 0xB4, 0x0A, 0x7B, + 0xD8, 0xCB, 0xED, 0x61, 0x2F, 0xBB, 0x07, 0xD5, 0xF7, 0x81, 0xE9, 0x4E, 0x35, 0x76, 0xEC, 0x90, + 0x5A, 0xD4, 0x7B, 0x20, 0x81, 0xC0, 0x9F, 0x02, 0xF8, 0x1F, 0x3B, 0x86, 0xA5, 0xF3, 0xEF, 0x47, + 0xAC, 0xA5, 0x28, 0x53, 0x24, 0x21, 0x49, 0xA1, 0x35, 0x03, 0x0D, 0x38, 0x94, 0x76, 0x24, 0x44, + 0x0E, 0x94, 0x94, 0x6F, 0x69, 0xBA, 0xBE, 0xED, 0x00, 0x19, 0x25, 0x27, 0x2B, 0xD9, 0x9B, 0x60, + 0x68, 0x1F, 0x76, 0xC5, 0xD1, 0xFD, 0xD3, 0x87, 0x7B, 0x5B, 0x7F, 0x92, 0x3C, 0x5E, 0x37, 0x1E, + 0x98, 0x86, 0x7C, 0xF3, 0x63, 0x03, 0x0F, 0x4A, 0x15, 0x10, 0xC4, 0x6D, 0x30, 0x43, 0xFF, 0xD8, + 0x90, 0xCB, 0xBB, 0x84, 0xC7, 0x8D, 0x09, 0x37, 0xA4, 0x06, 0xAA, 0x69, 0x0C, 0xAD, 0x8F, 0x0D, + 0x9A, 0x6F, 0x23, 0x6C, 0x2E, 0xDF, 0x8F, 0xBD, 0x4B, 0xEF, 0x1B, 0xE3, 0xE1, 0x74, 0x77, 0x17, + 0x86, 0xC9, 0x6F, 0xE0, 0xB4, 0x6E, 0x4C, 0x8E, 0x96, 0x13, 0xF1, 0xED, 0x09, 0x48, 0x1A, 0xDF, + 0x9A, 0x8E, 0x35, 0x6C, 0xC0, 0x18, 0x70, 0x64, 0xCB, 0xC7, 0xCC, 0xE4, 0x0F, 0xDC, 0x6C, 0x74, + 0x81, 0x37, 0x3B, 0xAA, 0x15, 0xEF, 0xAE, 0xC7, 0x5D, 0x0D, 0xCE, 0x84, 0x46, 0x62, 0x4C, 0xC2, + 0x6B, 0x31, 0x29, 0xC2, 0x3C, 0x18, 0x07, 0x21, 0xF0, 0xB1, 0x11, 0x52, 0x82, 0x24, 0x04, 0x3A, + 0xB8, 0xA0, 0xC3, 0xD8, 0xEA, 0x76, 0x61, 0x79, 0x12, 0x32, 0xE2, 0xCF, 0x3C, 0x28, 0x4D, 0xF5, + 0x4A, 0xCC, 0x26, 0xBE, 0x1B, 0x84, 0x7C, 0x93, 0xBD, 0x13, 0x5B, 0x27, 0x80, 0xEB, 0x72, 0x10, + 0x99, 0x2E, 0xAD, 0x9E, 0x6B, 0x23, 0xC1, 0xC6, 0xE1, 0x7B, 0xDF, 0xBD, 0xC5, 0xEF, 0x7C, 0xE0, + 0x8D, 0x1F, 0x76, 0xEF, 0xBB, 0x1F, 0xEE, 0x5D, 0xFA, 0x0F, 0x25, 0x1F, 0x21, 0xBA, 0x30, 0xC3, + 0x03, 0x3E, 0x81, 0x67, 0x31, 0xBC, 0xD2, 0x64, 0x3D, 0x13, 0x39, 0x31, 0x7B, 0x54, 0x0D, 0xBF, + 0xD9, 0x6C, 0xAE, 0x6A, 0xEA, 0x28, 0xC6, 0x99, 0xDC, 0xE7, 0x29, 0x33, 0x67, 0x67, 0xD0, 0x59, + 0xC6, 0xD4, 0x47, 0xAA, 0x07, 0x3C, 0xF9, 0x91, 0x51, 0x1F, 0xAB, 0x98, 0xEC, 0xC0, 0x70, 0xC7, + 0x8F, 0x70, 0xF4, 0x7F, 0x75, 0x4C, 0x5B, 0xD5, 0xD3, 0x67, 0x3D, 0x3D, 0xDF, 0x0B, 0xD9, 0x86, + 0x05, 0x8E, 0xAE, 0xFA, 0x1C, 0x58, 0xA4, 0x68, 0xD5, 0x64, 0xC9, 0x4D, 0x10, 0x0B, 0x09, 0x37, + 0xA2, 0xE4, 0x62, 0xBA, 0x3F, 0xA5, 0x92, 0x12, 0x22, 0x31, 0x2E, 0x35, 0x7A, 0x1F, 0x44, 0xD2, + 0xF1, 0x4E, 0xAB, 0x0D, 0x28, 0x8A, 0x04, 0x14, 0xD1, 0x89, 0xEB, 0x7F, 0xDB, 0xF1, 0x50, 0x00, + 0x8E, 0x11, 0x49, 0x42, 0x3A, 0xFE, 0xD9, 0xB8, 0x30, 0x84, 0x88, 0x8C, 0xD8, 0x1D, 0x9B, 0x4D, + 0x69, 0x30, 0xC7, 0x00, 0xDB, 0xCA, 0x06, 0xEC, 0x18, 0x1A, 0xF5, 0xD4, 0x21, 0x2F, 0xB9, 0x20, + 0xD7, 0x7E, 0x9C, 0xD9, 0xC7, 0x7B, 0xD3, 0xD6, 0xBE, 0xFD, 0x29, 0xDE, 0x41, 0x41, 0x27, 0xE2, + 0x18, 0x41, 0xB6, 0x3C, 0xC5, 0x64, 0xF0, 0x1F, 0x2E, 0xFE, 0x1C, 0x24, 0x99, 0xA7, 0xC7, 0x11, + 0x87, 0xBD, 0x0B, 0x37, 0xF1, 0x28, 0xC6, 0x33, 0x00, 0x78, 0xE1, 0xE3, 0xBF, 0x70, 0xD7, 0x03, + 0x26, 0x9D, 0xCD, 0x19, 0x1E, 0x94, 0xA6, 0x22, 0xB9, 0x03, 0xE2, 0xC4, 0xCC, 0x70, 0x93, 0x5E, + 0x87, 0x96, 0xE7, 0x95, 0xEE, 0xF6, 0xD3, 0x4D, 0xBF, 0x1F, 0x9B, 0x5B, 0x6C, 0x14, 0x56, 0x30, + 0x8C, 0xC0, 0xBB, 0x93, 0xBB, 0xCB, 0xB3, 0xEC, 0xDE, 0xCF, 0x04, 0x6E, 0x9E, 0x98, 0x01, 0xF7, + 0x01, 0x2D, 0x47, 0xEC, 0xF2, 0x0C, 0xCE, 0x56, 0xF8, 0x57, 0x72, 0x0C, 0xCD, 0x06, 0xB9, 0xC9, + 0xB0, 0x00, 0xE9, 0xBD, 0xAB, 0xAB, 0xCF, 0xD9, 0xE3, 0x5C, 0x5D, 0x8D, 0x8E, 0x66, 0xBA, 0x99, + 0x82, 0x0A, 0xB7, 0x75, 0x0E, 0x62, 0xF3, 0x95, 0xEA, 0x67, 0xF7, 0xB3, 0x07, 0xCB, 0x7F, 0xAF, + 0xB4, 0xDF, 0xEF, 0xBD, 0x7B, 0x2F, 0x67, 0xB8, 0x5D, 0xB6, 0xDB, 0x3C, 0x20, 0xEF, 0xB4, 0x94, + 0xFD, 0x66, 0xEB, 0x70, 0x5F, 0xD9, 0x7F, 0x77, 0xD0, 0xAA, 0xD8, 0xF1, 0xB1, 0x99, 0x33, 0xDF, + 0xD6, 0xFE, 0x01, 0xCC, 0xF8, 0x30, 0x9C, 0x2C, 0xDB, 0x3A, 0xEE, 0x9D, 0xBE, 0x9D, 0x85, 0x67, + 0x29, 0xB4, 0x89, 0xC1, 0xFA, 0xFC, 0xF4, 0xFC, 0x22, 0x7B, 0x50, 0xFC, 0xB6, 0x08, 0xDA, 0x5C, + 0xE3, 0x83, 0x5F, 0xF2, 0x00, 0xD2, 0x3E, 0x54, 0xDA, 0xCA, 0x41, 0x73, 0xFF, 0xE0, 0xB0, 0x24, + 0x3C, 0xB0, 0xC7, 0x5F, 0x73, 0x7A, 0xDC, 0x7B, 0xD7, 0x3A, 0x38, 0x54, 0xF6, 0x9A, 0x7B, 0x4A, + 0xA7, 0x42, 0x8F, 0xBF, 0xE5, 0xE1, 0xC2, 0xE1, 0xC1, 0xC1, 0xC1, 0x7E, 0x73, 0xEF, 0x70, 0x6F, + 0xFA, 0x54, 0x2E, 0x02, 0x6C, 0x9C, 0xB7, 0xA5, 0x7E, 0x1E, 0xB9, 0x21, 0x0B, 0x19, 0xFB, 0x3B, + 0xCA, 0xB4, 0x34, 0x33, 0xCB, 0xF7, 0xE8, 0x40, 0x99, 0x61, 0x4C, 0xFF, 0xB0, 0xB3, 0xC3, 0x76, + 0xC2, 0x7F, 0x0C, 0x8E, 0xEE, 0x01, 0xC8, 0x31, 0xEC, 0xD4, 0xB6, 0x06, 0xC6, 0x30, 0xF6, 0xC5, + 0xCE, 0x4E, 0x77, 0x96, 0xA1, 0xC9, 0xE1, 0x75, 0xD0, 0xCB, 0x40, 0x29, 0x1A, 0xAA, 0xCE, 0x4E, + 0x3B, 0x85, 0x87, 0x7D, 0x10, 0x8A, 0x47, 0x24, 0x51, 0xF9, 0x16, 0x83, 0xFF, 0x76, 0x1C, 0xD7, + 0x80, 0xC9, 0x3D, 0xB1, 0x89, 0xB2, 0x2C, 0x78, 0xB0, 0x23, 0xA6, 0x20, 0x66, 0xD0, 0x60, 0xFE, + 0x93, 0x03, 0xCB, 0x10, 0x5D, 0x34, 0x18, 0x1C, 0x5D, 0xEA, 0x8E, 0x68, 0x41, 0xE7, 0x89, 0xA9, + 0x3A, 0x1E, 0x6F, 0xA4, 0xEE, 0x91, 0x78, 0x95, 0xD4, 0xEA, 0x8F, 0x8D, 0x7F, 0x0C, 0xDF, 0xED, + 0x25, 0x7B, 0x57, 0x5D, 0x43, 0xDD, 0xE1, 0xDF, 0x61, 0x03, 0x74, 0x8E, 0x07, 0xAB, 0x6A, 0x42, + 0x77, 0xE2, 0x29, 0x9E, 0x21, 0xAE, 0x6D, 0x7A, 0x93, 0x71, 0x92, 0x6D, 0xBB, 0xA9, 0xA3, 0x26, + 0x01, 0x18, 0xB8, 0x2A, 0xA9, 0xFE, 0x1F, 0x8C, 0xC4, 0xD2, 0x50, 0x6B, 0x9F, 0x9C, 0x8A, 0xA4, + 0xC3, 0xA3, 0x3A, 0xCF, 0xEE, 0x0D, 0x36, 0xA5, 0xE6, 0xE3, 0x71, 0x67, 0xA4, 0xE1, 0x8C, 0x00, + 0x48, 0x2A, 0xC6, 0x64, 0x6D, 0x53, 0xB8, 0x0C, 0x36, 0xBE, 0x87, 0x7D, 0x92, 0xE4, 0x5A, 0x6E, + 0x65, 0x84, 0x25, 0xA9, 0x7D, 0x79, 0x23, 0x90, 0x17, 0x0A, 0x3B, 0x9C, 0x41, 0x9F, 0x99, 0xB9, + 0xA9, 0xAE, 0xCE, 0xF0, 0xC7, 0x0E, 0x4A, 0xF1, 0xD3, 0x48, 0x9A, 0xD6, 0x62, 0x60, 0xBB, 0x63, + 0x69, 0x0F, 0x00, 0xF4, 0x6F, 0x67, 0x6C, 0x47, 0x6C, 0x4B, 0x8E, 0x32, 0x5F, 0x10, 0xD4, 0x2C, + 0xFB, 0xF5, 0x7D, 0x89, 0x65, 0xF7, 0xDE, 0x0E, 0xD0, 0xB2, 0xC6, 0xC7, 0x64, 0x66, 0x13, 0x5A, + 0x41, 0x66, 0x17, 0x64, 0x53, 0x40, 0xDB, 0x1D, 0x08, 0x2E, 0xDC, 0xE4, 0x9A, 0xCF, 0x54, 0x26, + 0x77, 0x9B, 0x01, 0x6E, 0x81, 0x2E, 0xCF, 0x2D, 0x06, 0xFD, 0x83, 0x00, 0xC0, 0xA4, 0x1C, 0x0C, + 0x0A, 0xBE, 0x0D, 0xCF, 0x55, 0x3F, 0x7C, 0xB1, 0xC9, 0x8E, 0x7D, 0x21, 0x43, 0x6E, 0xC7, 0x65, + 0xB2, 0x47, 0x03, 0xC4, 0x83, 0x00, 0x41, 0x4D, 0x1D, 0x73, 0x7D, 0xF2, 0x7E, 0x88, 0x6C, 0xDA, + 0x48, 0xB5, 0x86, 0xDC, 0x63, 0x28, 0xDE, 0x79, 0xEA, 0x03, 0xBC, 0xF2, 0x48, 0xE3, 0x81, 0x92, + 0x3C, 0x18, 0x70, 0x34, 0x2F, 0x45, 0x93, 0x01, 0x09, 0x2F, 0xEA, 0x07, 0x94, 0x79, 0x7A, 0xEF, + 0x4D, 0x1F, 0xDA, 0x24, 0x31, 0xF6, 0x0D, 0xBE, 0xE8, 0xC0, 0x64, 0x3C, 0xAE, 0x37, 0x73, 0x60, + 0x3B, 0x03, 0x3E, 0xC2, 0x5F, 0xC3, 0x1A, 0xD8, 0x3B, 0x9A, 0xE1, 0x6A, 0x30, 0xA0, 0xCF, 0xBF, + 0xFB, 0x11, 0xAD, 0x8F, 0x3D, 0xDC, 0xA9, 0x2C, 0x4E, 0x38, 0xC5, 0x11, 0xD3, 0x51, 0x60, 0x8A, + 0x0B, 0x96, 0x40, 0x0F, 0x94, 0xD2, 0xBA, 0x05, 0x9B, 0x9F, 0xCE, 0xBF, 0x13, 0x3A, 0x73, 0xC8, + 0x3E, 0x73, 0x41, 0x61, 0x58, 0x4E, 0xE0, 0x4B, 0x9E, 0xE5, 0xAA, 0xBA, 0x61, 0x37, 0xA4, 0x05, + 0x57, 0xC2, 0xFF, 0x56, 0x3C, 0x7B, 0x50, 0x41, 0x98, 0xF9, 0xD8, 0x50, 0x8A, 0xBA, 0x33, 0xD5, + 0x7B, 0x6E, 0xC6, 0x59, 0x87, 0x42, 0x1A, 0x66, 0x57, 0x6E, 0x3C, 0x88, 0x01, 0xF4, 0xC6, 0x42, + 0xA0, 0x7C, 0x11, 0x90, 0x6C, 0x55, 0x86, 0x64, 0x4B, 0x40, 0xB2, 0xD5, 0xEE, 0xEC, 0xED, 0x1F, + 0xBC, 0x3B, 0x7C, 0xAF, 0x4C, 0xFE, 0x7A, 0x85, 0xAA, 0x84, 0x6A, 0xBB, 0x32, 0x54, 0xDB, 0x02, + 0xAA, 0xAF, 0x10, 0x94, 0x10, 0xEC, 0x54, 0x86, 0x60, 0xE7, 0x15, 0x82, 0x09, 0x08, 0xEE, 0x55, + 0x86, 0xE0, 0xDE, 0x2B, 0x04, 0x13, 0x10, 0xDC, 0xAF, 0x0C, 0xC1, 0xFD, 0x57, 0x08, 0x26, 0x20, + 0x78, 0x50, 0x19, 0x82, 0x07, 0xAF, 0x10, 0x4C, 0x40, 0xF0, 0x5D, 0x65, 0x08, 0xBE, 0xAB, 0x0F, + 0x82, 0x35, 0x82, 0x50, 0x4C, 0x13, 0xDE, 0x8F, 0xE6, 0x29, 0x4C, 0xFE, 0xA1, 0x6E, 0x1B, 0x77, + 0xE0, 0x48, 0x73, 0x67, 0x87, 0xFE, 0xD8, 0xA3, 0x9F, 0x34, 0x10, 0xF5, 0x11, 0xC9, 0x70, 0xB9, + 0x60, 0xC1, 0xCE, 0x8F, 0x8A, 0x41, 0x90, 0x54, 0xCC, 0x70, 0xD0, 0x43, 0x1A, 0xEE, 0x5D, 0x95, + 0x4D, 0x44, 0x41, 0xBD, 0x91, 0x80, 0x88, 0xD4, 0x80, 0x13, 0x6A, 0xB9, 0xD8, 0x95, 0xFC, 0x5E, + 0x9D, 0xE9, 0x06, 0xE4, 0x38, 0x8C, 0xFA, 0x8E, 0x39, 0x13, 0x71, 0x7F, 0x9D, 0xBC, 0xBD, 0xCD, + 0xA4, 0x80, 0xD9, 0x81, 0x4E, 0x49, 0x09, 0xBA, 0x06, 0x95, 0x05, 0x0D, 0xB8, 0xC9, 0xC1, 0xA4, + 0x0B, 0x31, 0x67, 0xB8, 0xFA, 0x51, 0x65, 0xD6, 0x08, 0x23, 0x7D, 0xC8, 0xFB, 0x25, 0xA8, 0x4B, + 0x9A, 0x4C, 0x92, 0xC6, 0x0F, 0xF2, 0x10, 0xF9, 0x16, 0xF9, 0x23, 0x24, 0xF6, 0x34, 0xB2, 0xAC, + 0x2A, 0xA9, 0x98, 0x98, 0xAF, 0xBF, 0x92, 0x23, 0xD8, 0x3A, 0xC5, 0x28, 0x86, 0x99, 0x71, 0xB6, + 0xDE, 0x36, 0xA4, 0x1F, 0x44, 0x3E, 0x48, 0xB7, 0x40, 0x2C, 0x49, 0xB3, 0x8E, 0x69, 0xD7, 0x62, + 0x12, 0xD3, 0xAA, 0x30, 0xAA, 0xD2, 0x03, 0x55, 0xF3, 0x6D, 0x58, 0xB9, 0xCE, 0x07, 0x6A, 0x60, + 0xFA, 0x5E, 0x91, 0xDA, 0xBA, 0x14, 0xD5, 0xB5, 0x88, 0x23, 0x95, 0xC7, 0x6A, 0x37, 0x06, 0xFD, + 0x6B, 0x6F, 0x58, 0x1B, 0x42, 0xA7, 0x19, 0x89, 0x52, 0x5E, 0x9D, 0xB2, 0x0B, 0x92, 0x85, 0x7F, + 0x85, 0x46, 0xC1, 0xB1, 0x0F, 0x7C, 0x33, 0x6E, 0x19, 0xAC, 0xD9, 0x0C, 0x88, 0xEB, 0x99, 0xCB, + 0x06, 0x18, 0x6B, 0x98, 0x0E, 0xF7, 0x18, 0xA4, 0xA6, 0xAC, 0x7F, 0xE8, 0x52, 0x79, 0x66, 0xD3, + 0x5F, 0xD2, 0x48, 0x97, 0xBB, 0x96, 0x6C, 0xEB, 0x1C, 0x73, 0xFC, 0x9D, 0x56, 0xAE, 0x89, 0x8E, + 0x5C, 0x69, 0x5C, 0xF5, 0x02, 0x97, 0x68, 0xFC, 0x56, 0xF5, 0xF9, 0x25, 0x9E, 0x34, 0x39, 0x14, + 0x79, 0x3D, 0x79, 0x9D, 0xE1, 0xFB, 0x47, 0xA5, 0x4E, 0xBB, 0x7C, 0x16, 0x9C, 0x71, 0x36, 0xB6, + 0x89, 0x1F, 0xB6, 0xDA, 0x48, 0xD2, 0x1D, 0x36, 0x61, 0xE8, 0x65, 0xF8, 0x45, 0xEC, 0xFC, 0x9F, + 0x5A, 0xE0, 0xE7, 0x3F, 0x12, 0x7E, 0xCE, 0xF8, 0x49, 0x7F, 0x69, 0x15, 0x76, 0x8C, 0xFF, 0x3E, + 0xFF, 0x71, 0x54, 0xEA, 0xBD, 0x1A, 0x99, 0xEA, 0x14, 0x73, 0xBD, 0x1B, 0x71, 0x66, 0x05, 0xE3, + 0x7B, 0xEE, 0x32, 0x7B, 0xC0, 0x28, 0xCE, 0x03, 0xF0, 0xD7, 0x43, 0x43, 0xA1, 0x69, 0x6B, 0x02, + 0x99, 0xFF, 0xEB, 0xEF, 0xFF, 0x39, 0x30, 0xBE, 0x73, 0xEF, 0xBF, 0xFE, 0xFE, 0x7F, 0x98, 0x03, + 0x2F, 0x7A, 0x1C, 0xD0, 0x56, 0x6F, 0xB2, 0x63, 0xEB, 0xC9, 0x1F, 0x19, 0xD6, 0x90, 0xA9, 0xF7, + 0xF6, 0x03, 0x67, 0x7B, 0x9F, 0xFF, 0x00, 0x99, 0xF2, 0x09, 0xB0, 0x06, 0x4D, 0x97, 0x13, 0xDF, + 0x1D, 0xBC, 0x3C, 0xE4, 0x1E, 0xF5, 0x04, 0xF4, 0xB6, 0x4B, 0x3D, 0x0F, 0x87, 0xD8, 0x0E, 0x24, + 0x52, 0xCD, 0xE5, 0xB0, 0x34, 0xCD, 0xE0, 0x5E, 0x93, 0xDD, 0xD8, 0x80, 0x04, 0x0C, 0x67, 0x14, + 0x03, 0x34, 0x73, 0xD1, 0x75, 0x6D, 0x78, 0x14, 0xDD, 0xE5, 0x52, 0x5C, 0x17, 0xB2, 0xFE, 0x16, + 0x0C, 0x46, 0x96, 0x4C, 0xC3, 0x62, 0x27, 0x18, 0x37, 0x30, 0xB6, 0x75, 0xDE, 0x64, 0x67, 0xE2, + 0x24, 0x38, 0xC2, 0xC9, 0x34, 0xD9, 0x95, 0x31, 0x36, 0x7C, 0xEF, 0x88, 0x29, 0x4D, 0x45, 0x51, + 0x5A, 0xED, 0x36, 0x35, 0x54, 0xE0, 0x9B, 0x12, 0xFB, 0xBE, 0xD4, 0xF3, 0xA2, 0xEC, 0xB9, 0x31, + 0x79, 0xAF, 0x40, 0x1E, 0x2C, 0x71, 0xC8, 0x64, 0x90, 0x86, 0x90, 0x52, 0xF7, 0xE7, 0xA1, 0x8C, + 0xB8, 0x28, 0x29, 0x70, 0x28, 0x55, 0x98, 0x8C, 0xF9, 0x0A, 0x66, 0x09, 0xA8, 0xC4, 0x30, 0x4E, + 0x7A, 0xD3, 0x79, 0x25, 0xCC, 0x22, 0xD1, 0x2F, 0x36, 0x6E, 0xC2, 0x5D, 0x4F, 0x00, 0x42, 0xB7, + 0x1B, 0xAE, 0x47, 0x81, 0x41, 0xF8, 0xB8, 0x6B, 0xBB, 0x1F, 0x76, 0xE1, 0x17, 0x8D, 0xB7, 0x1E, + 0x3C, 0xA9, 0xCF, 0xB5, 0x46, 0xB7, 0x4F, 0x04, 0xEA, 0xB1, 0x7B, 0xEE, 0x3F, 0x72, 0xA0, 0x91, + 0xD8, 0x3B, 0xDE, 0x9A, 0x31, 0x9C, 0x9C, 0x99, 0x36, 0x81, 0x15, 0x00, 0xDD, 0x0B, 0x2C, 0x33, + 0x30, 0x38, 0x12, 0xF8, 0x80, 0x05, 0x5C, 0x00, 0xA8, 0x1D, 0x9A, 0xFA, 0x69, 0x7C, 0x02, 0x1D, + 0x2F, 0xF0, 0x2A, 0x30, 0xA0, 0x41, 0x60, 0x0A, 0x06, 0xE1, 0xAB, 0xDF, 0x88, 0x47, 0x25, 0x5E, + 0xE6, 0x18, 0x60, 0xC1, 0x06, 0xFC, 0x31, 0x9A, 0x81, 0xAA, 0xB9, 0xB6, 0x07, 0xBF, 0x80, 0x39, + 0xC1, 0xDB, 0xF0, 0xE2, 0x03, 0x7F, 0x62, 0x5B, 0xED, 0xBD, 0xFF, 0xCE, 0x46, 0x76, 0xE0, 0x7A, + 0x6F, 0xEB, 0x60, 0x4F, 0x13, 0x7E, 0xD4, 0xC2, 0x97, 0x0E, 0x5B, 0xEF, 0x0F, 0xC2, 0xF1, 0x81, + 0x25, 0x11, 0xCC, 0x4B, 0x83, 0x33, 0x16, 0x1B, 0xF6, 0xCA, 0x95, 0x6A, 0xE5, 0x4A, 0x44, 0x42, + 0x73, 0xB2, 0x25, 0x68, 0x5B, 0x03, 0x5F, 0x9A, 0xE3, 0xEB, 0x39, 0x95, 0x59, 0x11, 0x91, 0xF3, + 0x64, 0xA9, 0x63, 0x43, 0xBB, 0x06, 0x14, 0x35, 0xCF, 0x5C, 0xDB, 0x11, 0xA2, 0x68, 0x29, 0x8B, + 0x48, 0xBC, 0x69, 0x23, 0x75, 0x0F, 0x0F, 0x66, 0xAC, 0x20, 0x67, 0xA2, 0x0D, 0xA3, 0x46, 0x47, + 0x2B, 0x56, 0x26, 0x8F, 0xF5, 0xBF, 0x06, 0x9E, 0x1F, 0x32, 0x13, 0x9F, 0xBB, 0x96, 0x6A, 0x32, + 0xD5, 0x1C, 0xDA, 0xAE, 0xE1, 0x8F, 0xC6, 0x48, 0x95, 0x63, 0xD5, 0xD7, 0x46, 0xF4, 0x3D, 0x28, + 0x08, 0x42, 0xE5, 0x54, 0x1D, 0x07, 0x54, 0x64, 0x21, 0x0C, 0x71, 0xEB, 0xC1, 0x70, 0x6D, 0x0B, + 0xC7, 0x96, 0x0C, 0x4A, 0x3A, 0x77, 0x99, 0x31, 0x06, 0xD5, 0xF4, 0x81, 0x8B, 0xBE, 0x5D, 0xAE, + 0x71, 0x03, 0x58, 0xC2, 0x1B, 0x4F, 0x0C, 0xE3, 0x80, 0x8C, 0x2F, 0x3A, 0x00, 0xD6, 0x15, 0xE7, + 0x72, 0xD2, 0x57, 0x1C, 0xA0, 0xEF, 0xD5, 0x7E, 0x30, 0x74, 0xF4, 0xE9, 0x02, 0xB7, 0x70, 0x81, + 0x97, 0x69, 0x5A, 0x40, 0xDC, 0x25, 0x8C, 0xC4, 0xC5, 0x98, 0x6D, 0xC0, 0xED, 0x26, 0x86, 0xC5, + 0xD1, 0x88, 0xF1, 0x81, 0x70, 0xEA, 0x00, 0xAB, 0xC0, 0xF2, 0x02, 0xC3, 0xC7, 0x2B, 0x1E, 0x0C, + 0x60, 0xE4, 0x23, 0xDC, 0x89, 0xF7, 0xD0, 0x7E, 0x51, 0x83, 0x21, 0xBC, 0x6D, 0x65, 0x2D, 0x09, + 0x39, 0x99, 0x69, 0x7C, 0xE3, 0x26, 0x06, 0x69, 0xA0, 0x67, 0x1A, 0x84, 0x29, 0xE4, 0x61, 0xC8, + 0x16, 0x81, 0x3B, 0xC2, 0xDC, 0xA3, 0xF1, 0x40, 0x12, 0xC4, 0xDE, 0x41, 0x78, 0x13, 0x6C, 0x37, + 0x9A, 0xA5, 0x98, 0xB7, 0xF6, 0xB4, 0xBE, 0xCA, 0x78, 0x75, 0xE3, 0x9A, 0xC4, 0xE5, 0x42, 0xB7, + 0xB8, 0x08, 0x04, 0x10, 0x56, 0xD1, 0x24, 0x6D, 0x4C, 0x13, 0x5A, 0x92, 0x29, 0xE9, 0x92, 0xEC, + 0x04, 0x57, 0x2A, 0x5C, 0x1F, 0x0D, 0xB3, 0x72, 0x3E, 0x31, 0x36, 0xAC, 0x73, 0x93, 0x3F, 0xE4, + 0xEA, 0xC2, 0x73, 0x1B, 0xCF, 0x66, 0xE4, 0x1A, 0x31, 0x58, 0x59, 0xA6, 0x72, 0x0D, 0x48, 0xDA, + 0xFF, 0x0B, 0xC3, 0x26, 0x84, 0xD4, 0x47, 0x3F, 0xAD, 0x58, 0xC4, 0x91, 0xFC, 0x05, 0xE6, 0x81, + 0xD7, 0xAE, 0x18, 0x0F, 0x27, 0x82, 0xD4, 0xA3, 0x73, 0xBC, 0x96, 0xE0, 0x11, 0x09, 0xAA, 0xC2, + 0x5C, 0xE0, 0x01, 0x61, 0x9B, 0xA6, 0xE1, 0x93, 0x1D, 0xEB, 0x9E, 0xA3, 0xC4, 0xA2, 0x0B, 0x42, + 0x03, 0x55, 0xAB, 0xAC, 0x7E, 0xB2, 0x34, 0xDD, 0xA4, 0x1C, 0x99, 0x95, 0x39, 0xFD, 0xE7, 0x25, + 0xA5, 0x2A, 0x47, 0x79, 0x02, 0x3B, 0x2B, 0x1C, 0xDD, 0xA2, 0xC1, 0xE6, 0x9D, 0xD7, 0x30, 0xF1, + 0xD3, 0x9B, 0x2F, 0x2B, 0x23, 0x43, 0x18, 0xAB, 0x0A, 0x15, 0x9E, 0xEE, 0xDE, 0x28, 0xCF, 0x4D, + 0x7D, 0x13, 0xEA, 0xC2, 0xF0, 0x2B, 0xD5, 0x14, 0xF7, 0x2E, 0x52, 0x49, 0x6D, 0x62, 0x32, 0x38, + 0xD0, 0x4F, 0x40, 0x6A, 0x47, 0x1A, 0xFD, 0xED, 0xFC, 0x6C, 0xE7, 0xE2, 0x7D, 0x8F, 0x8E, 0xB5, + 0x96, 0x12, 0x3D, 0xFE, 0x7A, 0xFD, 0xFE, 0x50, 0x79, 0xA5, 0xCD, 0xF9, 0x68, 0x13, 0xB1, 0xA8, + 0x0A, 0x69, 0xC2, 0xFB, 0x1B, 0x43, 0x99, 0x68, 0xBA, 0x0E, 0xED, 0xAC, 0x96, 0x87, 0xA8, 0x47, + 0xAC, 0xFF, 0x74, 0xC4, 0xB5, 0x6F, 0x27, 0xF6, 0x77, 0xEE, 0x15, 0x4A, 0xD3, 0xDD, 0xD3, 0x78, + 0x43, 0x6F, 0xD5, 0x52, 0xF1, 0x5D, 0x5C, 0x90, 0x04, 0x11, 0x50, 0x53, 0x1D, 0x12, 0x21, 0x41, + 0xDE, 0x83, 0x15, 0xC9, 0xFB, 0xAA, 0x20, 0x13, 0x8A, 0x77, 0x50, 0xF4, 0x14, 0x74, 0x05, 0x47, + 0x9A, 0x6B, 0x83, 0x80, 0x09, 0xF4, 0x63, 0x38, 0x26, 0x9F, 0xD0, 0x5D, 0xA4, 0x4F, 0x47, 0x5F, + 0x25, 0x20, 0x03, 0xBA, 0x7D, 0xDF, 0x1E, 0xF3, 0xB8, 0x14, 0xEA, 0x31, 0xDD, 0xD0, 0x7C, 0x14, + 0x77, 0x51, 0x48, 0xB5, 0x38, 0xD0, 0x28, 0x06, 0x4B, 0x06, 0x2E, 0x4A, 0xCC, 0x30, 0x0D, 0xEE, + 0xE2, 0xF5, 0x8E, 0x64, 0x37, 0x34, 0x1F, 0x07, 0xFF, 0x42, 0x32, 0x16, 0x52, 0x91, 0xD0, 0xF5, + 0x85, 0x90, 0x9B, 0x7C, 0x99, 0xA2, 0x2A, 0x85, 0x71, 0x72, 0x5A, 0x70, 0x86, 0xC5, 0xA0, 0xC4, + 0xED, 0x8F, 0x6C, 0x8F, 0x47, 0x4B, 0x03, 0x91, 0x1D, 0x3A, 0x09, 0x05, 0xED, 0xB1, 0x58, 0xEA, + 0x3D, 0xC7, 0xCF, 0xC4, 0x42, 0xF4, 0xC0, 0xC5, 0xBF, 0x23, 0xB9, 0x57, 0x53, 0x4D, 0x2D, 0x88, + 0xD6, 0x17, 0xB1, 0x95, 0x63, 0x18, 0x95, 0x5B, 0x08, 0x4E, 0xBD, 0xB9, 0xD9, 0x22, 0xF1, 0x0C, + 0x82, 0x9F, 0x70, 0xE3, 0xCC, 0x0E, 0xA6, 0xE8, 0x1E, 0x91, 0x5E, 0x38, 0x73, 0xE2, 0x0E, 0xC9, + 0x72, 0x47, 0xCE, 0x4C, 0x47, 0xF2, 0x60, 0x11, 0x67, 0x51, 0x62, 0xEC, 0xDF, 0xE5, 0xE0, 0x5D, + 0xF1, 0xBB, 0x1C, 0xC7, 0x13, 0x4C, 0x6B, 0x76, 0x14, 0x7A, 0x1E, 0x7A, 0x9C, 0xE8, 0x11, 0xCC, + 0x3D, 0x8A, 0x64, 0x48, 0x21, 0xED, 0x68, 0xF4, 0xB9, 0x5D, 0x7E, 0xA9, 0x00, 0xFD, 0xA4, 0x9A, + 0x86, 0xC9, 0xED, 0x67, 0x82, 0x68, 0x38, 0x7A, 0x57, 0xFE, 0xB1, 0x6A, 0x98, 0x46, 0xE3, 0xD7, + 0x0C, 0x54, 0xD3, 0xB6, 0x60, 0x72, 0xCF, 0x05, 0xD4, 0xAB, 0x2F, 0x37, 0xC7, 0xFD, 0x3E, 0x00, + 0x55, 0xFC, 0xB1, 0x72, 0xA0, 0x86, 0xE3, 0xD7, 0x0C, 0x54, 0xE7, 0xD9, 0x00, 0xDA, 0x43, 0x60, + 0xF6, 0x56, 0x0F, 0xC8, 0x5E, 0xED, 0x40, 0xBC, 0x51, 0x1F, 0x0C, 0xED, 0x99, 0xC0, 0x08, 0x63, + 0x5F, 0x9E, 0x36, 0xBA, 0x37, 0xC7, 0x7F, 0xB9, 0x3C, 0x5D, 0x35, 0x28, 0xE5, 0xD8, 0xF5, 0x02, + 0xF3, 0x5F, 0xFF, 0x78, 0x36, 0x1A, 0xFF, 0xD7, 0xDF, 0x90, 0xC0, 0xF0, 0xE7, 0xAA, 0x21, 0x29, + 0x46, 0xAE, 0x17, 0x90, 0xFD, 0x7B, 0xF5, 0xB9, 0x00, 0xD9, 0x3F, 0x39, 0x86, 0xE5, 0xE0, 0xCF, + 0x55, 0x03, 0x52, 0x8C, 0xBC, 0x10, 0x20, 0xE7, 0x52, 0xB5, 0x9D, 0x49, 0x9C, 0x48, 0x42, 0x40, + 0x5E, 0x42, 0xFC, 0x5C, 0xA1, 0x62, 0x43, 0x33, 0x11, 0x67, 0xF0, 0x67, 0xD5, 0x93, 0x46, 0xE6, + 0x2A, 0x06, 0x86, 0x09, 0x9E, 0xD4, 0x81, 0x1A, 0x42, 0x68, 0xFE, 0x14, 0x4D, 0xA8, 0xD1, 0x3D, + 0xA7, 0x27, 0x4C, 0x3E, 0x62, 0x9F, 0x8F, 0xFB, 0xBB, 0xE7, 0x07, 0x85, 0x12, 0xF5, 0xA9, 0x0D, + 0xEA, 0x0B, 0xE5, 0xE3, 0xF1, 0x96, 0x8F, 0x55, 0xB3, 0x93, 0x5E, 0xB1, 0x2A, 0xF7, 0x15, 0x34, + 0x98, 0xCF, 0xD0, 0x82, 0x1D, 0x4B, 0x33, 0x3C, 0xEB, 0x73, 0x97, 0x6E, 0x95, 0x69, 0x13, 0x38, + 0x84, 0xBE, 0x06, 0x9D, 0xDC, 0x96, 0xA4, 0x0E, 0x85, 0x40, 0x4D, 0x90, 0x45, 0x4C, 0x8D, 0x39, + 0x5F, 0x7B, 0x15, 0xA6, 0x34, 0xAB, 0xA3, 0x38, 0x2D, 0xDE, 0x73, 0x9C, 0x62, 0x14, 0x5F, 0x88, + 0xB8, 0xA7, 0x6D, 0x69, 0x93, 0xA1, 0x7B, 0xBD, 0x12, 0xF1, 0xC3, 0xFB, 0x33, 0xE6, 0xB5, 0x30, + 0xC6, 0x8C, 0x33, 0xE8, 0x61, 0x1D, 0x1C, 0xF9, 0x5A, 0x22, 0xE8, 0xCD, 0xF3, 0x49, 0x21, 0x46, + 0x53, 0x19, 0xCC, 0xAF, 0x09, 0x28, 0xE3, 0x03, 0x72, 0x11, 0x79, 0xA0, 0x97, 0xCC, 0x51, 0xD1, + 0x9B, 0xA5, 0xB3, 0xFB, 0x27, 0x06, 0x93, 0xD2, 0xB8, 0xB7, 0xCD, 0x2C, 0xDB, 0xC7, 0xAC, 0x14, + 0x63, 0x35, 0xAE, 0x30, 0xB7, 0x59, 0x8B, 0xB5, 0x00, 0x18, 0x4A, 0xB3, 0x45, 0x3F, 0xF6, 0x5F, + 0x64, 0xB4, 0x4E, 0x6E, 0x14, 0xF7, 0x41, 0x59, 0x23, 0x63, 0x85, 0x68, 0xEE, 0x04, 0xF6, 0x95, + 0xEC, 0xDE, 0x99, 0x69, 0xB9, 0x88, 0x4D, 0xAE, 0x6C, 0x38, 0xC0, 0xF2, 0x4C, 0x77, 0xB8, 0x1A, + 0x73, 0xD8, 0x7E, 0xAF, 0x38, 0x9F, 0xE0, 0xC4, 0x95, 0xE4, 0xEF, 0x3D, 0xDF, 0x11, 0x17, 0x78, + 0xFC, 0xBA, 0x7F, 0xFD, 0xAE, 0xD1, 0xC5, 0x9F, 0xEC, 0xF6, 0xEE, 0xF4, 0x9A, 0x89, 0xBB, 0xC4, + 0x40, 0x4E, 0xCB, 0x3F, 0xAB, 0xA2, 0xD1, 0x9F, 0xE1, 0x88, 0xA2, 0x05, 0x93, 0xFF, 0xD8, 0x17, + 0xEB, 0x1E, 0x73, 0x0C, 0xE2, 0x8F, 0xF3, 0x81, 0x33, 0xC3, 0xA3, 0x23, 0x87, 0x6D, 0xC1, 0xCB, + 0x7B, 0x6F, 0xD7, 0xFD, 0xE4, 0x99, 0x47, 0x38, 0x94, 0xD9, 0x5C, 0xB4, 0xF1, 0x75, 0x49, 0xD7, + 0x6A, 0xAD, 0xE7, 0x51, 0x6C, 0xE0, 0x79, 0xDD, 0xAC, 0xC4, 0xEC, 0x71, 0xFF, 0x9E, 0xFB, 0x34, + 0x5A, 0xC8, 0xEF, 0x1A, 0x2E, 0x22, 0x2E, 0x22, 0xC5, 0x10, 0x71, 0xE7, 0xBD, 0xF2, 0x23, 0x1D, + 0x41, 0x7B, 0xF3, 0x1F, 0x41, 0x85, 0x8E, 0xA0, 0x38, 0xCA, 0x55, 0x3A, 0x83, 0x62, 0x0D, 0x37, + 0xFB, 0x08, 0xAA, 0x7C, 0x98, 0x54, 0xD0, 0x95, 0x6E, 0x40, 0x00, 0x73, 0x4E, 0x4D, 0x03, 0x13, + 0xC9, 0x85, 0xCA, 0xD2, 0xCD, 0xDD, 0xED, 0x65, 0x8F, 0x89, 0x87, 0xC5, 0x66, 0xFE, 0xC5, 0x55, + 0x9F, 0xC4, 0x1C, 0x56, 0x94, 0x7F, 0xE3, 0x2B, 0xB9, 0x74, 0x0C, 0x4F, 0x2E, 0x56, 0xA3, 0xD1, + 0x91, 0xC0, 0x31, 0xA4, 0x06, 0xF3, 0xA5, 0xC5, 0x08, 0x9B, 0x46, 0x12, 0xBE, 0x1C, 0x95, 0x69, + 0xAA, 0x47, 0xFE, 0x1D, 0x4F, 0xA8, 0x48, 0x4D, 0xF6, 0xAB, 0x1D, 0xB8, 0x61, 0x16, 0x8E, 0x71, + 0xE0, 0xF9, 0xC8, 0x22, 0x1E, 0x0D, 0x8C, 0x72, 0x17, 0x09, 0xC9, 0x5C, 0xBC, 0x70, 0xC6, 0xE0, + 0xCC, 0xC2, 0x88, 0x60, 0xDF, 0x18, 0xA7, 0x1E, 0x58, 0x9B, 0x95, 0x3D, 0x03, 0xB7, 0xCE, 0x9A, + 0x6C, 0x5A, 0x78, 0x45, 0x26, 0x35, 0x83, 0xCC, 0x92, 0x83, 0x0D, 0xE2, 0xD3, 0x80, 0x9D, 0xE1, + 0xEE, 0x67, 0xDB, 0xF3, 0xE7, 0xD3, 0x94, 0xA8, 0x79, 0x21, 0x2B, 0xC0, 0xFE, 0x8F, 0xE6, 0x75, + 0x96, 0x1F, 0xCE, 0xE7, 0x2C, 0x2F, 0x10, 0xD3, 0xD3, 0x61, 0x50, 0xDA, 0x73, 0x9E, 0xDA, 0x7C, + 0xF9, 0x8E, 0xF4, 0x15, 0xE3, 0x45, 0x0F, 0x13, 0x63, 0x2F, 0x11, 0x2F, 0xB0, 0xFF, 0x55, 0xE3, + 0x45, 0xE1, 0xD9, 0x99, 0x0E, 0x85, 0xF9, 0x31, 0x03, 0x9B, 0xBF, 0x38, 0xCC, 0x80, 0xA3, 0xC0, + 0x5D, 0x26, 0x66, 0x60, 0xFF, 0xEB, 0xCE, 0x31, 0x08, 0x06, 0xF3, 0xE3, 0x05, 0x36, 0x7F, 0x91, + 0x78, 0xD1, 0xFB, 0xB9, 0x58, 0xAD, 0xC8, 0xC1, 0x9C, 0x2C, 0x9D, 0xA8, 0x02, 0xE6, 0xB0, 0xDE, + 0xCF, 0x73, 0x23, 0xCF, 0x3B, 0x81, 0xB8, 0xAB, 0x40, 0x1E, 0x00, 0xD4, 0x62, 0xE8, 0xD3, 0xFB, + 0xF9, 0x05, 0x21, 0xD0, 0xB5, 0x1D, 0x58, 0x7E, 0xCF, 0x36, 0xAC, 0xF9, 0x8E, 0x1C, 0x6A, 0x5E, + 0xE2, 0xC4, 0x81, 0xFE, 0xD7, 0x97, 0xB1, 0xC4, 0x60, 0x30, 0x0F, 0x66, 0x4C, 0x9A, 0xBF, 0x48, + 0xBC, 0x58, 0x12, 0x63, 0xA9, 0x80, 0x39, 0xC5, 0x6F, 0xAD, 0x31, 0xE3, 0x49, 0x00, 0x72, 0x31, + 0xF4, 0x5A, 0x2F, 0xC6, 0x13, 0xE9, 0xF7, 0xAD, 0xDA, 0xFD, 0xE6, 0xB1, 0xD5, 0xDF, 0x61, 0x61, + 0x8B, 0xB1, 0xE1, 0x7F, 0xFA, 0x74, 0xDC, 0xE8, 0x86, 0x1F, 0x18, 0x7C, 0x42, 0x0D, 0x58, 0xF0, + 0xE4, 0xE5, 0xDB, 0x92, 0x33, 0xE6, 0x53, 0xB8, 0x99, 0x81, 0x45, 0x1D, 0x72, 0x7D, 0xD5, 0x46, + 0x68, 0x8A, 0x3F, 0xD5, 0x08, 0x3A, 0x98, 0x86, 0xFE, 0x6F, 0x81, 0x81, 0x57, 0xAE, 0xE0, 0xAF, + 0x61, 0x60, 0xAA, 0xEE, 0x24, 0xAA, 0x53, 0xE6, 0x4E, 0x27, 0x83, 0x01, 0x85, 0x8D, 0x92, 0xC7, + 0x74, 0x0B, 0xC1, 0x3B, 0x16, 0x89, 0x67, 0xDE, 0x32, 0x4F, 0x66, 0xF5, 0xC4, 0xEF, 0x45, 0x97, + 0xF0, 0xCB, 0x62, 0x6A, 0xE0, 0xDB, 0x63, 0x2C, 0xB9, 0xA2, 0x9A, 0xE6, 0x93, 0x4C, 0x60, 0x22, + 0xA3, 0x5B, 0x55, 0x97, 0x7B, 0x3E, 0x53, 0x1F, 0x54, 0x83, 0xCA, 0xF1, 0x4C, 0xDB, 0x27, 0x52, + 0x8C, 0x0A, 0x1B, 0xE8, 0x77, 0x2D, 0x65, 0x7A, 0x90, 0x40, 0xC4, 0xCB, 0x93, 0x27, 0x22, 0xD5, + 0x47, 0xCE, 0x58, 0x32, 0x83, 0x48, 0x94, 0xB2, 0x66, 0xC8, 0x7D, 0x99, 0xFD, 0xE7, 0xCA, 0xF0, + 0xFC, 0xAD, 0xB7, 0x33, 0xB9, 0x71, 0xC6, 0x3A, 0xFD, 0x92, 0xC5, 0x4E, 0x32, 0x73, 0x8D, 0xE4, + 0x1B, 0x99, 0x4A, 0xE4, 0x21, 0x29, 0xCC, 0x39, 0x82, 0xF9, 0x5C, 0x72, 0x47, 0x99, 0x33, 0x25, + 0x09, 0xF6, 0x9B, 0xBF, 0x81, 0x12, 0x40, 0x94, 0x62, 0xC3, 0x8B, 0x27, 0x26, 0x81, 0xA6, 0x8B, + 0xE7, 0x26, 0x99, 0xEC, 0x75, 0x51, 0x72, 0xA0, 0xF2, 0x24, 0x3C, 0x8D, 0x17, 0x97, 0x80, 0xC5, + 0x77, 0x78, 0x9A, 0x94, 0xB1, 0x05, 0xDE, 0x5C, 0x9F, 0x1F, 0xD3, 0xC5, 0x8D, 0xDB, 0xE3, 0x9F, + 0x7F, 0xA1, 0xF4, 0xB8, 0x48, 0x71, 0xFE, 0xA3, 0xCD, 0xC6, 0xB6, 0x27, 0xBC, 0xCD, 0xB6, 0x45, + 0xA1, 0xEC, 0x58, 0x5D, 0x0B, 0xA3, 0xCC, 0x61, 0x7B, 0x3D, 0x71, 0x2B, 0x53, 0x00, 0xEA, 0x3E, + 0xF0, 0x93, 0x01, 0xE2, 0x5E, 0xE0, 0xE0, 0xBB, 0x9E, 0xB8, 0x96, 0x09, 0x94, 0x6E, 0xB1, 0x77, + 0x4A, 0x2C, 0xD1, 0xAE, 0x6C, 0xE8, 0x35, 0xD9, 0xB9, 0xAA, 0x8D, 0xA2, 0x7E, 0xC4, 0xCD, 0x70, + 0xC1, 0x53, 0xE5, 0x0E, 0xB2, 0xC7, 0x91, 0x31, 0x79, 0x43, 0x64, 0xEF, 0xD5, 0x23, 0x37, 0x97, + 0xF2, 0x96, 0x26, 0x8E, 0xE9, 0x95, 0xED, 0x81, 0x8F, 0x17, 0xC9, 0xE9, 0xAE, 0xB9, 0xE8, 0x8D, + 0x8A, 0x65, 0xC8, 0x29, 0x6F, 0xB5, 0xD8, 0x47, 0x20, 0x82, 0xC9, 0x97, 0xD1, 0x37, 0x98, 0x9E, + 0xA3, 0x85, 0xF7, 0x5A, 0xB6, 0xD9, 0xBE, 0x7C, 0x47, 0x7C, 0x27, 0x6F, 0xBC, 0xEF, 0x33, 0xCA, + 0xE4, 0xF1, 0x36, 0xC6, 0x60, 0x08, 0x60, 0xC0, 0xCE, 0xB6, 0xD9, 0xA7, 0x3E, 0xFD, 0xB8, 0xC3, + 0x1F, 0x7F, 0xD9, 0x16, 0x40, 0xBC, 0x3E, 0x8D, 0xA5, 0xD1, 0xC0, 0x03, 0xA5, 0xAD, 0x6C, 0x64, + 0x72, 0xE0, 0xA2, 0x74, 0x38, 0xF9, 0x74, 0x94, 0x93, 0xB7, 0x3A, 0x25, 0xEB, 0xFA, 0x7E, 0x4A, + 0xD2, 0xF5, 0xD4, 0x1E, 0xE7, 0xCD, 0x15, 0x16, 0xE7, 0x85, 0xB3, 0xF9, 0xC2, 0xAC, 0x31, 0x57, + 0xE5, 0xEE, 0x7A, 0x59, 0xC9, 0xC2, 0xCA, 0xF9, 0xD7, 0x22, 0x3E, 0x4B, 0x99, 0xA9, 0xEE, 0xEC, + 0x3E, 0x65, 0x45, 0x30, 0xAC, 0x61, 0xD8, 0xFD, 0x24, 0x47, 0x18, 0x60, 0x46, 0xF8, 0xB0, 0x64, + 0x9E, 0xB0, 0x92, 0x79, 0x01, 0x96, 0x03, 0x23, 0x99, 0x81, 0x66, 0x39, 0x60, 0xBA, 0x4A, 0x76, + 0x9E, 0x00, 0x52, 0xAF, 0xD7, 0x63, 0xF2, 0xFB, 0xFA, 0xE0, 0x94, 0x56, 0xA0, 0x21, 0xFD, 0xB0, + 0xB5, 0x3D, 0xD5, 0xD0, 0x90, 0xE2, 0xFB, 0xBE, 0xCB, 0xD5, 0x71, 0x78, 0xDB, 0xDF, 0x6B, 0x94, + 0xF4, 0x14, 0xA6, 0x75, 0xD2, 0x2A, 0x91, 0x33, 0x20, 0x4B, 0x9D, 0xF2, 0xA8, 0x87, 0x4B, 0x0C, + 0x14, 0x02, 0x71, 0x12, 0xFB, 0xFC, 0x1D, 0xC4, 0x63, 0x62, 0x49, 0xB2, 0x73, 0x71, 0x7D, 0x1E, + 0xBE, 0x3C, 0x2A, 0xEF, 0xD4, 0x14, 0x5C, 0x28, 0x7E, 0x17, 0x3B, 0x75, 0x1C, 0x5A, 0x4D, 0xEA, + 0x37, 0xA5, 0x9D, 0xBD, 0xF3, 0xDE, 0xE1, 0x4E, 0xCC, 0xD4, 0xA6, 0x2B, 0x4C, 0xB1, 0x0C, 0xE1, + 0x2D, 0x65, 0x0C, 0x54, 0x24, 0x1E, 0xCF, 0xDD, 0x4F, 0xAB, 0xD1, 0x6D, 0xD7, 0xD1, 0x4F, 0x1B, + 0x4B, 0x5A, 0xD4, 0xD0, 0x4F, 0xA7, 0xD1, 0xDD, 0xAF, 0xA3, 0x9F, 0x3D, 0x84, 0x4F, 0x1D, 0x1D, + 0xED, 0x23, 0x80, 0xEA, 0xE8, 0xE8, 0x00, 0x57, 0x56, 0x47, 0x47, 0xEF, 0x60, 0x69, 0x8B, 0xF7, + 0x72, 0x08, 0xEB, 0x5A, 0xBC, 0x97, 0xF7, 0xB0, 0xA8, 0x1A, 0x90, 0x90, 0xB0, 0xB9, 0x86, 0x7E, + 0x5A, 0x58, 0xB4, 0xA6, 0x86, 0x7E, 0x00, 0x9B, 0x3B, 0x75, 0xCC, 0x07, 0xB0, 0xF9, 0xA0, 0x8E, + 0x7E, 0x00, 0x9B, 0xDB, 0x63, 0xC3, 0x5A, 0xBC, 0x23, 0xC0, 0xE6, 0xFD, 0x5A, 0x3A, 0x3A, 0x20, + 0xFE, 0x53, 0x47, 0x4F, 0x88, 0xCE, 0xF5, 0xCC, 0xE9, 0x10, 0x77, 0xAD, 0x96, 0x9E, 0xDE, 0xE3, + 0xBE, 0x55, 0xEE, 0xA9, 0x38, 0xE5, 0xC6, 0x6A, 0xA2, 0x9C, 0xFA, 0x13, 0x1B, 0x42, 0x78, 0x2C, + 0x52, 0xF0, 0x52, 0xFC, 0xC0, 0xDC, 0xB4, 0x50, 0xA5, 0x52, 0x12, 0x4C, 0x49, 0x49, 0x28, 0x57, + 0x4E, 0x69, 0xD7, 0x2B, 0xA7, 0xB4, 0x12, 0x72, 0x4A, 0x7B, 0x69, 0x72, 0x4A, 0x2B, 0x53, 0x4E, + 0x69, 0xBD, 0xCA, 0x29, 0xAF, 0x72, 0xCA, 0xAB, 0x9C, 0xF2, 0x2A, 0xA7, 0xBC, 0xCA, 0x29, 0xAF, + 0x72, 0xCA, 0xA6, 0xC9, 0x29, 0xED, 0xCD, 0x0B, 0xA9, 0x5E, 0x34, 0x6C, 0x38, 0xCD, 0xEF, 0x81, + 0x7E, 0x0B, 0xB4, 0x15, 0x2E, 0x37, 0x1C, 0xB9, 0xC4, 0xE3, 0xD0, 0x90, 0x9A, 0x97, 0x12, 0x9E, + 0x32, 0x99, 0x3E, 0x67, 0x4A, 0x78, 0x51, 0x30, 0xDB, 0x5B, 0x56, 0xA5, 0xC8, 0x93, 0x58, 0xD7, + 0x95, 0xFC, 0x31, 0xB1, 0x86, 0x19, 0xFB, 0x80, 0x80, 0x4C, 0x29, 0xFF, 0x9C, 0x51, 0x27, 0x11, + 0xFF, 0xC5, 0x80, 0x3D, 0x95, 0x55, 0x9E, 0x20, 0xB0, 0x4E, 0x59, 0xE5, 0x73, 0x97, 0x3F, 0x67, + 0xCD, 0x47, 0x92, 0x79, 0xC9, 0xDE, 0x7C, 0x69, 0x89, 0xC2, 0x32, 0x85, 0x61, 0xEB, 0x89, 0xCA, + 0x34, 0x21, 0xA0, 0xEE, 0xE0, 0x61, 0x5F, 0xF6, 0x13, 0xD6, 0xAB, 0x09, 0x9F, 0x27, 0xC3, 0x13, + 0x64, 0xC3, 0x42, 0x7F, 0x74, 0x5C, 0x2F, 0x98, 0x19, 0xA1, 0x2B, 0xFE, 0xDA, 0xB9, 0x2C, 0xBE, + 0xBF, 0x55, 0x6F, 0x0C, 0xFC, 0xA5, 0xC8, 0x88, 0xEC, 0xB8, 0x5C, 0x33, 0x00, 0x71, 0xA2, 0xE4, + 0xED, 0xF6, 0x80, 0xA9, 0x0C, 0xA7, 0x09, 0xE8, 0x27, 0x2F, 0xC6, 0x78, 0x74, 0xEF, 0xF2, 0x9B, + 0x85, 0x3A, 0x80, 0xE1, 0x53, 0xCE, 0xF6, 0x7B, 0xCE, 0xEC, 0x7B, 0xAA, 0x9F, 0x4D, 0xF7, 0x33, + 0xFF, 0xEB, 0xEF, 0xFF, 0xE9, 0x85, 0xB6, 0x7E, 0xCC, 0xFA, 0x8E, 0x3D, 0x87, 0x3D, 0x36, 0x29, + 0x05, 0x32, 0xF5, 0x08, 0x3D, 0xA1, 0x3B, 0x89, 0xB2, 0xA9, 0xA1, 0xAB, 0x89, 0x26, 0x2E, 0x12, + 0x9A, 0xAA, 0xDF, 0xD0, 0xBD, 0xE5, 0x38, 0xAE, 0xFD, 0x1D, 0x68, 0xD9, 0xC7, 0x84, 0xA2, 0x07, + 0x4A, 0x94, 0x6C, 0xF9, 0xD1, 0x76, 0xFD, 0x91, 0xC8, 0x26, 0x0A, 0x40, 0x97, 0x85, 0x31, 0xC5, + 0x04, 0x70, 0xB6, 0xE8, 0x1B, 0x1F, 0xC0, 0xCC, 0xA2, 0x45, 0xE0, 0x68, 0x3A, 0xB3, 0xAD, 0xE9, + 0xA4, 0xCF, 0x61, 0x8E, 0xE8, 0x31, 0xF7, 0x47, 0xB6, 0xCE, 0x54, 0x6D, 0x64, 0x70, 0xCC, 0xC0, + 0xFA, 0x1F, 0x1D, 0x45, 0x1B, 0xA7, 0x24, 0x50, 0x45, 0xD7, 0x1E, 0x7A, 0xE6, 0x1F, 0x80, 0xBB, + 0x34, 0xD9, 0xA5, 0xA5, 0xC1, 0xF8, 0x5E, 0x98, 0x49, 0x35, 0xBC, 0x42, 0xF4, 0xE5, 0x1E, 0xAF, + 0x03, 0x88, 0x81, 0xEF, 0x8C, 0x31, 0x0F, 0xB3, 0xD6, 0xDF, 0x8A, 0x20, 0x01, 0x1D, 0x0B, 0x17, + 0x58, 0x0C, 0x4B, 0x54, 0xC7, 0xF2, 0x4A, 0x19, 0xA2, 0x2F, 0x1E, 0x65, 0x3F, 0xA5, 0xB1, 0xC8, + 0xD3, 0x88, 0x89, 0x59, 0x61, 0x0A, 0x06, 0x26, 0x8C, 0x3D, 0xE1, 0x3E, 0x46, 0x07, 0x44, 0x2F, + 0x19, 0x5E, 0x38, 0x69, 0x9D, 0xEE, 0x19, 0x50, 0xF6, 0xE9, 0x1D, 0x78, 0x65, 0x1C, 0x25, 0xC9, + 0x97, 0xB9, 0x55, 0xA9, 0x9E, 0x27, 0x16, 0x00, 0xC1, 0x1A, 0xED, 0xB1, 0xA4, 0x75, 0x8A, 0xC8, + 0x20, 0xBB, 0xDF, 0x54, 0xC6, 0x13, 0x4F, 0xDD, 0x01, 0xB9, 0xEA, 0x0E, 0x14, 0xC5, 0xDB, 0x66, + 0xAD, 0x26, 0x7D, 0xA0, 0x17, 0x36, 0xEE, 0x62, 0x42, 0xC8, 0x01, 0xCA, 0x5E, 0xD5, 0x8C, 0xB7, + 0x99, 0xF3, 0x26, 0xC3, 0x42, 0xA1, 0x62, 0xD3, 0xFC, 0xC1, 0x9E, 0xE0, 0x92, 0x4C, 0xCA, 0x9E, + 0x1B, 0x43, 0xD8, 0x6A, 0xA7, 0xDD, 0xB8, 0x43, 0xAC, 0x2C, 0xE7, 0x88, 0x8A, 0x61, 0x2E, 0x5E, + 0x4E, 0x61, 0x5B, 0xDE, 0xDB, 0xA3, 0xC5, 0xAF, 0x82, 0xC9, 0x34, 0xDC, 0x15, 0xCC, 0x05, 0xD5, + 0x02, 0xDB, 0x53, 0x80, 0x54, 0xE9, 0x6E, 0xD8, 0x6C, 0xFB, 0xD5, 0x5D, 0x11, 0x5B, 0x39, 0x1A, + 0xF5, 0x24, 0x2F, 0x0B, 0xD3, 0x3B, 0x94, 0x93, 0xCD, 0xAB, 0xE1, 0x5C, 0xC8, 0xE9, 0x4A, 0x75, + 0x4D, 0xDC, 0xB0, 0x73, 0x06, 0x62, 0x3D, 0xF0, 0x21, 0x3C, 0xDF, 0x23, 0xCE, 0x58, 0xAA, 0xF9, + 0xD6, 0x78, 0x51, 0x14, 0x25, 0xE4, 0x94, 0x78, 0x7A, 0x5F, 0x78, 0x2F, 0x7B, 0x61, 0x14, 0x9D, + 0xD9, 0x80, 0x79, 0x71, 0x75, 0xBA, 0xA3, 0xCD, 0xBF, 0x5A, 0x4F, 0xC2, 0xC0, 0xA2, 0xC2, 0xDA, + 0x05, 0x76, 0x32, 0x2B, 0xA9, 0x45, 0xD6, 0xC2, 0x14, 0x99, 0xAD, 0x9A, 0xAC, 0x26, 0x06, 0xE8, + 0xD2, 0xAF, 0xC4, 0x89, 0x47, 0x75, 0x3E, 0x40, 0x22, 0xDF, 0x3A, 0x1D, 0xD9, 0x98, 0x08, 0xF2, + 0xFC, 0xF4, 0xFC, 0x82, 0xD9, 0xC5, 0x91, 0xFD, 0x9F, 0xB8, 0xAD, 0x73, 0xDF, 0xD0, 0xDE, 0xCA, + 0xE3, 0xEE, 0x79, 0x24, 0xBF, 0xB8, 0xC4, 0xE7, 0xC7, 0x24, 0xB4, 0x48, 0xCE, 0x43, 0xC1, 0x07, + 0xE4, 0x3C, 0x8E, 0x0A, 0xB9, 0x90, 0xD9, 0x38, 0x48, 0x1C, 0x20, 0x8D, 0xC8, 0x75, 0x46, 0xEB, + 0x00, 0x62, 0xB2, 0x5D, 0x10, 0xCB, 0x30, 0x60, 0x0C, 0xA5, 0x24, 0x71, 0xB7, 0x12, 0xB3, 0xC8, + 0x27, 0xE3, 0xA2, 0x84, 0xE0, 0x33, 0x1E, 0x73, 0xDD, 0x10, 0x12, 0xDE, 0x3D, 0x1F, 0x1A, 0x61, + 0x96, 0x7A, 0xBA, 0x57, 0x39, 0x75, 0xA9, 0x5A, 0xC6, 0x36, 0x1E, 0x4B, 0xA9, 0x31, 0x12, 0xCB, + 0x0C, 0x4F, 0xC8, 0x7C, 0x91, 0x08, 0x4A, 0xA2, 0x10, 0x86, 0x4A, 0x6C, 0x39, 0x26, 0x49, 0x55, + 0x1E, 0x07, 0x01, 0x35, 0x70, 0x99, 0x1F, 0xF8, 0x36, 0xA8, 0x60, 0xE6, 0x5B, 0xAA, 0x64, 0x8E, + 0x6F, 0x4D, 0x89, 0x46, 0x4C, 0x1D, 0x42, 0x17, 0x18, 0x5B, 0x09, 0xF3, 0xA4, 0xF8, 0x2C, 0x2D, + 0x92, 0x7C, 0x63, 0x62, 0x53, 0xDF, 0x51, 0xDD, 0x6F, 0x17, 0x81, 0xF5, 0xC6, 0x9B, 0xC0, 0x0D, + 0x4B, 0x75, 0xD8, 0x81, 0xA9, 0x73, 0x77, 0x1B, 0xF4, 0x2E, 0xD3, 0x06, 0xDC, 0xB2, 0x37, 0x4F, + 0x62, 0x22, 0xD0, 0xD6, 0x70, 0x89, 0xB3, 0x4C, 0x8A, 0x8B, 0x0C, 0x4A, 0xA6, 0x29, 0x08, 0x9D, + 0x30, 0xC4, 0x23, 0xA4, 0x3B, 0x44, 0xB3, 0xA8, 0x62, 0xA8, 0xDC, 0xFA, 0x04, 0x6D, 0x2B, 0xA5, + 0xA3, 0xE8, 0x27, 0xB4, 0x3F, 0x47, 0x60, 0x35, 0x31, 0x83, 0xBC, 0x39, 0x76, 0x89, 0x20, 0x26, + 0x5F, 0x44, 0x69, 0xA3, 0x72, 0xDD, 0x54, 0xA5, 0xA2, 0xC3, 0xE9, 0x9E, 0xB4, 0xC6, 0x07, 0x05, + 0x1B, 0xB4, 0x44, 0xA9, 0x22, 0xD6, 0x78, 0x02, 0xBA, 0xBD, 0x48, 0x1A, 0x10, 0x37, 0x49, 0x0E, + 0x67, 0x44, 0x82, 0x92, 0x6E, 0xBC, 0xAC, 0x78, 0xAB, 0xC0, 0x23, 0xD0, 0xC6, 0x60, 0x5A, 0xAA, + 0x8C, 0x65, 0x79, 0xC3, 0x63, 0x14, 0x83, 0x35, 0x3B, 0x12, 0xC6, 0x5F, 0x5D, 0xE1, 0x25, 0x70, + 0xDA, 0xD6, 0x0B, 0x0C, 0xE4, 0xC6, 0xB8, 0xBF, 0x72, 0xE1, 0x57, 0xCB, 0xB7, 0x95, 0xF6, 0x02, + 0x59, 0x8E, 0x44, 0xA6, 0x59, 0x16, 0xD3, 0x8C, 0xB1, 0x60, 0x34, 0xA1, 0xDA, 0xF4, 0x86, 0x60, + 0x9B, 0xBF, 0xEC, 0xFE, 0xBA, 0xFB, 0x1B, 0x82, 0x89, 0x7B, 0xCD, 0x97, 0x6B, 0x44, 0x5D, 0x0D, + 0x09, 0x24, 0x6A, 0x71, 0x75, 0xE6, 0x70, 0x0C, 0xD3, 0x96, 0x9C, 0x03, 0x45, 0xFF, 0xD2, 0xC8, + 0x24, 0xAB, 0x38, 0x1D, 0xFD, 0x52, 0x41, 0xD8, 0xAD, 0xE0, 0xEF, 0x4E, 0x53, 0xDB, 0x0E, 0x97, + 0x22, 0x09, 0xC7, 0x16, 0x5C, 0x49, 0xF0, 0x9D, 0xB4, 0x7B, 0x11, 0xCA, 0xD9, 0x52, 0x70, 0xE8, + 0xD7, 0x72, 0x38, 0xF4, 0xEB, 0x8B, 0xC1, 0xA1, 0x5F, 0xE7, 0xC4, 0xA1, 0x5F, 0x5F, 0x71, 0x28, + 0x0B, 0x87, 0x7E, 0x2B, 0x87, 0x43, 0xBF, 0xBD, 0x18, 0x1C, 0xFA, 0x6D, 0x4E, 0x1C, 0xFA, 0xED, + 0x15, 0x87, 0xA6, 0x70, 0xC8, 0x02, 0x01, 0x0A, 0xC5, 0x73, 0x21, 0xA8, 0x97, 0xC1, 0xA2, 0x72, + 0xC5, 0xEA, 0x9F, 0x15, 0x91, 0x8A, 0xAE, 0xA1, 0xC6, 0xD7, 0x5C, 0x09, 0x91, 0xE2, 0x2D, 0x5F, + 0x8E, 0xBD, 0xB1, 0x7B, 0x1A, 0x5E, 0x90, 0xFA, 0x8A, 0x2E, 0x97, 0x98, 0x18, 0xFD, 0xEC, 0xE9, + 0x46, 0xA9, 0x34, 0x1D, 0x5A, 0x09, 0x06, 0x09, 0xE9, 0x58, 0x9A, 0x35, 0x28, 0x91, 0x1B, 0xC8, + 0xC9, 0x7F, 0x0B, 0x60, 0x5F, 0x60, 0xFA, 0x9A, 0xED, 0x3C, 0xED, 0x3A, 0x78, 0x19, 0x53, 0x5A, + 0x40, 0x66, 0x24, 0xEA, 0xCD, 0x96, 0xA3, 0xCB, 0x97, 0xDE, 0x5C, 0x2E, 0xF7, 0xA9, 0xA2, 0x3E, + 0x4D, 0x93, 0x0D, 0x5D, 0xEA, 0x9B, 0x76, 0x8B, 0x0B, 0xEA, 0xF9, 0x13, 0x30, 0x17, 0xF9, 0xE6, + 0x91, 0xD8, 0x29, 0x09, 0x9A, 0x72, 0xB1, 0xA2, 0x62, 0xCC, 0x78, 0x64, 0x65, 0x5F, 0xD8, 0x80, + 0x62, 0x08, 0x2D, 0xD8, 0x1C, 0xCE, 0x29, 0xEB, 0x3B, 0xCF, 0xF8, 0x83, 0xE2, 0xEF, 0x4A, 0xE3, + 0x46, 0x74, 0x59, 0xE9, 0xFB, 0xCE, 0xA3, 0xA1, 0xFB, 0xA3, 0xA3, 0xCE, 0xBE, 0x52, 0xEE, 0xAA, + 0x52, 0x56, 0x1C, 0x10, 0xAA, 0xAE, 0xC2, 0x3E, 0x75, 0xCC, 0x76, 0x5A, 0xED, 0x43, 0xA5, 0xAD, + 0x1C, 0x34, 0xF7, 0x0F, 0x0E, 0xD9, 0xCE, 0xDE, 0xBB, 0xD6, 0xC1, 0xA1, 0xB2, 0xD7, 0xDC, 0x53, + 0x3A, 0x6C, 0x4F, 0x39, 0x3C, 0x38, 0x38, 0xD8, 0x6F, 0xEE, 0x1D, 0xEE, 0xD5, 0x11, 0x47, 0x19, + 0x0E, 0x79, 0xB2, 0xA2, 0x21, 0x3B, 0x34, 0xE4, 0xE9, 0x8A, 0x46, 0xDB, 0x6B, 0x74, 0x8F, 0xF1, + 0xE0, 0xBA, 0x1B, 0xA9, 0xFE, 0xA5, 0x77, 0x67, 0xDB, 0x57, 0xB6, 0x35, 0xBC, 0xB3, 0x4F, 0xF8, + 0x99, 0xC0, 0x40, 0xE0, 0x23, 0x99, 0x13, 0xA9, 0x54, 0x9E, 0x77, 0xEE, 0x49, 0x97, 0x0F, 0xE3, + 0x5A, 0x37, 0x19, 0x64, 0xC6, 0xC1, 0x54, 0xA3, 0x0D, 0x49, 0xD5, 0xF5, 0xA4, 0x64, 0x52, 0xAF, + 0xE1, 0x48, 0x76, 0x8F, 0xD6, 0xA2, 0x63, 0x5D, 0xAF, 0x68, 0x1D, 0xCA, 0xB9, 0x68, 0xA8, 0x2E, + 0x75, 0xD6, 0x61, 0xFF, 0xA1, 0x91, 0xAB, 0xAE, 0x79, 0xEB, 0x80, 0x80, 0x3E, 0x5F, 0xE6, 0xCC, + 0x27, 0x23, 0xE0, 0xDC, 0xCF, 0xE8, 0xD3, 0xBA, 0xD8, 0xE4, 0x00, 0x01, 0x40, 0x96, 0xD8, 0x46, + 0x27, 0x03, 0xA5, 0x8F, 0xC4, 0xEC, 0x0F, 0xDB, 0x64, 0x82, 0x13, 0x84, 0x09, 0x2C, 0xC2, 0xE5, + 0x1A, 0x9C, 0x16, 0x31, 0x49, 0x82, 0xDE, 0x16, 0x8B, 0x62, 0x86, 0xDF, 0xFC, 0xF1, 0xC2, 0x1B, + 0xAB, 0xA4, 0x47, 0xA9, 0xDF, 0xBB, 0xF0, 0x09, 0xCB, 0x66, 0xE5, 0x38, 0x17, 0x5A, 0xCF, 0xEF, + 0x5C, 0xF8, 0x44, 0xB5, 0xB5, 0xA4, 0x93, 0xAD, 0x5E, 0x9F, 0xC2, 0x50, 0xF6, 0xFA, 0x6C, 0x31, + 0x2F, 0xCF, 0xE6, 0x56, 0xF8, 0x14, 0xAD, 0x7C, 0xE2, 0x5A, 0xA8, 0x7A, 0x2D, 0x26, 0x97, 0xB3, + 0x25, 0x5C, 0x0B, 0x29, 0xA3, 0x45, 0xEE, 0x85, 0xAB, 0xAB, 0x51, 0xE9, 0x81, 0xD7, 0xDF, 0x0B, + 0x01, 0xAB, 0x99, 0x76, 0x3C, 0xE0, 0xA3, 0x57, 0xB7, 0x43, 0x1D, 0xF1, 0x3C, 0x04, 0xCF, 0x2B, + 0xD5, 0x2F, 0xCE, 0x6A, 0x92, 0x19, 0xC0, 0xB3, 0x37, 0x95, 0x78, 0x6E, 0x6F, 0x86, 0xB6, 0xA0, + 0x7F, 0xC3, 0x0F, 0x74, 0x7E, 0xF4, 0x4C, 0xC9, 0xC0, 0x0B, 0x2C, 0x2F, 0x09, 0x18, 0x54, 0x37, + 0xE1, 0xC9, 0x96, 0x2F, 0x2D, 0xD2, 0x4B, 0xAC, 0x0D, 0x15, 0x92, 0xA5, 0xA2, 0x06, 0x0C, 0xB0, + 0xFE, 0xB8, 0x11, 0x42, 0x61, 0x0E, 0xE4, 0x90, 0x4D, 0x5F, 0x8C, 0x89, 0x57, 0x88, 0xE4, 0x3E, + 0x89, 0x9E, 0x17, 0x54, 0x35, 0x23, 0xD5, 0x40, 0x5B, 0xCD, 0xE8, 0x9B, 0x95, 0x61, 0x0E, 0x84, + 0x71, 0x31, 0x12, 0x13, 0x43, 0x1D, 0x55, 0xBC, 0xD0, 0x1A, 0x9A, 0x7A, 0x92, 0x13, 0xCE, 0x37, + 0xF6, 0x6C, 0xAA, 0x03, 0xB9, 0x72, 0xE3, 0x54, 0x82, 0x3F, 0x36, 0x05, 0xAB, 0x6E, 0x14, 0x13, + 0xF3, 0x6C, 0x9A, 0xC8, 0xCF, 0xC7, 0xE7, 0xA5, 0x4F, 0xE3, 0x6B, 0xD5, 0xFD, 0xB6, 0x0B, 0xA3, + 0x61, 0xD4, 0xE5, 0x7C, 0x47, 0x78, 0x3D, 0x52, 0x47, 0x4C, 0xF2, 0xF8, 0xCC, 0xB1, 0x29, 0x3B, + 0xBE, 0xB7, 0x1F, 0x38, 0x3B, 0x37, 0x4D, 0xC3, 0xF1, 0x6C, 0x43, 0x0F, 0xA3, 0xD8, 0x00, 0x08, + 0xDF, 0x64, 0x90, 0xBF, 0x21, 0x05, 0x94, 0x48, 0xF4, 0x42, 0x85, 0x4B, 0x95, 0x90, 0x8B, 0xBF, + 0x8F, 0xCF, 0xC7, 0xB6, 0x15, 0xE0, 0xCC, 0xC2, 0x4B, 0x03, 0xB8, 0x45, 0x96, 0x5E, 0x45, 0x70, + 0x59, 0xBA, 0xF0, 0x52, 0x45, 0x80, 0x29, 0x6D, 0xF3, 0x2D, 0x64, 0xD7, 0x7B, 0x55, 0x64, 0xB7, + 0xEA, 0x1E, 0xB9, 0x08, 0x93, 0xCB, 0xAE, 0xA9, 0x9C, 0x4B, 0xA8, 0xE4, 0x6B, 0xCE, 0xEC, 0x44, + 0x6A, 0xC8, 0x07, 0xBA, 0x44, 0x4E, 0x42, 0xF8, 0x95, 0xCE, 0x13, 0x99, 0x4C, 0x79, 0x65, 0xF2, + 0x81, 0x7F, 0xB4, 0x57, 0xC1, 0x8C, 0x9C, 0xA6, 0x38, 0x0B, 0xC5, 0x18, 0x89, 0x43, 0x84, 0xE7, + 0xC6, 0xC2, 0x69, 0x63, 0x06, 0xB0, 0xBF, 0x06, 0x9E, 0x0F, 0xDC, 0x04, 0x35, 0x9A, 0x2A, 0x7C, + 0x8C, 0xAE, 0x82, 0xA9, 0xA6, 0x06, 0x4D, 0x91, 0xBF, 0x60, 0x46, 0x6C, 0x51, 0x09, 0x9D, 0x33, + 0x78, 0x44, 0x3C, 0x67, 0x8E, 0x13, 0x64, 0x19, 0x5A, 0xCE, 0xE5, 0x20, 0x2C, 0xC5, 0xBE, 0x1D, + 0x4D, 0x4D, 0xD4, 0xBB, 0x97, 0x13, 0xA6, 0xDB, 0x4F, 0xFF, 0xE2, 0x05, 0xF7, 0xBE, 0xAB, 0x52, + 0x2D, 0xF9, 0x7F, 0x21, 0xEE, 0x11, 0xC6, 0xCC, 0x1E, 0xC3, 0x6F, 0xCB, 0x52, 0x99, 0xE4, 0x59, + 0x78, 0xF1, 0xE6, 0xF8, 0xB6, 0x37, 0x49, 0x0E, 0x1A, 0x71, 0xA3, 0x28, 0x21, 0x1F, 0x74, 0x47, + 0xD5, 0x15, 0xB1, 0xF6, 0x50, 0x18, 0x38, 0x3B, 0xE1, 0x67, 0x23, 0xE8, 0xE1, 0x89, 0x3D, 0x8E, + 0xB8, 0x25, 0x6F, 0x35, 0x89, 0xEA, 0xF5, 0xC4, 0xC4, 0x28, 0xBA, 0x55, 0x95, 0xCE, 0x2B, 0xC7, + 0x06, 0x7E, 0x33, 0x4A, 0x8C, 0xBA, 0x4D, 0x37, 0x8C, 0x02, 0x4B, 0xBC, 0x40, 0x4D, 0xA2, 0xE2, + 0x47, 0x4D, 0x76, 0x63, 0xFB, 0xFC, 0x88, 0x6E, 0x6A, 0x45, 0xEB, 0xA4, 0x2D, 0xA7, 0x1B, 0x47, + 0xE6, 0xA3, 0xFA, 0xE4, 0x49, 0x0B, 0x96, 0xF0, 0x9A, 0xE1, 0x1C, 0x33, 0x3D, 0x7F, 0xCC, 0x47, + 0x90, 0x6D, 0xA0, 0xD2, 0x57, 0x26, 0xBB, 0x69, 0xB9, 0x1B, 0xBB, 0x1B, 0x4B, 0xE0, 0xED, 0x0C, + 0x02, 0x67, 0xA5, 0xD2, 0xEE, 0xA6, 0x13, 0xBA, 0x09, 0x5D, 0x1C, 0xF7, 0x4E, 0xA7, 0xE9, 0x1C, + 0x1E, 0xAD, 0x29, 0x99, 0xC3, 0xCC, 0x52, 0xA8, 0x5C, 0xD5, 0xF5, 0xB2, 0x04, 0x2E, 0x29, 0xA4, + 0x2C, 0x79, 0xBF, 0x12, 0x5F, 0x15, 0xE2, 0x5B, 0xA1, 0x62, 0x2D, 0x11, 0xB7, 0x58, 0xCA, 0xDE, + 0x4F, 0x93, 0xB2, 0x11, 0x8F, 0x4A, 0x0B, 0xCE, 0xCB, 0xC3, 0xEE, 0x7C, 0x81, 0x39, 0xC4, 0xE0, + 0xDE, 0x88, 0xEE, 0x8F, 0x13, 0x62, 0x27, 0x05, 0x68, 0x2F, 0x18, 0x87, 0x2F, 0xAB, 0xF2, 0x65, + 0x71, 0xB2, 0x6C, 0x33, 0x87, 0x1A, 0x69, 0xD4, 0x48, 0x24, 0x80, 0xA5, 0x73, 0x45, 0x7C, 0x4D, + 0x78, 0x8D, 0x71, 0x16, 0x2E, 0xE3, 0xBA, 0x41, 0x68, 0xB9, 0xCD, 0xBC, 0x11, 0x9E, 0x3E, 0x98, + 0xDB, 0x01, 0x91, 0x0C, 0xF5, 0x3C, 0xBA, 0x82, 0x02, 0x98, 0xDC, 0xFC, 0xF1, 0x6A, 0xE6, 0xED, + 0x2F, 0x2F, 0xD2, 0x2D, 0xC4, 0xDC, 0x30, 0x5B, 0x70, 0x75, 0x9B, 0x88, 0xE8, 0x61, 0x65, 0x16, + 0x11, 0xF2, 0x6B, 0xAC, 0x86, 0xB4, 0xC3, 0x90, 0x92, 0xD0, 0x38, 0xDF, 0x98, 0xC7, 0x24, 0x46, + 0xA1, 0x6C, 0xCF, 0x4C, 0xD9, 0x9F, 0xE0, 0xF8, 0x10, 0x97, 0xAD, 0xE8, 0xBA, 0x38, 0x48, 0x7F, + 0xE1, 0xD2, 0xD8, 0x3D, 0x1F, 0x60, 0xF2, 0x69, 0x71, 0x66, 0xE1, 0x6D, 0x2E, 0x79, 0x6E, 0x44, + 0xF9, 0xAC, 0x29, 0xFE, 0x29, 0x1E, 0xE3, 0x84, 0xB1, 0x52, 0xCD, 0xD7, 0xBA, 0x95, 0x75, 0x98, + 0x23, 0x67, 0x10, 0x6C, 0xAE, 0x40, 0xC1, 0xB0, 0xF5, 0x6B, 0xB0, 0xE0, 0xD2, 0x09, 0xA9, 0xFE, + 0x60, 0xC1, 0x2B, 0xD5, 0xDF, 0x45, 0xAB, 0x32, 0x1A, 0xCF, 0x5E, 0x63, 0x06, 0x9F, 0x29, 0x66, + 0x30, 0xA4, 0xA0, 0x92, 0x71, 0x83, 0xA5, 0xB7, 0x27, 0xBE, 0xB9, 0xB5, 0x87, 0x19, 0x4E, 0x4E, + 0xA5, 0xF4, 0x50, 0xC3, 0xC9, 0xF7, 0x6B, 0x16, 0x6E, 0xB8, 0xA7, 0x34, 0x95, 0xF7, 0x4A, 0xFB, + 0xFD, 0xDE, 0xBB, 0xF7, 0x6C, 0xA7, 0xA5, 0xEC, 0x37, 0x5B, 0x87, 0xFB, 0xCA, 0xFE, 0xBB, 0x83, + 0x16, 0x6B, 0xED, 0x1F, 0xC0, 0x77, 0x87, 0xEF, 0xEB, 0x8D, 0x35, 0x5C, 0xC1, 0x78, 0x61, 0xA0, + 0xE1, 0x0A, 0x86, 0x2A, 0x11, 0x65, 0x98, 0x39, 0x8B, 0x4A, 0x36, 0xEA, 0xF9, 0x66, 0xFC, 0x1A, + 0x62, 0x98, 0x11, 0x62, 0x38, 0x2B, 0x44, 0xD6, 0x1E, 0x66, 0x18, 0x0E, 0xB1, 0x84, 0x50, 0xC3, + 0x65, 0xCF, 0x3E, 0x3E, 0xC6, 0x72, 0x42, 0x0E, 0x97, 0xBD, 0x82, 0xE4, 0x28, 0x1B, 0x1F, 0x7A, + 0x18, 0x3F, 0xBA, 0x7E, 0x98, 0x08, 0xC4, 0xCD, 0x2C, 0xCC, 0xDE, 0xE7, 0xEE, 0x03, 0x16, 0x66, + 0x4D, 0x14, 0x66, 0x17, 0x0F, 0x57, 0x56, 0x98, 0x3D, 0x9C, 0xC3, 0xF3, 0x14, 0x66, 0xF7, 0x68, + 0x74, 0x14, 0xBC, 0x03, 0x87, 0x90, 0x3B, 0xCC, 0x53, 0xF2, 0xC6, 0x9B, 0xA9, 0xD0, 0x4E, 0x59, + 0xD3, 0x66, 0xEA, 0xB3, 0x7F, 0xA1, 0x84, 0x25, 0xA2, 0x40, 0xBB, 0x90, 0xE6, 0x7D, 0x74, 0x9E, + 0xA8, 0x1A, 0xA6, 0xFF, 0x90, 0x0A, 0x71, 0xB2, 0x9F, 0x40, 0x64, 0x05, 0xB1, 0x12, 0xB5, 0xE1, + 0x5F, 0x4E, 0xD1, 0x76, 0xB1, 0xA1, 0xF3, 0xA6, 0x93, 0xF8, 0x50, 0xA2, 0xB6, 0x4C, 0x6A, 0x86, + 0xCE, 0x92, 0x75, 0xD5, 0x92, 0x5C, 0xBE, 0x90, 0x03, 0x94, 0xAA, 0xAD, 0x36, 0xB3, 0x6C, 0x25, + 0x23, 0x59, 0x67, 0xE1, 0x70, 0x53, 0xC9, 0x3C, 0x53, 0x3A, 0x2E, 0x66, 0x5A, 0x71, 0x2A, 0x66, + 0x2D, 0xCC, 0xD0, 0x59, 0x43, 0x31, 0x35, 0x81, 0x02, 0x85, 0x05, 0xD5, 0x2A, 0xC4, 0x5B, 0x27, + 0xF3, 0x76, 0x56, 0x5E, 0x69, 0xFD, 0xF5, 0xAF, 0x6A, 0x8F, 0xA3, 0x89, 0xAF, 0x29, 0x2A, 0x7C, + 0x3F, 0x47, 0x29, 0x9F, 0x25, 0xD4, 0x0C, 0x0F, 0xFF, 0xE1, 0x8C, 0x8E, 0x16, 0x8D, 0xE2, 0x38, + 0xAC, 0x64, 0xE5, 0xAA, 0x6C, 0xE9, 0xCA, 0x80, 0x62, 0x85, 0xD1, 0x9C, 0xBC, 0x8E, 0x16, 0xB5, + 0x7D, 0x55, 0x8F, 0x19, 0x79, 0x66, 0x2C, 0xEC, 0xD9, 0xEE, 0x9A, 0x61, 0x21, 0xCE, 0xE8, 0xB9, + 0xB1, 0xB0, 0xD0, 0xE7, 0x91, 0x05, 0xC7, 0xC5, 0xF1, 0x50, 0x74, 0xF4, 0xC3, 0xE1, 0x21, 0x56, + 0x65, 0x5F, 0x2F, 0x3C, 0xC4, 0x19, 0x6D, 0x1A, 0x37, 0x94, 0x50, 0x5C, 0x1C, 0x0B, 0x45, 0x47, + 0x3F, 0x24, 0x16, 0xF6, 0x7E, 0xAE, 0x09, 0x0F, 0xB3, 0xCA, 0xA6, 0xCF, 0x81, 0x87, 0xA5, 0xCB, + 0xA3, 0xE7, 0xA0, 0xE2, 0xBB, 0x4A, 0x2E, 0xE0, 0x5A, 0x50, 0x91, 0x40, 0x59, 0x0F, 0x32, 0x62, + 0x57, 0x3F, 0x10, 0x3A, 0x4E, 0x2A, 0xC6, 0x2F, 0x99, 0x29, 0xD2, 0x40, 0x15, 0xCE, 0x66, 0x98, + 0xD1, 0xE6, 0x30, 0xC5, 0x04, 0x14, 0x17, 0xC1, 0xC3, 0x78, 0x47, 0x3F, 0x24, 0x16, 0x2E, 0x9D, + 0x29, 0xCE, 0x81, 0x87, 0x1B, 0xC5, 0x14, 0xA7, 0x40, 0x59, 0x0F, 0x32, 0x3E, 0x0F, 0x53, 0x5C, + 0xE0, 0x95, 0x32, 0x26, 0x81, 0x8D, 0xB7, 0xF7, 0xB4, 0x96, 0x65, 0xEF, 0x69, 0x55, 0xB5, 0xF7, + 0xB4, 0x37, 0xD5, 0xDE, 0xD3, 0x7A, 0xA9, 0xF6, 0x9E, 0xD6, 0xAB, 0xBD, 0xA7, 0x06, 0x7B, 0x4F, + 0xAB, 0x2E, 0x7B, 0x4F, 0xEB, 0xC7, 0xB4, 0xF7, 0xB4, 0x5E, 0xED, 0x3D, 0xB5, 0xD8, 0x7B, 0x5A, + 0x75, 0xD9, 0x7B, 0x5A, 0x3F, 0xA6, 0xBD, 0xA7, 0xF5, 0x6A, 0xEF, 0xA9, 0xC1, 0xDE, 0xD3, 0xAA, + 0xCB, 0xDE, 0xD3, 0xFA, 0x51, 0xED, 0x3D, 0xAD, 0x57, 0x7B, 0x4F, 0x5D, 0xF6, 0x9E, 0x56, 0x7D, + 0xF6, 0x9E, 0xD6, 0x8F, 0x69, 0xEF, 0x69, 0xBD, 0xDA, 0x7B, 0x6A, 0xB0, 0xF7, 0xB4, 0xEA, 0xB2, + 0xF7, 0xB4, 0x7E, 0x54, 0x7B, 0x4F, 0xEB, 0xD5, 0xDE, 0x53, 0x97, 0xBD, 0xA7, 0x55, 0x9F, 0xBD, + 0xA7, 0xF5, 0x6A, 0xEF, 0x59, 0x37, 0x7B, 0x4F, 0x7B, 0x59, 0xF6, 0x9E, 0x76, 0x55, 0x7B, 0x4F, + 0x67, 0x53, 0xED, 0x3D, 0xED, 0x97, 0x6A, 0xEF, 0x69, 0xBF, 0xDA, 0x7B, 0x6A, 0xB0, 0xF7, 0xB4, + 0xEB, 0xB2, 0xF7, 0xB4, 0x7F, 0x4C, 0x7B, 0x4F, 0xFB, 0xD5, 0xDE, 0x53, 0x8B, 0xBD, 0xA7, 0x5D, + 0x97, 0xBD, 0xA7, 0xFD, 0x63, 0xDA, 0x7B, 0xDA, 0xAF, 0xF6, 0x9E, 0x1A, 0xEC, 0x3D, 0xED, 0xBA, + 0xEC, 0x3D, 0xED, 0x1F, 0xD5, 0xDE, 0xD3, 0x7E, 0xB5, 0xF7, 0xD4, 0x65, 0xEF, 0x69, 0xD7, 0x67, + 0xEF, 0x69, 0xFF, 0x98, 0xF6, 0x9E, 0xF6, 0xAB, 0xBD, 0xA7, 0x06, 0x7B, 0x4F, 0xBB, 0x2E, 0x7B, + 0x4F, 0xFB, 0x47, 0xB5, 0xF7, 0xB4, 0x5F, 0xED, 0x3D, 0x75, 0xD9, 0x7B, 0xDA, 0xF5, 0xD9, 0x7B, + 0xDA, 0xAF, 0xF6, 0x9E, 0x75, 0xB3, 0xF7, 0x74, 0x96, 0x65, 0xEF, 0xE9, 0x54, 0xB5, 0xF7, 0xEC, + 0x6D, 0xAA, 0xBD, 0xA7, 0xF3, 0x52, 0xED, 0x3D, 0x9D, 0x57, 0x7B, 0x4F, 0x0D, 0xF6, 0x9E, 0x4E, + 0x5D, 0xF6, 0x9E, 0xCE, 0x8F, 0x69, 0xEF, 0xE9, 0xBC, 0xDA, 0x7B, 0x6A, 0xB1, 0xF7, 0x74, 0xEA, + 0xB2, 0xF7, 0x74, 0x7E, 0x4C, 0x7B, 0x4F, 0xE7, 0xD5, 0xDE, 0x53, 0x83, 0xBD, 0xA7, 0x53, 0x97, + 0xBD, 0xA7, 0xF3, 0xA3, 0xDA, 0x7B, 0x3A, 0xAF, 0xF6, 0x9E, 0xBA, 0xEC, 0x3D, 0x9D, 0xFA, 0xEC, + 0x3D, 0x9D, 0x1F, 0xD3, 0xDE, 0xD3, 0x79, 0xB5, 0xF7, 0xD4, 0x60, 0xEF, 0xE9, 0xD4, 0x65, 0xEF, + 0xE9, 0xFC, 0xA8, 0xF6, 0x9E, 0xCE, 0xAB, 0xBD, 0xA7, 0x2E, 0x7B, 0x4F, 0xA7, 0x3E, 0x7B, 0x4F, + 0xE7, 0xC5, 0xD8, 0x7B, 0x8A, 0x72, 0x04, 0xE5, 0xF4, 0x2A, 0x6D, 0x40, 0x51, 0x4E, 0xB4, 0x21, + 0xF7, 0xAF, 0xB9, 0xE7, 0xA9, 0x43, 0x7E, 0x65, 0x78, 0x3E, 0x16, 0xAE, 0xA4, 0x0A, 0x01, 0x73, + 0x99, 0x88, 0xF2, 0xD3, 0x42, 0x25, 0x92, 0xBE, 0x95, 0x32, 0x0F, 0x85, 0xCF, 0x31, 0xC5, 0xBE, + 0x30, 0x6E, 0x5C, 0x7B, 0x43, 0x9C, 0x62, 0xFE, 0x48, 0xA9, 0x16, 0xA4, 0x69, 0x0B, 0x51, 0x76, + 0xDF, 0xF9, 0xBB, 0x76, 0x7B, 0x77, 0x7A, 0xCD, 0x6E, 0x29, 0x39, 0xEC, 0x07, 0x83, 0xD0, 0x0D, + 0x93, 0x58, 0x41, 0xDB, 0x53, 0xB4, 0x08, 0x35, 0xEA, 0x30, 0x19, 0x95, 0x30, 0x17, 0x95, 0xCE, + 0xD4, 0x45, 0x33, 0x74, 0x7D, 0x6D, 0x8C, 0x53, 0xBE, 0xB4, 0x06, 0x76, 0x71, 0x6D, 0x39, 0x99, + 0xBF, 0x8B, 0x16, 0x8A, 0x69, 0xE3, 0x5D, 0xD5, 0xF2, 0xC6, 0x86, 0x1F, 0x2B, 0x79, 0x80, 0x2B, + 0x66, 0x2A, 0xE6, 0xA8, 0xD6, 0x45, 0x2A, 0x2D, 0x4C, 0xB5, 0xDB, 0xFA, 0xFC, 0x07, 0xE5, 0x82, + 0x1F, 0x0B, 0x6C, 0xF2, 0x58, 0x4B, 0x51, 0xF6, 0xB7, 0xE1, 0xE7, 0xBB, 0x3D, 0xFC, 0x79, 0x48, + 0x3F, 0xDF, 0xE3, 0xCF, 0x56, 0x7B, 0x4F, 0x24, 0x98, 0x57, 0x9A, 0x61, 0xA3, 0x56, 0xBB, 0xA3, + 0xC8, 0x4C, 0xF5, 0x32, 0x4D, 0xAF, 0x69, 0x3F, 0x52, 0x55, 0x06, 0xFC, 0x96, 0xEA, 0x5C, 0x78, + 0xA2, 0x2A, 0x0A, 0x3C, 0x87, 0xF1, 0x2D, 0x9D, 0x92, 0x9E, 0x62, 0xD2, 0x3B, 0x5F, 0x35, 0x4C, + 0xDB, 0x95, 0xD5, 0x14, 0xE4, 0x5C, 0xA1, 0xF7, 0xA7, 0x5D, 0xD5, 0x34, 0xC5, 0x6E, 0x85, 0x33, + 0x6A, 0xB2, 0x2B, 0x03, 0xBE, 0xF4, 0x8E, 0x98, 0x82, 0x2F, 0xB7, 0x95, 0x78, 0xB5, 0x06, 0x51, + 0x83, 0x85, 0x60, 0x07, 0xE3, 0xF9, 0x54, 0xAF, 0xC1, 0x06, 0x0E, 0xE2, 0x1A, 0xBA, 0xCE, 0x2D, + 0x7C, 0x1F, 0xE7, 0x4A, 0xE5, 0x5A, 0x0C, 0x8B, 0x21, 0xA2, 0xB0, 0xB1, 0xAD, 0xF3, 0xCD, 0x4A, + 0x1D, 0x96, 0x6A, 0x41, 0x9C, 0x87, 0x12, 0xEA, 0x37, 0x22, 0x52, 0x8F, 0xC9, 0xA6, 0xF7, 0x36, + 0x50, 0xC1, 0x38, 0x6C, 0x5D, 0xC8, 0x71, 0x53, 0x93, 0x4B, 0xA6, 0x27, 0x92, 0x8C, 0x15, 0x46, + 0x71, 0xB9, 0xC7, 0xFD, 0x3B, 0x1B, 0x11, 0x45, 0xE6, 0x85, 0xA3, 0xAA, 0xAE, 0xB7, 0xF8, 0x18, + 0x76, 0xBD, 0xD4, 0x99, 0x10, 0x36, 0x2C, 0x97, 0x47, 0xB2, 0x6C, 0xDD, 0x99, 0xE7, 0x05, 0xC6, + 0x95, 0xFD, 0x78, 0x12, 0x92, 0x59, 0x04, 0x90, 0x52, 0xD0, 0xC0, 0xCC, 0x94, 0x40, 0xA4, 0x51, + 0x6B, 0xA0, 0x3A, 0xEB, 0x5B, 0x25, 0xD0, 0x14, 0xC3, 0x06, 0xF1, 0x76, 0x9C, 0x3C, 0xB6, 0x1A, + 0xCB, 0x4E, 0x1F, 0x59, 0xE2, 0x71, 0xDA, 0x20, 0x1F, 0xFE, 0x61, 0x67, 0x87, 0xED, 0x84, 0xFF, + 0x42, 0x71, 0x8C, 0xBB, 0x03, 0x4C, 0x1C, 0x2D, 0xE8, 0x2D, 0xF6, 0xF5, 0xCE, 0xCE, 0x54, 0x8F, + 0x31, 0x42, 0xD3, 0x41, 0x56, 0x35, 0x74, 0x36, 0x54, 0x9D, 0xD4, 0x82, 0xCE, 0x19, 0xEE, 0x9D, + 0x4C, 0x7F, 0x0E, 0xC2, 0xD0, 0x71, 0xC2, 0xF4, 0x81, 0x65, 0x8E, 0xE7, 0x9F, 0xB2, 0x1D, 0x3D, + 0xD3, 0x47, 0x76, 0xAF, 0x17, 0x76, 0x5C, 0xE9, 0x34, 0x8E, 0x9A, 0xA5, 0x0E, 0x95, 0xCC, 0xFA, + 0x9D, 0xB1, 0xE1, 0x42, 0xDA, 0x4B, 0xC0, 0x37, 0x70, 0x45, 0x69, 0x12, 0x79, 0x60, 0x3B, 0xB1, + 0x37, 0x16, 0x3F, 0xB5, 0xD3, 0x31, 0x3B, 0x0D, 0x39, 0x0A, 0x39, 0x70, 0xB4, 0xFA, 0x94, 0x51, + 0xB2, 0x19, 0xEE, 0x5C, 0x72, 0xE0, 0x19, 0xA5, 0xD1, 0x64, 0x97, 0x67, 0x47, 0xA1, 0xD4, 0x3C, + 0x82, 0x0E, 0x1F, 0x61, 0xB1, 0x97, 0x67, 0x39, 0xE9, 0xD5, 0x77, 0x8F, 0x51, 0x50, 0xCE, 0xCC, + 0x8F, 0x5E, 0x2A, 0x77, 0x65, 0x1C, 0xFC, 0x7D, 0x91, 0xDC, 0xF3, 0xCC, 0xB5, 0x1D, 0x01, 0xE2, + 0xA2, 0x8C, 0xAB, 0xA4, 0x76, 0xA5, 0xF4, 0xD0, 0xE8, 0x26, 0xF6, 0x5D, 0x3E, 0x2D, 0xD6, 0x79, + 0x92, 0x19, 0xDC, 0xD3, 0x3A, 0xCE, 0x9A, 0x73, 0x52, 0x97, 0xD1, 0xE5, 0x0A, 0x8A, 0xAA, 0xAD, + 0x17, 0xE7, 0xDE, 0xAE, 0x37, 0x0B, 0x2B, 0x8A, 0x36, 0x22, 0x65, 0x2A, 0x88, 0x4F, 0x20, 0x10, + 0xA9, 0x20, 0xC7, 0x8D, 0x1D, 0x2A, 0x21, 0x12, 0x80, 0x08, 0x93, 0x00, 0x1A, 0x8A, 0x5A, 0x93, + 0x14, 0xAA, 0x5E, 0x93, 0xC5, 0x1A, 0x8F, 0x03, 0xCF, 0x47, 0xB1, 0xCC, 0xE5, 0x43, 0xC3, 0x13, + 0xF5, 0xB2, 0xFC, 0x11, 0x68, 0xCE, 0xC3, 0x11, 0xEB, 0x3B, 0xAA, 0xFB, 0xED, 0x22, 0xC0, 0xC2, + 0x73, 0xE8, 0x40, 0xDD, 0x25, 0x99, 0x4B, 0x66, 0x6D, 0x85, 0xF7, 0xFF, 0x16, 0x18, 0x70, 0xAC, + 0xB0, 0x9F, 0x8D, 0x0B, 0x23, 0x25, 0xF5, 0xEA, 0x3A, 0x89, 0x4F, 0x31, 0x15, 0x32, 0x65, 0xBF, + 0xE7, 0x51, 0x1E, 0xCB, 0xD1, 0x03, 0xE8, 0xAA, 0x3E, 0xA6, 0xBA, 0xF5, 0xAE, 0xF0, 0xCC, 0xBC, + 0x39, 0xCE, 0x64, 0x02, 0xE5, 0x5D, 0xFD, 0x67, 0x58, 0x67, 0x0C, 0x54, 0x5F, 0xC3, 0x64, 0xDF, + 0x38, 0xFC, 0x09, 0xFC, 0x17, 0x76, 0x21, 0xA2, 0x75, 0x1D, 0xBE, 0xBE, 0xE5, 0x63, 0xD5, 0xB0, + 0x60, 0xD8, 0x1C, 0x72, 0xB7, 0xD9, 0x9F, 0xA1, 0x75, 0xAE, 0x6E, 0x5C, 0xC5, 0x73, 0x5D, 0x3E, + 0xBF, 0x72, 0x8C, 0xE2, 0xF3, 0x73, 0x2C, 0x23, 0x7E, 0x71, 0xCF, 0x87, 0x69, 0x7E, 0x75, 0x80, + 0x50, 0x4A, 0x44, 0x0A, 0x4C, 0x6F, 0x6F, 0xD4, 0xF4, 0x4A, 0x58, 0x57, 0x6E, 0x45, 0x8F, 0xB8, + 0x72, 0x26, 0xBE, 0x28, 0x57, 0x3C, 0x63, 0x91, 0x2C, 0xCD, 0x33, 0xAB, 0xA8, 0x40, 0x15, 0x8B, + 0x65, 0x20, 0x97, 0x6C, 0xE2, 0x67, 0xD4, 0x6B, 0x64, 0x59, 0x40, 0x91, 0x71, 0x3C, 0xC1, 0x19, + 0x08, 0x87, 0x88, 0x7F, 0xDC, 0x0B, 0x92, 0x86, 0xC9, 0x02, 0x07, 0x40, 0x1D, 0x2E, 0xA0, 0x09, + 0xEB, 0xA8, 0x0E, 0x62, 0x33, 0x0B, 0x48, 0x92, 0xD9, 0x0E, 0x96, 0xC8, 0x0B, 0x2C, 0xC3, 0x7F, + 0xAA, 0x4E, 0xF2, 0x4B, 0x21, 0xFB, 0x52, 0xA4, 0x5F, 0x06, 0x93, 0x71, 0xB7, 0x86, 0xDC, 0x1E, + 0xBA, 0xAA, 0x33, 0x32, 0xB4, 0x5B, 0xE0, 0x86, 0xB6, 0x55, 0xE2, 0xF4, 0x9A, 0x3E, 0xC1, 0xA6, + 0xBB, 0x68, 0x74, 0x3F, 0x45, 0x4F, 0x98, 0x78, 0x54, 0xCE, 0x5E, 0x97, 0x3C, 0xBF, 0x66, 0xBA, + 0x4D, 0x9D, 0xEF, 0x7C, 0x27, 0x57, 0x34, 0x62, 0xB2, 0xD6, 0x85, 0xD2, 0xE8, 0x7E, 0xED, 0x97, + 0xAF, 0x3F, 0x31, 0x5B, 0x74, 0xE4, 0xFC, 0xEB, 0xDC, 0xAD, 0x61, 0xBA, 0xC7, 0xF3, 0xB7, 0x06, + 0xFE, 0xF3, 0xE7, 0xDB, 0xB9, 0x5B, 0xEF, 0x35, 0xBA, 0xFF, 0x43, 0x05, 0x7C, 0x2A, 0xD7, 0x41, + 0xB9, 0x92, 0x1B, 0xF5, 0xD3, 0x75, 0x5F, 0x60, 0xC7, 0x93, 0x1D, 0xB8, 0x6C, 0x82, 0x06, 0x74, + 0x8A, 0x63, 0xA5, 0x58, 0x32, 0xB8, 0xE8, 0x7C, 0x00, 0xEC, 0x5E, 0x64, 0x50, 0xBF, 0xDA, 0xC1, + 0x23, 0x88, 0x0D, 0x88, 0xC6, 0x2D, 0xED, 0x89, 0x48, 0x5C, 0x60, 0x8D, 0x6A, 0x82, 0x34, 0x1D, + 0xE5, 0x57, 0x07, 0xB5, 0xDE, 0xD0, 0x62, 0xC4, 0xFD, 0xB5, 0xBF, 0xAE, 0x64, 0x2D, 0x54, 0x23, + 0x77, 0x6D, 0x4F, 0x30, 0x35, 0xF0, 0x6D, 0x60, 0xFC, 0xB7, 0xDC, 0xE2, 0x8F, 0x2A, 0x9C, 0x3F, + 0xC7, 0xF0, 0x99, 0x0E, 0x1F, 0xF9, 0x84, 0x2D, 0xFF, 0xF8, 0x99, 0x9E, 0xC2, 0x73, 0x1C, 0x3E, + 0x74, 0xC4, 0x20, 0x2F, 0x82, 0x23, 0x06, 0x6D, 0x7C, 0xED, 0x43, 0x86, 0x52, 0x0A, 0x0A, 0xAA, + 0x24, 0xBC, 0x3C, 0x6D, 0x33, 0x9C, 0x26, 0x16, 0x99, 0xC4, 0x32, 0xB4, 0x4F, 0x71, 0x49, 0x16, + 0x30, 0xC9, 0x42, 0x34, 0x87, 0x3F, 0xDF, 0x7C, 0xB6, 0xC7, 0xFC, 0x0D, 0x1C, 0x43, 0xFE, 0xA3, + 0xED, 0x7E, 0xDB, 0x66, 0xB6, 0x05, 0x42, 0xA8, 0x8A, 0x5D, 0x6D, 0xE3, 0xD7, 0x2E, 0x2E, 0x91, + 0xC6, 0x8A, 0xE1, 0xAE, 0x28, 0xCA, 0xB0, 0xD9, 0xE7, 0xD2, 0x3C, 0x1E, 0xAD, 0x2C, 0x95, 0x4A, + 0xE8, 0x86, 0x3D, 0xD7, 0x1E, 0x18, 0x26, 0xBF, 0xB3, 0xBF, 0xF1, 0x12, 0xE1, 0x9E, 0x85, 0xEE, + 0xD4, 0xD9, 0xAA, 0x8B, 0x52, 0x05, 0x95, 0xE3, 0x30, 0x1A, 0xE8, 0xA8, 0xDA, 0x16, 0x2C, 0x5E, + 0x7D, 0x65, 0x52, 0x35, 0x98, 0x78, 0xA4, 0xED, 0x0E, 0x55, 0xCB, 0xF8, 0x43, 0x98, 0x0B, 0x46, + 0xAA, 0x87, 0x75, 0x28, 0x6C, 0x17, 0xA4, 0x19, 0xB4, 0x08, 0x03, 0xB7, 0xB4, 0x86, 0x7D, 0xDF, + 0xE5, 0xEA, 0x98, 0xF8, 0x62, 0x42, 0x44, 0x52, 0x35, 0x0D, 0x7D, 0x4D, 0xDB, 0xA2, 0xE6, 0x05, + 0xFC, 0xFF, 0x71, 0x04, 0x5A, 0x12, 0xF6, 0xCA, 0x90, 0x30, 0xA9, 0x77, 0x0D, 0x94, 0x28, 0x7B, + 0x1C, 0xAA, 0x54, 0x8E, 0x5C, 0xB8, 0x8F, 0x0B, 0x8F, 0xA3, 0x23, 0x60, 0xF5, 0x13, 0xDB, 0x61, + 0xA2, 0x80, 0x06, 0x8F, 0xF4, 0x2B, 0x01, 0xA1, 0xC6, 0x1C, 0x45, 0x6A, 0xEA, 0xAC, 0xEA, 0x52, + 0x0E, 0xA3, 0xCB, 0x70, 0xAC, 0x2C, 0x67, 0xF7, 0xBB, 0x32, 0x84, 0x58, 0xC1, 0xB3, 0x58, 0x80, + 0xDA, 0x25, 0x06, 0x73, 0x4A, 0xF4, 0xB3, 0x88, 0x6F, 0xB1, 0x9C, 0x27, 0x70, 0x05, 0xA6, 0x49, + 0xD7, 0xF7, 0x9E, 0xDF, 0x24, 0x89, 0xB3, 0x58, 0x96, 0x55, 0x32, 0xDE, 0x77, 0x35, 0xC3, 0x64, + 0xAC, 0x65, 0x96, 0xDD, 0x71, 0x02, 0xBD, 0x19, 0x83, 0x23, 0x36, 0x5E, 0x2B, 0x4B, 0x63, 0xEE, + 0x72, 0xE6, 0x33, 0x36, 0xA6, 0x9C, 0x41, 0xB0, 0xC1, 0xF9, 0x35, 0x68, 0x10, 0x01, 0x2F, 0x6C, + 0x77, 0x62, 0xA2, 0xF2, 0x47, 0x58, 0xAF, 0x07, 0x08, 0x9A, 0xBB, 0x28, 0x71, 0x9E, 0x1D, 0xDF, + 0x1D, 0x33, 0x04, 0x9F, 0xA8, 0x36, 0xCD, 0x06, 0x01, 0xE8, 0xA0, 0x52, 0x10, 0x47, 0x07, 0xCD, + 0x34, 0x6E, 0xA6, 0xEA, 0x6B, 0x61, 0x6F, 0xB8, 0xE8, 0x2F, 0xD4, 0xD6, 0x2B, 0x13, 0x23, 0x4F, + 0x8A, 0x39, 0x7A, 0x1E, 0xB1, 0xDD, 0xE9, 0x48, 0x05, 0x19, 0xC3, 0x8C, 0x54, 0xBD, 0x70, 0xB1, + 0x65, 0x95, 0xA6, 0xD8, 0x51, 0x1B, 0xF5, 0x79, 0xA2, 0x06, 0x20, 0x74, 0xDC, 0xE2, 0x47, 0xC2, + 0x1E, 0x86, 0x0F, 0xC8, 0xB7, 0x7C, 0x54, 0xA1, 0x18, 0x6E, 0x42, 0x01, 0x4C, 0xF6, 0x9D, 0x5C, + 0x82, 0x78, 0x94, 0xA6, 0xFA, 0x95, 0x3D, 0x53, 0x70, 0xB7, 0xEE, 0x46, 0x1C, 0x9D, 0xBF, 0x2E, + 0x0F, 0x4B, 0x10, 0x3B, 0x80, 0xEA, 0x58, 0xD3, 0x4A, 0xEC, 0x8A, 0x47, 0x56, 0xC4, 0xDF, 0xCE, + 0xCF, 0x76, 0x2E, 0xDE, 0xF7, 0x44, 0x15, 0x71, 0xDB, 0x53, 0x41, 0xE5, 0xC8, 0xDB, 0xA9, 0x3C, + 0x35, 0xEB, 0x50, 0x01, 0x0D, 0x13, 0x7F, 0x56, 0xAC, 0x71, 0x98, 0xEC, 0xE6, 0xFD, 0x01, 0x76, + 0x83, 0x3F, 0x17, 0xEA, 0xA6, 0xF5, 0xBE, 0x8D, 0xFD, 0xD0, 0xAF, 0x85, 0x3A, 0xEA, 0x1C, 0xEE, + 0x61, 0x47, 0xF4, 0x6B, 0xA1, 0x8E, 0xF6, 0xDF, 0xD1, 0xCA, 0xE8, 0xD7, 0x62, 0x4B, 0x6B, 0xED, + 0x8B, 0xB5, 0xD1, 0xEF, 0x85, 0xBA, 0x6A, 0x77, 0x14, 0x5A, 0x9D, 0xF8, 0xBD, 0x50, 0x57, 0x7B, + 0x07, 0x8A, 0x40, 0x00, 0xFA, 0xBD, 0x18, 0x0A, 0xB4, 0x5B, 0x02, 0x09, 0xE8, 0x77, 0x05, 0xBD, + 0xBF, 0x7C, 0xB5, 0xCC, 0xA5, 0x88, 0xA6, 0x77, 0x14, 0x70, 0x01, 0x8C, 0x81, 0x64, 0x50, 0xA4, + 0x2E, 0x24, 0xBC, 0xDB, 0xE3, 0xB3, 0xCB, 0x2F, 0xC4, 0x19, 0xC3, 0x80, 0x09, 0x0D, 0x38, 0xD4, + 0x50, 0x84, 0x41, 0x80, 0x92, 0xA4, 0x01, 0x1F, 0x45, 0x0B, 0xBF, 0x8B, 0xE5, 0xD5, 0x46, 0x36, + 0x32, 0x57, 0x7B, 0x20, 0x02, 0x29, 0x62, 0xA2, 0x26, 0xA1, 0xCD, 0xBD, 0xE3, 0x61, 0x1C, 0x85, + 0xD8, 0x78, 0xF8, 0xB0, 0x09, 0x12, 0x66, 0xA1, 0x52, 0x5F, 0xD9, 0x9B, 0x8C, 0x7B, 0x55, 0x33, + 0xA3, 0x9F, 0xEA, 0xB2, 0xD1, 0xBD, 0x0E, 0xBE, 0x33, 0xF9, 0x61, 0x6E, 0x0E, 0x3F, 0xDD, 0x69, + 0xDA, 0xE4, 0x17, 0xE3, 0xF2, 0x33, 0xF6, 0xBD, 0x9B, 0xEB, 0xF3, 0xE3, 0xC5, 0x78, 0x4B, 0xA3, + 0xDB, 0xEB, 0xF5, 0x77, 0xCF, 0x1F, 0x30, 0xB8, 0xE6, 0x0E, 0x48, 0x60, 0x88, 0x65, 0x0F, 0x17, + 0xE1, 0x30, 0x62, 0xD9, 0xE3, 0xE0, 0xBB, 0x5C, 0x31, 0x6C, 0xCD, 0x65, 0xFB, 0x74, 0x31, 0x96, + 0xDC, 0xE8, 0x1E, 0x9F, 0x9D, 0xEE, 0x9E, 0x1D, 0x9F, 0x6E, 0x16, 0x6F, 0x88, 0x44, 0xA4, 0x88, + 0x11, 0x48, 0x11, 0x54, 0x06, 0x4F, 0xE9, 0xC6, 0x60, 0x00, 0x9A, 0x28, 0x40, 0x5E, 0x75, 0x1C, + 0xD3, 0x10, 0x15, 0x97, 0xBD, 0x26, 0xC3, 0x5D, 0x45, 0x3D, 0x95, 0xEA, 0xA1, 0xE3, 0x8B, 0xC0, + 0x2C, 0x0C, 0x10, 0xB9, 0xEE, 0x7E, 0xD9, 0xBD, 0xFD, 0x05, 0x99, 0x85, 0x29, 0xAB, 0x33, 0x33, + 0xA4, 0x6B, 0x77, 0x4C, 0x7F, 0x37, 0x19, 0x6E, 0xA4, 0xDC, 0xC2, 0x44, 0x6B, 0x27, 0x00, 0xF1, + 0x99, 0x39, 0x1C, 0xFB, 0x81, 0x19, 0xE8, 0xCC, 0x0E, 0x7C, 0x54, 0xD1, 0x50, 0x04, 0xD8, 0x07, + 0xB1, 0x00, 0xF4, 0xE3, 0x80, 0x38, 0x98, 0x1F, 0x36, 0x46, 0x0D, 0x0E, 0xE6, 0x01, 0xFB, 0x16, + 0x75, 0x84, 0x0A, 0xB7, 0xC5, 0x54, 0x5D, 0x37, 0x7C, 0x61, 0x71, 0xEC, 0x9F, 0x1D, 0xEF, 0xF6, + 0x4F, 0xAF, 0x44, 0x39, 0x47, 0x4D, 0xEC, 0x75, 0x93, 0xFD, 0x3C, 0xE2, 0xDC, 0xDC, 0x3D, 0x33, + 0x5C, 0x76, 0x67, 0x68, 0xDF, 0x12, 0xD3, 0x20, 0x1B, 0x91, 0xED, 0x1B, 0x0F, 0x1C, 0x6B, 0xA4, + 0x82, 0xB2, 0xA6, 0x6A, 0xA0, 0xB4, 0x37, 0x99, 0xDC, 0xDA, 0xC4, 0xBB, 0x52, 0x1D, 0x1F, 0x18, + 0xEE, 0x18, 0x1D, 0xDF, 0x53, 0xF0, 0x89, 0x98, 0x24, 0x02, 0x6A, 0x33, 0xB4, 0xEE, 0x39, 0xD8, + 0x1D, 0x0A, 0x85, 0x75, 0xF2, 0x3A, 0x21, 0xD3, 0x9E, 0xE1, 0x76, 0xD5, 0x24, 0xD2, 0x26, 0x7A, + 0x9E, 0x99, 0x7B, 0x9D, 0xAC, 0xEE, 0x55, 0xD6, 0x7C, 0x95, 0x35, 0x7F, 0x6C, 0x59, 0xF3, 0xD2, + 0x12, 0xC7, 0x02, 0x46, 0xB6, 0x6E, 0xCB, 0x50, 0xDF, 0x69, 0xC9, 0x73, 0xF6, 0xBC, 0xC9, 0x14, + 0x3C, 0x63, 0x0C, 0x35, 0xC6, 0x4F, 0x05, 0x7C, 0x37, 0x44, 0xD0, 0xAC, 0xC4, 0x54, 0x23, 0x43, + 0x03, 0x9E, 0x85, 0x05, 0x75, 0x79, 0x0B, 0x27, 0x37, 0xB7, 0xD7, 0xA9, 0x92, 0xF7, 0x49, 0xD4, + 0x87, 0x3E, 0x8F, 0x4F, 0x3C, 0xAA, 0x52, 0x1D, 0x3E, 0x2D, 0x7F, 0xD5, 0x04, 0x9B, 0x57, 0xBB, + 0x66, 0xB2, 0x78, 0x6D, 0xEB, 0xA9, 0xB9, 0x3F, 0x73, 0x09, 0xF7, 0x4F, 0xDC, 0xE2, 0x44, 0x2E, + 0xAA, 0x80, 0x06, 0x46, 0x7A, 0xB2, 0xBE, 0x94, 0x88, 0x40, 0x3C, 0x81, 0xF7, 0xC6, 0x32, 0x80, + 0x7E, 0x1C, 0x00, 0xAD, 0x0C, 0xE8, 0xD6, 0xDE, 0xB6, 0xB0, 0x7C, 0x01, 0xFE, 0x60, 0x04, 0xBA, + 0x94, 0x95, 0xB4, 0xA7, 0x26, 0xBB, 0x0D, 0xC3, 0xA7, 0x30, 0x38, 0x1B, 0x8B, 0xBF, 0x73, 0x67, + 0x8A, 0x9A, 0xA4, 0xF3, 0x4A, 0x74, 0xD0, 0x52, 0x94, 0x6D, 0x45, 0x51, 0x02, 0x4F, 0x8A, 0x63, + 0x26, 0xB7, 0x86, 0x64, 0x51, 0xD3, 0xD9, 0xFB, 0xE8, 0x2B, 0x31, 0x03, 0xEE, 0x3F, 0x72, 0x6E, + 0x89, 0xF7, 0xBC, 0x4D, 0xAD, 0x17, 0x5F, 0x8E, 0x8A, 0x32, 0x48, 0xF3, 0x8C, 0xE3, 0xD5, 0x01, + 0x6F, 0x6E, 0x0A, 0x5D, 0xC8, 0xF7, 0x96, 0x25, 0x47, 0x25, 0xE6, 0x79, 0x07, 0x3B, 0x75, 0x22, + 0x36, 0x4A, 0x60, 0x77, 0xE9, 0x2E, 0xE7, 0x74, 0xC9, 0xDD, 0xCD, 0xA2, 0x06, 0xDB, 0xFA, 0x7F, + 0xFF, 0xD7, 0x7B, 0x7B, 0x54, 0x7E, 0x31, 0x55, 0xC8, 0x7F, 0x61, 0x3F, 0x50, 0xA6, 0x4F, 0x28, + 0x2F, 0x2B, 0x41, 0xA5, 0x5E, 0xC3, 0x90, 0xB1, 0xFC, 0x8D, 0xA9, 0x38, 0x53, 0xA7, 0xB8, 0xCB, + 0x3A, 0xEE, 0xAA, 0x95, 0xF0, 0x2D, 0xCD, 0x43, 0x54, 0xCB, 0x47, 0xFC, 0x2B, 0xE2, 0x5B, 0x4B, + 0x47, 0xF7, 0x5E, 0x8C, 0x49, 0x56, 0x1A, 0x4B, 0xD0, 0xC4, 0x06, 0xA0, 0xFA, 0x2C, 0x9E, 0x49, + 0xD0, 0x2E, 0x8E, 0xB0, 0xA2, 0xA3, 0x4D, 0x40, 0x53, 0x72, 0xC1, 0x11, 0x4D, 0xE9, 0x43, 0x3E, + 0xAF, 0xB2, 0x5B, 0x88, 0xB3, 0x3D, 0xDB, 0x54, 0x5D, 0xC3, 0x7F, 0x5A, 0x11, 0xD6, 0x86, 0xC3, + 0x1D, 0xCD, 0xC1, 0x71, 0x13, 0xFA, 0x75, 0xFA, 0x22, 0x66, 0xF7, 0x7B, 0xA1, 0xF5, 0xCD, 0xA3, + 0x9D, 0x67, 0x1B, 0x24, 0x6F, 0x0D, 0xCF, 0xB0, 0x86, 0x0C, 0xB7, 0xB3, 0x9A, 0x9A, 0x96, 0x6D, + 0x9F, 0xBC, 0x50, 0x4D, 0x73, 0xFE, 0x3E, 0xCB, 0xEB, 0x6D, 0x4B, 0x94, 0x40, 0xA7, 0xEC, 0x82, + 0x42, 0x02, 0xF4, 0x8C, 0x21, 0xDA, 0xD1, 0xC2, 0xD8, 0xDD, 0x11, 0x74, 0x29, 0x2E, 0x31, 0xAA, + 0x1A, 0x19, 0xC9, 0xB6, 0x5C, 0x01, 0x4B, 0x0E, 0xEB, 0x7E, 0x8B, 0x12, 0x2A, 0xC6, 0x5E, 0x25, + 0x5E, 0x18, 0x48, 0xC8, 0xD0, 0x1B, 0x31, 0xC1, 0x33, 0xB6, 0x09, 0x55, 0x37, 0x74, 0x99, 0x12, + 0x64, 0x15, 0x29, 0xB2, 0x02, 0xE3, 0x99, 0x3B, 0xBD, 0xC0, 0x2A, 0xD4, 0xB6, 0xCF, 0xF2, 0xEA, + 0x0E, 0x19, 0xD8, 0xAF, 0xEC, 0xE1, 0x10, 0xA3, 0xFA, 0xA5, 0x16, 0x57, 0x1A, 0x68, 0x95, 0xB5, + 0x3D, 0x61, 0xCE, 0x97, 0xC3, 0xAD, 0x44, 0xEB, 0x2B, 0x3D, 0xB5, 0x59, 0xED, 0x30, 0x1D, 0x44, + 0xCF, 0xAC, 0x2C, 0xC2, 0x3C, 0x26, 0xA1, 0x0E, 0xA1, 0xB8, 0xCD, 0x71, 0x86, 0xDE, 0x5B, 0xA1, + 0xD0, 0x75, 0x94, 0xC8, 0x74, 0xAE, 0x3D, 0xB1, 0xDB, 0xEB, 0x7E, 0x13, 0xC3, 0xC2, 0x06, 0x81, + 0x29, 0xCD, 0x31, 0x78, 0x6B, 0x84, 0x99, 0xC6, 0x37, 0xD0, 0x19, 0x03, 0x0C, 0x23, 0xF0, 0x5D, + 0x43, 0xB5, 0x86, 0x81, 0x29, 0x6D, 0x2E, 0x7D, 0x2E, 0xDC, 0xF4, 0x28, 0x5C, 0x02, 0x3D, 0x7D, + 0x43, 0xDB, 0x3C, 0x31, 0x3E, 0x7B, 0x40, 0xCF, 0x43, 0x3F, 0xFD, 0xA5, 0xE5, 0xF3, 0xA1, 0x8C, + 0x59, 0xB9, 0x56, 0xAD, 0x40, 0x15, 0xFD, 0x8F, 0x6D, 0x97, 0x27, 0xAD, 0xFF, 0xC5, 0xFA, 0x68, + 0x85, 0x28, 0xFF, 0x97, 0xA1, 0x51, 0xC6, 0x31, 0xAA, 0x36, 0x95, 0x92, 0x06, 0xC0, 0x8E, 0x97, + 0x25, 0xB2, 0xD0, 0xAC, 0x57, 0x26, 0xB2, 0x08, 0x56, 0x51, 0xBB, 0xC8, 0x92, 0x5C, 0xC4, 0xEC, + 0xAE, 0xAC, 0x91, 0xC8, 0x82, 0x37, 0xA2, 0x7D, 0x9B, 0x7D, 0x06, 0x3E, 0x51, 0x97, 0xC8, 0x82, + 0x7D, 0xC9, 0xCB, 0xD6, 0x2F, 0x43, 0x62, 0x89, 0x58, 0x21, 0x61, 0x7E, 0x24, 0xB3, 0x98, 0x40, + 0x5B, 0x5C, 0x67, 0x78, 0xE9, 0x60, 0x14, 0xE6, 0xA3, 0x30, 0xA6, 0xB8, 0x4E, 0x0C, 0xBC, 0xAF, + 0xC2, 0x48, 0x75, 0xC3, 0x75, 0x00, 0xBA, 0x51, 0x78, 0x5C, 0xE2, 0x25, 0x0F, 0x8A, 0x49, 0x5B, + 0x43, 0x23, 0x75, 0x6C, 0x6E, 0x53, 0x36, 0x6A, 0x46, 0x8F, 0x4B, 0x6F, 0xCA, 0xE4, 0x26, 0x8B, + 0xF7, 0x0C, 0xF6, 0xEA, 0x2A, 0x20, 0xAE, 0x46, 0x7A, 0x19, 0xE3, 0x94, 0x4B, 0xFC, 0x92, 0x42, + 0x96, 0x12, 0xCA, 0x11, 0x65, 0x52, 0x00, 0x51, 0xFC, 0x92, 0xF0, 0x11, 0xA5, 0x58, 0xD9, 0xFD, + 0x7A, 0xF2, 0xCB, 0x6E, 0xBF, 0x77, 0x7C, 0x7B, 0x77, 0x83, 0x74, 0x1A, 0x8A, 0x15, 0x5F, 0xE1, + 0x41, 0x3B, 0x46, 0xA5, 0x17, 0x6A, 0x35, 0x5B, 0xD9, 0xC6, 0x0A, 0x06, 0x11, 0xE0, 0x05, 0x4C, + 0xFA, 0x76, 0xE0, 0x6A, 0x29, 0xC7, 0x78, 0x65, 0x32, 0x09, 0x8F, 0xF0, 0xD4, 0xFE, 0x81, 0x26, + 0xC2, 0x6D, 0x92, 0x5B, 0x21, 0x9E, 0x57, 0x3C, 0x6E, 0x67, 0x8E, 0xDA, 0xD4, 0xC1, 0xEE, 0x00, + 0xD1, 0x1B, 0xB9, 0xCB, 0xAD, 0x9C, 0x02, 0x6D, 0xDE, 0x03, 0x77, 0xF6, 0x64, 0x14, 0xB7, 0xD8, + 0xE6, 0x38, 0x14, 0x67, 0x8E, 0xED, 0xCB, 0x5E, 0x45, 0x3F, 0x70, 0xA5, 0x63, 0x75, 0x79, 0x9A, + 0x05, 0x5D, 0xA9, 0x92, 0x58, 0x10, 0xA3, 0x56, 0x8A, 0xDB, 0x75, 0x5C, 0xFB, 0xC1, 0xD0, 0xC5, + 0x89, 0x4A, 0x14, 0x2A, 0xEF, 0xAC, 0xC4, 0xEF, 0x01, 0x7A, 0xB4, 0x85, 0x4D, 0x8A, 0xCD, 0xBE, + 0x39, 0xFF, 0xB2, 0x73, 0xF6, 0xFE, 0xF4, 0x88, 0x49, 0xC4, 0x10, 0xD0, 0x8D, 0x91, 0xF5, 0x65, + 0xEF, 0x65, 0xFB, 0x8F, 0x56, 0x75, 0xC0, 0xDD, 0x8C, 0xB9, 0xFA, 0xC5, 0x4A, 0x9E, 0x6F, 0xE4, + 0x8E, 0x97, 0xA1, 0x54, 0xB6, 0x55, 0x1A, 0xC8, 0xD4, 0xC9, 0xAA, 0x4F, 0xB6, 0xC4, 0xFC, 0x97, + 0x77, 0xB0, 0xC5, 0x86, 0x59, 0xF4, 0x5C, 0x4B, 0x42, 0x77, 0xEA, 0x98, 0x8B, 0x61, 0xF8, 0x9D, + 0x1B, 0x6C, 0xEA, 0xB9, 0xB5, 0xC0, 0x2B, 0x85, 0x17, 0x0F, 0xF1, 0x3E, 0xC0, 0xB1, 0xF9, 0x88, + 0xD7, 0x34, 0xE9, 0x76, 0x86, 0x84, 0x2A, 0xD9, 0x06, 0x42, 0xA8, 0x62, 0x2D, 0x85, 0xAF, 0xFD, + 0x93, 0xE2, 0x9B, 0x1A, 0xCB, 0xBB, 0x61, 0x2B, 0xD0, 0xE6, 0x93, 0xE5, 0x79, 0x77, 0xF6, 0x57, + 0xEF, 0xBE, 0x4F, 0x71, 0x8E, 0x11, 0x85, 0x4D, 0xCF, 0xB6, 0x10, 0xB0, 0xB0, 0x9A, 0xE5, 0x5F, + 0xC9, 0xCD, 0x98, 0xF3, 0x8A, 0x6F, 0xE6, 0x7E, 0x11, 0x60, 0x21, 0x10, 0xC9, 0xF0, 0x50, 0x8A, + 0xC4, 0xDC, 0x32, 0xF8, 0xB6, 0x20, 0x1E, 0xBA, 0x1F, 0x0E, 0x12, 0xE0, 0x5B, 0xB1, 0xD3, 0x78, + 0x76, 0xE0, 0x6E, 0x53, 0x7C, 0x90, 0x61, 0x79, 0x3E, 0x57, 0x75, 0x34, 0x36, 0x79, 0xBE, 0xEA, + 0x07, 0x5E, 0x2C, 0x13, 0x5F, 0x65, 0x99, 0xF0, 0x39, 0xAF, 0xDE, 0x56, 0xF8, 0x2A, 0xFB, 0xE6, + 0x5D, 0x16, 0x55, 0x4D, 0x5D, 0xC2, 0xC3, 0x3C, 0x39, 0xF9, 0x77, 0xF0, 0x4A, 0xDE, 0xBF, 0xAB, + 0x7A, 0xF7, 0x6E, 0xAE, 0xAB, 0x76, 0xE9, 0xD7, 0xEC, 0x70, 0x0D, 0x73, 0xDD, 0xB2, 0x8B, 0x35, + 0x9C, 0x05, 0x6D, 0x0C, 0x32, 0x53, 0xF7, 0xEB, 0x1E, 0x8D, 0x81, 0xB1, 0xD8, 0xF5, 0xBA, 0xD9, + 0xAB, 0x75, 0xD3, 0xBB, 0x56, 0x78, 0xA5, 0x2E, 0x73, 0xEE, 0xD5, 0x6E, 0xD3, 0xE5, 0xDF, 0xA4, + 0x4B, 0xC3, 0xC4, 0x1B, 0x71, 0xD7, 0xDD, 0x4B, 0x8F, 0xD1, 0xA8, 0x81, 0x29, 0x44, 0x67, 0x26, + 0x9C, 0x8E, 0x4C, 0x73, 0xB9, 0x0E, 0x8D, 0x80, 0x15, 0x88, 0xAB, 0x5E, 0x30, 0x37, 0xDF, 0x66, + 0x7B, 0x62, 0x77, 0xE4, 0xB5, 0x7B, 0xA0, 0xEF, 0x63, 0xD3, 0x8C, 0x3E, 0x45, 0x96, 0x1C, 0xDF, + 0x35, 0x64, 0xD6, 0x18, 0x0A, 0x2D, 0xC4, 0x2C, 0x3B, 0xF2, 0x1D, 0xA6, 0x3E, 0xA8, 0x86, 0x49, + 0xFC, 0x38, 0x7C, 0x19, 0xC3, 0xB4, 0xF3, 0xE4, 0xCA, 0x5A, 0x19, 0x42, 0xD6, 0x77, 0x59, 0x47, + 0x60, 0xE5, 0xF0, 0x87, 0xB8, 0x02, 0x87, 0xE8, 0x2A, 0x37, 0xED, 0x77, 0xA5, 0xDF, 0xC7, 0x84, + 0x6B, 0xB1, 0xA0, 0x80, 0xCE, 0x8C, 0xF5, 0x14, 0x5F, 0x61, 0xAD, 0xFC, 0x70, 0x83, 0xB9, 0x42, + 0x0B, 0xAA, 0xDC, 0xA2, 0x4E, 0x99, 0xB4, 0x3C, 0xB0, 0x7C, 0xD8, 0xC7, 0x46, 0x61, 0x46, 0xAD, + 0x99, 0xF6, 0x0B, 0xE4, 0xD3, 0x5A, 0xFD, 0x2E, 0xF5, 0xA0, 0x0F, 0xF8, 0x4B, 0x2F, 0xD8, 0xA9, + 0xDE, 0xCF, 0x99, 0x60, 0x58, 0xAB, 0xFD, 0x8B, 0x96, 0x53, 0x6D, 0xDB, 0xC2, 0x66, 0x9B, 0xB4, + 0x75, 0xAD, 0xB2, 0x04, 0xD6, 0x5E, 0xA3, 0x0D, 0x12, 0x93, 0xAE, 0xB4, 0x39, 0xAD, 0x4D, 0xA3, + 0xA9, 0xD6, 0xE2, 0x34, 0xB5, 0x56, 0x5B, 0x36, 0x1F, 0x4D, 0xB5, 0x36, 0x91, 0xA6, 0xDA, 0x65, + 0x69, 0xAA, 0xB3, 0x46, 0x1B, 0xD4, 0xAE, 0x4E, 0x53, 0xED, 0x4D, 0xA3, 0xA9, 0xF6, 0xE2, 0x34, + 0xB5, 0x56, 0x5B, 0x36, 0x1F, 0x4D, 0xB5, 0x37, 0x91, 0xA6, 0x3A, 0x65, 0x69, 0x6A, 0x6F, 0x8D, + 0x36, 0xA8, 0x53, 0x9D, 0xA6, 0x3A, 0x9B, 0x46, 0x53, 0x9D, 0xC5, 0x69, 0x6A, 0xAD, 0xB6, 0x6C, + 0x3E, 0x9A, 0xEA, 0xAC, 0x9A, 0xA6, 0x22, 0xBD, 0x9E, 0x54, 0x6A, 0x74, 0x37, 0x55, 0xF1, 0x9F, + 0x4D, 0x6F, 0xA6, 0xE8, 0xE5, 0xCB, 0x03, 0x77, 0x8F, 0x7B, 0x8D, 0x6E, 0x68, 0x44, 0xE0, 0xEC, + 0xDA, 0xD6, 0x8B, 0xFC, 0x63, 0x49, 0x7F, 0x58, 0x72, 0x4A, 0x8D, 0xA9, 0x69, 0xCA, 0x01, 0xAA, + 0x7A, 0xB4, 0x66, 0x3D, 0x58, 0xC7, 0x25, 0xFC, 0x4E, 0xB3, 0xDE, 0x2A, 0xD4, 0xC1, 0xF3, 0xDB, + 0xE5, 0xFB, 0xA7, 0xEA, 0xB3, 0x15, 0x5C, 0x5A, 0xEC, 0xB8, 0x17, 0xBB, 0x46, 0x18, 0x4F, 0x41, + 0x7D, 0xEF, 0xDA, 0xAA, 0xAE, 0xA9, 0xA0, 0xFC, 0xCB, 0xEB, 0xDE, 0x9A, 0xC6, 0x3D, 0x8F, 0x51, + 0x7A, 0x2D, 0x86, 0xB9, 0xFD, 0x38, 0x9A, 0x14, 0xFF, 0xBC, 0x23, 0x40, 0xDA, 0x64, 0xD0, 0x17, + 0x19, 0x17, 0xD2, 0x7B, 0x8B, 0xE5, 0xFE, 0xC3, 0x0B, 0xEB, 0xA6, 0x78, 0x17, 0x6D, 0x0C, 0xB1, + 0xAB, 0xF0, 0x64, 0x58, 0xA0, 0x00, 0x12, 0x68, 0x2C, 0xB2, 0x1C, 0xC3, 0x20, 0x97, 0x3D, 0xBC, + 0x6A, 0xEE, 0xC2, 0xE0, 0x6B, 0x69, 0x67, 0xA8, 0x66, 0x37, 0xBC, 0x3B, 0xED, 0xB1, 0x5D, 0xF6, + 0xF5, 0xAC, 0xB7, 0xE9, 0xC6, 0x43, 0x58, 0x08, 0xAC, 0x62, 0x2E, 0xF3, 0x61, 0xA2, 0xE9, 0x2C, + 0x90, 0xA7, 0x41, 0x34, 0x65, 0x45, 0xF4, 0x35, 0xE7, 0xAB, 0xEE, 0x3C, 0xBB, 0x1D, 0x31, 0x67, + 0x11, 0x0B, 0x5A, 0x12, 0x0B, 0xBD, 0x2A, 0x15, 0xBC, 0x29, 0x77, 0x9A, 0x73, 0x6A, 0x1A, 0xC0, + 0x11, 0x1A, 0x5D, 0x04, 0xAB, 0xF8, 0x3B, 0x9F, 0x8F, 0x2E, 0xEE, 0x0E, 0x99, 0x0C, 0x9A, 0x49, + 0xAD, 0x51, 0x29, 0x13, 0x3F, 0x7C, 0xF7, 0xC4, 0xFE, 0xCE, 0xA9, 0xA4, 0xCB, 0xB2, 0x59, 0xDE, + 0x80, 0x89, 0x59, 0xEA, 0xDB, 0x59, 0x0C, 0x2A, 0x62, 0x4D, 0x4E, 0xE0, 0x8D, 0x84, 0xFF, 0x04, + 0x8B, 0x16, 0x01, 0x53, 0x1A, 0x1A, 0x0F, 0xDC, 0x22, 0x04, 0xF5, 0x44, 0xF9, 0xF1, 0xC8, 0x9B, + 0x22, 0xBE, 0x41, 0x7F, 0xCA, 0xBA, 0x30, 0xA9, 0xCC, 0xE3, 0x3A, 0x02, 0x79, 0x6E, 0x9E, 0xBC, + 0xB9, 0x6E, 0x8E, 0xC5, 0xCF, 0xF3, 0x68, 0x18, 0xCC, 0x01, 0xD1, 0x98, 0xEB, 0x06, 0x0D, 0x96, + 0x4D, 0xAE, 0xC9, 0x95, 0x16, 0x05, 0x30, 0xC2, 0xDE, 0x91, 0xD7, 0x4B, 0x54, 0x56, 0x88, 0x79, + 0xB8, 0xDA, 0xEF, 0xF7, 0x0E, 0xD7, 0xD7, 0xC1, 0x55, 0x54, 0x1F, 0x63, 0xDE, 0x2B, 0x6B, 0x55, + 0xE4, 0xD3, 0xE4, 0x8E, 0x16, 0xF4, 0xEB, 0xCC, 0x36, 0x99, 0xF7, 0x12, 0x5A, 0x75, 0xF7, 0x5E, + 0xBD, 0x08, 0x8C, 0x75, 0xD4, 0xE7, 0x42, 0x60, 0x6C, 0x88, 0x7D, 0xE5, 0x42, 0x6A, 0xC2, 0x97, + 0x8F, 0x56, 0xEC, 0x36, 0xC6, 0x60, 0x5E, 0x14, 0x97, 0xE9, 0xC6, 0xBB, 0x90, 0xB0, 0xC2, 0x1B, + 0x07, 0x23, 0x9C, 0xF9, 0xE3, 0xC8, 0xD0, 0x46, 0xE2, 0x62, 0x02, 0xCC, 0x51, 0xA3, 0x39, 0x0A, + 0xC7, 0x72, 0xE8, 0xFC, 0x41, 0x06, 0x49, 0x29, 0x25, 0x9A, 0xAF, 0x94, 0x53, 0x8A, 0x72, 0x04, + 0x2A, 0x95, 0xF3, 0xC8, 0xA4, 0x91, 0x11, 0xB6, 0x5F, 0x1D, 0x19, 0xE5, 0x9D, 0x24, 0x95, 0x74, + 0x76, 0x27, 0x4D, 0x3A, 0xA8, 0xBA, 0x8E, 0xD2, 0x26, 0x84, 0x9A, 0x05, 0x28, 0x51, 0xA2, 0x54, + 0x08, 0x50, 0xE2, 0xEF, 0x15, 0x08, 0x50, 0x72, 0xD0, 0x52, 0x02, 0x94, 0x78, 0xF7, 0xB9, 0x05, + 0x28, 0xD0, 0x08, 0xED, 0x47, 0x66, 0x58, 0xF7, 0x76, 0x00, 0xA2, 0x13, 0x71, 0x0C, 0x21, 0x52, + 0x89, 0x88, 0xC6, 0x84, 0x38, 0x95, 0x22, 0x36, 0xC9, 0xDB, 0x8C, 0x21, 0x9B, 0xC1, 0x0A, 0x93, + 0xA2, 0xF9, 0xFA, 0xB8, 0x97, 0xF3, 0x24, 0x2A, 0x59, 0xDC, 0x7B, 0xD9, 0x12, 0x95, 0x18, 0xE6, + 0x55, 0xA2, 0x7A, 0x39, 0xE7, 0x42, 0x6C, 0x47, 0xCB, 0x1E, 0x05, 0x93, 0x26, 0xCB, 0x3B, 0x0A, + 0xCA, 0x61, 0x70, 0xA9, 0x00, 0xC0, 0x04, 0x40, 0xF2, 0x23, 0x53, 0xB1, 0x22, 0xF4, 0x29, 0xA5, + 0xDA, 0x69, 0x54, 0xE6, 0x70, 0x33, 0xF1, 0xF7, 0x33, 0x5D, 0x76, 0xA9, 0xF0, 0x19, 0x13, 0x9F, + 0x4A, 0x94, 0x9C, 0xAB, 0xB3, 0xC0, 0x5B, 0x16, 0xD7, 0xE4, 0x63, 0xBC, 0x05, 0xCA, 0xD1, 0xC0, + 0x26, 0x66, 0xA7, 0xC9, 0x4C, 0x43, 0xC4, 0x4E, 0xF1, 0xE6, 0x76, 0xC8, 0x51, 0xE5, 0xE4, 0x89, + 0x3D, 0x7A, 0xF1, 0x72, 0x1A, 0xC8, 0x5A, 0x87, 0xDC, 0x17, 0x45, 0x74, 0x2B, 0x2A, 0xA4, 0x4B, + 0xA1, 0xBF, 0x12, 0xB5, 0x6F, 0x33, 0xB1, 0x4B, 0xA2, 0x38, 0xAA, 0xE0, 0x55, 0x8D, 0xC9, 0x29, + 0xEC, 0x12, 0x0D, 0xBD, 0xD8, 0x55, 0xDF, 0x27, 0x13, 0x52, 0xFC, 0x0C, 0x47, 0xE3, 0x92, 0x3C, + 0x9D, 0x4A, 0xDC, 0xBC, 0x48, 0x5A, 0x97, 0x63, 0x13, 0x8C, 0xE8, 0x78, 0x7A, 0xA8, 0x79, 0xAE, + 0x4B, 0xCC, 0x1A, 0x98, 0x8B, 0x4D, 0xC5, 0xD9, 0x66, 0xE6, 0x52, 0xC6, 0xE9, 0x15, 0xD7, 0x39, + 0xCC, 0x37, 0x12, 0xA7, 0xD7, 0x8A, 0x89, 0xD9, 0x8B, 0xE1, 0xD3, 0xC4, 0x2C, 0x4D, 0x07, 0x8F, + 0xAA, 0x7D, 0xE3, 0x94, 0x9E, 0x34, 0xCF, 0x92, 0xCD, 0x35, 0x7B, 0x4C, 0x24, 0x76, 0x2C, 0x6C, + 0xD8, 0xA2, 0xB8, 0xAB, 0x3F, 0x52, 0x7D, 0xF9, 0x9E, 0x28, 0x67, 0x1D, 0x1B, 0x93, 0xC8, 0x88, + 0x6A, 0x21, 0x6E, 0x00, 0xF1, 0x2C, 0x4B, 0x4C, 0x17, 0x84, 0xB2, 0x11, 0x62, 0xFA, 0x57, 0x3D, + 0x12, 0xD3, 0xD1, 0x70, 0xBC, 0x1A, 0x31, 0x7D, 0x32, 0xE8, 0xE4, 0xB0, 0x0A, 0x74, 0xE7, 0xB9, + 0x05, 0xF1, 0x09, 0x85, 0x90, 0xAC, 0xED, 0x41, 0x97, 0xDC, 0x42, 0x1C, 0x17, 0x41, 0xFE, 0x67, + 0xBD, 0x75, 0x17, 0xA7, 0x03, 0x3D, 0x2A, 0xB5, 0xB9, 0x5C, 0x81, 0x3A, 0xD0, 0xD7, 0x51, 0xA0, + 0x46, 0x04, 0x4E, 0x17, 0xA8, 0x5B, 0x4A, 0xAB, 0xA5, 0xBC, 0x4A, 0xD4, 0x79, 0x12, 0x75, 0x72, + 0x4B, 0x4B, 0x49, 0xD4, 0x89, 0x26, 0x4B, 0x90, 0xA8, 0xA7, 0x71, 0x3B, 0x4F, 0xB6, 0xC1, 0xBC, + 0xD8, 0x15, 0xCA, 0x81, 0x41, 0x6F, 0x33, 0x22, 0xCE, 0x84, 0xFF, 0x55, 0x13, 0x71, 0x66, 0xC5, + 0x9C, 0xD8, 0x5C, 0x23, 0xE0, 0xD6, 0x21, 0xE6, 0x2C, 0x2A, 0xEA, 0xCC, 0x2F, 0xEE, 0x94, 0x13, + 0x79, 0x96, 0x63, 0x6D, 0xAD, 0x53, 0xF4, 0x21, 0x16, 0xF1, 0xDC, 0xA2, 0xCF, 0x66, 0x5F, 0xF7, + 0x59, 0x5C, 0x42, 0x8A, 0x8E, 0xFF, 0x39, 0x25, 0xA4, 0xF9, 0x83, 0x08, 0x44, 0x2D, 0xA2, 0x0D, + 0x0F, 0x20, 0xA0, 0x45, 0xCC, 0x15, 0x3F, 0x10, 0x6F, 0x39, 0x0B, 0xDD, 0x38, 0x70, 0xA6, 0x42, + 0x07, 0xE8, 0xBE, 0xE8, 0xB3, 0x47, 0x0E, 0x64, 0x4F, 0x7F, 0x8D, 0x02, 0x07, 0xCE, 0x3D, 0xE7, + 0x06, 0xC9, 0xE0, 0xBC, 0xDF, 0xDB, 0xB9, 0xF9, 0xF2, 0xF3, 0xB2, 0x45, 0xE9, 0x70, 0xB8, 0x25, + 0x8B, 0xCC, 0xE8, 0xF1, 0xA2, 0x7A, 0x13, 0x78, 0x7B, 0x18, 0x96, 0xD6, 0x69, 0x87, 0xD9, 0xD1, + 0xA3, 0xBA, 0x16, 0x22, 0xC0, 0x09, 0xB0, 0x7A, 0x87, 0xFE, 0xD8, 0x46, 0xE7, 0x58, 0xF4, 0x68, + 0x0C, 0x62, 0x98, 0x21, 0x22, 0xA0, 0x44, 0x8A, 0x0D, 0xBC, 0x5A, 0x45, 0x76, 0x17, 0x4A, 0x77, + 0x33, 0x36, 0x3C, 0x2F, 0x99, 0xF0, 0xE6, 0xCB, 0x60, 0xB0, 0xD6, 0x77, 0xA3, 0x22, 0xAA, 0x98, + 0x27, 0x25, 0x56, 0x3A, 0x02, 0xE6, 0xAC, 0x57, 0x90, 0xE6, 0xF5, 0xF1, 0x69, 0x54, 0xE1, 0x9E, + 0xC6, 0x86, 0x07, 0xD9, 0xC5, 0xED, 0x8F, 0x8F, 0x8F, 0x4E, 0x4E, 0x8E, 0x4E, 0x4F, 0x8F, 0xCE, + 0xCE, 0x8E, 0xCE, 0xCF, 0x8F, 0x2E, 0x2E, 0xAA, 0x86, 0x2F, 0xCE, 0x35, 0xD3, 0x9E, 0x6A, 0x60, + 0x61, 0x16, 0x9A, 0xB0, 0x77, 0x54, 0xF1, 0x46, 0x74, 0x39, 0xB1, 0xD3, 0xE1, 0xDC, 0x85, 0x95, + 0x7B, 0xD9, 0x4B, 0xBF, 0xB1, 0x2D, 0xBE, 0x12, 0x33, 0x6E, 0x29, 0xBD, 0x09, 0x1B, 0xC9, 0x99, + 0x0A, 0xED, 0x08, 0x18, 0x13, 0x70, 0xC2, 0xF1, 0xD1, 0xBE, 0xF3, 0xFD, 0x4F, 0x45, 0x4B, 0x96, + 0xC7, 0x4C, 0xF2, 0xF8, 0x40, 0x28, 0xC0, 0xA9, 0x82, 0xB0, 0x16, 0x80, 0x6E, 0x64, 0x9D, 0x43, + 0xA9, 0x2A, 0x59, 0xB1, 0xE4, 0x15, 0x69, 0xE5, 0x4E, 0x34, 0x04, 0xE8, 0xE5, 0x18, 0x5A, 0x48, + 0x6A, 0x33, 0x30, 0x13, 0x4A, 0x18, 0x80, 0x13, 0x90, 0x5B, 0x9D, 0x5E, 0xBB, 0x71, 0x05, 0xAE, + 0xF8, 0x98, 0xD8, 0xF7, 0x68, 0x87, 0xA2, 0xD9, 0x36, 0xE3, 0xDF, 0x0D, 0x1F, 0xA5, 0x3B, 0x79, + 0xD6, 0x0B, 0x21, 0x8F, 0x7C, 0x69, 0xE4, 0xAD, 0xF7, 0xB8, 0x0F, 0x1B, 0x27, 0x81, 0x1B, 0x58, + 0xBE, 0x61, 0xB2, 0x37, 0xB8, 0x9A, 0x37, 0xE8, 0x3F, 0xF3, 0x38, 0xD6, 0xAB, 0xFD, 0x6A, 0x19, + 0xBE, 0xBC, 0xDA, 0xE9, 0x3D, 0xAA, 0x0E, 0x52, 0x5F, 0xE8, 0xEC, 0xE7, 0x9E, 0x0C, 0xC0, 0x04, + 0xB8, 0x62, 0x89, 0xC0, 0x71, 0x60, 0x51, 0x19, 0x08, 0x6B, 0x08, 0xE2, 0x28, 0xB3, 0x80, 0xFD, + 0x00, 0xE7, 0x7B, 0xC4, 0x28, 0x27, 0x6B, 0x83, 0x65, 0xC1, 0x7A, 0x18, 0xC2, 0x4A, 0x72, 0x1F, + 0x5C, 0xD8, 0x28, 0x23, 0x49, 0x5A, 0x08, 0x13, 0x1F, 0x88, 0x87, 0x78, 0x53, 0xB7, 0x70, 0x07, + 0x42, 0x1C, 0x5E, 0x4D, 0xD6, 0x83, 0xC4, 0x6C, 0x01, 0xFB, 0xE8, 0x65, 0xAE, 0x3F, 0x03, 0xE9, + 0x00, 0x31, 0x50, 0x2A, 0x3A, 0x55, 0xD3, 0x0C, 0xBC, 0xF5, 0x8C, 0xF9, 0x0F, 0x40, 0xC7, 0x0B, + 0x53, 0x68, 0x3A, 0x82, 0x99, 0xD3, 0x59, 0x23, 0xF2, 0xE6, 0x84, 0xEB, 0x62, 0xE3, 0x00, 0x23, + 0x74, 0x0C, 0x17, 0x7E, 0xDE, 0xCB, 0xC7, 0x1C, 0x29, 0x62, 0x60, 0xCB, 0xCA, 0x99, 0x92, 0xB6, + 0x80, 0x9C, 0x88, 0xE2, 0xF2, 0x9D, 0xD1, 0xEB, 0x4A, 0x09, 0xF3, 0x1F, 0x55, 0x79, 0x7C, 0x3B, + 0xB9, 0xFF, 0xE9, 0x9C, 0xBB, 0x02, 0x8F, 0x1E, 0x50, 0x77, 0xE2, 0xE0, 0x9D, 0xE5, 0xD5, 0xDD, + 0x09, 0x19, 0x54, 0x63, 0xD5, 0x4E, 0xDA, 0x74, 0xAF, 0xBD, 0xE1, 0x94, 0xBE, 0xD6, 0x0F, 0x48, + 0x3F, 0x5E, 0x56, 0x08, 0x4D, 0xB6, 0xF4, 0x65, 0xDA, 0xAE, 0x9A, 0x5B, 0x83, 0x66, 0x5A, 0x3C, + 0xB0, 0x40, 0x2A, 0xA8, 0x24, 0x90, 0xB1, 0x72, 0x3E, 0xB3, 0x32, 0x0C, 0xEA, 0x0A, 0x26, 0x8B, + 0x49, 0x32, 0x6F, 0xD5, 0x62, 0x6B, 0xDF, 0xE2, 0x0C, 0x46, 0x8C, 0xB6, 0x22, 0xCF, 0x54, 0x42, + 0x35, 0xC0, 0x15, 0x4A, 0x69, 0xF5, 0x39, 0xF5, 0x83, 0xE7, 0x72, 0x30, 0xE5, 0xBB, 0x67, 0x11, + 0x63, 0xE7, 0xCD, 0xA0, 0x3B, 0x17, 0x17, 0x3A, 0xB5, 0x6D, 0x57, 0x37, 0x2C, 0xA1, 0xCA, 0x5F, + 0xB8, 0xFC, 0x6F, 0x01, 0xB7, 0xB4, 0x27, 0xB6, 0x75, 0xFD, 0xF9, 0x8F, 0xB7, 0xCF, 0x11, 0x33, + 0x49, 0x65, 0x81, 0x06, 0xD1, 0x3C, 0x08, 0x35, 0x84, 0xDD, 0x0E, 0x0D, 0x15, 0x6C, 0x64, 0x3B, + 0x0E, 0xCA, 0x50, 0x61, 0x81, 0x16, 0x59, 0x0F, 0xD1, 0x6B, 0x4A, 0xC6, 0x25, 0xAC, 0x6F, 0x16, + 0x17, 0xAD, 0x46, 0x5C, 0x75, 0x19, 0x57, 0xB5, 0x11, 0xB3, 0xE1, 0xBC, 0x71, 0xC5, 0x89, 0x04, + 0x5D, 0x8A, 0xFC, 0x6E, 0x18, 0x9D, 0xA9, 0xC5, 0x97, 0x1F, 0x0D, 0x1B, 0x43, 0xA2, 0xF7, 0x2D, + 0x05, 0x40, 0xD1, 0x64, 0x57, 0xC6, 0x18, 0x64, 0x3D, 0xF8, 0xAC, 0xA0, 0xD1, 0x86, 0xBD, 0x6F, + 0xBF, 0xC3, 0xC7, 0x2F, 0xE0, 0xBC, 0x92, 0x12, 0xBF, 0x70, 0xBF, 0xEC, 0xE3, 0x1C, 0x3A, 0x6C, + 0xA2, 0xB8, 0x54, 0xF1, 0x1E, 0xE4, 0x14, 0xE1, 0x90, 0xDC, 0x76, 0xC2, 0x93, 0x27, 0x50, 0x8F, + 0x70, 0xAE, 0x9C, 0x66, 0x97, 0xD9, 0x7C, 0x41, 0xE7, 0x42, 0xBD, 0x54, 0x25, 0xAA, 0x5D, 0x79, + 0xA1, 0xB0, 0xA3, 0x73, 0x1D, 0x85, 0x7F, 0x40, 0x4A, 0xD3, 0xF0, 0x7C, 0x6E, 0x21, 0x06, 0xA3, + 0xBA, 0xB1, 0x6A, 0x02, 0x3B, 0x1E, 0xF8, 0x14, 0xC1, 0x02, 0x12, 0x97, 0xD8, 0x2C, 0xCA, 0x4B, + 0x25, 0xE6, 0xBA, 0x0D, 0x1C, 0x1A, 0xF4, 0x14, 0x9C, 0x9A, 0x4C, 0x73, 0x15, 0xE5, 0x2D, 0x83, + 0xD7, 0x8D, 0xA1, 0x65, 0xA3, 0x9C, 0xE7, 0xD9, 0x82, 0xC2, 0x88, 0x89, 0xCB, 0xF7, 0x90, 0x8B, + 0x0F, 0x30, 0x3E, 0x31, 0x24, 0x4A, 0xA9, 0x61, 0x61, 0xAA, 0x74, 0x2C, 0x50, 0x1F, 0xB3, 0x9B, + 0x03, 0xE5, 0xB8, 0x7C, 0x47, 0x9C, 0x40, 0xD3, 0xC3, 0xC4, 0x88, 0xAE, 0xA3, 0x78, 0x13, 0x8A, + 0x6B, 0x29, 0xD8, 0xEC, 0x40, 0x51, 0xBC, 0x57, 0x72, 0x9B, 0x8F, 0xDC, 0x44, 0xE6, 0x34, 0x4C, + 0x70, 0xEF, 0xAA, 0xE4, 0xB1, 0xC2, 0x5C, 0xF8, 0x76, 0xE0, 0xFF, 0xEE, 0x95, 0xA7, 0xB9, 0xEC, + 0x3E, 0x96, 0x41, 0x78, 0x15, 0x04, 0xBE, 0x6A, 0xD6, 0xFD, 0x58, 0xD2, 0x63, 0xD6, 0x73, 0x0D, + 0x1B, 0x53, 0xA3, 0x6F, 0xBA, 0xB1, 0x3F, 0xB6, 0xA6, 0x70, 0x49, 0xB9, 0xA6, 0xFF, 0x99, 0x6E, + 0x33, 0x5C, 0x01, 0xD9, 0xFD, 0xCE, 0xEE, 0x4C, 0x1C, 0xAE, 0xA9, 0xEE, 0x81, 0x58, 0x06, 0xD6, + 0x25, 0x39, 0x09, 0x2A, 0x78, 0x09, 0xCA, 0xAE, 0xAC, 0x96, 0xB4, 0x65, 0xE5, 0xAE, 0xDB, 0xC7, + 0xE0, 0x23, 0x72, 0x07, 0x7B, 0x57, 0xC6, 0x80, 0x63, 0x9D, 0xC2, 0x6C, 0xEE, 0x3E, 0x13, 0x53, + 0xB1, 0x17, 0x19, 0xF0, 0x0E, 0xE8, 0x8F, 0x83, 0x99, 0x98, 0x8A, 0xF8, 0x3E, 0x89, 0x71, 0x58, + 0x38, 0xCE, 0xD1, 0x8A, 0x94, 0x81, 0xE3, 0x58, 0x36, 0x5E, 0x99, 0x64, 0x97, 0x01, 0x8A, 0x52, + 0x49, 0x0D, 0x63, 0xC0, 0x2C, 0x5B, 0x5C, 0x83, 0x81, 0x43, 0x07, 0x6B, 0x6B, 0x18, 0x0F, 0xB2, + 0x52, 0x35, 0x9D, 0x5A, 0x63, 0xD5, 0x7A, 0x0A, 0x0F, 0xAC, 0xE6, 0x84, 0x80, 0xC3, 0x2B, 0x33, + 0x22, 0x2E, 0x53, 0xDE, 0x27, 0x24, 0x1B, 0x1B, 0x16, 0xFB, 0xC1, 0x1C, 0x6B, 0x61, 0x32, 0xDF, + 0xF0, 0x50, 0xD9, 0xC7, 0xB7, 0x5A, 0x6D, 0x25, 0xEA, 0x6C, 0xBD, 0x34, 0x85, 0x72, 0x99, 0x12, + 0xDE, 0x24, 0x0E, 0x93, 0xBD, 0x37, 0xE5, 0xC2, 0x84, 0xDF, 0x88, 0x83, 0xE3, 0x4D, 0xD8, 0x49, + 0xFC, 0xE0, 0x78, 0x33, 0x4D, 0xAB, 0xD3, 0xB8, 0x58, 0xDD, 0x3B, 0xE0, 0x14, 0x74, 0xB9, 0xB4, + 0x10, 0xB8, 0xC2, 0xA4, 0x81, 0xB3, 0xB4, 0x30, 0x39, 0x13, 0x96, 0x9D, 0x48, 0xF0, 0xD8, 0xC3, + 0xAA, 0x54, 0x84, 0xA7, 0x4E, 0x88, 0xC5, 0x20, 0x8B, 0x91, 0xAE, 0x12, 0x4F, 0x56, 0x1D, 0xE2, + 0x2D, 0xD9, 0x71, 0xF0, 0xFA, 0xBE, 0x1A, 0x92, 0x0C, 0xE0, 0x2F, 0x08, 0x6C, 0x2E, 0x47, 0x7D, + 0x09, 0xAD, 0xD0, 0x61, 0x37, 0xE1, 0xBB, 0x74, 0xD3, 0x4C, 0x62, 0x3F, 0x95, 0x25, 0xFE, 0x86, + 0xEF, 0xD1, 0x63, 0x90, 0xD5, 0xE0, 0x29, 0xBC, 0x48, 0x55, 0x8B, 0x45, 0x46, 0x6C, 0x4F, 0x45, + 0x42, 0xA3, 0x7B, 0x22, 0x6F, 0xFA, 0xF0, 0x77, 0x92, 0x8B, 0xBF, 0x29, 0x69, 0xA4, 0x5B, 0x9B, + 0x84, 0x84, 0xF1, 0x93, 0x5A, 0xB2, 0xC2, 0xF1, 0x77, 0x8A, 0x00, 0x12, 0x18, 0x31, 0x8D, 0x94, + 0xE1, 0xBE, 0x5F, 0x19, 0x99, 0xD7, 0xC6, 0xD2, 0xED, 0x75, 0x19, 0xA6, 0xB9, 0xA8, 0x7F, 0xEC, + 0xF8, 0x84, 0xDE, 0x55, 0x1A, 0x5D, 0x25, 0xDF, 0xAE, 0xB6, 0xE8, 0x08, 0xAD, 0x46, 0xB7, 0xB5, + 0xDC, 0x11, 0x60, 0xC7, 0xDA, 0xCB, 0x1D, 0xA1, 0xD3, 0xE8, 0x76, 0x96, 0x3B, 0xC2, 0x5E, 0xA3, + 0xBB, 0xB7, 0xDC, 0x11, 0xF6, 0x1B, 0xDD, 0xFD, 0xE5, 0x8E, 0x70, 0xD0, 0xE8, 0x1E, 0x2C, 0x77, + 0x84, 0x77, 0x8D, 0xEE, 0xBB, 0xA2, 0x11, 0xDC, 0x2A, 0x43, 0x67, 0x10, 0x9C, 0xD4, 0xF9, 0xE6, + 0x30, 0x72, 0x47, 0xC6, 0x6D, 0x17, 0xB5, 0xCC, 0x3B, 0xFB, 0x34, 0xBB, 0x73, 0x0C, 0x18, 0x96, + 0xBA, 0xA8, 0x1D, 0x6A, 0x99, 0x39, 0x36, 0xEE, 0x85, 0x63, 0x88, 0x2E, 0x2D, 0xCF, 0x77, 0x03, + 0x3C, 0x0F, 0x9E, 0x45, 0xB7, 0x40, 0x50, 0x1B, 0xD1, 0x14, 0x42, 0x5D, 0xA0, 0x46, 0x8D, 0xE3, + 0x72, 0xA6, 0xF3, 0x4A, 0x31, 0x46, 0x33, 0xCD, 0x67, 0xB7, 0x60, 0x06, 0x82, 0x53, 0xEA, 0x44, + 0x6C, 0x79, 0xCF, 0x1D, 0x72, 0x54, 0xB0, 0x9A, 0x39, 0x74, 0x08, 0xBA, 0xF5, 0x62, 0x98, 0x15, + 0x73, 0x48, 0xD4, 0xED, 0x8F, 0xB8, 0xA3, 0x19, 0x8C, 0x1D, 0x6E, 0x79, 0x32, 0xFA, 0x55, 0x3A, + 0x4D, 0xF1, 0x8B, 0x02, 0x9B, 0xF2, 0xA4, 0xD5, 0x2A, 0x7C, 0x19, 0xB3, 0x33, 0x5D, 0x95, 0x2A, + 0x43, 0xD7, 0x72, 0x71, 0xAB, 0xD0, 0xC5, 0x1F, 0x8D, 0x4F, 0xB6, 0x3D, 0x0A, 0x2A, 0x05, 0xCD, + 0x06, 0x2D, 0x26, 0x5C, 0x9F, 0xAD, 0x56, 0xDF, 0xDC, 0x28, 0xDF, 0xC4, 0x72, 0x10, 0x4D, 0x94, + 0x1C, 0xB8, 0x33, 0x9C, 0x63, 0x13, 0x20, 0x1A, 0xE8, 0xA0, 0x5F, 0xC8, 0x74, 0xFB, 0xF0, 0x8C, + 0x85, 0x0F, 0x97, 0x8B, 0x42, 0x29, 0x73, 0x58, 0x11, 0xF6, 0xC8, 0xA5, 0x3A, 0x36, 0xEE, 0x27, + 0xAC, 0x57, 0x95, 0x13, 0x88, 0x17, 0x0D, 0x50, 0xF1, 0x7E, 0x89, 0xA5, 0x46, 0xDF, 0xA5, 0x54, + 0x99, 0xDC, 0xA0, 0x5B, 0x54, 0xD9, 0xEC, 0x4E, 0xAE, 0xB3, 0x37, 0x02, 0x75, 0xE6, 0x94, 0x68, + 0xE6, 0xF7, 0xF1, 0x78, 0xB9, 0x17, 0x54, 0x52, 0x87, 0x6C, 0xA4, 0xDA, 0x69, 0x67, 0xED, 0x28, + 0xC7, 0x72, 0x5F, 0xA8, 0x75, 0x3E, 0x33, 0xA4, 0xAE, 0xD9, 0xD6, 0x78, 0xBC, 0x72, 0x7F, 0xDA, + 0x71, 0xEF, 0x14, 0xF5, 0x36, 0x99, 0xF1, 0xCD, 0x57, 0x2D, 0x0D, 0x5D, 0x6B, 0xF6, 0x58, 0x04, + 0x5F, 0xA0, 0xE2, 0x28, 0x33, 0x92, 0x84, 0x58, 0x26, 0x2D, 0x27, 0xE1, 0x47, 0x07, 0x17, 0xC7, + 0x34, 0x5A, 0x40, 0x93, 0xDD, 0xA1, 0x01, 0x06, 0xFE, 0x1F, 0x78, 0x81, 0x6A, 0x9A, 0x4F, 0xA8, + 0x70, 0x5A, 0x7E, 0x58, 0x94, 0x10, 0xAB, 0x2C, 0xEB, 0x33, 0xFD, 0x61, 0x04, 0x14, 0x26, 0x1B, + 0x50, 0x4D, 0x8D, 0x6E, 0xE2, 0xEA, 0x4C, 0x0F, 0x5C, 0x0A, 0x81, 0x92, 0x2F, 0xC0, 0x37, 0xC6, + 0xBD, 0x2B, 0x0B, 0xAB, 0x1E, 0x8F, 0xED, 0x40, 0x64, 0x27, 0x50, 0x75, 0x5D, 0x38, 0xF0, 0x3E, + 0x1F, 0x9F, 0x87, 0x3E, 0x14, 0x98, 0xBF, 0x4B, 0xE1, 0x53, 0x03, 0xE3, 0x3B, 0x86, 0x91, 0xA8, + 0x78, 0x7B, 0x07, 0xB8, 0xFE, 0xD8, 0xC6, 0x10, 0xFD, 0x53, 0xEF, 0x88, 0xDD, 0xD9, 0xAE, 0x36, + 0xDA, 0x6A, 0xB5, 0xDE, 0x01, 0xA8, 0xD9, 0xF9, 0x5F, 0xFE, 0xBC, 0xB5, 0xD7, 0xC6, 0xBF, 0x2E, + 0x00, 0x7A, 0x3E, 0xB0, 0x64, 0x4F, 0x35, 0xB4, 0xAD, 0x83, 0xF7, 0x93, 0x47, 0xA2, 0x88, 0x13, + 0x7B, 0x68, 0x27, 0x9E, 0xC2, 0xC7, 0x77, 0x0A, 0x7C, 0x7C, 0x49, 0x57, 0x81, 0x24, 0x16, 0xD7, + 0xE4, 0x5D, 0x68, 0x64, 0x53, 0x6C, 0x39, 0x7F, 0x42, 0x6A, 0xD3, 0x95, 0x67, 0x5E, 0x29, 0x64, + 0x46, 0x9F, 0x39, 0x52, 0xDB, 0xEF, 0xAB, 0x61, 0x43, 0xE1, 0x60, 0x55, 0x19, 0x90, 0x68, 0xC7, + 0xB6, 0xD4, 0xE6, 0xB7, 0xA6, 0xDA, 0xCC, 0x85, 0x7E, 0x0F, 0x0F, 0x9A, 0x2B, 0x6E, 0x0D, 0xFD, + 0xD1, 0x5B, 0xE0, 0x47, 0xCF, 0xE0, 0xDE, 0x17, 0x0C, 0x84, 0x4C, 0x50, 0x34, 0x8D, 0x90, 0x5F, + 0x00, 0x95, 0x78, 0x63, 0x71, 0x10, 0x22, 0x45, 0xA2, 0x91, 0xD7, 0xB0, 0x34, 0x33, 0x40, 0x2E, + 0x80, 0x05, 0xA9, 0x2C, 0x8C, 0xEC, 0xF0, 0x9A, 0xEC, 0xC6, 0x46, 0xD6, 0x40, 0x85, 0x4F, 0x55, + 0x93, 0x1D, 0xDF, 0xF6, 0xB0, 0xE6, 0x52, 0x60, 0x52, 0x9E, 0xCB, 0xB0, 0x41, 0xFC, 0x4A, 0x5F, + 0xF3, 0x70, 0xFC, 0x4A, 0xC6, 0xA5, 0xC8, 0x38, 0x42, 0xBF, 0x2A, 0x04, 0x1C, 0x36, 0x7A, 0x5E, + 0xD2, 0xCD, 0x50, 0xCD, 0xB3, 0x74, 0xF3, 0xFE, 0x13, 0x08, 0x57, 0xE3, 0x4D, 0xF7, 0xF9, 0x89, + 0x55, 0xCC, 0xA5, 0x7D, 0x27, 0x9A, 0xCE, 0x82, 0x38, 0x01, 0x9F, 0x29, 0xAD, 0xDB, 0x13, 0x4D, + 0x9F, 0xDD, 0x7F, 0x97, 0xB3, 0x84, 0x39, 0xD5, 0xED, 0xC0, 0x31, 0x6D, 0x55, 0xBF, 0xE1, 0x8F, + 0x17, 0x86, 0x3B, 0x7E, 0x84, 0xF9, 0x9F, 0x19, 0x0F, 0x65, 0x6A, 0x8D, 0x17, 0xA8, 0x39, 0x5D, + 0x09, 0xCD, 0xB0, 0xD7, 0x82, 0x24, 0xD8, 0xC4, 0x88, 0xE8, 0xEA, 0x86, 0xFF, 0x2D, 0x6C, 0xF2, + 0x17, 0xEE, 0x22, 0xF7, 0xFB, 0xEA, 0x0C, 0x5D, 0x15, 0x94, 0x93, 0xCC, 0x0B, 0x0D, 0x0F, 0x4A, + 0x53, 0x99, 0xC7, 0x62, 0x9E, 0x7D, 0xAC, 0xE5, 0x10, 0x6E, 0x5E, 0xE8, 0xEA, 0x29, 0xAE, 0x3F, + 0x06, 0xC9, 0xF9, 0xC2, 0x57, 0x23, 0xEB, 0x9E, 0x36, 0xD5, 0x1D, 0xDA, 0xF2, 0x68, 0x08, 0xF2, + 0x0A, 0xC2, 0x17, 0x11, 0x70, 0x27, 0x98, 0xB5, 0x22, 0x05, 0x4E, 0x4C, 0xA3, 0xEF, 0xA8, 0xEE, + 0xB7, 0x8B, 0x80, 0xFC, 0x8E, 0x1E, 0xE7, 0xE4, 0xC3, 0x84, 0x59, 0x0D, 0xE4, 0xAC, 0x48, 0x9E, + 0x8D, 0x2A, 0x3B, 0x45, 0x9E, 0x4C, 0x11, 0x10, 0xB3, 0x56, 0xBA, 0x5B, 0x8C, 0xC1, 0x87, 0x93, + 0x0F, 0xF7, 0x12, 0x63, 0x7A, 0x05, 0x2F, 0x7F, 0xDE, 0x20, 0xFE, 0xDB, 0xD3, 0x08, 0xAB, 0xBA, + 0xC2, 0xF8, 0x72, 0xC2, 0x7D, 0x35, 0x86, 0x01, 0xAB, 0x89, 0xCE, 0x8F, 0x4F, 0x63, 0xC5, 0x42, + 0x14, 0xAD, 0x37, 0xC2, 0x2D, 0xE4, 0xEE, 0xAA, 0x61, 0x79, 0xD2, 0xE1, 0x8D, 0x6E, 0x3D, 0x36, + 0xE0, 0xAA, 0x1F, 0xA0, 0x33, 0x1D, 0xA8, 0x81, 0x8D, 0xD5, 0x27, 0x66, 0xD9, 0x14, 0x80, 0x0F, + 0x0A, 0x14, 0x4C, 0x1D, 0x85, 0x28, 0x1F, 0x3D, 0xEB, 0xA0, 0x39, 0x71, 0x3C, 0x2E, 0x08, 0x25, + 0x07, 0x06, 0x07, 0x29, 0x0A, 0xB3, 0xDC, 0xAF, 0x7B, 0x8C, 0xD5, 0xF3, 0xE2, 0xDF, 0x71, 0xE0, + 0xDB, 0xE1, 0xD6, 0x7F, 0x75, 0x60, 0x33, 0x79, 0x64, 0x15, 0xC5, 0xAF, 0xC6, 0x70, 0x5A, 0x6A, + 0x11, 0x36, 0x16, 0x57, 0xD1, 0xA4, 0x1E, 0x56, 0x76, 0xA7, 0x24, 0x6D, 0xF2, 0xAB, 0xBE, 0xA7, + 0x9F, 0x91, 0x56, 0xC5, 0xE1, 0xAE, 0x61, 0x63, 0x8C, 0x24, 0x1A, 0x16, 0xB4, 0x88, 0xBB, 0xC7, + 0xF9, 0x68, 0x93, 0x41, 0x63, 0x95, 0x1E, 0x39, 0xAE, 0xAD, 0x07, 0x22, 0x7E, 0xE4, 0x41, 0x9C, + 0x8E, 0xE9, 0xDC, 0x76, 0x1B, 0x1D, 0xDE, 0x61, 0x6C, 0x08, 0x1A, 0xD5, 0x44, 0x62, 0x7D, 0x35, + 0xDC, 0x29, 0x1C, 0x6D, 0xB3, 0xF1, 0x3D, 0xB9, 0xB9, 0xB4, 0xA8, 0xE4, 0x0E, 0xCF, 0x1B, 0x4B, + 0x3E, 0xB7, 0x6A, 0x9B, 0xAA, 0xE2, 0xC6, 0x10, 0x8F, 0x4E, 0x94, 0x6B, 0xC3, 0x0A, 0x00, 0xF1, + 0xCB, 0x95, 0x2C, 0xCE, 0x89, 0x72, 0x12, 0x99, 0x63, 0xDE, 0xCD, 0x28, 0xC7, 0xB2, 0xFF, 0x58, + 0x94, 0x38, 0x0C, 0xEA, 0x1D, 0x3D, 0x73, 0x41, 0x72, 0xC4, 0xDF, 0x88, 0x49, 0x44, 0x08, 0x1B, + 0xD0, 0x3E, 0x21, 0xDE, 0x46, 0x94, 0x31, 0x53, 0xDF, 0x21, 0x95, 0x20, 0x98, 0x3A, 0x89, 0xE6, + 0xA5, 0xB8, 0xA8, 0xB1, 0x5C, 0xF5, 0x08, 0xC3, 0x37, 0x38, 0x6D, 0x73, 0x42, 0x1B, 0xDE, 0x03, + 0xC0, 0x6D, 0xB5, 0x60, 0x3D, 0x4F, 0x6F, 0x37, 0xAF, 0x90, 0x73, 0xC9, 0x32, 0xDE, 0xA5, 0x23, + 0x64, 0x11, 0x9D, 0xBC, 0x31, 0x70, 0x00, 0xA9, 0x06, 0x67, 0xA1, 0x68, 0x89, 0x21, 0x9D, 0xDC, + 0x1E, 0xE6, 0x55, 0x8E, 0xCB, 0xC4, 0x15, 0x57, 0x8F, 0xA0, 0x8D, 0x1C, 0xF7, 0xD9, 0xC6, 0x2C, + 0xD5, 0x34, 0x86, 0x16, 0x70, 0x0A, 0x32, 0xCC, 0x09, 0xE8, 0xC0, 0xE3, 0x4F, 0xDC, 0x4F, 0xC8, + 0xF4, 0xE5, 0x2F, 0x4E, 0x15, 0x2A, 0x0C, 0xD3, 0x5D, 0x97, 0xB8, 0xA7, 0x5C, 0x52, 0x77, 0x18, + 0x26, 0x7A, 0x46, 0xCD, 0x41, 0x70, 0x45, 0x14, 0xD5, 0x1F, 0x3A, 0xCD, 0xD6, 0x5E, 0xB3, 0xB5, + 0x5F, 0x46, 0x6B, 0x10, 0xB0, 0xE8, 0x7E, 0x80, 0x83, 0x67, 0x48, 0x77, 0x83, 0xE3, 0x32, 0xB2, + 0xE8, 0xB2, 0x27, 0xBF, 0x3A, 0x51, 0xDD, 0xE8, 0xF0, 0x6D, 0xB5, 0x1B, 0x40, 0x99, 0xDF, 0xE1, + 0x0F, 0x45, 0x29, 0xE6, 0x16, 0x12, 0xA2, 0x8F, 0x86, 0xEE, 0x8F, 0x8E, 0x3A, 0x8A, 0x42, 0x37, + 0xBF, 0x01, 0x45, 0x64, 0xC7, 0xA5, 0x0C, 0x33, 0xE9, 0x73, 0xCA, 0xB9, 0x91, 0xD7, 0x79, 0xF7, + 0x4F, 0x05, 0x26, 0x1A, 0xB9, 0xF6, 0xBA, 0x0C, 0xAC, 0x65, 0xD4, 0xE8, 0x69, 0x45, 0xB1, 0x64, + 0xFA, 0xD3, 0x81, 0x61, 0x02, 0xF6, 0x88, 0xF4, 0x4A, 0xF7, 0xC0, 0xA4, 0xE8, 0x23, 0x99, 0x2D, + 0x82, 0xFB, 0xB1, 0xE1, 0x87, 0x68, 0x70, 0x41, 0xCF, 0x6D, 0x4B, 0xA3, 0xE8, 0xB7, 0x38, 0xCC, + 0xD0, 0x04, 0xF0, 0xB3, 0x6A, 0xF8, 0x78, 0x37, 0x72, 0x37, 0x7B, 0x50, 0xF1, 0x22, 0x3B, 0xB9, + 0xBC, 0x99, 0x23, 0x7A, 0xB3, 0xB6, 0x08, 0xC2, 0x10, 0x93, 0xE1, 0xAC, 0x08, 0x2C, 0xC3, 0x7F, + 0xE3, 0x4D, 0x0E, 0x86, 0xFB, 0x27, 0x26, 0xEC, 0x19, 0xE4, 0x6A, 0x61, 0x00, 0x0B, 0xA4, 0x1F, + 0x84, 0xC7, 0xC4, 0xFD, 0x13, 0x25, 0x80, 0x66, 0xCE, 0x08, 0x68, 0x17, 0x6F, 0xDA, 0xF5, 0x4E, + 0x57, 0x1D, 0xDA, 0x97, 0x1D, 0x42, 0x34, 0x8D, 0xCE, 0xB8, 0x9A, 0xAA, 0x17, 0x4B, 0xB3, 0xB0, + 0x33, 0x95, 0xFD, 0x4D, 0x6E, 0xE0, 0xA9, 0x9E, 0x8F, 0x09, 0xB8, 0x52, 0x52, 0x88, 0x15, 0x9A, + 0x81, 0x48, 0xDA, 0x89, 0x3A, 0x88, 0xAC, 0x3F, 0x97, 0xB0, 0x3F, 0x78, 0xD3, 0x85, 0x9E, 0x56, + 0x2A, 0xB5, 0x35, 0xE9, 0x2B, 0x39, 0xB7, 0x45, 0xCB, 0x6B, 0x29, 0x8D, 0xEE, 0xAD, 0x4D, 0x59, + 0x1C, 0x2B, 0x56, 0xD8, 0x6A, 0x35, 0xBA, 0x27, 0xAA, 0xC7, 0x2B, 0xB7, 0x6B, 0x63, 0x82, 0xE0, + 0xEA, 0x05, 0xBD, 0x3A, 0x62, 0x38, 0xCC, 0x2A, 0xBC, 0x1E, 0x45, 0xBD, 0x7A, 0x81, 0x08, 0xA1, + 0x15, 0x96, 0x50, 0xBC, 0xD4, 0x2A, 0x5C, 0xA6, 0x62, 0x74, 0xA0, 0x26, 0x0A, 0xFD, 0x08, 0x33, + 0x3C, 0xF4, 0x28, 0xC3, 0xC3, 0x17, 0x0B, 0xA9, 0x8B, 0xE2, 0xCF, 0x9A, 0x6B, 0x9F, 0xB0, 0xC6, + 0xB4, 0x87, 0x77, 0x76, 0xFF, 0xEC, 0x54, 0xCD, 0xAC, 0x8E, 0xB7, 0x82, 0x8B, 0xD0, 0x43, 0x38, + 0xE4, 0x87, 0x78, 0x17, 0x7A, 0x88, 0x27, 0x75, 0xFF, 0x8C, 0xE1, 0x74, 0x56, 0x73, 0x2B, 0x5A, + 0x0E, 0xBD, 0xBA, 0xCC, 0xD5, 0x2A, 0xC8, 0xED, 0x9A, 0x0B, 0x20, 0x27, 0x4B, 0x35, 0x23, 0xD3, + 0xA0, 0x4F, 0xB8, 0x44, 0x79, 0xAA, 0xD9, 0x18, 0x18, 0x9C, 0x8A, 0x51, 0xDA, 0xA1, 0x22, 0x0B, + 0x3B, 0x34, 0x4C, 0x0B, 0x28, 0xDA, 0xB8, 0xBB, 0xCE, 0x09, 0x90, 0x17, 0x29, 0xAA, 0xE5, 0xED, + 0x3E, 0x65, 0xB5, 0xD4, 0x38, 0xCF, 0x06, 0x29, 0x0D, 0xE6, 0x81, 0x57, 0xDA, 0x1A, 0x73, 0xE9, + 0x9B, 0xEA, 0x77, 0x26, 0xD7, 0x51, 0x28, 0xE6, 0xE1, 0x20, 0x6C, 0x0B, 0x74, 0xB5, 0xB7, 0x47, + 0xD5, 0x0C, 0x0F, 0x8B, 0xEB, 0xA2, 0x61, 0xDC, 0x11, 0xC6, 0x81, 0x20, 0xD3, 0x82, 0x55, 0x23, + 0x36, 0x31, 0xBC, 0x86, 0x41, 0x86, 0x13, 0x6D, 0x64, 0xF0, 0x07, 0x44, 0x3C, 0x53, 0x2C, 0x46, + 0xAA, 0x9F, 0x9C, 0x62, 0x2D, 0x26, 0xF1, 0x1F, 0x7C, 0x10, 0x10, 0xDC, 0x98, 0x89, 0xB7, 0x69, + 0xF0, 0x3D, 0xD3, 0x86, 0x1F, 0x20, 0x26, 0x8E, 0xB7, 0xE9, 0x3A, 0xA7, 0x85, 0x73, 0xDA, 0x46, + 0x8B, 0x23, 0xAA, 0xBA, 0x5E, 0xE0, 0x3E, 0xF0, 0x27, 0x4A, 0xAB, 0xAE, 0x42, 0x67, 0x2E, 0x5A, + 0x2C, 0xE3, 0x0E, 0x60, 0x18, 0x7D, 0x5A, 0x4D, 0x95, 0xAA, 0xEC, 0xE4, 0xBE, 0x0E, 0xDD, 0x01, + 0x6D, 0x6D, 0x2B, 0xFB, 0xAD, 0xED, 0xB6, 0x12, 0xFB, 0x5E, 0x61, 0x1F, 0xF1, 0xC6, 0x10, 0x4D, + 0xA4, 0x59, 0x52, 0xAB, 0x5D, 0x9A, 0x46, 0x5B, 0xCE, 0xEC, 0x53, 0xDE, 0xD8, 0x57, 0x59, 0x8B, + 0x8D, 0xA1, 0x71, 0x29, 0x75, 0x61, 0xF2, 0xFE, 0xCA, 0x6E, 0x4F, 0xCF, 0x4F, 0x9D, 0x22, 0x72, + 0x61, 0x11, 0xFA, 0x2C, 0xDC, 0x40, 0x54, 0x0D, 0x64, 0x84, 0x84, 0x24, 0xD1, 0xA5, 0x52, 0x20, + 0x10, 0x53, 0x92, 0x0C, 0x92, 0x44, 0x28, 0x8C, 0x9D, 0x48, 0xA0, 0x21, 0xEB, 0xC7, 0xEB, 0x3E, + 0x58, 0xB3, 0x25, 0x8D, 0x16, 0xE9, 0x3B, 0xBA, 0x58, 0x4E, 0x79, 0x32, 0x4C, 0x3A, 0x28, 0x64, + 0x5E, 0x6A, 0x55, 0x10, 0xA8, 0x20, 0xC4, 0x72, 0xB4, 0xD6, 0x3E, 0x3C, 0x7C, 0x25, 0xB3, 0x5C, + 0x32, 0x93, 0xF8, 0x58, 0x81, 0xD0, 0x44, 0x8B, 0xD5, 0x26, 0x2A, 0x40, 0xB9, 0xAC, 0x95, 0xB4, + 0x9D, 0xD4, 0xE0, 0x0D, 0x21, 0x1B, 0x11, 0xD7, 0x61, 0x4D, 0x48, 0x32, 0x1E, 0x3A, 0xE3, 0xE8, + 0x01, 0x52, 0x19, 0x51, 0xD1, 0x0A, 0x9C, 0x1A, 0xD3, 0x73, 0x78, 0xBE, 0x2C, 0x59, 0x71, 0xAF, + 0x06, 0x92, 0x2B, 0x6A, 0xDA, 0x13, 0x79, 0x4D, 0xCE, 0x33, 0x0C, 0xAE, 0x94, 0xBC, 0x28, 0xCE, + 0x6B, 0x9A, 0xA0, 0x22, 0x60, 0x40, 0xA5, 0xED, 0x79, 0x06, 0xBA, 0x92, 0x8C, 0x41, 0xE2, 0x4D, + 0xC9, 0x90, 0x0C, 0xAA, 0x14, 0x8C, 0x31, 0x97, 0x43, 0x17, 0x94, 0xC9, 0x81, 0xBC, 0x87, 0x8F, + 0xBC, 0xA3, 0xBD, 0xC7, 0x46, 0x76, 0xE0, 0x7A, 0x9B, 0xEF, 0xCC, 0x30, 0xC5, 0x6E, 0x46, 0xE4, + 0x51, 0xE2, 0xA0, 0x88, 0xA1, 0x7D, 0x09, 0xA7, 0x46, 0x06, 0x8A, 0x8B, 0x63, 0x29, 0x49, 0x26, + 0x57, 0x72, 0x2B, 0x49, 0x17, 0x3F, 0x12, 0x80, 0x2B, 0x6D, 0x36, 0x8F, 0x2D, 0xE6, 0x46, 0x1D, + 0xE7, 0xC4, 0x6D, 0xF4, 0x2F, 0xCE, 0x7F, 0x87, 0x91, 0x9A, 0xC1, 0xFD, 0xF7, 0x5A, 0xAD, 0xE1, + 0x0B, 0xD8, 0x8E, 0x17, 0x3B, 0xB8, 0x17, 0xC9, 0x65, 0x99, 0x6F, 0x2B, 0xA6, 0x10, 0xE0, 0x1B, + 0xFE, 0x08, 0xE0, 0xAA, 0xC1, 0x4A, 0x3C, 0x63, 0x2D, 0x8E, 0x75, 0x8F, 0xA6, 0xE2, 0x3E, 0x7E, + 0xA4, 0x00, 0x13, 0x78, 0x50, 0x2E, 0x21, 0xDA, 0xF2, 0x64, 0xF6, 0x53, 0xD3, 0xC6, 0x94, 0x92, + 0x64, 0xB9, 0x0B, 0x5C, 0x17, 0xEF, 0x45, 0x21, 0xA7, 0xC1, 0x68, 0x49, 0x9A, 0xB6, 0x27, 0xA5, + 0x05, 0xDB, 0xE2, 0x1B, 0x72, 0x3E, 0xD7, 0x8B, 0x9D, 0x4B, 0x3C, 0xEB, 0xA4, 0x7F, 0xF5, 0xB6, + 0x17, 0x19, 0x07, 0x42, 0x8F, 0xFF, 0x6D, 0x2F, 0xD4, 0xFA, 0x56, 0xE6, 0xC2, 0x9F, 0xCC, 0x62, + 0x3D, 0x8E, 0x3B, 0x44, 0xC8, 0x30, 0x14, 0xF9, 0x96, 0x0F, 0xB8, 0x8B, 0xD5, 0x50, 0x58, 0xCF, + 0xF6, 0x0C, 0x99, 0x51, 0xCB, 0x1E, 0x8B, 0x1C, 0x6D, 0x2D, 0x45, 0xD9, 0xDF, 0x85, 0x1F, 0x07, + 0x93, 0x73, 0x31, 0x0C, 0xF2, 0x17, 0x57, 0xD2, 0x87, 0x2F, 0xC6, 0x13, 0x1F, 0xED, 0xD1, 0x5A, + 0x38, 0xDF, 0x27, 0xD3, 0xA1, 0xE4, 0x3D, 0x80, 0x54, 0x73, 0xA9, 0x50, 0xD0, 0x4D, 0x29, 0xAE, + 0x22, 0xC7, 0x62, 0xE1, 0x60, 0x6C, 0xCB, 0x7B, 0xBB, 0x06, 0x8E, 0x77, 0xA4, 0xD5, 0xD0, 0xA8, + 0x31, 0xED, 0x6A, 0xCF, 0xC1, 0xDF, 0xA4, 0xCD, 0x0D, 0xED, 0xBA, 0x86, 0x5C, 0x97, 0xAC, 0xE6, + 0x3B, 0x93, 0x93, 0xE4, 0xDA, 0xB0, 0x30, 0xF0, 0x9C, 0x84, 0xB7, 0x03, 0x45, 0x49, 0x14, 0x98, + 0x69, 0xBE, 0xBA, 0xDD, 0xA7, 0x34, 0xA9, 0x14, 0xE4, 0x2C, 0xED, 0x70, 0x9F, 0x6D, 0xBB, 0x7C, + 0x57, 0x7B, 0xAD, 0xB6, 0xCE, 0x6B, 0xBA, 0x92, 0x54, 0x83, 0xC5, 0x53, 0x1E, 0x7E, 0xD0, 0x4C, + 0xC4, 0x9C, 0x2F, 0xE7, 0x04, 0x94, 0x93, 0xBF, 0xBD, 0xBC, 0x39, 0xFF, 0x25, 0x3A, 0x03, 0xE9, + 0xD3, 0xAA, 0x4F, 0xC1, 0xC4, 0x4C, 0xD6, 0xE3, 0x1C, 0x14, 0x70, 0x48, 0xD4, 0xEF, 0x96, 0x3C, + 0x43, 0x38, 0x30, 0x1E, 0x0D, 0x7F, 0x24, 0xB3, 0x23, 0x83, 0x20, 0x67, 0x45, 0x6C, 0x84, 0x24, + 0x38, 0x52, 0x32, 0x74, 0x19, 0x6B, 0xFF, 0x52, 0x8E, 0xC1, 0xF8, 0x26, 0x2D, 0x7C, 0x10, 0x52, + 0x4C, 0x3C, 0x50, 0xF3, 0x77, 0xD4, 0xA7, 0xCE, 0x24, 0xA4, 0x52, 0x1D, 0xB4, 0x65, 0x02, 0x3E, + 0xA7, 0x8F, 0x48, 0x9A, 0x63, 0xBC, 0xE7, 0xB9, 0xCA, 0x95, 0x51, 0x2F, 0xA5, 0xD8, 0x6F, 0x62, + 0xBF, 0x8F, 0x2A, 0x70, 0xD9, 0x84, 0x6F, 0x38, 0x65, 0xD6, 0x08, 0xA6, 0xEC, 0xC5, 0x54, 0x2D, + 0x23, 0x95, 0xEE, 0x37, 0x6E, 0xB1, 0xCF, 0x76, 0xE0, 0x96, 0x2F, 0x26, 0x95, 0xEE, 0x44, 0x3E, + 0xA0, 0x5E, 0xBC, 0x85, 0xBA, 0xC1, 0x64, 0x34, 0x7B, 0x35, 0xF4, 0x03, 0xE8, 0xD2, 0xDA, 0x67, + 0x32, 0x5C, 0xAB, 0x42, 0x95, 0xAC, 0x52, 0xB5, 0xAE, 0x96, 0xA7, 0x12, 0x66, 0xB3, 0x9C, 0x64, + 0xBA, 0xB4, 0x30, 0x2C, 0x70, 0x57, 0xD8, 0x88, 0xC2, 0xFB, 0xB4, 0xAA, 0x0C, 0x26, 0x34, 0xC9, + 0xEA, 0x6C, 0x3B, 0xDC, 0x4A, 0x38, 0x15, 0x43, 0xC8, 0x6E, 0x92, 0x36, 0x59, 0x81, 0x8F, 0x7C, + 0xB9, 0xF7, 0x90, 0xFF, 0xE2, 0x4E, 0x87, 0xD2, 0x43, 0xBD, 0xEC, 0x04, 0x06, 0xC8, 0x91, 0xB7, + 0xEB, 0xE4, 0x26, 0xF6, 0x64, 0x29, 0xD1, 0xB1, 0xB2, 0x18, 0x53, 0x49, 0xCC, 0x3D, 0xE2, 0x29, + 0x69, 0x2B, 0xAA, 0x89, 0xA5, 0x78, 0x8B, 0xB2, 0x93, 0xF6, 0xC2, 0x9C, 0x64, 0x7F, 0x71, 0x1E, + 0xA2, 0x2C, 0xD6, 0xC5, 0x1E, 0xB2, 0xA1, 0xC5, 0xBA, 0xD8, 0x6F, 0x74, 0x3B, 0x0B, 0xCE, 0x02, + 0x33, 0x4B, 0x29, 0x2F, 0x82, 0x0B, 0xF2, 0x07, 0x0E, 0xCC, 0x26, 0x45, 0x45, 0x4B, 0xA4, 0x19, + 0x7E, 0x39, 0xC6, 0xB2, 0x9A, 0x02, 0x34, 0x45, 0x54, 0x2E, 0xE0, 0x82, 0x6F, 0xDB, 0xFE, 0x88, + 0xB2, 0xAA, 0xA7, 0x17, 0xD4, 0x2C, 0xE0, 0x8E, 0x71, 0x8E, 0x38, 0xDB, 0x5D, 0xA3, 0x7B, 0x12, + 0x3E, 0x63, 0x3D, 0xD7, 0xF6, 0x6D, 0xE0, 0x7F, 0x95, 0x22, 0xE3, 0x52, 0xBA, 0xCC, 0x98, 0x79, + 0x0D, 0xB1, 0x72, 0xFD, 0x5E, 0x6F, 0xAE, 0x48, 0xB9, 0xAB, 0xF3, 0x79, 0x02, 0xE5, 0x60, 0x34, + 0xF6, 0xCF, 0x6C, 0x9E, 0xC6, 0xB0, 0x17, 0x5F, 0x06, 0x83, 0xF5, 0x88, 0x94, 0x3B, 0x8D, 0x6A, + 0x1E, 0x61, 0x81, 0x07, 0xB4, 0xBB, 0x9C, 0x62, 0xAF, 0x86, 0xC6, 0x26, 0x3B, 0x2F, 0x92, 0x4A, + 0x33, 0xAC, 0x0D, 0x8B, 0x58, 0x40, 0xC2, 0xC8, 0x16, 0x2C, 0xFF, 0xED, 0x76, 0xEC, 0xA5, 0x2B, + 0xFB, 0x71, 0xE7, 0xDC, 0xE2, 0xEE, 0xF0, 0x89, 0x6D, 0x01, 0x50, 0xDE, 0x52, 0x55, 0x08, 0x3F, + 0x70, 0xAD, 0xD8, 0x3B, 0xF6, 0x60, 0x10, 0xA3, 0xEB, 0x08, 0x80, 0xEB, 0x1F, 0x6E, 0x77, 0xCF, + 0xB9, 0xC3, 0xDD, 0xD3, 0xF0, 0x46, 0xFE, 0xB2, 0x2A, 0x0E, 0x9E, 0xD0, 0x30, 0xB1, 0xBB, 0x6A, + 0x3A, 0x39, 0x1A, 0xC5, 0xE3, 0x65, 0xD7, 0x1F, 0x0C, 0x07, 0x5F, 0x76, 0x4A, 0x55, 0xBA, 0x0F, + 0x1A, 0x95, 0x19, 0xB9, 0x0F, 0xFE, 0xF8, 0x03, 0xAF, 0xC7, 0xD8, 0x94, 0x15, 0x98, 0xA9, 0x01, + 0x95, 0x0C, 0xE1, 0x5C, 0xBF, 0x57, 0x31, 0x3B, 0xAA, 0x30, 0x3B, 0x07, 0x1E, 0x66, 0xB6, 0xA9, + 0x10, 0x49, 0xB7, 0x1E, 0x58, 0x33, 0xE6, 0xAA, 0x17, 0xB8, 0x04, 0x9D, 0xBE, 0xA6, 0x9A, 0x8B, + 0x31, 0xE7, 0xE9, 0xCE, 0x1A, 0x5D, 0x2A, 0x6B, 0x56, 0x89, 0x1B, 0xCF, 0xF4, 0x91, 0x3A, 0xCD, + 0x1A, 0x38, 0xF1, 0x35, 0x87, 0xED, 0xF5, 0xE6, 0x61, 0xC6, 0x17, 0x9C, 0xFB, 0xBB, 0x97, 0x68, + 0x2B, 0xF2, 0xD6, 0x83, 0x41, 0x9E, 0x09, 0x4F, 0xB0, 0xAC, 0x38, 0x87, 0x65, 0x6D, 0x02, 0x2A, + 0x27, 0x67, 0x58, 0x6C, 0x4C, 0xAB, 0x44, 0x3E, 0x07, 0x08, 0xEB, 0xCB, 0x70, 0x1F, 0xDD, 0x06, + 0x25, 0x0E, 0xEF, 0xF2, 0xAA, 0x83, 0x01, 0x42, 0x9E, 0x0A, 0xD0, 0x8B, 0xEC, 0x65, 0xC0, 0x12, + 0x31, 0x80, 0x20, 0xC2, 0x7D, 0x79, 0x79, 0x8C, 0x7A, 0x15, 0x75, 0xE8, 0xA4, 0xDB, 0x39, 0x2E, + 0xFD, 0x08, 0x50, 0x6E, 0x42, 0x32, 0xDF, 0xDA, 0xD9, 0x21, 0x5E, 0x96, 0xA4, 0x78, 0xEC, 0x94, + 0xDB, 0xBB, 0x67, 0x02, 0x76, 0xF0, 0x35, 0xFA, 0x55, 0x97, 0xCD, 0x1B, 0x63, 0x33, 0x59, 0x32, + 0xBA, 0x95, 0xBA, 0x7A, 0xEB, 0x8A, 0x55, 0x4F, 0x02, 0xCC, 0x46, 0xDC, 0x74, 0x30, 0xC2, 0x8C, + 0x12, 0x43, 0xEB, 0xDC, 0x31, 0xED, 0x27, 0x71, 0xA9, 0x44, 0x76, 0x61, 0x60, 0x46, 0x6A, 0x20, + 0x71, 0xDB, 0xE7, 0x54, 0x50, 0xDB, 0x4F, 0x96, 0x60, 0x0A, 0x73, 0xD4, 0xAD, 0x3D, 0x47, 0x9D, + 0xBA, 0x44, 0x4B, 0x5B, 0x52, 0x4B, 0xD9, 0xD6, 0xAA, 0xE9, 0xA0, 0x5C, 0x7E, 0x0F, 0x12, 0x4D, + 0x78, 0xFB, 0xB0, 0x86, 0xCB, 0xAF, 0xB9, 0x9A, 0x85, 0xDC, 0x6F, 0xEF, 0x68, 0xF5, 0xA6, 0xF3, + 0xC9, 0x55, 0x58, 0x39, 0x89, 0xDC, 0x2B, 0xB0, 0x94, 0xE3, 0xB7, 0xD4, 0x8D, 0xD7, 0xCD, 0x4D, + 0xF8, 0x34, 0xA7, 0x0F, 0x2D, 0x89, 0x31, 0x85, 0xA9, 0x3D, 0x12, 0xAF, 0xCF, 0xE3, 0x31, 0x9B, + 0x57, 0xA7, 0xF4, 0x46, 0x81, 0x8F, 0xE7, 0xFD, 0x8D, 0x7D, 0x3A, 0xC2, 0x74, 0x46, 0xB2, 0x80, + 0x8C, 0x9C, 0xC9, 0xA9, 0xE4, 0x92, 0x82, 0xE8, 0x56, 0x7F, 0xF5, 0x24, 0x7F, 0x76, 0xA0, 0x94, + 0xC9, 0xEF, 0x31, 0x0B, 0xC1, 0x8D, 0x5D, 0x90, 0xFF, 0x76, 0x44, 0xA4, 0x3A, 0x5C, 0xDA, 0x8D, + 0x95, 0x9F, 0x8A, 0x22, 0xCF, 0xCA, 0xC1, 0x7A, 0x95, 0xD7, 0x5C, 0x52, 0xCF, 0x1E, 0xD2, 0xE2, + 0x40, 0x77, 0x93, 0x75, 0x3F, 0x30, 0xD5, 0x1B, 0xC9, 0x2F, 0x1A, 0x4D, 0xDA, 0x0D, 0x8B, 0x0E, + 0xC0, 0x68, 0x85, 0x27, 0x12, 0x4A, 0x4D, 0x18, 0x3A, 0x6D, 0xA1, 0xD1, 0x07, 0x04, 0x27, 0xF8, + 0x9A, 0x8C, 0xDC, 0x28, 0xE1, 0x53, 0x16, 0x14, 0x51, 0x02, 0x93, 0x04, 0x7F, 0x1C, 0x35, 0xC6, + 0x60, 0x92, 0xCA, 0x63, 0x89, 0x23, 0x6B, 0x29, 0x3C, 0x64, 0x19, 0x59, 0x55, 0xF3, 0xD1, 0xE0, + 0x59, 0xCE, 0xB7, 0x02, 0x3A, 0xCB, 0x85, 0xF9, 0x42, 0x87, 0x21, 0x3A, 0x3D, 0x72, 0x7B, 0x0F, + 0x67, 0xF6, 0x0C, 0x67, 0x61, 0x38, 0x74, 0xEE, 0x11, 0x18, 0x11, 0x4B, 0xD6, 0x29, 0x98, 0x4D, + 0x44, 0xE1, 0x8D, 0xB2, 0x78, 0x8C, 0xFF, 0x56, 0x58, 0xFD, 0xF5, 0x2D, 0x5D, 0xAD, 0x51, 0xB6, + 0x95, 0x43, 0xA5, 0xF9, 0xC3, 0x1D, 0x9E, 0x45, 0x6C, 0xBF, 0xE8, 0x34, 0xCD, 0x6F, 0xBF, 0x84, + 0xE3, 0x75, 0xB5, 0x8A, 0xD2, 0x85, 0xAA, 0xF9, 0xB6, 0x3B, 0x29, 0xD2, 0x10, 0xD5, 0xCD, 0x16, + 0xCF, 0x63, 0xB5, 0x14, 0x96, 0xAB, 0x26, 0x4D, 0xCF, 0xA3, 0x28, 0xE8, 0xA3, 0x3E, 0xB5, 0x69, + 0x7A, 0xA5, 0x82, 0x16, 0xB9, 0x8B, 0x99, 0x91, 0x91, 0xF8, 0xE8, 0x7C, 0x01, 0xD9, 0x14, 0xAF, + 0xDE, 0x08, 0x55, 0xDB, 0x8D, 0x8A, 0x1E, 0x46, 0xFA, 0xB8, 0x2C, 0x64, 0x45, 0xD6, 0x28, 0xCF, + 0xB7, 0x61, 0x7B, 0xC2, 0x16, 0x4D, 0x76, 0x0C, 0x9D, 0x88, 0x9B, 0x3A, 0x16, 0x06, 0x8A, 0xE0, + 0xFD, 0xFD, 0xB1, 0x6A, 0x50, 0x5A, 0x2F, 0xBA, 0xE9, 0x93, 0x5A, 0x81, 0x7B, 0x32, 0xC6, 0x92, + 0xAA, 0x6D, 0xAF, 0x52, 0x2B, 0x2B, 0x87, 0xD1, 0x8D, 0xAA, 0xC5, 0x46, 0x06, 0xD3, 0x38, 0xB3, + 0x68, 0x81, 0x91, 0x29, 0x24, 0x4C, 0x54, 0xD0, 0x8E, 0xAA, 0x8B, 0xCC, 0x52, 0x46, 0x6E, 0x0D, + 0x15, 0x27, 0x6D, 0xAA, 0x35, 0x24, 0x3A, 0xA8, 0x56, 0xAF, 0xE4, 0x1C, 0xAB, 0xE3, 0x5A, 0xFC, + 0xF9, 0xAA, 0x95, 0x70, 0x39, 0x81, 0x25, 0xD4, 0x2A, 0x39, 0x9F, 0xEA, 0xBA, 0x52, 0xAE, 0xD4, + 0xA9, 0xC6, 0x33, 0x43, 0x96, 0xCB, 0x82, 0x33, 0x05, 0xDE, 0xA9, 0xA4, 0xAA, 0xD1, 0xDA, 0x9F, + 0xBB, 0x90, 0xC9, 0xD4, 0x62, 0x6B, 0x2D, 0x85, 0x58, 0xD3, 0xA1, 0x24, 0x67, 0x78, 0xF6, 0xF9, + 0xB4, 0x07, 0x67, 0x51, 0x08, 0xD6, 0x00, 0xAF, 0x46, 0xE0, 0xB3, 0x25, 0x1E, 0x43, 0xF1, 0x91, + 0x27, 0x9C, 0x41, 0x1F, 0x69, 0x4E, 0x38, 0x0D, 0xE0, 0x07, 0xD9, 0x95, 0x1A, 0x57, 0x73, 0x58, + 0xC5, 0xF5, 0xAC, 0x08, 0x3A, 0x74, 0x60, 0x61, 0xD1, 0x6B, 0x9C, 0x7B, 0x33, 0xD4, 0x6F, 0x90, + 0x57, 0xE1, 0x43, 0x55, 0xE6, 0xD3, 0xBF, 0xEC, 0xB1, 0x63, 0x5D, 0xC7, 0x83, 0x61, 0x9B, 0x9D, + 0xDD, 0xF4, 0xB7, 0xD9, 0x27, 0xD5, 0xE7, 0x8F, 0xD2, 0x3C, 0xDD, 0x0F, 0xEE, 0xB1, 0xA7, 0x6B, + 0xD5, 0xFB, 0xB6, 0x41, 0xDE, 0x92, 0xFC, 0x3C, 0x2F, 0xB4, 0xEC, 0xCB, 0x5E, 0x5F, 0x1E, 0xC4, + 0x02, 0xE9, 0x43, 0xA0, 0x2D, 0x4B, 0xFB, 0x09, 0xD1, 0xE8, 0xB2, 0x97, 0xC8, 0xF3, 0xBE, 0x3F, + 0xA3, 0xB7, 0x5C, 0x4C, 0x6D, 0xCA, 0x33, 0x28, 0x25, 0x88, 0x2E, 0xA4, 0x3C, 0xC8, 0x33, 0x2E, + 0x0D, 0xA5, 0x48, 0x09, 0x99, 0x46, 0xA0, 0x97, 0x94, 0x72, 0x7D, 0xBF, 0x4A, 0xB2, 0x75, 0x9C, + 0x77, 0x4E, 0xAA, 0xF5, 0xD8, 0xE6, 0x97, 0xBA, 0x34, 0x3C, 0x79, 0x7F, 0x75, 0x09, 0xD6, 0x6B, + 0xC5, 0x72, 0xE0, 0x23, 0x05, 0x68, 0x0E, 0x6F, 0xAC, 0x33, 0x66, 0xE3, 0x02, 0x5E, 0x91, 0x39, + 0x17, 0x99, 0x8B, 0x41, 0x34, 0x85, 0xCD, 0xD0, 0x60, 0x43, 0xD1, 0x59, 0x9E, 0x88, 0x05, 0x28, + 0x2D, 0xDF, 0x5A, 0x67, 0xB4, 0x0E, 0x17, 0xF2, 0x8A, 0xDA, 0xB9, 0xA8, 0x5D, 0x0E, 0x4C, 0x53, + 0xE8, 0x2D, 0x1B, 0x6D, 0x28, 0x8A, 0x0B, 0x41, 0xAF, 0x00, 0xC3, 0x63, 0xD2, 0xE0, 0x3A, 0x63, + 0xB9, 0x27, 0xA6, 0x39, 0x86, 0x69, 0xBE, 0x62, 0x7A, 0x3E, 0xA6, 0xCB, 0x6D, 0xAF, 0x84, 0xE8, + 0xA2, 0xCD, 0x1A, 0x54, 0x6D, 0xCA, 0x16, 0xF3, 0xAB, 0x50, 0x44, 0x1A, 0x35, 0xDC, 0xF8, 0x0E, + 0x86, 0x26, 0x16, 0x90, 0x43, 0x84, 0x7E, 0x37, 0x77, 0x3D, 0x0A, 0x65, 0x3C, 0xAA, 0xC1, 0xAB, + 0x16, 0x22, 0xFC, 0x4C, 0xE7, 0x91, 0xFE, 0x85, 0x34, 0xD0, 0x6A, 0x77, 0x36, 0xB1, 0x6E, 0x7D, + 0x19, 0x54, 0xAE, 0x56, 0xC5, 0x68, 0x7A, 0xC7, 0x0A, 0xED, 0xF6, 0x53, 0x0D, 0x96, 0xEC, 0x07, + 0xAF, 0x66, 0x8D, 0xC3, 0xAD, 0x7E, 0x2E, 0x43, 0x9C, 0xE5, 0x3B, 0x4B, 0xB0, 0xC1, 0xC1, 0x8A, + 0xE6, 0x32, 0xBF, 0x4D, 0xDA, 0xCD, 0x69, 0x79, 0x9B, 0x80, 0x52, 0x1A, 0xDD, 0xA4, 0xCD, 0x0D, + 0x97, 0xF9, 0xDC, 0xE6, 0xB6, 0xC9, 0xE2, 0x6A, 0xB5, 0xB4, 0x55, 0x61, 0x74, 0x16, 0x62, 0xBF, + 0x69, 0x9E, 0x7F, 0x77, 0x00, 0x7C, 0x56, 0x11, 0xA3, 0xC3, 0x57, 0x59, 0xF8, 0xEE, 0xD1, 0x8A, + 0x42, 0x07, 0x84, 0xDB, 0xDF, 0xD2, 0x29, 0x90, 0xDC, 0x0B, 0xD3, 0x16, 0x1A, 0xE3, 0x60, 0x3C, + 0xB9, 0x43, 0x1B, 0xA6, 0xF9, 0xF7, 0x84, 0x95, 0x1C, 0xC3, 0x7D, 0xC3, 0xAC, 0x99, 0x4D, 0x76, + 0xDE, 0x1C, 0x36, 0xA5, 0x2F, 0x55, 0xF0, 0x4D, 0xB2, 0xEB, 0xE1, 0xED, 0xFD, 0x03, 0xF4, 0xC2, + 0x78, 0x13, 0x4F, 0x0D, 0x76, 0x85, 0x99, 0xCF, 0xFE, 0xF7, 0x01, 0xFB, 0xC8, 0x0E, 0xF6, 0xBC, + 0x57, 0xD6, 0x2A, 0x49, 0x25, 0x81, 0x23, 0x85, 0xAC, 0x75, 0xAA, 0x41, 0xFD, 0xAC, 0xB5, 0x76, + 0x12, 0x70, 0xB9, 0x66, 0x78, 0xF1, 0x9B, 0xB2, 0x19, 0xF8, 0x1F, 0xBE, 0xF7, 0x8C, 0xB8, 0xEF, + 0x84, 0x73, 0x08, 0x4B, 0x27, 0xCA, 0x44, 0xC4, 0x9A, 0x69, 0x6B, 0xDF, 0xF2, 0x90, 0x7D, 0xA7, + 0xAD, 0x4C, 0xD0, 0x7D, 0xD2, 0x0B, 0xE1, 0x3B, 0x7E, 0xF7, 0x91, 0xFD, 0x47, 0x2B, 0x78, 0x45, + 0xF9, 0x08, 0x83, 0x23, 0x9C, 0x28, 0x85, 0xEF, 0xE1, 0xDB, 0xEB, 0x8F, 0xEC, 0xB7, 0xB6, 0xED, + 0x9F, 0x71, 0xB3, 0xD0, 0x8C, 0x81, 0xEF, 0x31, 0x7A, 0xF1, 0x19, 0xB1, 0xDD, 0xB7, 0xC9, 0xD9, + 0x6D, 0x07, 0x96, 0xBE, 0xE3, 0xBB, 0x86, 0x03, 0x68, 0x8D, 0x11, 0xF3, 0xF2, 0xF2, 0x86, 0x1B, + 0xE5, 0x6B, 0x21, 0xEC, 0xC7, 0x10, 0xB0, 0x20, 0x1E, 0xE0, 0xAE, 0xBC, 0x62, 0xB3, 0xC4, 0xCF, + 0xC9, 0xA6, 0x97, 0xC1, 0xE6, 0xE8, 0xED, 0x0D, 0xC1, 0x66, 0x10, 0x01, 0x45, 0x15, 0xA8, 0x52, + 0x28, 0x1D, 0xBD, 0xBD, 0x06, 0x12, 0x0C, 0x47, 0x60, 0x02, 0x1E, 0x9B, 0x20, 0x9B, 0x3E, 0xF0, + 0xB2, 0x78, 0xDD, 0x52, 0x94, 0x57, 0xD4, 0x4E, 0x20, 0xEB, 0x04, 0x03, 0x4A, 0xE3, 0x77, 0xD4, + 0x64, 0x03, 0x90, 0x3C, 0xC4, 0x87, 0x4B, 0xBD, 0x08, 0xC3, 0x23, 0xCC, 0xB9, 0x3C, 0x5B, 0x29, + 0x7A, 0x6B, 0x58, 0xF5, 0x80, 0x82, 0x93, 0x8C, 0x81, 0x21, 0x91, 0x7C, 0x0A, 0x8D, 0x63, 0x08, + 0xFC, 0xA9, 0xD7, 0x9F, 0x44, 0x22, 0xB6, 0x30, 0xF9, 0xC1, 0x48, 0xC5, 0x6C, 0xA6, 0xF9, 0xD7, + 0x91, 0x5E, 0x0E, 0x5E, 0x17, 0x58, 0xE5, 0xA6, 0xB6, 0xBC, 0x14, 0x4A, 0x4F, 0xDE, 0x5F, 0x2B, + 0x53, 0x06, 0x25, 0xB9, 0xBD, 0x56, 0x2D, 0x15, 0x03, 0x51, 0x6B, 0x31, 0x66, 0xD8, 0x96, 0x16, + 0xD5, 0x76, 0xC2, 0xDE, 0xAF, 0x0C, 0x8F, 0xEA, 0xF5, 0x08, 0x97, 0xBE, 0xC9, 0xE5, 0x60, 0x8D, + 0xF9, 0x8A, 0x32, 0x67, 0xD8, 0x33, 0xA6, 0xCD, 0x1E, 0x19, 0x66, 0x8E, 0x8B, 0xF8, 0xF8, 0xA9, + 0x86, 0x8E, 0x99, 0xFE, 0x33, 0x0C, 0x1F, 0x89, 0x9E, 0xCA, 0x99, 0x3A, 0x12, 0xA0, 0x96, 0x66, + 0x8E, 0x18, 0x40, 0x9E, 0xDD, 0xDC, 0x11, 0x5F, 0xD2, 0xC2, 0x06, 0x8F, 0x64, 0x8D, 0xB2, 0x74, + 0xA4, 0xEE, 0x9F, 0xB1, 0xBE, 0xF1, 0x07, 0x26, 0xEE, 0x95, 0xA1, 0xBA, 0x3A, 0x7E, 0xCC, 0x4E, + 0xC4, 0xAB, 0xB0, 0xEB, 0x13, 0xA4, 0x10, 0xB6, 0xCB, 0x2E, 0x5C, 0x1E, 0x6F, 0x87, 0x1F, 0xFB, + 0x0E, 0xF0, 0xC6, 0x6C, 0x86, 0x58, 0xD4, 0x69, 0x79, 0x73, 0x36, 0x55, 0x69, 0x9D, 0xDE, 0xBD, + 0x3B, 0x7C, 0x98, 0x75, 0x5A, 0xF8, 0xAE, 0x84, 0xC7, 0x1B, 0x93, 0x0F, 0xFC, 0x37, 0x39, 0xFC, + 0xC2, 0x1F, 0x75, 0x31, 0x19, 0xF1, 0x87, 0x5D, 0xF8, 0x23, 0xF7, 0x2D, 0x84, 0x54, 0xD1, 0x5B, + 0x7A, 0x37, 0xC1, 0xD4, 0x26, 0x81, 0x53, 0xE1, 0xDC, 0xFB, 0x74, 0x8D, 0xF6, 0xD8, 0x4C, 0xBB, + 0xD7, 0x2E, 0x83, 0xAE, 0x0A, 0xDD, 0x32, 0x51, 0xA4, 0x55, 0x1C, 0x18, 0x44, 0x8E, 0x98, 0xA2, + 0x17, 0xA6, 0x98, 0x15, 0x53, 0xB5, 0xEB, 0xBB, 0x8B, 0x83, 0x4B, 0xA7, 0xEC, 0xCC, 0xE7, 0xDF, + 0x29, 0x60, 0xF6, 0xF7, 0x30, 0x54, 0xE8, 0x77, 0xA5, 0xE9, 0x7F, 0xF7, 0xB3, 0xC7, 0x0E, 0xDB, + 0xEE, 0xD3, 0xDE, 0x17, 0xBD, 0x95, 0x01, 0x44, 0x71, 0xAF, 0x1A, 0x57, 0x7D, 0x79, 0x26, 0x40, + 0x9A, 0x3D, 0x95, 0x62, 0x30, 0x66, 0xC0, 0x9F, 0xC5, 0x19, 0x44, 0x4E, 0x90, 0xAD, 0x84, 0xE8, + 0x0A, 0x61, 0xDD, 0x6E, 0xB7, 0x94, 0x4E, 0xEB, 0x77, 0xA5, 0xAD, 0xB4, 0x94, 0x03, 0x91, 0x1B, + 0xBB, 0x08, 0x90, 0xD0, 0x84, 0xFD, 0x79, 0x59, 0x00, 0x9F, 0x99, 0xCF, 0x8B, 0x86, 0x79, 0x5B, + 0x79, 0x5F, 0x0E, 0xE6, 0x7B, 0xCA, 0xE1, 0x2A, 0x60, 0x2E, 0xE7, 0xB3, 0x96, 0x30, 0x87, 0xA7, + 0xC8, 0x9C, 0xBB, 0x19, 0x9C, 0xBC, 0x70, 0x93, 0xC4, 0x19, 0x56, 0xB0, 0x4D, 0xF9, 0xAE, 0x9C, + 0xC6, 0x44, 0x2A, 0x8A, 0x2D, 0x14, 0x54, 0x78, 0xEE, 0x13, 0x9B, 0x14, 0x7F, 0x15, 0xA7, 0x30, + 0x2F, 0xB1, 0x8F, 0x75, 0xBC, 0x31, 0xCF, 0x5A, 0x40, 0x2C, 0xC1, 0x12, 0x80, 0xB4, 0x1A, 0xF9, + 0xF7, 0x22, 0xEB, 0x29, 0xD8, 0xCA, 0x74, 0x27, 0x73, 0x7E, 0xC8, 0x72, 0xB9, 0xA2, 0x95, 0x99, + 0x05, 0x2B, 0xF1, 0xEF, 0xD6, 0xE4, 0xEC, 0x6C, 0xC5, 0x2B, 0x54, 0x8A, 0x62, 0x8E, 0x28, 0x40, + 0xE5, 0x54, 0xA6, 0x14, 0x35, 0x12, 0x7F, 0x2A, 0xAD, 0xC4, 0xA4, 0x17, 0x35, 0x75, 0x52, 0xCA, + 0x98, 0x2A, 0xB1, 0x2A, 0xA6, 0x85, 0x55, 0x4A, 0xB3, 0x0B, 0x86, 0x4A, 0x71, 0x4A, 0x2C, 0x06, + 0xAB, 0x18, 0x06, 0xE1, 0x7D, 0x86, 0x45, 0x6E, 0x2E, 0x58, 0xFA, 0x94, 0x5E, 0x31, 0x79, 0x73, + 0xE4, 0xA6, 0xCB, 0xA7, 0xB3, 0x8A, 0x77, 0x5A, 0xDD, 0xDB, 0x29, 0xDD, 0x0E, 0x6F, 0xDE, 0x79, + 0x20, 0x20, 0xC3, 0xDF, 0x2D, 0xD2, 0xBB, 0x5B, 0xED, 0xF0, 0x91, 0x92, 0x75, 0x61, 0x32, 0xA7, + 0x92, 0x81, 0xFA, 0xC0, 0x4F, 0x7C, 0x6B, 0x46, 0x4B, 0x11, 0x39, 0xCA, 0x92, 0x64, 0x80, 0xEF, + 0x0A, 0x47, 0x21, 0x55, 0x25, 0x80, 0x4F, 0xA9, 0xFB, 0x3F, 0x75, 0xB7, 0x60, 0x46, 0x51, 0xC6, + 0x6E, 0x50, 0x29, 0x6E, 0x45, 0x4A, 0x71, 0x36, 0x01, 0x85, 0x92, 0xAF, 0x98, 0x65, 0x55, 0x8D, + 0x32, 0xD9, 0x3A, 0xBC, 0xBA, 0x52, 0xF6, 0x42, 0x4B, 0xDA, 0x65, 0x96, 0x12, 0xDB, 0x23, 0xB6, + 0xA4, 0xD2, 0x26, 0xF0, 0xEF, 0x86, 0x9F, 0xB6, 0x09, 0x76, 0xE0, 0xE3, 0x14, 0x53, 0x37, 0x03, + 0xDB, 0x4C, 0x36, 0xE3, 0x1C, 0x3E, 0x61, 0x80, 0x7C, 0xEA, 0x86, 0xD0, 0x95, 0xA0, 0xD9, 0x7D, + 0xC0, 0x64, 0x19, 0x0F, 0xD2, 0x56, 0x11, 0x8D, 0x50, 0x71, 0x63, 0xE4, 0xCC, 0xD3, 0x36, 0xA6, + 0xE0, 0xA6, 0x90, 0xD3, 0xFD, 0x67, 0xEB, 0xDE, 0x73, 0xFE, 0x54, 0x04, 0xF6, 0xD8, 0xC7, 0xF8, + 0x9F, 0x9E, 0xE6, 0x1A, 0x8E, 0xCF, 0x3C, 0x57, 0x83, 0xFD, 0x75, 0xB5, 0x5D, 0xBC, 0xA9, 0xD6, + 0xFC, 0x2B, 0x8D, 0x26, 0xBE, 0xCA, 0x6A, 0x32, 0xE9, 0x19, 0x56, 0xEC, 0xE1, 0x4D, 0x29, 0x1B, + 0xAB, 0x54, 0x79, 0xEC, 0x23, 0xD3, 0x6D, 0x2D, 0x40, 0xA3, 0x53, 0xF3, 0x6F, 0x01, 0x77, 0x9F, + 0x84, 0xD2, 0x60, 0xBB, 0xA0, 0x36, 0x6C, 0xBD, 0x69, 0xFA, 0xFE, 0x9B, 0xB7, 0x51, 0xCB, 0xB0, + 0x4D, 0x13, 0x8E, 0xF7, 0x73, 0x55, 0x1B, 0x6D, 0xF9, 0xEC, 0x63, 0x97, 0xFD, 0x5B, 0x62, 0x19, + 0x98, 0xD3, 0x14, 0xF3, 0x1B, 0x78, 0xBE, 0xAB, 0x3A, 0xCD, 0x3B, 0xD1, 0x62, 0xCB, 0x9F, 0x74, + 0xF2, 0xEF, 0x6F, 0xE5, 0x0C, 0xC3, 0x79, 0x01, 0xB0, 0x41, 0xD3, 0x04, 0xBE, 0xF1, 0x61, 0x77, + 0xE4, 0x8F, 0xCD, 0xEE, 0xFF, 0x07, 0x58, 0x97, 0xEE, 0x33, 0x3A, 0x65, 0x00 }; ///index_html //Content of bootstrap.bundle.min.jss with gzip compression diff --git a/Firmware/RTK_Everywhere/makefile b/Firmware/RTK_Everywhere/makefile index f62865c11..6a14bce00 100644 --- a/Firmware/RTK_Everywhere/makefile +++ b/Firmware/RTK_Everywhere/makefile @@ -74,6 +74,7 @@ PARTITION_SRC_PATH=../$(PARTITION_CSV_FILE).csv PATCH_SRC_PATH=Patch/ # Linux patch destination paths +BT_LIB_DEST_PATH=$(ESP_IDF_PATH)/$(ESP_IDF_VERSION)/esp32/lib/ MBED_LIB_DEST_PATH=$(ESP_IDF_PATH)/$(ESP_IDF_VERSION)/esp32/lib/ NET_EVENT_PATCH_PATH=$(HOME_BOARD_PATH)/hardware/esp32/$(ESP_CORE_VERSION)/libraries/Network/src/ PARTITION_DST_PATH=$(HOME_BOARD_PATH)/hardware/esp32/$(ESP_CORE_VERSION)/tools/partitions/$(PARTITION_CSV_FILE).csv @@ -165,9 +166,13 @@ $(MBED_LIB_DEST_PATH)libmbedcrypto.a: $(PATCH_SRC_PATH)libmbedcrypto.a $(MBED_LIB_DEST_PATH)libmbedx509.a: $(PATCH_SRC_PATH)libmbedx509.a $(COPY) $< $@ +$(BT_LIB_DEST_PATH)libbt.a: $(PATCH_SRC_PATH)libbt.a + $(COPY) $< $@ + .PHONY: patch patch: + touch $(PATCH_SRC_PATH)libbt.a touch $(PATCH_SRC_PATH)libmbedtls.a touch $(PATCH_SRC_PATH)libmbedtls_2.a touch $(PATCH_SRC_PATH)libmbedcrypto.a @@ -189,7 +194,7 @@ form.h: AP-Config/* AP-Config/src/* AP-Config/src/fonts/* python ../Tools/index_html_zipper.py AP-Config/index.html form.h python ../Tools/main_js_zipper.py AP-Config/src/main.js form.h -$(RTK_BIN_PATH): RTK_Everywhere.ino *.ino *.h makefile $(PARTITION_DST_PATH) $(MBED_LIB_DEST_PATH)libmbedtls.a $(MBED_LIB_DEST_PATH)libmbedtls_2.a $(MBED_LIB_DEST_PATH)libmbedcrypto.a $(MBED_LIB_DEST_PATH)libmbedx509.a +$(RTK_BIN_PATH): RTK_Everywhere.ino *.ino *.h makefile $(PARTITION_DST_PATH) $(MBED_LIB_DEST_PATH)libmbedtls.a $(MBED_LIB_DEST_PATH)libmbedtls_2.a $(MBED_LIB_DEST_PATH)libmbedcrypto.a $(MBED_LIB_DEST_PATH)libmbedx509.a $(BT_LIB_DEST_PATH)libbt.a $(CLEAR) arduino-cli compile --fqbn "esp32:esp32:esp32":DebugLevel=$(DEBUG_LEVEL),PSRAM=enabled RTK_Everywhere.ino \ --warnings default \ diff --git a/Firmware/RTK_Everywhere/menuBase.ino b/Firmware/RTK_Everywhere/menuBase.ino index d63037a56..4fb9e4937 100644 --- a/Firmware/RTK_Everywhere/menuBase.ino +++ b/Firmware/RTK_Everywhere/menuBase.ino @@ -27,8 +27,8 @@ void menuBase() // Print the combined HAE APC if we are in the given mode if (settings.fixedBase == true && settings.fixedBaseCoordinateType == COORD_TYPE_GEODETIC) { - systemPrintf("Total Height Above Ellipsoid - Antenna Phase Center (HAE APC): %0.3fmm\r\n", - (((settings.fixedAltitude * 1000) + + systemPrintf("Total Height Above Ellipsoid of Antenna Phase Center (HAE APC): %0.4fmm\r\n", + ((settings.fixedAltitude + (settings.antennaHeight_mm + settings.antennaPhaseCenter_mm) / 1000))); } diff --git a/Firmware/RTK_Everywhere/menuCommands.ino b/Firmware/RTK_Everywhere/menuCommands.ino index 621160167..91d81ae88 100644 --- a/Firmware/RTK_Everywhere/menuCommands.ino +++ b/Firmware/RTK_Everywhere/menuCommands.ino @@ -1,3 +1,7 @@ +char otaOutcome[21] = {0}; // Modified by otaUpdate(), used to respond to rtkRemoteFirmwareVersion commands +int systemWriteCounts = + 0; // Modified by systemWrite(), used to calculate the number of items in the LIST command for CLI + void menuCommands() { char cmdBuffer[200]; @@ -42,6 +46,8 @@ t_cliResult processCommand(char *cmdBuffer) // These commands are not part of the CLI and allow quick testing without validity check if ((strcmp(cmdBuffer, "x") == 0) || (strcmp(cmdBuffer, "exit") == 0)) { + if (settings.debugCLI == true) + systemPrintln("Exiting CLI..."); return (CLI_EXIT); // Exit command mode } else if (strcmp(cmdBuffer, "list") == 0) @@ -178,7 +184,7 @@ t_cliResult processCommand(char *cmdBuffer) } else { - commandSendErrorResponse(tokens[0], (char *)"Unknown setting"); + commandSendErrorResponse(tokens[0], field, (char *)"Unknown setting"); return (CLI_UNKNOWN_SETTING); } } @@ -187,8 +193,13 @@ t_cliResult processCommand(char *cmdBuffer) { if (tokenCount != 3) { - commandSendErrorResponse(tokens[0], - (char *)"Incorrect number of arguments"); // Incorrect number of arguments + if (tokenCount == 2) + commandSendErrorResponse(tokens[0], tokens[1], + (char *)"Incorrect number of arguments"); // Incorrect number of arguments + else + commandSendErrorResponse(tokens[0], + (char *)"Incorrect number of arguments"); // Incorrect number of arguments + return (CLI_BAD_FORMAT); } else @@ -209,9 +220,14 @@ t_cliResult processCommand(char *cmdBuffer) value); // Wrap the string setting in quotes in the response, add OK return (CLI_OK); } + else if (response == SETTING_KNOWN_READ_ONLY) + { + commandSendErrorResponse(tokens[0], field, (char *)"Setting is read only"); + return (CLI_SETTING_READ_ONLY); + } else { - commandSendErrorResponse(tokens[0], (char *)"Unknown setting"); + commandSendErrorResponse(tokens[0], field, (char *)"Unknown setting"); return (CLI_UNKNOWN_SETTING); } } @@ -226,39 +242,86 @@ t_cliResult processCommand(char *cmdBuffer) } else { - if (strcmp(tokens[1], "EXIT") == 0) + if (strcmp(tokens[1], "APPLY") == 0) + { + commandSendExecuteOkResponse(tokens[0], tokens[1]); + // TODO - Do an apply... + return (CLI_OK); + } + else if (strcmp(tokens[1], "EXIT") == 0) { commandSendExecuteOkResponse(tokens[0], tokens[1]); return (CLI_EXIT); } - else if (strcmp(tokens[1], "APPLY") == 0) + else if (strcmp(tokens[1], "FACTORYRESET") == 0) { + // Apply factory defaults, then reset commandSendExecuteOkResponse(tokens[0], tokens[1]); - // TODO - Do an apply... - return (CLI_OK); + factoryReset(false); // We do not have the SD semaphore + return (CLI_OK); // We should never get this far. } - else if (strcmp(tokens[1], "SAVE") == 0) + else if (strcmp(tokens[1], "LIST") == 0) { - recordSystemSettings(); + // Respond with a list of variables, types, and current value + + // First calculate the lines in the LIST response + PrintEndpoint originalPrintEndpoint = printEndpoint; + printEndpoint = PRINT_ENDPOINT_COUNT; + systemWriteCounts = 0; + printAvailableSettings(); + printEndpoint = originalPrintEndpoint; + + // Print the list entry with the number of items in the list, including the list entry + char settingValue[6]; // 12345 + snprintf(settingValue, sizeof(settingValue), "%d", systemWriteCounts + 1); // Add list command + commandSendExecuteListResponse("list", "int", settingValue); + + // Now actually print the list + printAvailableSettings(); commandSendExecuteOkResponse(tokens[0], tokens[1]); return (CLI_OK); } + else if (strcmp(tokens[1], "PAIR") == 0) + { + commandSendExecuteOkResponse(tokens[0], tokens[1]); + espnowRequestPair = true; // Start ESP-NOW pairing process + // Force exit all config menus and/or command modes to allow OTA state machine to run + btPrintEchoExit = true; + return (CLI_EXIT); // Exit the CLI to allow OTA state machine to run + } + else if (strcmp(tokens[1], "PAIRSTOP") == 0) + { + commandSendExecuteOkResponse(tokens[0], tokens[1]); + espnowRequestPair = false; // Stop ESP-NOW pairing process + // Force exit all config menus and/or command modes to allow OTA state machine to run + btPrintEchoExit = true; + return (CLI_EXIT); // Exit the CLI to allow OTA state machine to run + } else if (strcmp(tokens[1], "REBOOT") == 0) { commandSendExecuteOkResponse(tokens[0], tokens[1]); delay(50); // Allow for final print ESP.restart(); } - else if (strcmp(tokens[1], "LIST") == 0) + else if (strcmp(tokens[1], "SAVE") == 0) { - // Respond with a list of variables, types, and current value - printAvailableSettings(); + recordSystemSettings(); commandSendExecuteOkResponse(tokens[0], tokens[1]); return (CLI_OK); } + else if (strcmp(tokens[1], "UPDATEFIRMWARE") == 0) + { + // Begin a firmware update. WiFi networks and enableRCFirmware should previously be set. + commandSendExecuteOkResponse(tokens[0], tokens[1]); + otaRequestFirmwareUpdate = true; + + // Force exit all config menus and/or command modes to allow OTA state machine to run + btPrintEchoExit = true; + return (CLI_EXIT); // Exit the CLI to allow OTA state machine to run + } else { - commandSendErrorResponse(tokens[0], tokens[1], (char *)"Unknown command"); + commandSendExecuteErrorResponse(tokens[0], tokens[1], (char *)"Unknown command"); return (CLI_UNKNOWN_COMMAND); } } @@ -292,6 +355,17 @@ void commandSendExecuteOkResponse(const char *command, const char *settingName) commandSendResponse(innerBuffer); } +// Given a command, send structured ERROR response +// Response format: $SPEXE,[setting name],ERROR,[Verbose error description]*FF +// Ex: $SPEXE,UPDATEFIRMWARE*77 = $SPEXE,UPDATEFIRMWARE,ERROR,No Internet*15 +void commandSendExecuteErrorResponse(const char *command, const char *settingName, const char *errorVerbose) +{ + // Create string between $ and * for checksum calculation + char innerBuffer[200]; + snprintf(innerBuffer, sizeof(innerBuffer), "%s,%s,ERROR,%s", command, settingName, errorVerbose); + commandSendResponse(innerBuffer); +} + // Given a command, and a value, send response sentence with OK and checksum and // Ex: SPSET,ntripClientCasterUserPW,thePassword = $SPSET,ntripClientCasterUserPW,"thePassword",OK*2F void commandSendStringOkResponse(char *command, char *settingName, char *valueBuffer) @@ -402,6 +476,7 @@ void commandSendErrorResponse(const char *command, const char *settingName, cons snprintf(innerBuffer, sizeof(innerBuffer), "%s,%s,,ERROR,%s", command, settingName, errorVerbose); commandSendResponse(innerBuffer); } + // Given a command, send structured ERROR response // Response format: $SPxET,,,ERROR,[Verbose error description]*FF // Ex: SPGET, 'Incorrect number of arguments' = "$SPGET,ERROR,Incorrect number of arguments*1E" @@ -425,7 +500,54 @@ void commandSendResponse(const char *innerBuffer) sprintf(responseBuffer, "$%s*%02X\r\n", innerBuffer, calculatedChecksum); - systemPrint(responseBuffer); + // CLI interactions may come from BLE or serial, respond to all interfaces + commandSendAllInterfaces(responseBuffer); +} + +// Given an inner buffer, send response sentence with checksum and +// Ex: SPGET,elvMask,0.25 = $SPGET,elvMask,0.25*07 +void commandSendResponseUnbuffered(const char *prefix, const char *innerBuffer) +{ + uint8_t calculatedChecksum = 0; // XOR chars between '$' and '*' + for (int x = 1; x < strlen(prefix); x++) + calculatedChecksum = calculatedChecksum ^ prefix[x]; + for (int x = 0; x < strlen(innerBuffer); x++) + calculatedChecksum = calculatedChecksum ^ innerBuffer[x]; + + char suffix[6]; + sprintf(suffix, "*%02X\r\n", calculatedChecksum); + + // CLI interactions may come from BLE or serial, respond to all interfaces + commandSendAllInterfaces((char *)prefix); + commandSendAllInterfaces((char *)innerBuffer); + commandSendAllInterfaces(suffix); +} + +// Pass a command string to the all interfaces +void commandSendAllInterfaces(char *rxData) +{ + // Direct output to Bluetooth Command + PrintEndpoint originalPrintEndpoint = printEndpoint; + + // Don't re-direct if we're doing a count of the print output + if (printEndpoint != PRINT_ENDPOINT_COUNT) + { + printEndpoint = PRINT_ENDPOINT_ALL; + + // The LIST command dumps a large amount of data across the BLE link causing "esp_ble_gatts_send_ notify: rc=-1" + // errors + + // With debug=debug, 788 characters are printed locally that slow down the interface enough to avoid errors, + // or 68.4ms at 115200 + // With debug=error, can we delay 70ms after every line print and avoid errors? Yes! Works + // well. 50ms is good, 25ms works sometimes without error, 5 is bad. + + if (bluetoothCommandIsConnected()) + delay(settings.cliBlePrintDelay_ms); + } + + systemPrint(rxData); // Send command output to BLE, SPP, and Serial + printEndpoint = originalPrintEndpoint; } // Checks structure of command and checksum @@ -492,13 +614,34 @@ void commandSplitName(const char *settingName, char *truncatedName, int truncate } // Using the settingName string, return the index of the setting within command array +int commandLookupSettingNameAfterPriority(bool inCommands, const char *settingName, char *truncatedName, + int truncatedNameLen, char *suffix, int suffixLen) +{ + return commandLookupSettingNameSelective(inCommands, settingName, truncatedName, truncatedNameLen, suffix, + suffixLen, true); +} int commandLookupSettingName(bool inCommands, const char *settingName, char *truncatedName, int truncatedNameLen, char *suffix, int suffixLen) +{ + return commandLookupSettingNameSelective(inCommands, settingName, truncatedName, truncatedNameLen, suffix, + suffixLen, false); +} +int commandLookupSettingNameSelective(bool inCommands, const char *settingName, char *truncatedName, + int truncatedNameLen, char *suffix, int suffixLen, bool usePrioritySettingsEnd) { const char *command; - // Loop through the valid command entries - for (int i = 0; i < commandCount; i++) + int prioritySettingsEnd = 0; + if (usePrioritySettingsEnd) + // Find "endOfPrioritySettings" + prioritySettingsEnd = findEndOfPrioritySettings(); + // If "endOfPrioritySettings" is not found, prioritySettingsEnd will be zero + + // Adjust prioritySettingsEnd if needed - depending on platform type + prioritySettingsEnd = adjustEndOfPrioritySettings(prioritySettingsEnd); + + // Loop through the valid command entries - starting at prioritySettingsEnd + for (int i = prioritySettingsEnd; i < commandCount; i++) { // Verify that this command does not get split if ((commandIndex[i] >= 0) && (!rtkSettingsEntries[commandIndex[i]].useSuffix) && @@ -518,9 +661,10 @@ int commandLookupSettingName(bool inCommands, const char *settingName, char *tru commandSplitName(settingName, truncatedName, truncatedNameLen, suffix, suffixLen); // Loop through the settings entries + // This could be speeded up by // E.g. by storing the previous value of i and starting there. // Most of the time, the match will be i+1. - for (int i = 0; i < commandCount; i++) + for (int i = prioritySettingsEnd; i < commandCount; i++) { // Verify that this command gets split if ((commandIndex[i] >= 0) && rtkSettingsEntries[commandIndex[i]].useSuffix) @@ -536,11 +680,14 @@ int commandLookupSettingName(bool inCommands, const char *settingName, char *tru } // Command not found + if (settings.debugCLI == true) + systemPrintf("commandLookupSettingName: Setting not found: %s\r\n", settingName); + return COMMAND_UNKNOWN; } // Check for unknown variables -bool commandCheckForUnknownVariable(const char *settingName, const char **entry, int tableEntries) +bool commandCheckListForVariable(const char *settingName, const char **entry, int tableEntries) { const char **tableEnd; @@ -575,8 +722,8 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting settingValue = 0; bool knownSetting = false; - bool settingIsString = false; // Goes true when setting needs to be surrounded by quotes during command response. - // Generally char arrays but some others. + bool settingIsString = false; // Goes true when setting needs to be surrounded by quotes during command + // response. Generally char arrays but some others. // Loop through the valid command entries i = commandLookupSettingName(inCommands, settingName, truncatedName, sizeof(truncatedName), suffix, sizeof(suffix)); @@ -703,8 +850,8 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting // Update the profile name in the file system if necessary if (strcmp(settingName, "profileName") == 0) - setProfileName(profileNumber); // Copy the current settings.profileName into the array of profile names - // at location profileNumber + setProfileName(profileNumber); // Copy the current settings.profileName into the array of profile + // names at location profileNumber settingIsString = true; } break; @@ -717,9 +864,21 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting } break; + case tCmnCnst: { +#ifdef COMPILE_MOSAICX5 + for (int x = 0; x < MAX_MOSAIC_CONSTELLATIONS; x++) + { + if ((suffix[0] == mosaicSignalConstellations[x].configName[0]) && + (strcmp(suffix, mosaicSignalConstellations[x].configName) == 0)) + { + settings.mosaicConstellations[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_MOSAICX5 #ifdef COMPILE_ZED - case tUbxConst: { - for (int x = 0; x < qualifier; x++) + for (int x = 0; x < MAX_UBX_CONSTELLATIONS; x++) { if ((suffix[0] == settings.ubxConstellations[x].textName[0]) && (strcmp(suffix, settings.ubxConstellations[x].textName) == 0)) @@ -729,6 +888,118 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting break; } } +#endif // COMPILE_ZED +#ifdef COMPILE_UM980 + for (int x = 0; x < MAX_UM980_CONSTELLATIONS; x++) + { + if ((suffix[0] == um980ConstellationCommands[x].textName[0]) && + (strcmp(suffix, um980ConstellationCommands[x].textName) == 0)) + { + settings.um980Constellations[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_UM980 +#ifdef COMPILE_LG290P + for (int x = 0; x < MAX_LG290P_CONSTELLATIONS; x++) + { + if ((suffix[0] == lg290pConstellationNames[x][0]) && (strcmp(suffix, lg290pConstellationNames[x]) == 0)) + { + settings.lg290pConstellations[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_LG290P + } + break; + + case tCmnRtNm: { +#ifdef COMPILE_UM980 + for (int x = 0; x < MAX_UM980_NMEA_MSG; x++) + { + if ((suffix[0] == umMessagesNMEA[x].msgTextName[0]) && + (strcmp(suffix, umMessagesNMEA[x].msgTextName) == 0)) + { + settings.um980MessageRatesNMEA[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_UM980 +#ifdef COMPILE_LG290P + for (int x = 0; x < MAX_LG290P_NMEA_MSG; x++) + { + if ((suffix[0] == lgMessagesNMEA[x].msgTextName[0]) && + (strcmp(suffix, lgMessagesNMEA[x].msgTextName) == 0)) + { + settings.lg290pMessageRatesNMEA[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_LG290P + } + break; + case tCnRtRtB: { +#ifdef COMPILE_UM980 + for (int x = 0; x < MAX_UM980_RTCM_MSG; x++) + { + if ((suffix[0] == umMessagesRTCM[x].msgTextName[0]) && + (strcmp(suffix, umMessagesRTCM[x].msgTextName) == 0)) + { + settings.um980MessageRatesRTCMBase[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_UM980 +#ifdef COMPILE_LG290P + for (int x = 0; x < MAX_LG290P_RTCM_MSG; x++) + { + if ((suffix[0] == lgMessagesRTCM[x].msgTextName[0]) && + (strcmp(suffix, lgMessagesRTCM[x].msgTextName) == 0)) + { + settings.lg290pMessageRatesRTCMBase[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_LG290P + } + break; + case tCnRtRtR: { +#ifdef COMPILE_UM980 + for (int x = 0; x < MAX_UM980_RTCM_MSG; x++) + { + if ((suffix[0] == umMessagesRTCM[x].msgTextName[0]) && + (strcmp(suffix, umMessagesRTCM[x].msgTextName) == 0)) + { + settings.um980MessageRatesRTCMRover[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_UM980 +#ifdef COMPILE_LG290P + for (int x = 0; x < MAX_LG290P_RTCM_MSG; x++) + { + if ((suffix[0] == lgMessagesRTCM[x].msgTextName[0]) && + (strcmp(suffix, lgMessagesRTCM[x].msgTextName) == 0)) + { + settings.lg290pMessageRatesRTCMRover[x] = settingValue; + knownSetting = true; + break; + } + } +#endif // COMPILE_LG290P + } + break; + +#ifdef COMPILE_ZED + case tUbxConst: { + // Covered by tCmnCnst } break; case tUbxMsgRt: { @@ -869,55 +1140,19 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting #ifdef COMPILE_UM980 case tUmMRNmea: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == umMessagesNMEA[x].msgTextName[0]) && - (strcmp(suffix, umMessagesNMEA[x].msgTextName) == 0)) - { - settings.um980MessageRatesNMEA[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCmnRtNm } break; case tUmMRRvRT: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == umMessagesRTCM[x].msgTextName[0]) && - (strcmp(suffix, umMessagesRTCM[x].msgTextName) == 0)) - { - settings.um980MessageRatesRTCMRover[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCnRtRtR } break; case tUmMRBaRT: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == umMessagesRTCM[x].msgTextName[0]) && - (strcmp(suffix, umMessagesRTCM[x].msgTextName) == 0)) - { - settings.um980MessageRatesRTCMBase[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCnRtRtB } break; case tUmConst: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == um980ConstellationCommands[x].textName[0]) && - (strcmp(suffix, um980ConstellationCommands[x].textName) == 0)) - { - settings.um980Constellations[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCmnCnst } break; #endif // COMPILE_UM980 @@ -947,16 +1182,7 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting #ifdef COMPILE_MOSAICX5 case tMosaicConst: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == mosaicSignalConstellations[x].configName[0]) && - (strcmp(suffix, mosaicSignalConstellations[x].configName) == 0)) - { - settings.mosaicConstellations[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCmnCnst } break; case tMosaicMSNmea: { @@ -976,7 +1202,24 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting int stream; if (sscanf(suffix, "%d", &stream) == 1) { - settings.mosaicStreamIntervalsNMEA[stream] = settingValue; + double settingValue_d; + int x; + + // Check if stream interval settingValue is text format ("10ms" etc.) + for (x = 0; x < MAX_MOSAIC_MSG_RATES; x++) + { + if (strcmp(settingValueStr, mosaicMsgRates[x].humanName) == 0) + { + settingValue_d = x; + break; + } + } + + // If stream interval is not text, x will be MAX_MOSAIC_MSG_RATES + if (x == MAX_MOSAIC_MSG_RATES) + settingValue_d = settingValue; + + settings.mosaicStreamIntervalsNMEA[stream] = settingValue_d; knownSetting = true; break; } @@ -1038,42 +1281,15 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting #ifdef COMPILE_LG290P case tLgMRNmea: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == lgMessagesNMEA[x].msgTextName[0]) && - (strcmp(suffix, lgMessagesNMEA[x].msgTextName) == 0)) - { - settings.lg290pMessageRatesNMEA[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCmnRtNm } break; case tLgMRRvRT: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == lgMessagesRTCM[x].msgTextName[0]) && - (strcmp(suffix, lgMessagesRTCM[x].msgTextName) == 0)) - { - settings.lg290pMessageRatesRTCMRover[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCnRtRtR } break; case tLgMRBaRT: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == lgMessagesRTCM[x].msgTextName[0]) && - (strcmp(suffix, lgMessagesRTCM[x].msgTextName) == 0)) - { - settings.lg290pMessageRatesRTCMBase[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCnRtRtB } break; case tLgMRPqtm: { @@ -1090,26 +1306,35 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting } break; case tLgConst: { - for (int x = 0; x < qualifier; x++) - { - if ((suffix[0] == lg290pConstellationNames[x][0]) && (strcmp(suffix, lg290pConstellationNames[x]) == 0)) - { - settings.lg290pConstellations[x] = settingValue; - knownSetting = true; - break; - } - } + // Covered by tCmnCnst } break; #endif // COMPILE_LG290P + + case tGnssReceiver: { + gnssReceiverType_e *ptr = (gnssReceiverType_e *)var; + *ptr = (gnssReceiverType_e)settingValue; + knownSetting = true; + } + break; } - } - // Done when the setting is found - if (knownSetting == true && settingIsString == true) - return (SETTING_KNOWN_STRING); - else if (knownSetting == true) - return (SETTING_KNOWN); + // Done when the setting is found + if (knownSetting == true && settingIsString == true) + { + // Determine if extra work needs to be done when the setting changes + if (rtkSettingsEntries[i].afterSetCmd) + rtkSettingsEntries[i].afterSetCmd(i); + return (SETTING_KNOWN_STRING); + } + else if (knownSetting == true) + { + // Determine if extra work needs to be done when the setting changes + if (rtkSettingsEntries[i].afterSetCmd) + rtkSettingsEntries[i].afterSetCmd(i); + return (SETTING_KNOWN); + } + } if (strcmp(settingName, "fixedLatText") == 0) { @@ -1190,7 +1415,7 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting knownSetting = true; } - // Special actions + // Special human-machine-interface commands/actions else if (strcmp(settingName, "enableRCFirmware") == 0) { enableRCFirmware = settingValue; @@ -1226,6 +1451,8 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting ESP.restart(); } + + // setProfile was used in the original Web Config interface else if (strcmp(settingName, "setProfile") == 0) { // Change to new profile @@ -1247,9 +1474,24 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting systemPrintf("Profile contents: %s\r\n", settingsCSV); } - sendStringToWebsocket(settingsCSV); + sendStringToWebsocket(settingsCSV); + knownSetting = true; + } + + // profileNumber is used in the newer CLI with get/set capabilities + else if (strcmp(settingName, "profileNumber") == 0) + { + // Change to new profile + if (settings.debugCLI == true) + systemPrintf("Changing to profile number %d\r\n", settingValue); + changeProfileNumber(settingValue); + + // Load new profile into system + loadSettings(); + knownSetting = true; } + else if (strcmp(settingName, "resetProfile") == 0) { settingsToDefaults(); // Overwrite our current settings with defaults @@ -1273,9 +1515,22 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting sendStringToWebsocket(settingsCSV); knownSetting = true; } + + // Is this a profile name change request? ie, 'profile2Name' + // Search by first letter first to speed up search + else if ((settingName[0] == 'p') && (strstr(settingName, "profile") != nullptr) && + (strcmp(&settingName[8], "Name") == 0)) + { + int profileNumber = settingName[7] - '0'; + if (profileNumber >= 0 && profileNumber <= MAX_PROFILE_COUNT) + { + strncpy(profileNames[profileNumber], settingValueStr, sizeof(profileNames[0])); + knownSetting = true; + } + } else if (strcmp(settingName, "forgetEspNowPeers") == 0) { - // Forget all ESP-Now Peers + // Forget all ESP-NOW Peers for (int x = 0; x < settings.espnowPeerCount; x++) espNowRemovePeer(settings.espnowPeers[x]); settings.espnowPeerCount = 0; @@ -1331,11 +1586,13 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting knownSetting = true; } - // Unused variables - read to avoid errors - else + // Unused variables from the Web Config interface - read to avoid errors + // Check if this setting an unused element from the Web Config interface + if (knownSetting == false) { const char *table[] = { "baseTypeSurveyIn", + "enableAutoReset", "enableFactoryDefaults", "enableFirmwareUpdate", "enableForgetRadios", @@ -1346,21 +1603,39 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting "nicknameECEF", "nicknameGeodetic", "saveToArduino", - "enableAutoReset", "shutdownNoChargeTimeoutMinutesCheckbox", }; const int tableEntries = sizeof(table) / sizeof(table[0]); - knownSetting = commandCheckForUnknownVariable(settingName, table, tableEntries); + // Compare the above table against this settingName + if (commandCheckListForVariable(settingName, table, tableEntries)) + { + if (settings.debugWebServer == true) + systemPrintf("Setting '%s' is known web interface element. Ignoring.\r\n", settingName); + return (SETTING_KNOWN_WEB_CONFIG_INTERFACE_ELEMENT); + } } - // If we've received a setting update for a setting that is not valid to this platform, - // allow it, but throw a warning. - // This is often caused by the Web Config page reporting all cells including - // those that are hidden because of platform limitations - if (knownSetting == true && settingAvailableOnPlatform(i) == false) + // Check if this setting is read only. Used with the CLI. + if (knownSetting == false) { - systemPrintf("Setting '%s' stored but not supported on this platform\r\n", settingName); + const char *table[] = { + "batteryLevelPercent", + "batteryVoltage", + "batteryChargingPercentPerHour", + "bluetoothId", + "deviceId", + "deviceName", + "gnssModuleInfo", + "list", + "rtkFirmwareVersion", + "rtkRemoteFirmwareVersion", + }; + const int tableEntries = sizeof(table) / sizeof(table[0]); + + // Compare the above table against this settingName + if (commandCheckListForVariable(settingName, table, tableEntries)) + return (SETTING_KNOWN_READ_ONLY); } // Last catch @@ -1395,7 +1670,7 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting } if (rtkIndex >= numRtkSettingsEntries) - systemPrintf("ERROR: Unknown '%s': %0.3lf\r\n", settingName, settingValue); + systemPrintf("updateSettingWithValue: Unknown '%s': %0.3lf\r\n", settingName, settingValue); else { // Display the warning @@ -1409,6 +1684,16 @@ SettingValueResponse updateSettingWithValue(bool inCommands, const char *setting rtkFree(name, "name & suffix buffers"); } + // If we've received a setting update for a setting that is not valid to this platform, + // allow it, but throw a warning. + // This is often caused by the Web Config page reporting all cells including + // those that are hidden because of platform limitations + if (knownSetting == false && rtkSettingsEntries[i].inWebConfig && (settingAvailableOnPlatform(i) == false)) + { + if (settings.debugWebServer == true) + systemPrintf("Setting '%s' received but not supported on this platform\r\n", settingName); + } + if (knownSetting == true && settingIsString == true) return (SETTING_KNOWN_STRING); else if (knownSetting == true) @@ -1431,32 +1716,8 @@ void createSettingsString(char *newSettings) strncpy(apPlatformPrefix, platformPrefixTable[productVariant], sizeof(apPlatformPrefix)); stringRecord(newSettings, "platformPrefix", apPlatformPrefix); - char apRtkFirmwareVersion[86]; - firmwareVersionGet(apRtkFirmwareVersion, sizeof(apRtkFirmwareVersion), true); - stringRecord(newSettings, "rtkFirmwareVersion", apRtkFirmwareVersion); - - char apGNSSFirmwareVersion[80]; - if (present.gnss_zedf9p) - { - snprintf(apGNSSFirmwareVersion, sizeof(apGNSSFirmwareVersion), "ZED-F9P Firmware: %s ID: %s", - gnssFirmwareVersion, gnssUniqueId); - } - else if (present.gnss_um980) - { - snprintf(apGNSSFirmwareVersion, sizeof(apGNSSFirmwareVersion), "UM980 Firmware: %s ID: %s", gnssFirmwareVersion, - gnssUniqueId); - } - else if (present.gnss_mosaicX5) - { - snprintf(apGNSSFirmwareVersion, sizeof(apGNSSFirmwareVersion), "mosaic-X5 Firmware: %s ID: %s", - gnssFirmwareVersion, gnssUniqueId); - } - else if (present.gnss_lg290p) - { - snprintf(apGNSSFirmwareVersion, sizeof(apGNSSFirmwareVersion), "LG290P Firmware: %s ID: %s", - gnssFirmwareVersion, gnssUniqueId); - } - stringRecord(newSettings, "gnssFirmwareVersion", apGNSSFirmwareVersion); + stringRecord(newSettings, "rtkFirmwareVersion", (char *)printRtkFirmwareVersion()); + stringRecord(newSettings, "gnssFirmwareVersion", (char *)printGnssModuleInfo()); stringRecord(newSettings, "gnssFirmwareVersionInt", gnssFirmwareVersionInt); char apDeviceBTID[30]; @@ -1562,6 +1823,15 @@ void createSettingsString(char *newSettings) } break; + case tCmnCnst: + break; // Nothing to do here. Let each GNSS add its settings + case tCmnRtNm: + break; // Nothing to do here. Let each GNSS add its settings + case tCnRtRtB: + break; // Nothing to do here. Let each GNSS add its settings + case tCnRtRtR: + break; // Nothing to do here. Let each GNSS add its settings + #ifdef COMPILE_ZED case tUbxConst: { // Record constellation settings @@ -1604,7 +1874,7 @@ void createSettingsString(char *newSettings) #endif // COMPILE_ZED case tEspNowPr: { - // Record ESP-Now peer MAC addresses + // Record ESP-NOW peer MAC addresses for (int x = 0; x < rtkSettingsEntries[i].qualifier; x++) { char tempString[50]; // espnowPeers_1=B4:C1:33:42:DE:01, @@ -1728,9 +1998,9 @@ void createSettingsString(char *newSettings) break; case tUmConst: { // Record UM980 Constellations - // um980Constellations are uint8_t, but here we have to convert to bool (true / false) so the web page - // check boxes are populated correctly. (We can't make it bool, otherwise the 254 initializer will - // probably fail...) + // um980Constellations are uint8_t, but here we have to convert to bool (true / false) so the web + // page check boxes are populated correctly. (We can't make it bool, otherwise the 254 initializer + // will probably fail...) for (int x = 0; x < rtkSettingsEntries[i].qualifier; x++) { char tempString[50]; // um980Constellations.GLONASS=true @@ -1895,9 +2165,9 @@ void createSettingsString(char *newSettings) break; case tLgConst: { // Record LG290P Constellations - // lg290pConstellations are uint8_t, but here we have to convert to bool (true / false) so the web page - // check boxes are populated correctly. (We can't make it bool, otherwise the 254 initializer will - // probably fail...) + // lg290pConstellations are uint8_t, but here we have to convert to bool (true / false) so the web + // page check boxes are populated correctly. (We can't make it bool, otherwise the 254 initializer + // will probably fail...) for (int x = 0; x < rtkSettingsEntries[i].qualifier; x++) { char tempString[50]; // lg290pConstellations.GLONASS=true @@ -1908,6 +2178,12 @@ void createSettingsString(char *newSettings) } break; #endif // COMPILE_LG290P + + case tGnssReceiver: { + gnssReceiverType_e *ptr = (gnssReceiverType_e *)rtkSettingsEntries[i].var; + stringRecord(newSettings, rtkSettingsEntries[i].name, (int)*ptr); + } + break; } } } @@ -1950,9 +2226,6 @@ void createSettingsString(char *newSettings) } stringRecord(newSettings, "lastState", lastState); - stringRecord( - newSettings, "profileName", - profileNames[profileNumber]); // Must come before profile number so AP config page JS has name before number stringRecord(newSettings, "profileNumber", profileNumber); for (int index = 0; index < MAX_PROFILE_COUNT; index++) { @@ -1968,10 +2241,15 @@ void createSettingsString(char *newSettings) else stringRecord(newSettings, "wifiConfigOverAP", 0); // 1 = AP mode, 0 = WiFi - if (settings.tcpUdpOverWiFiStation == true) - stringRecord(newSettings, "tcpUdpOverWiFiStation", 1); // 1 = WiFi mode, 0 = AP + if (settings.tcpOverWiFiStation == true) + stringRecord(newSettings, "tcpOverWiFiStation", 1); // 1 = WiFi mode, 0 = AP + else + stringRecord(newSettings, "tcpOverWiFiStation", 0); // 1 = WiFi mode, 0 = AP + + if (settings.udpOverWiFiStation == true) + stringRecord(newSettings, "udpOverWiFiStation", 1); // 1 = WiFi mode, 0 = AP else - stringRecord(newSettings, "tcpUdpOverWiFiStation", 0); // 1 = WiFi mode, 0 = AP + stringRecord(newSettings, "udpOverWiFiStation", 0); // 1 = WiFi mode, 0 = AP // Single variables needed on Config page stringRecord(newSettings, "minCNO", gnss->getMinCno()); @@ -2021,7 +2299,7 @@ void createSettingsString(char *newSettings) stringRecord(newSettings, "ecefY", ecefY, 3); stringRecord(newSettings, "ecefZ", ecefZ, 3); - // Radio / ESP-Now settings + // Radio / ESP-NOW settings char radioMAC[18]; // Send radio MAC snprintf(radioMAC, sizeof(radioMAC), "%02X:%02X:%02X:%02X:%02X:%02X", wifiMACAddress[0], wifiMACAddress[1], wifiMACAddress[2], wifiMACAddress[3], wifiMACAddress[4], wifiMACAddress[5]); @@ -2169,7 +2447,7 @@ void stringRecord(char *settingsCSV, const char *id, int settingValue) void stringRecord(char *settingsCSV, const char *id, uint32_t settingValue) { char record[100]; - snprintf(record, sizeof(record), "%s,%d,", id, settingValue); + snprintf(record, sizeof(record), "%s,%lu,", id, settingValue); strcat(settingsCSV, record); } @@ -2288,11 +2566,12 @@ SettingValueResponse getSettingValue(bool inCommands, const char *settingName, c void *var; bool knownSetting = false; - bool settingIsString = false; // Goes true when setting needs to be surrounded by quotes during command response. - // Generally char arrays but some others. + bool settingIsString = false; // Goes true when setting needs to be surrounded by quotes during command + // response. Generally char arrays but some others. - // Loop through the valid command entries - i = commandLookupSettingName(inCommands, settingName, truncatedName, sizeof(truncatedName), suffix, sizeof(suffix)); + // Loop through the valid command entries - but skip the priority settings and use the GNSS-specific types + i = commandLookupSettingNameAfterPriority(inCommands, settingName, truncatedName, sizeof(truncatedName), suffix, + sizeof(suffix)); // Determine if settingName is in the command table if (i >= 0) @@ -2300,6 +2579,7 @@ SettingValueResponse getSettingValue(bool inCommands, const char *settingName, c qualifier = rtkSettingsEntries[i].qualifier; type = rtkSettingsEntries[i].type; var = rtkSettingsEntries[i].var; + switch (type) { default: @@ -2415,6 +2695,15 @@ SettingValueResponse getSettingValue(bool inCommands, const char *settingName, c } break; + case tCmnCnst: + break; // Nothing to do here. Let each GNSS add its settings + case tCmnRtNm: + break; // Nothing to do here. Let each GNSS add its settings + case tCnRtRtB: + break; // Nothing to do here. Let each GNSS add its settings + case tCnRtRtR: + break; // Nothing to do here. Let each GNSS add its settings + #ifdef COMPILE_ZED case tUbxConst: { for (int x = 0; x < qualifier; x++) @@ -2792,6 +3081,13 @@ SettingValueResponse getSettingValue(bool inCommands, const char *settingName, c } break; #endif // COMPILE_LG290P + + case tGnssReceiver: { + gnssReceiverType_e *ptr = (gnssReceiverType_e *)var; + writeToString(settingValueStr, (int)*ptr); + knownSetting = true; + } + break; } } @@ -2801,13 +3097,61 @@ SettingValueResponse getSettingValue(bool inCommands, const char *settingName, c else if (knownSetting == true) return (SETTING_KNOWN); - // Report deviceID over CLI - Useful for label generation - if (strcmp(settingName, "deviceId") == 0) + // Report special human-machine-interface settings + + // Is this a profile name request? profile2Name + // Search by first letter first to speed up search + if ((settingName[0] == 'p') && (strstr(settingName, "profile") != nullptr) && + (strcmp(&settingName[8], "Name") == 0)) + { + int profileNumber = settingName[7] - '0'; + if (profileNumber >= 0 && profileNumber <= MAX_PROFILE_COUNT) + { + writeToString(settingValueStr, profileNames[profileNumber]); + knownSetting = true; + settingIsString = true; + } + } + else if (strcmp(settingName, "bluetoothId") == 0) + { + // Get the last two digits of Bluetooth MAC + char macAddress[5]; + snprintf(macAddress, sizeof(macAddress), "%02X%02X", btMACAddress[4], btMACAddress[5]); + + writeToString(settingValueStr, macAddress); + knownSetting = true; + settingIsString = true; + } + else if (strcmp(settingName, "deviceName") == 0) + { + writeToString(settingValueStr, (char *)productDisplayNames[productVariant]); + knownSetting = true; + settingIsString = true; + } + else if (strcmp(settingName, "deviceId") == 0) { writeToString(settingValueStr, (char *)printDeviceId()); knownSetting = true; settingIsString = true; } + else if (strcmp(settingName, "rtkFirmwareVersion") == 0) + { + writeToString(settingValueStr, (char *)printRtkFirmwareVersion()); + knownSetting = true; + settingIsString = true; + } + else if (strcmp(settingName, "rtkRemoteFirmwareVersion") == 0) + { + // otaUpdate() is synchronous and called from loop() so we respond here with OK, then go check the firmware + // version + writeToString(settingValueStr, (char *)"OK"); + knownSetting = true; + + otaRequestFirmwareVersionCheck = true; + + // Force exit all config menus and/or command modes to allow OTA state machine to run + btPrintEchoExit = true; + } // Special actions else if (strcmp(settingName, "enableRCFirmware") == 0) @@ -2815,22 +3159,30 @@ SettingValueResponse getSettingValue(bool inCommands, const char *settingName, c writeToString(settingValueStr, enableRCFirmware); knownSetting = true; } + else if (strcmp(settingName, "gnssModuleInfo") == 0) + { + writeToString(settingValueStr, (char *)printGnssModuleInfo()); + knownSetting = true; + settingIsString = true; + } + else if (strcmp(settingName, "batteryLevelPercent") == 0) { checkBatteryLevels(); - writeToString(settingValueStr, batteryLevelPercent); + writeToString(settingValueStr, batteryLevelPercent, 0); knownSetting = true; + settingIsString = true; } else if (strcmp(settingName, "batteryVoltage") == 0) { checkBatteryLevels(); - writeToString(settingValueStr, batteryVoltage); + writeToString(settingValueStr, batteryVoltage, 2); knownSetting = true; } else if (strcmp(settingName, "batteryChargingPercentPerHour") == 0) { checkBatteryLevels(); - writeToString(settingValueStr, batteryChargingPercentPerHour); + writeToString(settingValueStr, batteryChargingPercentPerHour, 0); knownSetting = true; } @@ -2869,12 +3221,12 @@ SettingValueResponse getSettingValue(bool inCommands, const char *settingName, c }; const int tableEntries = sizeof(table) / sizeof(table[0]); - knownSetting = commandCheckForUnknownVariable(settingName, table, tableEntries); + knownSetting = commandCheckListForVariable(settingName, table, tableEntries); } if (knownSetting == false) { - if (settings.debugWebServer) + if (settings.debugWebServer || settings.debugCLI) systemPrintf("getSettingValue() Unknown setting: %s\r\n", settingName); } @@ -2990,6 +3342,15 @@ void commandList(bool inCommands, int i) } break; + case tCmnCnst: + break; // Nothing to do here. Let each GNSS add its commands + case tCmnRtNm: + break; // Nothing to do here. Let each GNSS add its commands + case tCnRtRtB: + break; // Nothing to do here. Let each GNSS add its commands + case tCnRtRtR: + break; // Nothing to do here. Let each GNSS add its commands + #ifdef COMPILE_ZED case tUbxConst: { // Record constellation settings @@ -2999,7 +3360,7 @@ void commandList(bool inCommands, int i) settings.ubxConstellations[x].textName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "bool", settingValue); + commandSendExecuteListResponse(settingName, "tUbxConst", settingValue); } } break; @@ -3010,7 +3371,7 @@ void commandList(bool inCommands, int i) snprintf(settingName, sizeof(settingName), "%s%s", rtkSettingsEntries[i].name, ubxMessages[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tUbxMsgRt", settingValue); } } break; @@ -3025,14 +3386,14 @@ void commandList(bool inCommands, int i) ubxMessages[firstRTCMRecord + x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tUbMsgRtb", settingValue); } } break; #endif // COMPILE_ZED case tEspNowPr: { - // Record ESP-Now peer MAC addresses + // Record ESP-NOW peer MAC addresses for (int x = 0; x < rtkSettingsEntries[i].qualifier; x++) { snprintf(settingType, sizeof(settingType), "uint8_t[%d]", sizeof(settings.espnowPeers[0])); @@ -3136,7 +3497,7 @@ void commandList(bool inCommands, int i) umMessagesNMEA[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "float", settingValue); + commandSendExecuteListResponse(settingName, "tUmMRNmea", settingValue); } } break; @@ -3148,7 +3509,7 @@ void commandList(bool inCommands, int i) umMessagesRTCM[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "float", settingValue); + commandSendExecuteListResponse(settingName, "tUmMRRvRT", settingValue); } } break; @@ -3160,7 +3521,7 @@ void commandList(bool inCommands, int i) umMessagesRTCM[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "float", settingValue); + commandSendExecuteListResponse(settingName, "tUmMRBaRT", settingValue); } } break; @@ -3172,7 +3533,7 @@ void commandList(bool inCommands, int i) um980ConstellationCommands[x].textName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tUmConst", settingValue); } } break; @@ -3200,6 +3561,8 @@ void commandList(bool inCommands, int i) } } break; + +#ifdef COMPILE_MOSAICX5 case tMosaicConst: { // Record Mosaic Constellations for (int x = 0; x < rtkSettingsEntries[i].qualifier; x++) @@ -3208,7 +3571,7 @@ void commandList(bool inCommands, int i) mosaicSignalConstellations[x].configName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tMosaicConst", settingValue); } } break; @@ -3220,7 +3583,7 @@ void commandList(bool inCommands, int i) mosaicMessagesNMEA[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tMosaicMSNmea", settingValue); } } break; @@ -3231,7 +3594,7 @@ void commandList(bool inCommands, int i) snprintf(settingName, sizeof(settingName), "%s%d", rtkSettingsEntries[i].name, x); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tMosaicSINmea", mosaicMsgRates[atoi(settingValue)].humanName); } } break; @@ -3243,7 +3606,7 @@ void commandList(bool inCommands, int i) mosaicRTCMv3MsgIntervalGroups[x].name); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "float", settingValue); + commandSendExecuteListResponse(settingName, "tMosaicMIRvRT", settingValue); } } break; @@ -3255,7 +3618,7 @@ void commandList(bool inCommands, int i) mosaicRTCMv3MsgIntervalGroups[x].name); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "float", settingValue); + commandSendExecuteListResponse(settingName, "tMosaicMIBaRT", settingValue); } } break; @@ -3267,7 +3630,7 @@ void commandList(bool inCommands, int i) mosaicMessagesRTCMv3[x].name); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tMosaicMERvRT", settingValue); } } break; @@ -3279,10 +3642,11 @@ void commandList(bool inCommands, int i) mosaicMessagesRTCMv3[x].name); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tMosaicMEBaRT", settingValue); } } break; +#endif // COMPILE_MOSAICX5 #ifdef COMPILE_LG290P case tLgMRNmea: { @@ -3293,7 +3657,7 @@ void commandList(bool inCommands, int i) lgMessagesNMEA[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tLgMRNmea", settingValue); } } break; @@ -3305,7 +3669,7 @@ void commandList(bool inCommands, int i) lgMessagesRTCM[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tLgMRRvRT", settingValue); } } break; @@ -3317,7 +3681,7 @@ void commandList(bool inCommands, int i) lgMessagesRTCM[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tLgMRBaRT", settingValue); } } break; @@ -3329,7 +3693,7 @@ void commandList(bool inCommands, int i) lgMessagesPQTM[x].msgTextName); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "uint8_t", settingValue); + commandSendExecuteListResponse(settingName, "tLgMRPqtm", settingValue); } } break; @@ -3340,11 +3704,17 @@ void commandList(bool inCommands, int i) snprintf(settingName, sizeof(settingName), "%s%s", rtkSettingsEntries[i].name, lg290pConstellationNames[x]); getSettingValue(inCommands, settingName, settingValue); - commandSendExecuteListResponse(settingName, "bool", settingValue); + commandSendExecuteListResponse(settingName, "tLgConst", settingValue); } } break; #endif // COMPILE_LG290P + + case tGnssReceiver: { + getSettingValue(inCommands, rtkSettingsEntries[i].name, settingValue); + commandSendExecuteListResponse(rtkSettingsEntries[i].name, "gnssReceiverType_e", settingValue); + } + break; } } @@ -3369,8 +3739,48 @@ const char *commandGetName(int stringIndex, int rtkIndex) else if (rtkIndex == COMMAND_PROFILE_NUMBER) return "profileNumber"; - // Display the device ID - used in PointPerfect - return "deviceId"; + // Display the current firmware version number + else if (rtkIndex == COMMAND_FIRMWARE_VERSION) + return "rtkFirmwareVersion"; + + // Connect to the internet and retrieve the remote firmware version + else if (rtkIndex == COMMAND_REMOTE_FIRMWARE_VERSION) + return "rtkRemoteFirmwareVersion"; + + // Allow release candidate firmware to be installed + else if (rtkIndex == COMMAND_ENABLE_RC_FIRMWARE) + return "enableRCFirmware"; + + // Display the current GNSS firmware version number + else if (rtkIndex == COMMAND_GNSS_MODULE_INFO) + return "gnssModuleInfo"; + + // Display the current battery level as a percent + else if (rtkIndex == COMMAND_BATTERY_LEVEL_PERCENT) + return "batteryLevelPercent"; + + // Display the current battery level as a percent + else if (rtkIndex == COMMAND_BATTERY_VOLTAGE) + return "batteryVoltage"; + + // Display the current battery charging percent per hour + else if (rtkIndex == COMMAND_BATTERY_CHARGING_PERCENT) + return "batteryChargingPercentPerHour"; + + // Display the last four characters of the Bluetooth MAC address + else if (rtkIndex == COMMAND_BLUETOOTH_ID) + return "bluetoothId"; + + // Display the device Name + else if (rtkIndex == COMMAND_DEVICE_NAME) + return "deviceName"; + + // Display the device ID + else if (rtkIndex == COMMAND_DEVICE_ID) + return "deviceId"; + + systemPrintln("commandGetName Error: Uncaught command type"); + return "unknown"; } // Determine if the setting is available on this platform @@ -3391,14 +3801,120 @@ bool settingAvailableOnPlatform(int i) break; if ((productVariant == RTK_POSTCARD) && rtkSettingsEntries[i].platPostcard) break; + if (productVariant == RTK_FLEX) + { + // TODO: check if we need to tighten up the logic here + // Maybe settings.detectedGnssReceiver and Facet_Flex_Variant should be amalgamated somehow? + if (rtkSettingsEntries[i].platFlex == ALL) // All + break; + if ((rtkSettingsEntries[i].platFlex == L29) && (settings.detectedGnssReceiver == GNSS_RECEIVER_LG290P)) + break; + if ((rtkSettingsEntries[i].platFlex == MX5) && (settings.detectedGnssReceiver == GNSS_RECEIVER_MOSAIC_X5)) + break; + } + if ((productVariant == RTK_TORCH_X2) && rtkSettingsEntries[i].platTorchX2) + break; + return false; + } while (0); + return true; +} + +// Determine if the named setting is available on this platform +// Note: this does a simple 1:1 comparison of settingName and +// rtkSettingsEntries[].name. It doesn't handle suffixes. +bool namedSettingAvailableOnPlatform(const char *settingName) +{ + // Loop through the settings entries + int rtkIndex; + for (rtkIndex = 0; rtkIndex < numRtkSettingsEntries; rtkIndex++) + { + const char *command = rtkSettingsEntries[rtkIndex].name; + + if (strcmp(command, settingName) == 0) // match found + break; + } + + if (rtkIndex == numRtkSettingsEntries) + return false; // Not found + + return settingAvailableOnPlatform(rtkIndex); +} + +// Determine if the setting is possible on this platform +bool settingPossibleOnPlatform(int i) +{ + do + { + // Verify that the command is available on the platform + if ((productVariant == RTK_EVK) && rtkSettingsEntries[i].platEvk) + break; + if ((productVariant == RTK_FACET_V2) && rtkSettingsEntries[i].platFacetV2) + break; + if ((productVariant == RTK_FACET_V2_LBAND) && rtkSettingsEntries[i].platFacetV2LBand) + break; + if ((productVariant == RTK_FACET_MOSAIC) && rtkSettingsEntries[i].platFacetMosaic) + break; + if ((productVariant == RTK_TORCH) && rtkSettingsEntries[i].platTorch) + break; + if ((productVariant == RTK_POSTCARD) && rtkSettingsEntries[i].platPostcard) + break; + if ((productVariant == RTK_FLEX) && (rtkSettingsEntries[i].platFlex > NON)) + break; + if ((productVariant == RTK_TORCH_X2) && rtkSettingsEntries[i].platTorchX2) + break; return false; } while (0); return true; } +int findEndOfPrioritySettings() +{ + // Find "endOfPrioritySettings" + int prioritySettingsEnd = 0; + for (int i = 0; i < numRtkSettingsEntries; i++) + { + if (strcmp(rtkSettingsEntries[i].name, "endOfPrioritySettings") == 0) + { + prioritySettingsEnd = i; + break; + } + } + // If "endOfPrioritySettings" is not found, prioritySettingsEnd will be zero + return prioritySettingsEnd; +} + +int adjustEndOfPrioritySettings(int prioritySettingsEnd) +{ + // If prioritySettingsEnd is zero, don't adjust + if (prioritySettingsEnd == 0) + return 0; + + int adjustedPrioritySettingsEnd = prioritySettingsEnd; + + // Check which of the priority settings are possible on this platform + // Deduct the ones which are not + for (int i = 0; i < prioritySettingsEnd; i++) + { + if (!settingPossibleOnPlatform(i)) + adjustedPrioritySettingsEnd--; + } + + return adjustedPrioritySettingsEnd; +} + // Allocate and fill the commandIndex table -bool commandIndexFill() +bool commandIndexFillPossible() +{ + return commandIndexFill(true); +} +bool commandIndexFillActual() +{ + return commandIndexFill(false); +} +bool commandIndexFill(bool usePossibleSettings) { + savePossibleSettings = usePossibleSettings; // Update savePossibleSettings + int i; const char *iCommandName; int j; @@ -3410,14 +3926,26 @@ bool commandIndexFill() commandCount = 0; for (i = 0; i < numRtkSettingsEntries; i++) { - if (settingAvailableOnPlatform(i)) - commandCount += 1; + if (usePossibleSettings) + { + // commandIndexFill is called after identifyBoard. On Flex, we don't yet know + // the detectedGnssReceiver, so we have to use settingPossibleOnPlatform + if (settingPossibleOnPlatform(i)) + commandCount += 1; + } + else + { + if (settingAvailableOnPlatform(i)) + commandCount += 1; + } } commandCount += COMMAND_COUNT - 1; // Allocate the command array. Never freed length = commandCount * sizeof(*commandIndex); + if (commandIndex) + rtkFree(commandIndex, "Command index array (commandIndex)"); commandIndex = (int16_t *)rtkMalloc(length, "Command index array (commandIndex)"); if (!commandIndex) { @@ -3429,15 +3957,43 @@ bool commandIndexFill() // Initialize commandIndex with index values into rtkSettingsEntries commandCount = 0; for (i = 0; i < numRtkSettingsEntries; i++) - if (settingAvailableOnPlatform(i)) - commandIndex[commandCount++] = i; + { + if (usePossibleSettings) + { + if (settingPossibleOnPlatform(i)) + commandIndex[commandCount++] = i; + } + else + { + if (settingAvailableOnPlatform(i)) + commandIndex[commandCount++] = i; + } + } - // Add the man-machine interface commands to the list + // Add the human-machine-interface commands to the list for (i = 1; i < COMMAND_COUNT; i++) commandIndex[commandCount++] = -i; - // Sort the commands - for (i = 0; i < commandCount - 1; i++) + // Find "endOfPrioritySettings" + int prioritySettingsEnd = findEndOfPrioritySettings(); + // If "endOfPrioritySettings" is not found, prioritySettingsEnd will be zero + // and all settings will be sorted. Just like the good old days... + + // Adjust prioritySettingsEnd if needed - depending on platform type + prioritySettingsEnd = adjustEndOfPrioritySettings(prioritySettingsEnd); + + if (settings.debugSettings || settings.debugCLI) + { + systemPrintf("commandCount %d\r\n", commandCount); + + if (prioritySettingsEnd > 0) + systemPrintf("endOfPrioritySettings found at entry %d\r\n", prioritySettingsEnd); + else + systemPrintln("endOfPrioritySettings not found!"); + } + + // Sort the commands - starting at prioritySettingsEnd + for (i = prioritySettingsEnd; i < commandCount - 1; i++) { iCommandName = commandGetName(0, commandIndex[i]); for (j = i + 1; j < commandCount; j++) @@ -3461,9 +4017,19 @@ bool commandIndexFill() return true; } +void printSettingsCommandTypes() +{ + String json; + createCommandTypesJson(json); + commandSendResponseUnbuffered("$SPCTY,", json.c_str()); +} + // List available settings, their type in CSV, and value void printAvailableSettings() { + // Print the command types JSON blob + printSettingsCommandTypes(); + // Display the commands for (int i = 0; i < commandCount; i++) { @@ -3475,7 +4041,7 @@ void printAvailableSettings() commandList(false, commandIndex[i]); } - // Below are commands formed specifically for the Man-Machine-Interface + // Below are commands formed specifically for the Human-Machine-Interface // Display the profile name - used in Profiles else if (commandIndex[i] >= -MAX_PROFILE_COUNT) { @@ -3497,7 +4063,113 @@ void printAvailableSettings() commandSendExecuteListResponse("profileNumber", "uint8_t", settingValue); } - // Display the device ID - used in PointPerfect + // Display the current RTK Firmware version + else if (commandIndex[i] == COMMAND_FIRMWARE_VERSION) + { + // Create the settingType based on the length of the firmware version + char settingType[100]; + snprintf(settingType, sizeof(settingType), "char[%d]", strlen(printRtkFirmwareVersion())); + + commandSendExecuteListResponse("rtkFirmwareVersion", settingType, printRtkFirmwareVersion()); + } + + // Display the latest remote RTK Firmware version + else if (commandIndex[i] == COMMAND_REMOTE_FIRMWARE_VERSION) + { + // Report the available command but without data. That requires the user issue separate SPGET. + commandSendExecuteListResponse("rtkRemoteFirmwareVersion", "char[21]", "NotYetRetreived"); + } + + // Allow beta firmware release candidates + else if (commandIndex[i] == COMMAND_ENABLE_RC_FIRMWARE) + { + if (enableRCFirmware) + commandSendExecuteListResponse("enableRCFirmware", "bool", "true"); + else + commandSendExecuteListResponse("enableRCFirmware", "bool", "false"); + } + + // Display the GNSS receiver info + else if (commandIndex[i] == COMMAND_GNSS_MODULE_INFO) + { + // Create the settingType based on the length of the firmware version + char settingType[100]; + snprintf(settingType, sizeof(settingType), "char[%d]", strlen(printGnssModuleInfo())); + + commandSendExecuteListResponse("gnssModuleInfo", settingType, printGnssModuleInfo()); + } + + // Display the current battery level as a percent + else if (commandIndex[i] == COMMAND_BATTERY_LEVEL_PERCENT) + { + checkBatteryLevels(); + + // Convert int to string + char batteryLvlStr[4] = {0}; // 104 + snprintf(batteryLvlStr, sizeof(batteryLvlStr), "%d", batteryLevelPercent); + + // Create the settingType based on the length of the firmware version + char settingType[100]; + snprintf(settingType, sizeof(settingType), "char[%d]", strlen(batteryLvlStr)); + + commandSendExecuteListResponse("batteryLevelPercent", settingType, batteryLvlStr); + } + + // Display the current battery voltage + else if (commandIndex[i] == COMMAND_BATTERY_VOLTAGE) + { + checkBatteryLevels(); + + // Convert int to string + char batteryVoltageStr[6] = {0}; // 11.25 + snprintf(batteryVoltageStr, sizeof(batteryVoltageStr), "%0.2f", batteryVoltage); + + // Create the settingType based on the length of the firmware version + char settingType[100]; + snprintf(settingType, sizeof(settingType), "char[%d]", strlen(batteryVoltageStr)); + + commandSendExecuteListResponse("batteryVoltage", settingType, batteryVoltageStr); + } + + // Display the current battery charging percent per hour + else if (commandIndex[i] == COMMAND_BATTERY_CHARGING_PERCENT) + { + checkBatteryLevels(); + + // Convert int to string + char batteryChargingPercentStr[3] = {0}; // 45 + snprintf(batteryChargingPercentStr, sizeof(batteryChargingPercentStr), "%0.0f", batteryChargingPercentPerHour); + + // Create the settingType based on the length of the firmware version + char settingType[100]; + snprintf(settingType, sizeof(settingType), "char[%d]", strlen(batteryChargingPercentStr)); + + commandSendExecuteListResponse("batteryChargingPercentPerHour", settingType, batteryChargingPercentStr); + } + + // Display the last four characters of the Bluetooth MAC + else if (commandIndex[i] == COMMAND_BLUETOOTH_ID) + { + // Get the last two digits of Bluetooth MAC + char macAddress[5]; + snprintf(macAddress, sizeof(macAddress), "%02X%02X", btMACAddress[4], btMACAddress[5]); + + // Create the settingType based on the length of the MAC + char settingType[100]; + snprintf(settingType, sizeof(settingType), "char[%d]", strlen(macAddress)); + + commandSendExecuteListResponse("bluetoothId", settingType, macAddress); + } + + // Display the device name + else if (commandIndex[i] == COMMAND_DEVICE_NAME) + { + char settingType[100]; + snprintf(settingType, sizeof(settingType), "char[%d]", strlen(productDisplayNames[productVariant])); + commandSendExecuteListResponse("deviceName", settingType, productDisplayNames[productVariant]); + } + + // Display the device ID else if (commandIndex[i] == COMMAND_DEVICE_ID) { char settingType[100]; @@ -3505,5 +4177,263 @@ void printAvailableSettings() commandSendExecuteListResponse("deviceId", settingType, printDeviceId()); } } - systemPrintln(); } + +void createCommandTypesJson(String &output) +{ + JsonDocument doc; + + JsonArray command_types = doc["command types"].to(); + +#ifdef COMPILE_LG290P + // LG290P + + JsonObject command_types_tLgConst = command_types.add(); + command_types_tLgConst["name"] = "tLgConst"; + command_types_tLgConst["description"] = "LG290P GNSS constellations"; + command_types_tLgConst["instruction"] = "Enable / disable each GNSS constellation"; + command_types_tLgConst["prefix"] = "constellation_"; + JsonArray command_types_tLgConst_keys = command_types_tLgConst["keys"].to(); + for (int x = 0; x < MAX_LG290P_CONSTELLATIONS; x++) + command_types_tLgConst_keys.add(lg290pConstellationNames[x]); + JsonArray command_types_tLgConst_values = command_types_tLgConst["values"].to(); + command_types_tLgConst_values.add("0"); + command_types_tLgConst_values.add("1"); + + JsonObject command_types_tLgMRNmea = command_types.add(); + command_types_tLgMRNmea["name"] = "tLgMRNmea"; + command_types_tLgMRNmea["description"] = "LG290P NMEA message rates"; + command_types_tLgMRNmea["instruction"] = "Enable / disable each NMEA message"; + command_types_tLgMRNmea["prefix"] = "messageRateNMEA_"; + JsonArray command_types_tLgMRNmea_keys = command_types_tLgMRNmea["keys"].to(); + for (int y = 0; y < MAX_LG290P_NMEA_MSG; y++) + command_types_tLgMRNmea_keys.add(lgMessagesNMEA[y].msgTextName); + JsonArray command_types_tLgMRNmea_values = command_types_tLgMRNmea["values"].to(); + command_types_tLgMRNmea_values.add("0"); + command_types_tLgMRNmea_values.add("1"); + + JsonObject command_types_tLgMRBaRT = command_types.add(); + command_types_tLgMRBaRT["name"] = "tLgMRBaRT"; + command_types_tLgMRBaRT["description"] = "LG290P RTCM message rates - Base"; + command_types_tLgMRBaRT["instruction"] = "Set the RTCM message interval in seconds for Base (0 = Off)"; + command_types_tLgMRBaRT["prefix"] = "messageRateRTCMBase_"; + JsonArray command_types_tLgMRBaRT_keys = command_types_tLgMRBaRT["keys"].to(); + for (int x = 0; x < MAX_LG290P_RTCM_MSG; x++) + command_types_tLgMRBaRT_keys.add(lgMessagesRTCM[x].msgTextName); + command_types_tLgMRBaRT["type"] = "int"; + command_types_tLgMRBaRT["value min"] = 0; + command_types_tLgMRBaRT["value max"] = 1200; + + JsonObject command_types_tLgMRRvRT = command_types.add(); + command_types_tLgMRRvRT["name"] = "tLgMRRvRT"; + command_types_tLgMRRvRT["description"] = "LG290P RTCM message rates - Rover"; + command_types_tLgMRRvRT["instruction"] = "Set the RTCM message interval in seconds for Rover (0 = Off)"; + command_types_tLgMRRvRT["prefix"] = "messageRateRTCMRover_"; + JsonArray command_types_tLgMRRvRT_keys = command_types_tLgMRRvRT["keys"].to(); + for (int x = 0; x < MAX_LG290P_RTCM_MSG; x++) + command_types_tLgMRRvRT_keys.add(lgMessagesRTCM[x].msgTextName); + command_types_tLgMRRvRT["type"] = "int"; + command_types_tLgMRRvRT["value min"] = 0; + command_types_tLgMRRvRT["value max"] = 1200; + + JsonObject command_types_tLgMRPqtm = command_types.add(); + command_types_tLgMRPqtm["name"] = "tLgMRPqtm"; + command_types_tLgMRPqtm["description"] = "LG290P PQTM message rates"; + command_types_tLgMRPqtm["instruction"] = "Enable / disable each PQTM message"; + command_types_tLgMRPqtm["prefix"] = "messageRatePQTM_"; + JsonArray command_types_tLgMRPqtm_keys = command_types_tLgMRPqtm["keys"].to(); + for (int x = 0; x < MAX_LG290P_PQTM_MSG; x++) + command_types_tLgMRPqtm_keys.add(lgMessagesPQTM[x].msgTextName); + JsonArray command_types_tLgMRPqtm_values = command_types_tLgMRPqtm["values"].to(); + command_types_tLgMRPqtm_values.add("0"); + command_types_tLgMRPqtm_values.add("1"); +#endif // COMPILE_LG290P + +#ifdef COMPILE_MOSAICX5 + // mosaic-X5 + + JsonObject command_types_tMosaicConst = command_types.add(); + command_types_tMosaicConst["name"] = "tMosaicConst"; + command_types_tMosaicConst["description"] = "mosaic-X5 GNSS constellations"; + command_types_tMosaicConst["instruction"] = "Enable / disable each GNSS constellation"; + command_types_tMosaicConst["prefix"] = "constellation_"; + JsonArray command_types_tMosaicConst_keys = command_types_tMosaicConst["keys"].to(); + for (int x = 0; x < MAX_MOSAIC_CONSTELLATIONS; x++) + command_types_tMosaicConst_keys.add(mosaicSignalConstellations[x].configName); + JsonArray command_types_tMosaicConst_values = command_types_tMosaicConst["values"].to(); + command_types_tMosaicConst_values.add("0"); + command_types_tMosaicConst_values.add("1"); + + JsonObject command_types_tMosaicMSNmea = command_types.add(); + command_types_tMosaicMSNmea["name"] = "tMosaicMSNmea"; + command_types_tMosaicMSNmea["description"] = "mosaic-X5 message stream for NMEA"; + command_types_tMosaicMSNmea["instruction"] = "Select the message stream for each NMEA message (0 = Off)"; + command_types_tMosaicMSNmea["prefix"] = "messageStreamNMEA_"; + JsonArray command_types_tMosaicMSNmea_keys = command_types_tMosaicMSNmea["keys"].to(); + for (int x = 0; x < MAX_MOSAIC_NMEA_MSG; x++) + command_types_tMosaicMSNmea_keys.add(mosaicMessagesNMEA[x].msgTextName); + JsonArray command_types_tMosaicMSNmea_values = command_types_tMosaicMSNmea["values"].to(); + command_types_tMosaicMSNmea_values.add("0"); + command_types_tMosaicMSNmea_values.add("1"); + command_types_tMosaicMSNmea_values.add("2"); + + JsonObject command_types_tMosaicSINmea = command_types.add(); + command_types_tMosaicSINmea["name"] = "tMosaicSINmea"; + command_types_tMosaicSINmea["description"] = "mosaic-X5 NMEA message intervals"; + command_types_tMosaicSINmea["instruction"] = "Set the interval for each NMEA stream"; + command_types_tMosaicSINmea["prefix"] = "streamIntervalNMEA_"; + JsonArray command_types_tMosaicSINmea_keys = command_types_tMosaicSINmea["keys"].to(); + command_types_tMosaicSINmea_keys.add("1"); + command_types_tMosaicSINmea_keys.add("2"); + JsonArray command_types_tMosaicSINmea_values = command_types_tMosaicSINmea["values"].to(); + for (int y = 0; y < MAX_MOSAIC_MSG_RATES; y++) + command_types_tMosaicSINmea_values.add(mosaicMsgRates[y].humanName); + + JsonObject command_types_tMosaicMIRvRT = command_types.add(); + command_types_tMosaicMIRvRT["name"] = "tMosaicMIRvRT"; + command_types_tMosaicMIRvRT["description"] = "mosaic-X5 RTCM message intervals - Rover"; + command_types_tMosaicMIRvRT["instruction"] = "Set the RTCM message interval in seconds for Rover"; + command_types_tMosaicMIRvRT["prefix"] = "messageIntervalRTCMRover_"; + JsonArray command_types_tMosaicMIRvRT_keys = command_types_tMosaicMIRvRT["keys"].to(); + for (int y = 0; y < MAX_MOSAIC_RTCM_V3_INTERVAL_GROUPS; y++) + command_types_tMosaicMIRvRT_keys.add(mosaicRTCMv3MsgIntervalGroups[y].name); + command_types_tMosaicMIRvRT["type"] = "float"; + command_types_tMosaicMIRvRT["value min"] = 0.1; + command_types_tMosaicMIRvRT["value max"] = 600.0; + + JsonObject command_types_tMosaicMIBaRT = command_types.add(); + command_types_tMosaicMIBaRT["name"] = "tMosaicMIBaRT"; + command_types_tMosaicMIBaRT["description"] = "mosaic-X5 RTCM message intervals - Base"; + command_types_tMosaicMIBaRT["instruction"] = "Set the RTCM message interval in seconds for Base"; + command_types_tMosaicMIBaRT["prefix"] = "messageIntervalRTCMBase_"; + JsonArray command_types_tMosaicMIBaRT_keys = command_types_tMosaicMIBaRT["keys"].to(); + for (int y = 0; y < MAX_MOSAIC_RTCM_V3_INTERVAL_GROUPS; y++) + command_types_tMosaicMIBaRT_keys.add(mosaicRTCMv3MsgIntervalGroups[y].name); + command_types_tMosaicMIBaRT["type"] = "float"; + command_types_tMosaicMIBaRT["value min"] = 0.1; + command_types_tMosaicMIBaRT["value max"] = 600.0; + + JsonObject command_types_tMosaicMERvRT = command_types.add(); + command_types_tMosaicMERvRT["name"] = "tMosaicMERvRT"; + command_types_tMosaicMERvRT["description"] = "mosaic-X5 RTCM message enabled - Rover"; + command_types_tMosaicMERvRT["instruction"] = "Enable / disable Rover RTCM messages"; + command_types_tMosaicMERvRT["prefix"] = "messageEnabledRTCMRover_"; + JsonArray command_types_tMosaicMERvRT_keys = command_types_tMosaicMERvRT["keys"].to(); + for (int y = 0; y < MAX_MOSAIC_RTCM_V3_MSG; y++) + command_types_tMosaicMERvRT_keys.add(mosaicMessagesRTCMv3[y].name); + JsonArray command_types_tMosaicMERvRT_values = command_types_tMosaicMERvRT["values"].to(); + command_types_tMosaicMERvRT_values.add("0"); + command_types_tMosaicMERvRT_values.add("1"); + + JsonObject command_types_tMosaicMEBaRT = command_types.add(); + command_types_tMosaicMEBaRT["name"] = "tMosaicMEBaRT"; + command_types_tMosaicMEBaRT["description"] = "mosaic-X5 RTCM message enabled - Base"; + command_types_tMosaicMEBaRT["instruction"] = "Enable / disable Base RTCM messages"; + command_types_tMosaicMEBaRT["prefix"] = "messageEnabledRTCMBase_"; + JsonArray command_types_tMosaicMEBaRT_keys = command_types_tMosaicMEBaRT["keys"].to(); + for (int y = 0; y < MAX_MOSAIC_RTCM_V3_MSG; y++) + command_types_tMosaicMEBaRT_keys.add(mosaicMessagesRTCMv3[y].name); + JsonArray command_types_tMosaicMEBaRT_values = command_types_tMosaicMEBaRT["values"].to(); + command_types_tMosaicMEBaRT_values.add("0"); + command_types_tMosaicMEBaRT_values.add("1"); +#endif // COMPILE_MOSAICX5 + +#ifdef COMPILE_UM980 + // UM980 + + JsonObject command_types_tUmConst = command_types.add(); + command_types_tUmConst["name"] = "tUmConst"; + command_types_tUmConst["description"] = "UM980 GNSS constellations"; + command_types_tUmConst["instruction"] = "Enable / disable each GNSS constellation"; + command_types_tUmConst["prefix"] = "constellation_"; + JsonArray command_types_tUmConst_keys = command_types_tUmConst["keys"].to(); + for (int x = 0; x < MAX_UM980_CONSTELLATIONS; x++) + command_types_tUmConst_keys.add(um980ConstellationCommands[x].textName); + JsonArray command_types_tUmConst_values = command_types_tUmConst["values"].to(); + command_types_tUmConst_values.add("0"); + command_types_tUmConst_values.add("1"); + + JsonObject command_types_tUmMRNmea = command_types.add(); + command_types_tUmMRNmea["name"] = "tUmMRNmea"; + command_types_tUmMRNmea["description"] = "UM980 NMEA message rates"; + command_types_tUmMRNmea["instruction"] = "Set the NMEA message interval in seconds (0 = Off)"; + command_types_tUmMRNmea["prefix"] = "messageRateNMEA_"; + JsonArray command_types_tUmMRNmea_keys = command_types_tUmMRNmea["keys"].to(); + for (int y = 0; y < MAX_UM980_NMEA_MSG; y++) + command_types_tUmMRNmea_keys.add(umMessagesNMEA[y].msgTextName); + command_types_tUmMRNmea["type"] = "float"; + command_types_tUmMRNmea["value min"] = 0.0; + command_types_tUmMRNmea["value max"] = 65.0; + + JsonObject command_types_tUmMRBaRT = command_types.add(); + command_types_tUmMRBaRT["name"] = "tUmMRBaRT"; + command_types_tUmMRBaRT["description"] = "UM980 RTCM message rates - Base"; + command_types_tUmMRBaRT["instruction"] = "Set the RTCM message interval in seconds for Base (0 = Off)"; + command_types_tUmMRBaRT["prefix"] = "messageRateRTCMBase_"; + JsonArray command_types_tUmMRBaRT_keys = command_types_tUmMRBaRT["keys"].to(); + for (int x = 0; x < MAX_UM980_RTCM_MSG; x++) + command_types_tUmMRBaRT_keys.add(umMessagesRTCM[x].msgTextName); + command_types_tUmMRBaRT["type"] = "float"; + command_types_tUmMRBaRT["value min"] = 0.0; + command_types_tUmMRBaRT["value max"] = 65.0; + + JsonObject command_types_tUmMRRvRT = command_types.add(); + command_types_tUmMRRvRT["name"] = "tUmMRRvRT"; + command_types_tUmMRRvRT["description"] = "UM980 RTCM message rates - Rover"; + command_types_tUmMRRvRT["instruction"] = "Set the RTCM message interval in seconds for Rover (0 = Off)"; + command_types_tUmMRRvRT["prefix"] = "messageRateRTCMRover_"; + JsonArray command_types_tUmMRRvRT_keys = command_types_tUmMRRvRT["keys"].to(); + for (int x = 0; x < MAX_UM980_RTCM_MSG; x++) + command_types_tUmMRRvRT_keys.add(umMessagesRTCM[x].msgTextName); + command_types_tUmMRRvRT["type"] = "float"; + command_types_tUmMRRvRT["value min"] = 0.0; + command_types_tUmMRRvRT["value max"] = 65.0; +#endif // COMPILE_UM980 + +#ifdef COMPILE_ZED + // ublox GNSS Receiver + + JsonObject command_types_tUbxConst = command_types.add(); + command_types_tUbxConst["name"] = "tUbxConst"; + command_types_tUbxConst["description"] = "ZED GNSS constellations"; + command_types_tUbxConst["instruction"] = "Enable / disable each GNSS constellation"; + command_types_tUbxConst["prefix"] = "constellation_"; + JsonArray command_types_tUbxConst_keys = command_types_tUbxConst["keys"].to(); + for (int x = 0; x < MAX_UBX_CONSTELLATIONS; x++) + command_types_tUbxConst_keys.add(settings.ubxConstellations[x].textName); + JsonArray command_types_tUbxConst_values = command_types_tUbxConst["values"].to(); + command_types_tUbxConst_values.add("0"); + command_types_tUbxConst_values.add("1"); + + JsonObject command_types_tUbxMsgRt = command_types.add(); + command_types_tUbxMsgRt["name"] = "tUbxMsgRt"; + command_types_tUbxMsgRt["description"] = "ZED message rates - Rover"; + command_types_tUbxMsgRt["instruction"] = "Set the message interval in navigation cycles for Rover (0 = Off)"; + command_types_tUbxMsgRt["prefix"] = "ubxMessageRate_"; + JsonArray command_types_tUbxMsgRt_keys = command_types_tUbxMsgRt["keys"].to(); + for (int x = 0; x < MAX_UBX_MSG; x++) + command_types_tUbxMsgRt_keys.add(ubxMessages[x].msgTextName); + command_types_tUbxMsgRt["type"] = "int"; + command_types_tUbxMsgRt["value min"] = 0; + command_types_tUbxMsgRt["value max"] = 250; // Avoid 254! + + JsonObject command_types_tUbMsgRtb = command_types.add(); + command_types_tUbMsgRtb["name"] = "tUbMsgRtb"; + command_types_tUbMsgRtb["description"] = "ZED message rates - Base"; + command_types_tUbMsgRtb["instruction"] = "Set the message interval in navigation cycles for Base (0 = Off)"; + command_types_tUbMsgRtb["prefix"] = "ubxMessageRateBase_"; + JsonArray command_types_tUbMsgRtb_keys = command_types_tUbMsgRtb["keys"].to(); + GNSS_ZED zed; + int firstRTCMRecord = zed.getMessageNumberByNameSkipChecks("RTCM_1005"); + for (int x = 0; x < MAX_UBX_MSG_RTCM; x++) + command_types_tUbMsgRtb_keys.add(ubxMessages[firstRTCMRecord + x].msgTextName); + command_types_tUbMsgRtb["type"] = "int"; + command_types_tUbMsgRtb["value min"] = 0; + command_types_tUbMsgRtb["value max"] = 250; // Avoid 254! +#endif // COMPILE_ZED + + doc.shrinkToFit(); // optional + + // serializeJsonPretty(doc, output); // Pretty formatting - useful for testing + serializeJson(doc, output); // Standard JSON format +} \ No newline at end of file diff --git a/Firmware/RTK_Everywhere/menuCorrectionsPriorities.ino b/Firmware/RTK_Everywhere/menuCorrectionsPriorities.ino index 858447079..85de37daf 100644 --- a/Firmware/RTK_Everywhere/menuCorrectionsPriorities.ino +++ b/Firmware/RTK_Everywhere/menuCorrectionsPriorities.ino @@ -597,7 +597,7 @@ void correctionUpdateSource() uint32_t radioCheckIntervalMsec = settings.correctionsSourcesLifetime_s * 500; // Check twice per lifetime bool setCorrRadioPort = false; - if (millis() > (lastRadioExtCheck + radioCheckIntervalMsec)) + if ((millis() - lastRadioExtCheck) > radioCheckIntervalMsec) { // LG290P will return settings.enableExtCorrRadio. // ZED / mosaic will return true if settings.enableExtCorrRadio is diff --git a/Firmware/RTK_Everywhere/menuFirmware.ino b/Firmware/RTK_Everywhere/menuFirmware.ino index 2f7382cc1..fbd761812 100644 --- a/Firmware/RTK_Everywhere/menuFirmware.ino +++ b/Firmware/RTK_Everywhere/menuFirmware.ino @@ -166,6 +166,36 @@ void firmwareVersionGet(char *buffer, int bufferLength, bool includeDate) firmwareVersionFormat(FIRMWARE_VERSION_MAJOR, FIRMWARE_VERSION_MINOR, buffer, bufferLength, includeDate); } +// Returns string containing the current version number - ie "v2.0" +const char *printRtkFirmwareVersion() +{ + // Create the firmware version string + static char rtkFirmwareVersion[86]; + firmwareVersionGet(rtkFirmwareVersion, sizeof(rtkFirmwareVersion), true); + + return ((const char *)rtkFirmwareVersion); +} + +// Returns a string containing the module model, firmware, and ID. Similar to gnss->printModuleInfo() +const char *printGnssModuleInfo() +{ + static char gnssModuleInfo[80]; + char gnssMfg[10]; + if (present.gnss_zedf9p) + strncpy(gnssMfg, "ZED-F9P", sizeof(gnssMfg)); + else if (present.gnss_um980) + strncpy(gnssMfg, "UM980", sizeof(gnssMfg)); + else if (present.gnss_mosaicX5) + strncpy(gnssMfg, "mosaic-X5", sizeof(gnssMfg)); + else if (present.gnss_lg290p) + strncpy(gnssMfg, "LG290P", sizeof(gnssMfg)); + + snprintf(gnssModuleInfo, sizeof(gnssModuleInfo), "%s Firmware: %s ID: %s", gnssMfg, gnssFirmwareVersion, + gnssUniqueId); + + return ((const char *)gnssModuleInfo); +} + //---------------------------------------- // Returns true if otaReportedVersion is newer than currentVersion // Version number comes in as v2.7-Jan 5 2023 @@ -571,8 +601,15 @@ void otaDisplayPercentage(int bytesWritten, int totalLength, bool alwaysDisplay) if (bytesWritten == totalLength) systemPrintln("]"); + // Display progress on the display displayFirmwareUpdateProgress(percent); + // Report progress over the BLE Command Channel + char stringPercent[5]; + snprintf(stringPercent, sizeof(stringPercent), "%d", percent); + commandSendStringOkResponse((char *)"SPEXE", (char *)"UPDATEPROGRESS", stringPercent); + + // Report progress to the Web Config socket if (apConfigFirmwareUpdateInProcess == true) { char myProgress[50]; @@ -628,11 +665,8 @@ void otaMenuDisplay(char *currentVersion) if (firmwareVersionIsReportedNewer(otaReportedVersion, ¤tVersion[1]) == true || settings.debugFirmwareUpdate == true) { - systemPrintf("u) Update to new firmware: v%s - ", otaReportedVersion); - if (otaRequestFirmwareUpdate == true) - systemPrintln("Requested"); - else - systemPrintln("Not requested"); + systemPrintf("u) Update to new firmware: v%s - %s\r\n", otaReportedVersion, + otaRequestFirmwareUpdate ? "Requested" : "Not Requested"); } } @@ -754,16 +788,8 @@ void otaSetState(uint8_t newState) if (!online.rtc) systemPrintf("%s%s%s%s\r\n", asterisk, initialState, arrow, endingState); else - { // Timestamp the state change - // 1 2 - // 12345678901234567890123456 - // YYYY-mm-dd HH:MM:SS.xxxrn0 - struct tm timeinfo = rtc.getTimeStruct(); - char s[30]; - strftime(s, sizeof(s), "%Y-%m-%d %H:%M:%S", &timeinfo); - systemPrintf("%s%s%s%s, %s.%03ld\r\n", asterisk, initialState, arrow, endingState, s, rtc.getMillis()); - } + systemPrintf("%s%s%s%s, %s\r\n", asterisk, initialState, arrow, endingState, getTimeStamp()); } // Validate the firmware update state @@ -817,7 +843,7 @@ void otaUpdate() otaUpdateStop(); break; - // Wait for a request from a user or from the scheduler + // Wait for a request from a user, the Web Config, CLI, or from the scheduler case OTA_STATE_OFF: if (otaRequestFirmwareVersionCheck || otaRequestFirmwareUpdate) { @@ -845,16 +871,33 @@ void otaUpdate() otaSetState(OTA_STATE_GET_FIRMWARE_VERSION); } - else if ((millis() - connectTimer) > (5 * MILLISECONDS_IN_A_SECOND)) + else if ((millis() - connectTimer) > settings.wifiConnectTimeoutMs) { - // Report failed connection to web client + if (settings.debugFirmwareUpdate) + systemPrintln("Firmware update failed to connect to network"); + + // If we are connected to the Web Config or BLE CLI, then we assume the user + // is requesting the firmware update via those interfaces, thus we attempt an update + // only once, stopping the state machine on failure + if (websocketConnected) { - if (settings.debugFirmwareUpdate) - systemPrintln("Firmware update failed to connect to network"); + // Report failed connection to web client sendStringToWebsocket((char *)"newFirmwareVersion,NO_INTERNET,"); otaUpdateStop(); } + + if (bluetoothCommandIsConnected()) + { + // Report failure to the CLI + if (otaRequestFirmwareUpdate) + commandSendExecuteErrorResponse((char *)"SPEXE", (char *)"UPDATEFIRMWARE", + (char *)"No Internet"); + else if (otaRequestFirmwareVersionCheck) + commandSendErrorResponse((char *)"SPGET", (char *)"rtkRemoteFirmwareVersion", + (char *)"No Internet"); + otaUpdateStop(); + } } break; @@ -893,7 +936,7 @@ void otaUpdate() if (otaRequestFirmwareVersionCheck == true) { otaRequestFirmwareVersionCheck = false; - + if (websocketConnected) { char newVersionCSV[40]; @@ -902,6 +945,12 @@ void otaUpdate() sendStringToWebsocket(newVersionCSV); } + if (bluetoothCommandIsConnected()) + { + // Report value over the CLI + commandSendStringResponse((char *)"SPGET", (char *)"rtkRemoteVersion", otaReportedVersion); + } + otaUpdateStop(); return; } @@ -925,6 +974,12 @@ void otaUpdate() systemPrintln("Failed to get version number from server."); if (websocketConnected) sendStringToWebsocket((char *)"newFirmwareVersion,NO_SERVER,"); + + // Report failure over the CLI + if (bluetoothCommandIsConnected()) + commandSendExecuteErrorResponse((char *)"SPGET", (char *)"rtkRemoteFimrwareVersion", + (char *)"No Server"); + otaUpdateStop(); } break; @@ -938,6 +993,11 @@ void otaUpdate() if (websocketConnected) sendStringToWebsocket((char *)"gettingNewFirmware,ERROR,"); + + // Report failure over the CLI + if (bluetoothCommandIsConnected()) + commandSendExecuteErrorResponse((char *)"SPEXE", (char *)"UPDATEFIRMWARE", + (char *)"Connection Error"); } else { @@ -948,6 +1008,10 @@ void otaUpdate() if (websocketConnected) sendStringToWebsocket((char *)"gettingNewFirmware,ERROR,"); + // Report failure over the CLI + if (bluetoothCommandIsConnected()) + commandSendExecuteErrorResponse((char *)"SPEXE", (char *)"UPDATEFIRMWARE", (char *)"OTA Error"); + otaUpdateStop(); } break; diff --git a/Firmware/RTK_Everywhere/menuMain.ino b/Firmware/RTK_Everywhere/menuMain.ino index e6174f9d1..486900d01 100644 --- a/Firmware/RTK_Everywhere/menuMain.ino +++ b/Firmware/RTK_Everywhere/menuMain.ino @@ -32,7 +32,10 @@ void terminalUpdate() // Push RTCM to GNSS module over I2C / SPI if (correctionLastSeen(CORR_USB)) + { gnss->pushRawData((uint8_t *)buffer, length); + sempParseNextBytes(rtcmParse, (uint8_t *)buffer, length); // Parse the data for RTCM1005/1006 + } } // Does incoming data consist of RTCM correction messages @@ -51,7 +54,10 @@ void terminalUpdate() // Push RTCM to GNSS module over I2C / SPI if (correctionLastSeen(CORR_USB)) + { gnss->pushRawData((uint8_t *)buffer, length); + sempParseNextBytes(rtcmParse, (uint8_t *)buffer, length); // Parse the data for RTCM1005/1006 + } } else { @@ -105,6 +111,11 @@ void menuMain() forwardGnssDataToUsbSerial = false; inMainMenu = true; + + // Clear btPrintEchoExit on entering the menu, to prevent dropping straight + // through if the BT connection was dropped while we had the menu closed + btPrintEchoExit = false; + displaySerialConfig(); // Display 'Serial Config' while user is configuring if (settings.debugGnss == true) @@ -113,14 +124,6 @@ void menuMain() gnss->debuggingDisable(); } - // Check for remote app config entry into command mode - if (runCommandMode == true) - { - runCommandMode = false; - menuCommands(); - return; - } - while (1) { systemPrintln(); @@ -128,6 +131,7 @@ void menuMain() firmwareVersionGet(versionString, sizeof(versionString), true); RTKBrandAttribute *brandAttributes = getBrandAttributeFromBrand(present.brand); systemPrintf("%s RTK %s %s\r\n", brandAttributes->name, platformPrefix, versionString); + systemPrintf("Mode: %s\r\n", stateToRtkMode(systemState)); #ifdef COMPILE_BT @@ -146,6 +150,11 @@ void menuMain() systemPrint("** Bluetooth Low-Energy broadcasting as: "); systemPrint(deviceName); } + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + { + systemPrint("** Bluetooth SPP (Accessory Mode) broadcasting as: "); + systemPrint(deviceName); + } else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) { systemPrint("** Bluetooth Turned Off"); @@ -222,12 +231,8 @@ void menuMain() menuBase(); else if (incoming == 4) menuPorts(); -#ifdef COMPILE_MOSAICX5 - else if (incoming == 5 && productVariant == RTK_FACET_MOSAIC) - menuLogMosaic(); -#endif // COMPILE_MOSAICX5 else if (incoming == 5 && productVariant != RTK_TORCH) // Torch does not have logging - menuLog(); + menuLogSelection(); else if (incoming == 6) menuWiFi(); else if (incoming == 7) @@ -273,14 +278,14 @@ void menuMain() if (restartBase == true && inBaseMode() == true) { restartBase = false; - settings.gnssConfiguredBase = false; // Reapply configuration + settings.gnssConfiguredBase = false; // Reapply configuration requestChangeState(STATE_BASE_NOT_STARTED); // Restart base upon exit for latest changes to take effect } if (restartRover == true && inRoverMode() == true) { restartRover = false; - settings.gnssConfiguredRover = false; // Reapply configuration + settings.gnssConfiguredRover = false; // Reapply configuration requestChangeState(STATE_ROVER_NOT_STARTED); // Restart rover upon exit for latest changes to take effect } @@ -429,7 +434,7 @@ void menuUserProfiles() else if (incoming == MAX_PROFILE_COUNT + 4) { // Print profile - systemPrintf("Select the profile to be printed (1-%d): ",MAX_PROFILE_COUNT); + systemPrintf("Select the profile to be printed (1-%d): ", MAX_PROFILE_COUNT); int printThis = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long @@ -520,7 +525,8 @@ void factoryReset(bool alreadyHasSemaphore) // An error occurs when a settings file is on the microSD card and it is not // deleted, as such the settings on the microSD card will be loaded when the // RTK reboots, resulting in failure to achieve the factory reset condition - systemPrintf("sdCardSemaphore failed to yield, held by %s, menuMain.ino line %d\r\n", semaphoreHolder, __LINE__); + systemPrintf("sdCardSemaphore failed to yield, held by %s, menuMain.ino line %d\r\n", semaphoreHolder, + __LINE__); } } else @@ -539,7 +545,7 @@ void factoryReset(bool alreadyHasSemaphore) gnss->factoryReset(); } else - systemPrintln("GNSS not online. Unable to factoryReset..."); + systemPrintln("GNSS not online: Unable to factory reset."); systemPrintln("Settings erased successfully. Rebooting. Goodbye!"); delay(2000); @@ -556,6 +562,8 @@ void mmDisplayBluetoothRadioMenu(char menuChar, BluetoothRadioType_e bluetoothUs systemPrintln("Classic"); else if (bluetoothUserChoice == BLUETOOTH_RADIO_BLE) systemPrintln("BLE"); + else if (bluetoothUserChoice == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + systemPrintln("Classic - Accessory Mode"); else systemPrintln("Off"); } @@ -569,19 +577,93 @@ BluetoothRadioType_e mmChangeBluetoothProtocol(BluetoothRadioType_e bluetoothUse else if (bluetoothUserChoice == BLUETOOTH_RADIO_SPP) bluetoothUserChoice = BLUETOOTH_RADIO_BLE; else if (bluetoothUserChoice == BLUETOOTH_RADIO_BLE) + bluetoothUserChoice = BLUETOOTH_RADIO_SPP_ACCESSORY_MODE; + else if (bluetoothUserChoice == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) bluetoothUserChoice = BLUETOOTH_RADIO_OFF; else if (bluetoothUserChoice == BLUETOOTH_RADIO_OFF) bluetoothUserChoice = BLUETOOTH_RADIO_SPP_AND_BLE; return bluetoothUserChoice; } -// Restart Bluetooth radio if settings have changed -void mmSetBluetoothProtocol(BluetoothRadioType_e bluetoothUserChoice) +// Update Bluetooth radio if settings have changed +void mmSetBluetoothProtocol(BluetoothRadioType_e bluetoothUserChoice, bool clearBtPairings) { - if (bluetoothUserChoice != settings.bluetoothRadioType) + if ((bluetoothUserChoice != settings.bluetoothRadioType) + || (clearBtPairings != settings.clearBtPairings)) { + // To avoid connection failures, we may need to restart the ESP32 + + // If Bluetooth was on, and the user has selected OFF, then just stop + if ((settings.bluetoothRadioType != BLUETOOTH_RADIO_OFF) + && (bluetoothUserChoice == BLUETOOTH_RADIO_OFF)) + { + bluetoothStop(); + settings.bluetoothRadioType = bluetoothUserChoice; + settings.clearBtPairings = clearBtPairings; + return; + } + // If Bluetooth was off, and the user has selected on, and Bluetooth has not been started previously + // then just start + else if ((settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) + && (bluetoothUserChoice != BLUETOOTH_RADIO_OFF) + && (bluetoothRadioPreviousOnType == BLUETOOTH_RADIO_OFF)) + { + settings.bluetoothRadioType = bluetoothUserChoice; + settings.clearBtPairings = clearBtPairings; + bluetoothStart(); + return; + } + // If Bluetooth was off, and the user has selected on, and Bluetooth has been started previously + // then restart + else if ((settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) + && (bluetoothUserChoice != BLUETOOTH_RADIO_OFF) + && (bluetoothRadioPreviousOnType != BLUETOOTH_RADIO_OFF)) + { + settings.bluetoothRadioType = bluetoothUserChoice; + settings.clearBtPairings = clearBtPairings; + recordSystemSettings(); + systemPrintln("Rebooting to apply new Bluetooth choice. Goodbye!"); + delay(1000); + ESP.restart(); + return; + } + // If Bluetooth was in Accessory Mode, and still is, and clearBtPairings is true + // then (re)start Bluetooth skipping the online check + else if ((settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + && (bluetoothUserChoice == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + && clearBtPairings) + { + settings.clearBtPairings = clearBtPairings; + bluetoothStartSkipOnlineCheck(); + return; + } + // If Bluetooth was in Accessory Mode, and still is, and clearBtPairings is false + // then do nothing + else if ((settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + && (bluetoothUserChoice == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + && (!clearBtPairings)) + { + return; + } + // If Bluetooth was on, and the user has selected a different mode + // then restart + else if ((settings.bluetoothRadioType != BLUETOOTH_RADIO_OFF) + && (bluetoothUserChoice != settings.bluetoothRadioType)) + { + settings.bluetoothRadioType = bluetoothUserChoice; + settings.clearBtPairings = clearBtPairings; + recordSystemSettings(); + systemPrintln("Rebooting to apply new Bluetooth choice. Goodbye!"); + delay(1000); + ESP.restart(); + return; + } + // <--- Insert any new special cases here, or higher up if needed ---> + + // Previous catch-all. Likely to cause connection failures... bluetoothStop(); settings.bluetoothRadioType = bluetoothUserChoice; + settings.clearBtPairings = clearBtPairings; bluetoothStart(); } } @@ -590,6 +672,7 @@ void mmSetBluetoothProtocol(BluetoothRadioType_e bluetoothUserChoice) void menuRadio() { BluetoothRadioType_e bluetoothUserChoice = settings.bluetoothRadioType; + bool clearBtPairings = settings.clearBtPairings; while (1) { @@ -597,7 +680,7 @@ void menuRadio() systemPrintln("Menu: Radios"); #ifndef COMPILE_ESPNOW - systemPrintln("1) **ESP-Now Not Compiled**"); + systemPrintln("1) **ESP-NOW Not Compiled**"); #else // COMPILE_ESPNOW if (settings.enableEspNow == false) systemPrintln("1) ESP-NOW Radio: Disabled"); @@ -623,7 +706,16 @@ void menuRadio() else systemPrintln(" No Paired Radios - Broadcast Enabled"); - systemPrintln("2) Pair radios"); + if (espNowState == ESPNOW_BROADCASTING || espNowState == ESPNOW_PAIRED) + systemPrintf("2) Pairing: %s\r\n", espnowRequestPair ? "Requested" : "Not requested"); + else if (espNowState == ESPNOW_PAIRING) + { + if (espnowRequestPair == true) + systemPrintln("2) (Pairing in process) Stop pairing"); + else + systemPrintln("2) Pairing stopped"); + } + systemPrintln("3) Forget all radios"); systemPrintf("4) Current channel: %d\r\n", wifiChannel); @@ -664,6 +756,12 @@ void menuRadio() // Display Bluetooth menu mmDisplayBluetoothRadioMenu('b', bluetoothUserChoice); + // If in BLUETOOTH_RADIO_SPP_ACCESSORY_MODE, allow user to delete all pairings + if (bluetoothUserChoice == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE) + { + systemPrintf("c) Clear BT pairings: %s\r\n", clearBtPairings ? "Yes" : "No"); + } + systemPrintln("x) Exit"); byte incoming = getUserInputCharacterNumber(); @@ -672,19 +770,31 @@ void menuRadio() if (incoming == 'b') bluetoothUserChoice = mmChangeBluetoothProtocol(bluetoothUserChoice); + // Allow user to clear BT pairings - when BTClassicSerial is next begun + else if ((incoming == 'c') && (bluetoothUserChoice == BLUETOOTH_RADIO_SPP_ACCESSORY_MODE)) + clearBtPairings ^= 1; + else if (incoming == 1) { settings.enableEspNow ^= 1; // Start ESP-NOW so that getChannel runs correctly if (settings.enableEspNow == true) - wifiEspNowOn(__FILE__, __LINE__); + wifiEspNowOn(__FILE__, __LINE__); // Handles espNowStart else - wifiEspNowOff(__FILE__, __LINE__); + wifiEspNowOff(__FILE__, __LINE__); // Handles espNowStop } else if (settings.enableEspNow == true && incoming == 2) { - espNowStaticPairing(); + if (espNowIsBroadcasting() == true || espNowIsPaired() == true) + { + espnowRequestPair ^= 1; + } + else if (espNowIsPairing() == true) + { + espnowRequestPair = false; + systemPrintln("Pairing stop requested"); + } } else if (settings.enableEspNow == true && incoming == 3) { @@ -696,6 +806,8 @@ void menuRadio() { for (int x = 0; x < settings.espnowPeerCount; x++) espNowRemovePeer(settings.espnowPeers[x]); + + espNowStart(); //Restart ESP-NOW to enable broadcastMAC } settings.espnowPeerCount = 0; systemPrintln("Radios forgotten"); @@ -706,7 +818,7 @@ void menuRadio() if (getNewSetting("Enter the WiFi channel to use for ESP-NOW communication", 1, 14, &settings.wifiChannel) == INPUT_RESPONSE_VALID) { - wifiEspNowSetChannel(settings.wifiChannel); + wifiEspNowChannelSet(settings.wifiChannel); if (settings.wifiChannel) { if (settings.wifiChannel == wifiChannel) @@ -752,7 +864,7 @@ void menuRadio() if (wifiEspNowRunning == false) wifiEspNowOn(__FILE__, __LINE__); - uint8_t espNowData[] = + const uint8_t espNowData[] = "This is the long string to test how quickly we can send one string to the other unit. I am going to " "need a much longer sentence if I want to get a long amount of data into one transmission. This is " "nearing 200 characters but needs to be near 250."; @@ -765,13 +877,12 @@ void menuRadio() if (wifiEspNowRunning == false) wifiEspNowOn(__FILE__, __LINE__); - uint8_t espNowData[] = + const uint8_t espNowData[] = "This is the long string to test how quickly we can send one string to the other unit. I am going to " "need a much longer sentence if I want to get a long amount of data into one transmission. This is " "nearing 200 characters but needs to be near 250."; - uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; #ifdef COMPILE_ESPNOW - esp_now_send(broadcastMac, (uint8_t *)&espNowData, sizeof(espNowData)); // Send packet over broadcast + esp_now_send(espNowBroadcastAddr, (uint8_t *)&espNowData, sizeof(espNowData)); // Send packet over broadcast #endif } @@ -801,10 +912,10 @@ void menuRadio() printUnknown(incoming); } - wifiEspNowOn(__FILE__, __LINE__); + wifiEspNowOn(__FILE__, __LINE__); // Turn on the hardware if settings.enableEspNow is true - // Restart Bluetooth radio if settings have changed - mmSetBluetoothProtocol(bluetoothUserChoice); + // Update Bluetooth radio if settings have changed + mmSetBluetoothProtocol(bluetoothUserChoice, clearBtPairings); // LoRa radio state machine will start/stop radio upon next updateLora in loop() diff --git a/Firmware/RTK_Everywhere/menuMessages.ino b/Firmware/RTK_Everywhere/menuMessages.ino index aa726b230..f7730f1ab 100644 --- a/Firmware/RTK_Everywhere/menuMessages.ino +++ b/Firmware/RTK_Everywhere/menuMessages.ino @@ -1,3 +1,84 @@ +// Menu of Logging Menus +void menuLogSelection() +{ + if (present.microSd && !present.mosaicMicroSd) + menuLog(); +#ifdef COMPILE_MOSAICX5 + if (!present.microSd && present.mosaicMicroSd) + menuLogMosaic(); +#endif + if (present.microSd && present.mosaicMicroSd) + { + while (1) + { + systemPrintln(); + systemPrintln("Menu: Logging"); + systemPrintln(); + + systemPrintln("Accessible microSD:"); + printMicroSdInfo(); + systemPrintln(); +#ifdef COMPILE_MOSAICX5 + systemPrintln("Internal mosaic microSD:"); + printMosaicCardSpace(); + systemPrintln(); +#endif + systemPrintln("1) Accessible microSD logging"); + systemPrintln("2) Internal mosaic microSD logging"); + + systemPrintln("x) Exit"); + + int incoming = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long + + if (incoming == 1) + menuLog(); +#ifdef COMPILE_MOSAICX5 + else if (incoming == 2) + menuLogMosaic(); +#endif + else if (incoming == 'x') + break; + else if (incoming == INPUT_RESPONSE_GETNUMBER_EXIT) + break; + else if (incoming == INPUT_RESPONSE_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } + clearBuffer(); // Empty buffer of any newline chars + } +} + +// Print accessible microSd size and free space +void printMicroSdInfo() +{ + if (settings.enableSD && online.microSD) + { + char sdCardSizeChar[20]; + String cardSize; + stringHumanReadableSize(cardSize, sdCardSize); + cardSize.toCharArray(sdCardSizeChar, sizeof(sdCardSizeChar)); + char sdFreeSpaceChar[20]; + String freeSpace; + stringHumanReadableSize(freeSpace, sdFreeSpace); + freeSpace.toCharArray(sdFreeSpaceChar, sizeof(sdFreeSpaceChar)); + + char myString[70]; + snprintf(myString, sizeof(myString), "SD card size: %s / Free space: %s", sdCardSizeChar, sdFreeSpaceChar); + systemPrintln(myString); + + if (online.logging) + { + systemPrintf("Current log file name: %s\r\n", logFileName); + } + } + else + systemPrintln("No microSD card is detected"); + + if (bufferOverruns) + systemPrintf("Buffer overruns: %d\r\n", bufferOverruns); +} + // Control the messages that get logged to SD // Control max logging time (limit to a certain number of minutes) // The main use case is the setup for a base station to log RAW sentences that then get post processed @@ -7,32 +88,10 @@ void menuLog() { systemPrintln(); systemPrintln("Menu: Logging"); + systemPrintln(); - if (settings.enableSD && online.microSD) - { - char sdCardSizeChar[20]; - String cardSize; - stringHumanReadableSize(cardSize, sdCardSize); - cardSize.toCharArray(sdCardSizeChar, sizeof(sdCardSizeChar)); - char sdFreeSpaceChar[20]; - String freeSpace; - stringHumanReadableSize(freeSpace, sdFreeSpace); - freeSpace.toCharArray(sdFreeSpaceChar, sizeof(sdFreeSpaceChar)); - - char myString[70]; - snprintf(myString, sizeof(myString), "SD card size: %s / Free space: %s", sdCardSizeChar, sdFreeSpaceChar); - systemPrintln(myString); - - if (online.logging) - { - systemPrintf("Current log file name: %s\r\n", logFileName); - } - } - else - systemPrintln("No microSD card is detected"); - - if (bufferOverruns) - systemPrintf("Buffer overruns: %d\r\n", bufferOverruns); + printMicroSdInfo(); + systemPrintln(); systemPrint("1) Log to microSD: "); if (settings.enableLogging == true) @@ -82,6 +141,15 @@ void menuLog() systemPrintln("Disabled"); } + if (settings.enableLogging == true) + { + systemPrint("9) Log file length alignment: "); + if (settings.alignedLogFiles == true) + systemPrintln("Enabled"); + else + systemPrintln("Disabled"); + } + systemPrintln("x) Exit"); int incoming = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long @@ -90,15 +158,17 @@ void menuLog() { settings.enableLogging ^= 1; - // Reset the maximum logging time when logging is disabled to ensure that - // the next time logging is enabled that the maximum amount of data can be - // captured. - if (settings.enableLogging == false) - startLogTime_minutes = 0; + // Reset the start logging time when logging is enabled to ensure that + // data can be captured. + if (settings.enableLogging == true) + startLogTime_minutes = millis() / 1000L / 60; } else if (incoming == 2 && settings.enableLogging == true) { // Arbitrary 2 year limit. See https://github.com/sparkfun/SparkFun_RTK_Firmware/issues/86 + // Note: the 2 year limit is fine. But systemTime_minutes is based on millis(), and millis() + // will roll over every 2^32ms = ~50 days... + // TODO: use the GNSS epoch (uint32_t seconds plus uint32_t microseconds) to resolve this. getNewSetting("Enter max minutes before logging stops", 0, 60 * 24 * 365 * 2, &settings.maxLogTime_minutes); } else if (incoming == 3 && settings.enableLogging == true) @@ -113,14 +183,14 @@ void menuLog() beginLogging(); // Create new file based on current RTC. setLoggingType(); // Determine if we are standard, PPP, or custom. Changes logging icon accordingly. } - else if (incoming == 5 && settings.enableLogging == true && online.logging == true) + else if (incoming == 5 && settings.enableLogging == true) { settings.enableARPLogging ^= 1; } else if (incoming == 6 && settings.enableLogging == true && settings.enableARPLogging == true) { // Arbitrary 10 minute limit - getNewSetting("Enter the ARP logging interval in seconds", 0, 60 * 10, &settings.ARPLoggingInterval_s); + getNewSetting("Enter the ARP logging interval in seconds", 1, 60 * 10, &settings.ARPLoggingInterval_s); } else if (incoming == 7) { @@ -130,6 +200,10 @@ void menuLog() { settings.enableNTPFile ^= 1; } + else if (incoming == 9 && settings.enableLogging == true) + { + settings.alignedLogFiles ^= 1; + } else if (incoming == 'x') break; else if (incoming == INPUT_RESPONSE_GETNUMBER_EXIT) @@ -151,11 +225,16 @@ void menuMessagesBaseRTCM() systemPrintln(); systemPrintln("Menu: GNSS Messages - Base RTCM"); - systemPrintln("1) Set RXM Messages for Base Mode"); + systemPrintln("1) Set RTCM Messages for Base Mode"); systemPrintf("2) Reset to Defaults (%s)\r\n", gnss->getRtcmDefaultString()); systemPrintf("3) Reset to Low Bandwidth Link (%s)\r\n", gnss->getRtcmLowDataRateString()); + if (namedSettingAvailableOnPlatform("useMSM7")) + systemPrintf("4) MSM Selection: MSM%c\r\n", settings.useMSM7 ? '7' : '4'); + if (namedSettingAvailableOnPlatform("rtcmMinElev")) + systemPrintf("5) Minimum Elevation for RTCM: %d\r\n", settings.rtcmMinElev); + systemPrintln("x) Exit"); int incoming = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long @@ -179,6 +258,24 @@ void menuMessagesBaseRTCM() systemPrintf("Reset to Low Bandwidth Link (%s)\r\n", gnss->getRtcmLowDataRateString()); restartBase = true; } + else if ((incoming == 4) && (namedSettingAvailableOnPlatform("useMSM7"))) + { + settings.useMSM7 ^= 1; + restartBase = true; + } + else if ((incoming == 5) && (namedSettingAvailableOnPlatform("rtcmMinElev"))) + { + systemPrintf("Enter minimum elevation for RTCM: "); + + int elevation = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long + + if (elevation >= -90 && elevation <= 90) + { + settings.rtcmMinElev = elevation; + restartBase = true; + } + } + else if (incoming == INPUT_RESPONSE_GETNUMBER_EXIT) break; else if (incoming == INPUT_RESPONSE_GETNUMBER_TIMEOUT) @@ -194,7 +291,7 @@ void menuMessagesBaseRTCM() // Based on GPS data/time, create a log file in the format SFE_Everywhere_YYMMDD_HHMMSS.ubx bool beginLogging() { - return(beginLogging(nullptr)); + return (beginLogging(nullptr)); } bool beginLogging(const char *customFileName) @@ -234,9 +331,9 @@ bool beginLogging(const char *customFileName) if (strlen(logFileName) == 0) { - //u-blox platforms use ubx file extension for logs, all others use TXT + // u-blox platforms use ubx file extension for logs, all others use TXT char fileExtension[4] = "ubx"; - if(present.gnss_zedf9p == false) + if (present.gnss_zedf9p == false) strncpy(fileExtension, "txt", sizeof(fileExtension)); snprintf(logFileName, sizeof(logFileName), "/%s_%02d%02d%02d_%02d%02d%02d.%s", // SdFat library @@ -244,8 +341,7 @@ bool beginLogging(const char *customFileName) rtc.getDay(), // ESP32Time returns month:0-11 rtc.getHour(true), rtc.getMinute(), rtc.getSecond(), // ESP32Time getHour(true) returns hour:0-23 - fileExtension - ); + fileExtension); } } else @@ -261,7 +357,7 @@ bool beginLogging(const char *customFileName) if (!logFile) { systemPrintln("Failed to allocate logFile!"); - return(false); + return (false); } } @@ -278,22 +374,36 @@ bool beginLogging(const char *customFileName) systemPrintf("Failed to create GNSS log file: %s\r\n", logFileName); online.logging = false; xSemaphoreGive(sdCardSemaphore); - return(false); + return (false); } logFileSize = 0; - lastLogSize = 0; // Reset counter - used for displaying active logging icon + lastLogSize = 0; // Reset counter - used for displaying active logging icon lastFileReport = millis(); // Fake last file report to avoid an immediate timeout bufferOverruns = 0; // Reset counter sdUpdateFileCreateTimestamp(logFile); // Update the file to create time & date - startCurrentLogTime_minutes = millis() / 1000L / 60; // Mark now as start of logging - - // If it hasn't been done before, mark the initial start of logging for total run time - if (startLogTime_minutes == 0) - startLogTime_minutes = millis() / 1000L / 60; + // Calculate the time of the next log file change + nextLogTime_ms = 0; // Default to no limit + if ((settings.alignedLogFiles) && (settings.maxLogLength_minutes > 0)) + { + // Aligned logging is only possible if the interval is an integral fraction of 24 hours + if ((24 * 60 * 2) % settings.maxLogLength_minutes == 0) + { + // Calculate when the next log file should be opened - in millis() + unsigned long hoursAsMillis = rtc.getMillis() + (rtc.getSecond() * 1000) + + (rtc.getMinute() * 1000 * 60) + + (rtc.getHour(true) * 1000 * 60 * 60); + unsigned long maxLogLength_ms = (unsigned long)settings.maxLogLength_minutes * 60 * 1000; + unsigned long millisFromPreviousLog = hoursAsMillis % maxLogLength_ms; + unsigned long millisToNextLog = maxLogLength_ms - millisFromPreviousLog; + nextLogTime_ms = millis() + millisToNextLog; + } + } + if ((nextLogTime_ms == 0) && (settings.maxLogLength_minutes > 0)) // Non-aligned logging + nextLogTime_ms = millis() + ((unsigned long)settings.maxLogLength_minutes * 60 * 1000); // Add NMEA txt message with restart reason char rstReason[30]; @@ -378,6 +488,8 @@ bool beginLogging(const char *customFileName) currentDate); // textID, buffer, sizeOfBuffer, text logFile->println(nmeaMessage); + logFile->sync(); // Sync any partially written data + if (reuseLastLog == true) { systemPrintln("Appending last available log"); @@ -390,7 +502,7 @@ bool beginLogging(const char *customFileName) // A retry will happen during the next loop, the log will eventually be opened log_d("Failed to get file system lock to create GNSS log file"); online.logging = false; - return(false); + return (false); } systemPrintf("Log file name: %s\r\n", logFileName); @@ -422,6 +534,7 @@ void endLogging(bool gotSemaphore, bool releaseSemaphore) char nmeaMessage[82]; // Max NMEA sentence length is 82 createNMEASentence(CUSTOM_NMEA_TYPE_PARSER_STATS, nmeaMessage, sizeof(nmeaMessage), parserStats); // textID, buffer, sizeOfBuffer, text + logFile->sync(); // Sync any partially written data logFile->println(nmeaMessage); logFile->sync(); @@ -436,7 +549,7 @@ void endLogging(bool gotSemaphore, bool releaseSemaphore) delete logFile; logFile = nullptr; - systemPrintln("Log file closed"); + systemPrintf("Log file closed @ %s\r\n", getTimeStamp()); // Release the semaphore if requested if (releaseSemaphore) @@ -521,10 +634,16 @@ void checkGNSSArrayDefaults() if (present.gnss_zedf9p) { if (settings.dynamicModel == 254) + { + defaultsApplied = true; settings.dynamicModel = DYN_MODEL_PORTABLE; + } if (settings.enableExtCorrRadio == 254) + { + defaultsApplied = true; settings.enableExtCorrRadio = true; + } if (settings.ubxMessageRates[0] == 254) { @@ -546,25 +665,39 @@ void checkGNSSArrayDefaults() defaultsApplied = true; // Reset Base rates to defaults - GNSS_ZED * zed = (GNSS_ZED *)gnss; + GNSS_ZED *zed = (GNSS_ZED *)gnss; int firstRTCMRecord = zed->getMessageNumberByName("RTCM_1005"); for (int x = 0; x < MAX_UBX_MSG_RTCM; x++) settings.ubxMessageRatesBase[x] = ubxMessages[firstRTCMRecord + x].msgDefaultRate; } } #else - if(false) - {} + if (false) + { + } #endif // COMPILE_ZED #ifdef COMPILE_UM980 else if (present.gnss_um980) { + if (settings.dataPortBaud != 115200) + { + // Belt and suspenders... Let's make really sure COM3 only ever runs at 115200 + defaultsApplied = true; + settings.dataPortBaud = 115200; + } + if (settings.dynamicModel == 254) + { + defaultsApplied = true; settings.dynamicModel = UM980_DYN_MODEL_SURVEY; + } if (settings.enableExtCorrRadio == 254) + { + defaultsApplied = true; settings.enableExtCorrRadio = false; + } if (settings.um980Constellations[0] == 254) { @@ -608,10 +741,16 @@ void checkGNSSArrayDefaults() else if (present.gnss_mosaicX5) { if (settings.dynamicModel == 254) + { + defaultsApplied = true; settings.dynamicModel = MOSAIC_DYN_MODEL_QUASISTATIC; + } if (settings.enableExtCorrRadio == 254) + { + defaultsApplied = true; settings.enableExtCorrRadio = true; + } if (settings.mosaicConstellations[0] == 254) { @@ -669,7 +808,10 @@ void checkGNSSArrayDefaults() else if (present.gnss_lg290p) { if (settings.enableExtCorrRadio == 254) + { + defaultsApplied = true; settings.enableExtCorrRadio = false; + } if (settings.lg290pConstellations[0] == 254) { @@ -678,6 +820,8 @@ void checkGNSSArrayDefaults() // Reset constellations to defaults for (int x = 0; x < MAX_LG290P_CONSTELLATIONS; x++) settings.lg290pConstellations[x] = 1; + + settings.enableGalileoHas = false; // The default is true. Move to false so user must opt to turn it on. } if (settings.lg290pMessageRatesNMEA[0] == 254) @@ -715,29 +859,34 @@ void checkGNSSArrayDefaults() for (int x = 0; x < MAX_LG290P_PQTM_MSG; x++) settings.lg290pMessageRatesPQTM[x] = lgMessagesPQTM[x].msgDefaultRate; } - } -#endif // COMPILE_LG290P +#endif // COMPILE_LG290P + // If defaults have been applied, override antennaPhaseCenter_mm with default + // (This was in beginSystemState - for the Torch / UM980 only. Weird...) + if (defaultsApplied) + { + settings.antennaPhaseCenter_mm = present.antennaPhaseCenter_mm; + } // If defaults were applied, also default the non-array settings for this particular GNSS receiver if (defaultsApplied == true) { if (present.gnss_um980) { - settings.minCNO = 10; // Default 10 degrees + settings.minCNO = 10; // Default 10 dBHz settings.surveyInStartingAccuracy = 2.0; // Default 2m settings.measurementRateMs = 500; // Default 2Hz. } else if (present.gnss_zedf9p) { - settings.minCNO = 6; // Default 6 degrees + settings.minCNO = 6; // Default 6 dBHz settings.surveyInStartingAccuracy = 1.0; // Default 1m settings.measurementRateMs = 250; // Default 4Hz. } else if (present.gnss_lg290p) { - //settings.minCNO = 10; // Not yet supported + settings.minCNO = 10; // Default 10 dBHz settings.surveyInStartingAccuracy = 2.0; // Default 2m settings.measurementRateMs = 500; // Default 2Hz. } diff --git a/Firmware/RTK_Everywhere/menuPP.ino b/Firmware/RTK_Everywhere/menuPP.ino index 3d55f1b26..76028074c 100644 --- a/Firmware/RTK_Everywhere/menuPP.ino +++ b/Firmware/RTK_Everywhere/menuPP.ino @@ -44,7 +44,7 @@ enum PP_DeliveryMethod { PP_DELIVERY_NTRIP = 0, // Delivery over an internet connection (essentially TCP) PP_DELIVERY_MQTT, // Delivery over an internet connection using MQTT (deprecated) - PP_DELIVERY_LBAND_NA, // Delivery over L-Band signal, North America coverage + PP_DELIVERY_LBAND_NA, // Delivery over L-Band signal, North America coverage (deprecated) PP_DELIVERY_LBAND_GLOBAL, // Delivery over L-Band signal, global coverage PP_DELIVERY_NONE, }; @@ -60,7 +60,7 @@ enum PP_Encoding // Each service will have a printable name, delivery method, and encoding typedef struct { - const char serviceName[30]; + const char serviceName[40]; PP_ModelType modelType; PP_DeliveryMethod deliveryMethod; PP_Encoding encoding; @@ -68,11 +68,11 @@ typedef struct // The various services offered by PointPerfect const PP_Service ppServices[] = { - {"Disabled", PP_MODEL_NONE, PP_DELIVERY_NONE, PP_ENCODING_NONE}, // Do not use PointPerfect corrections - {"Flex NTRIP/RTCM", PP_MODEL_SSR, PP_DELIVERY_NTRIP, PP_ENCODING_RTCM}, // Uses "ZTP-RTCM-100" profile - {"Flex L-Band North America", PP_MODEL_SSR, PP_DELIVERY_LBAND_NA, PP_ENCODING_SPARTN}, // Uses "ZTP-LBand" profile - {"Global", PP_MODEL_SSR, PP_DELIVERY_LBAND_GLOBAL, PP_ENCODING_SPARTN}, // Uses "ZTP-Global" profile - {"Live", PP_MODEL_OSR, PP_DELIVERY_NTRIP, PP_ENCODING_RTCM}, // Uses "ZTP-Live" profile + {"Disabled", PP_MODEL_NONE, PP_DELIVERY_NONE, PP_ENCODING_NONE}, // Do not use PointPerfect corrections + {"Flex NTRIP/RTCM", PP_MODEL_SSR, PP_DELIVERY_NTRIP, PP_ENCODING_RTCM}, // Uses "ZTP-RTCM-100" profile + {"Flex L-Band North America (Deprecated)", PP_MODEL_SSR, PP_DELIVERY_LBAND_NA, PP_ENCODING_SPARTN}, // Uses "ZTP-LBand" profile + {"Global", PP_MODEL_SSR, PP_DELIVERY_LBAND_GLOBAL, PP_ENCODING_SPARTN}, // Uses "ZTP-Global" profile + {"Live", PP_MODEL_OSR, PP_DELIVERY_NTRIP, PP_ENCODING_RTCM}, // Uses "ZTP-Live" profile {"Flex MQTT (Deprecated)", PP_MODEL_SSR, PP_DELIVERY_MQTT, PP_ENCODING_SPARTN}, // Uses "ZTP-IP" profile, now deprecated // "ZTP-RTCM-100-Trial" profile deprecated @@ -151,8 +151,6 @@ void menuPointPerfect() // We also receive the full list of regional correction topics: /pp/ip/us , /pp/ip/eu , etc. // We need to subscribe to our regional correction topic and push the data to the PPL // RTCM from the PPL is pushed to the GNSS receiver (ie, UM980, LG290P) - // We do not need the user to tell us which pointPerfectCorrectionsSource to use. - // We identify the service level during ZTP and record it to settings (pointPerfectService) systemPrintf("1) Select PointPerfect Service: %s\r\n", ppServices[settings.pointPerfectService].serviceName); @@ -181,26 +179,31 @@ void menuPointPerfect() systemPrintln("Requested"); else systemPrintln("Not requested"); - systemPrint("5) Use localized distribution: "); - if (settings.useLocalizedDistribution == true) - systemPrintln("Enabled"); - else - systemPrintln("Disabled"); - if (settings.useLocalizedDistribution) - { - systemPrint("6) Localized distribution tile level: "); - systemPrint(settings.localizedDistributionTileLevel); - systemPrint(" ("); - systemPrint(localizedDistributionTileLevelNames[settings.localizedDistributionTileLevel]); - systemPrintln(")"); - } - if (productVariantSupportsAssistNow()) + + // Avoid showing features that are only available for the MQTT service + if (pointPerfectMqttNeeded()) { - systemPrint("a) Use AssistNow: "); - if (settings.useAssistNow == true) + systemPrint("5) Use localized distribution: "); + if (settings.useLocalizedDistribution == true) systemPrintln("Enabled"); else systemPrintln("Disabled"); + if (settings.useLocalizedDistribution) + { + systemPrint("6) Localized distribution tile level: "); + systemPrint(settings.localizedDistributionTileLevel); + systemPrint(" ("); + systemPrint(localizedDistributionTileLevelNames[settings.localizedDistributionTileLevel]); + systemPrintln(")"); + } + if (productVariantSupportsAssistNow()) + { + systemPrint("a) Use AssistNow: "); + if (settings.useAssistNow == true) + systemPrintln("Enabled"); + else + systemPrintln("Disabled"); + } } systemPrintln("c) Clear the Keys"); @@ -748,7 +751,7 @@ void updateLBandCorrections() i2cLBand.checkCallbacks(); // Check if any L-Band callbacks are waiting to be processed. // If a certain amount of time has elapsed between last decryption, turn off L-Band icon - if (lbandCorrectionsReceived == true && millis() - lastLBandDecryption > (5 * MILLISECONDS_IN_A_SECOND)) + if ((lbandCorrectionsReceived == true) && ((millis() - lastLBandDecryption) > (5 * MILLISECONDS_IN_A_SECOND))) lbandCorrectionsReceived = false; // If we don't get an L-Band fix within Timeout, hot-start ZED-F9x @@ -757,7 +760,7 @@ void updateLBandCorrections() if (lbandTimeFloatStarted == 0) lbandTimeFloatStarted = millis(); - if (millis() - lbandLastReport > MILLISECONDS_IN_A_SECOND) + if ((millis() - lbandLastReport) > MILLISECONDS_IN_A_SECOND) { lbandLastReport = millis(); @@ -858,73 +861,42 @@ bool pointPerfectNtripNeeded(uint8_t pointPerfectService) bool productVariantSupportsAssistNow() { - if (productVariant == RTK_EVK) + // Of all GNSS receiver types, only ZED-F9P supports Assist Now + // gnss_um980, gnss_zedf9p, gnss_mosaicX5, gnss_lg290p, gnss_zedx20p + + if (present.gnss_zedf9p) return true; - if (productVariant == RTK_FACET_V2) - return false; // TODO - will require specific module lookup - if (productVariant == RTK_FACET_MOSAIC) - return false; - if (productVariant == RTK_TORCH) - return false; - if (productVariant == RTK_POSTCARD) - return false; - - systemPrintln("Uncaught productVariantSupportsAssistNow()"); return false; } bool productVariantSupportsLbandNA() { - if (productVariant == RTK_EVK) - return true; - if (productVariant == RTK_FACET_V2) - return false; // TODO - will require specific module lookup - if (productVariant == RTK_FACET_MOSAIC) - return true; - if (productVariant == RTK_TORCH) - return false; - if (productVariant == RTK_POSTCARD) - return false; + // Of all GNSS receiver types, only ZED-F9P and mosaic-X5 support LBand North America + // gnss_um980, gnss_zedf9p, gnss_mosaicX5, gnss_lg290p, gnss_zedx20p - systemPrintln("Uncaught productVariantSupportsLbandNA()"); + if (present.gnss_zedf9p || present.gnss_mosaicX5) + return true; return false; } bool productVariantSupportsLbandGlobal() { - return false; // As of June 2025, LBand Global is not yet available - - if (productVariant == RTK_EVK) - return false; - if (productVariant == RTK_FACET_V2) - return false; // TODO - will require specific module lookup - if (productVariant == RTK_FACET_MOSAIC) + // Of all GNSS receiver types, only ZED-X20P supports LBand Global + // gnss_um980, gnss_zedf9p, gnss_mosaicX5, gnss_lg290p, gnss_zedx20p + if (present.gnss_zedx20p) return true; - if (productVariant == RTK_TORCH) - return false; - if (productVariant == RTK_POSTCARD) - return false; - - systemPrintln("Uncaught productVariantSupportsLbandGlobal()"); return false; } // Returns true if this platform requires the PointPerfect Library to run to use the corrections from PointPerfect bool productVariantNeedsPpl() { - if (productVariant == RTK_EVK) - return false; - if (productVariant == RTK_FACET_V2) - return false; // TODO - will require specific module lookup - if (productVariant == RTK_FACET_MOSAIC) - return true; - if (productVariant == RTK_TORCH) - return true; - if (productVariant == RTK_POSTCARD) - return true; + // Of all GNSS receiver types, all require PPL except ZED units + // gnss_um980, gnss_zedf9p, gnss_mosaicX5, gnss_lg290p, gnss_zedx20p - systemPrintln("Uncaught productVariantNeedsPpl()"); - return false; + if (present.gnss_zedf9p || present.gnss_zedx20p) + return (false); + return (true); } // Given a service nick name, return whether this platform supports it @@ -938,11 +910,6 @@ bool productVariantSupportsService(uint8_t ppNickName) // All platforms support RTCM over NTRIP/TCP return true; } - else if (ppNickName == PP_NICKNAME_FLEX_RTCM) - { - // All platforms support RTCM over NTRIP/TCP - return true; - } else if (ppNickName == PP_NICKNAME_FLEX_LBAND_NA) { return (productVariantSupportsLbandNA()); @@ -1506,13 +1473,15 @@ void provisioningUpdate() switch (provisioningState) { default: - case PROVISIONING_OFF: { + case PROVISIONING_OFF: + { // If RTC is not online after provisioningTimeout_ms, try to provision anyway if (enabled && rtcOnline) provisioningSetState(PROVISIONING_CHECK_REMAINING); } break; - case PROVISIONING_CHECK_REMAINING: { + case PROVISIONING_CHECK_REMAINING: + { if (provisioningKeysNeeded() == false) provisioningSetState(PROVISIONING_KEYS_REMAINING); else @@ -1525,7 +1494,8 @@ void provisioningUpdate() break; // Wait for connection to the network - case PROVISIONING_WAIT_FOR_NETWORK: { + case PROVISIONING_WAIT_FOR_NETWORK: + { // Stop waiting if PointPerfect has been disabled if (enabled == false) provisioningStop(__FILE__, __LINE__); @@ -1550,9 +1520,10 @@ void provisioningUpdate() } break; - case PROVISIONING_STARTED: { + case PROVISIONING_STARTED: + { // Only leave this state if we timeout or ZTP is complete - if (millis() > (provisioningStartTime_millis + provisioningTimeout_ms)) + if ((millis() - provisioningStartTime_millis) > provisioningTimeout_ms) { httpClientModeNeeded = false; // Tell HTTP_Client to give up. (But it probably already has...) paintKeyUpdateFail(5 * MILLISECONDS_IN_A_SECOND); @@ -1616,7 +1587,8 @@ void provisioningUpdate() } } break; - case PROVISIONING_KEYS_REMAINING: { + case PROVISIONING_KEYS_REMAINING: + { // Report expiration of keys if this PointPerfect service uses them if (pointPerfectServiceUsesKeys() == true) @@ -1654,7 +1626,7 @@ void provisioningUpdate() } // Periodically display the provisioning state - if (PERIODIC_DISPLAY(PD_PROVISIONING_STATE)) + if (PERIODIC_DISPLAY(PD_PROVISIONING_STATE) && !inMainMenu) { systemPrintf("Provisioning state: %s%s\r\n", provisioningStateName[provisioningState], line); PERIODIC_CLEAR(PD_PROVISIONING_STATE); diff --git a/Firmware/RTK_Everywhere/menuPorts.ino b/Firmware/RTK_Everywhere/menuPorts.ino index 5ecfd7137..598e14295 100644 --- a/Firmware/RTK_Everywhere/menuPorts.ino +++ b/Firmware/RTK_Everywhere/menuPorts.ino @@ -5,9 +5,9 @@ void menuPorts() // RTK Facet mosaic, Facet v2 L-Band, Facet v2 menuPortsMultiplexed(); } - else if (productVariant == RTK_TORCH) + else if (productVariant == RTK_TORCH || productVariant == RTK_TORCH_X2) { - // RTK Torch + // RTK Torch, RTK Torch X2 menuPortsUsb(); } else @@ -68,19 +68,19 @@ void menuPortsNoMux() settings.enableGnssToUsbSerial ? "Enabled" : "Disabled"); // EVK has no mux. LG290P has no mux. - if (present.gnss_zedf9p) + if (productVariant == RTK_EVK) { - systemPrintf("4) Toggle use of external corrections radio on UART2: %s\r\n", + systemPrintf("4) Allow incoming corrections on UART2: %s\r\n", settings.enableExtCorrRadio ? "Enabled" : "Disabled"); systemPrintf("5) Source of SPARTN corrections radio on UART2: %s\r\n", settings.extCorrRadioSPARTNSource == 0 ? "IP" : "L-Band"); } - else if (present.gnss_lg290p) + else if (productVariant == RTK_POSTCARD) { - systemPrintf("4) Toggle use of external corrections radio on UART3: %s\r\n", + systemPrintf("4) Allow incoming corrections on RADIO port: %s\r\n", settings.enableExtCorrRadio ? "Enabled" : "Disabled"); - systemPrintf("5) NMEA output on radio UART3: %s\r\n", - settings.enableNmeaOnRadio ? "Enabled" : "Disabled"); + systemPrintf("5) Limit RADIO port output to RTCM: %s\r\n", + settings.enableNmeaOnRadio ? "Disabled" : "Enabled"); //Reverse disabled/enabled to align with prompt } systemPrintln("x) Exit"); @@ -206,19 +206,19 @@ void menuPortsMultiplexed() // Facet mosaic has a mux. Radio Ext is COM2. Data port (COM3) is mux'd. if (present.gnss_zedf9p) { - systemPrintf("4) Toggle use of external corrections radio on UART2: %s\r\n", + systemPrintf("4) Allow Incoming Corrections on UART2: %s\r\n", settings.enableExtCorrRadio ? "Enabled" : "Disabled"); systemPrintf("5) Source of SPARTN corrections radio on UART2: %s\r\n", settings.extCorrRadioSPARTNSource == 0 ? "IP" : "L-Band"); } - else if (present.gnss_mosaicX5) + else if (productVariant == RTK_FACET_MOSAIC) { - systemPrintf("4) Toggle use of external RTCMv3 corrections radio on COM2: %s\r\n", + systemPrintf("4) Allow Incoming Corrections on COM2: %s\r\n", settings.enableExtCorrRadio ? "Enabled" : "Disabled"); systemPrintf("5) Output GNSS data to USB1 serial: %s\r\n", settings.enableGnssToUsbSerial ? "Enabled" : "Disabled"); - systemPrintf("6) NMEA output on radio COM2: %s\r\n", - settings.enableNmeaOnRadio ? "Enabled" : "Disabled"); + systemPrintf("6) Limit RADIO port output to RTCM: %s\r\n", + settings.enableNmeaOnRadio ? "Disabled" : "Enabled"); //Reverse disabled/enabled to align with prompt } systemPrintln("x) Exit"); diff --git a/Firmware/RTK_Everywhere/menuSystem.ino b/Firmware/RTK_Everywhere/menuSystem.ino index 4bb1a6134..6b686890c 100644 --- a/Firmware/RTK_Everywhere/menuSystem.ino +++ b/Firmware/RTK_Everywhere/menuSystem.ino @@ -8,7 +8,7 @@ void menuSystem() systemPrintln(); systemPrintln("System Status"); - printTimeStamp(); + printTimeStamp(true); systemPrint("GNSS: "); if (online.gnss == true) @@ -104,7 +104,7 @@ void menuSystem() } // Display the Bluetooth status - bluetoothTest(false); + bluetoothPrintStatus(); #ifdef COMPILE_NETWORK networkDisplayStatus(); @@ -417,8 +417,8 @@ void menuSystem() printUnknown(incoming); } - // Restart Bluetooth radio if settings have changed - mmSetBluetoothProtocol(bluetoothUserChoice); + // Update Bluetooth radio if settings have changed (ignore clearBtPairings) + mmSetBluetoothProtocol(bluetoothUserChoice, settings.clearBtPairings); clearBuffer(); // Empty buffer of any newline chars } @@ -435,9 +435,6 @@ void menuDebugHardware() systemPrint("1) Print battery status messages: "); systemPrintf("%s\r\n", settings.enablePrintBatteryMessages ? "Enabled" : "Disabled"); - // Bluetooth - systemPrintln("2) Run Bluetooth Test"); - // RTC systemPrint("3) Print RTC resyncs: "); systemPrintf("%s\r\n", settings.enablePrintRtcSync ? "Enabled" : "Disabled"); @@ -465,8 +462,24 @@ void menuDebugHardware() systemPrint("12) Print Tilt/IMU Compensation Debugging: "); systemPrintf("%s\r\n", settings.enableImuCompensationDebug ? "Enabled" : "Disabled"); + // GNSS Firmware upgrades: + // On Torch: we need a direct connection (passthrough) from USB to CH342 B to + // ESP32 UART0 to ESP32 UART1 to UM980 UART3 for firmware upgrade. + // On Postcard: firmware can be updated over USB and the CH342 B connection to GNSS + // UART1. A hardware GNSS reset may be beneficial, but it is possible + // to reset over USB / UART too ($PQTMSRR*4B). + // On Flex: mosaic-X5 can be updated over USB via the USB Hub. + // A direct connection can be created from USB to USB Hub to CH342 B to + // ESP32 UART0 to ESP32 UART1 to GNSS UART1. + // ZED-X20P will need a direct connection. Update via USB is not possible. + // LG290P needs a direct connection. + // A future UM980 variant will also need a direct connection. + // Updates via the 4-pin JST RADIO connector and GNSS UART2 may also be possible. + if (present.gnss_um980) - systemPrintln("13) UM980 direct connect"); + systemPrintln("13) UM980 direct connect for firmware upgrade"); + else if ((productVariant == RTK_FLEX) && (present.gnss_lg290p || present.gnss_zedx20p)) + systemPrintln("13) GNSS direct connect for firmware update"); else if (present.gnss_lg290p) systemPrintln("13) LG290P reset for firmware update"); @@ -485,17 +498,29 @@ void menuDebugHardware() systemPrint("): "); systemPrintf("%s\r\n", settings.enablePsram ? "Enabled" : "Disabled"); - systemPrint("15) Print ESP-Now Debugging: "); + systemPrint("15) Print ESP-NOW Debugging: "); systemPrintf("%s\r\n", settings.debugEspNow ? "Enabled" : "Disabled"); systemPrint("16) Print LoRa Debugging: "); systemPrintf("%s\r\n", settings.debugLora ? "Enabled" : "Disabled"); + // LoRa Firmware upgrades: + // On Torch: we need a direct connection from USB to CH342 B to ESP32 UART0 to + // ESP32 UART1 to LoRa UART0. + // On Flex: we need a direct connection from USB to USB Hub to ESP32 UART0 to + // ESP32 UART2 to LoRa UART2. + // TODO: check STM32 can be updated via UART2!! + if (present.radio_lora) - systemPrintln("17) STM32 direct connect"); + systemPrintln("17) STM32 direct connect for LoRa firmware upgrade"); systemPrintln("18) Display littleFS stats"); + systemPrint("19) Print CLI Debugging: "); + systemPrintf("%s\r\n", settings.debugCLI ? "Enabled" : "Disabled"); + + systemPrintf("20) Delay between CLI LIST prints over BLE: %d\r\n", settings.cliBlePrintDelay_ms); + systemPrintln("e) Erase LittleFS"); systemPrintln("t) Test Screen"); @@ -508,8 +533,6 @@ void menuDebugHardware() if (incoming == 1) settings.enablePrintBatteryMessages ^= 1; - else if (incoming == 2) - bluetoothTest(true); else if (incoming == 3) settings.enablePrintRtcSync ^= 1; else if (incoming == 4) @@ -554,13 +577,27 @@ void menuDebugHardware() ESP.restart(); } } + else if ((productVariant == RTK_FLEX) && (present.gnss_lg290p || present.gnss_zedx20p)) + { + // Create a file in LittleFS + if (createGNSSPassthrough() == true) + { + systemPrintln(); + systemPrintln("GNSS passthrough mode has been recorded to LittleFS. Device will now reset."); + systemFlush(); // Complete prints + + ESP.restart(); + } + } else if (present.gnss_lg290p) { systemPrintln(); - systemPrintln("QGNSS must be connected to CH342 Port B at 460800bps. Begin firmware update from QGNSS (hit the play button) then reset the LG290P."); - lg290pReset(); + systemPrintf("QGNSS must be connected to CH342 Port B at %dbps. Begin firmware update from QGNSS (hit " + "the play button) then reset the LG290P.\r\n", + settings.dataPortBaud); + gnssReset(); delay(100); - lg290pBoot(); + gnssBoot(); systemPrintln("LG290P reset complete."); } } @@ -592,6 +629,19 @@ void menuDebugHardware() systemPrintf("LittleFS total bytes: %d\r\n", LittleFS.totalBytes()); systemPrintf("LittleFS used bytes: %d\r\n", LittleFS.usedBytes()); } + else if (incoming == 19) + { + settings.debugCLI ^= 1; + } + else if (incoming == 20) + { + systemPrintf("Enter millisecond delay (%d to %d) for CLI LIST command over BLE: ", 0, 1000); + int newDelay = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long + if ((newDelay != INPUT_RESPONSE_GETNUMBER_EXIT) && (newDelay != INPUT_RESPONSE_GETNUMBER_TIMEOUT)) + { + settings.cliBlePrintDelay_ms = newDelay; + } + } else if (incoming == 'e') { @@ -801,6 +851,7 @@ void menuDebugSoftware() systemPrintf("40) Print LittleFS and settings management: %s\r\n", settings.debugSettings ? "Enabled" : "Disabled"); + systemPrintf("41) Halt on ESP_RST_PANIC: %s\r\n", settings.haltOnPanic ? "Enabled" : "Disabled"); // Tasks systemPrint("50) Task Highwater Reporting: "); @@ -856,6 +907,8 @@ void menuDebugSoftware() else if (incoming == 40) settings.debugSettings ^= 1; + else if (incoming == 41) + settings.haltOnPanic ^= 1; else if (incoming == 50) settings.enableTaskReports ^= 1; @@ -1171,6 +1224,9 @@ void menuPeriodicPrint() systemPrint("27) RTK correction source: "); systemPrintf("%s\r\n", PERIODIC_SETTING(PD_CORRECTION_SOURCE) ? "Enabled" : "Disabled"); + systemPrint("28) Firmware mode: "); + systemPrintf("%s\r\n", PERIODIC_SETTING(PD_FIRMWARE_MODE) ? "Enabled" : "Disabled"); + systemPrintln("------ Clients -----"); systemPrint("40) NTP server data: "); systemPrintf("%s\r\n", PERIODIC_SETTING(PD_NTP_SERVER_DATA) ? "Enabled" : "Disabled"); @@ -1279,12 +1335,14 @@ void menuPeriodicPrint() else if (incoming == 20) { + systemPrint("Enter the new periodic print mask: "); int value = getUserInputNumber(); if ((value != INPUT_RESPONSE_GETNUMBER_EXIT) && (value != INPUT_RESPONSE_GETNUMBER_TIMEOUT)) settings.periodicDisplay = value; } else if (incoming == 21) { + systemPrint("Enter the new periodic display interval (s): "); int seconds = getUserInputNumber(); if ((seconds != INPUT_RESPONSE_GETNUMBER_EXIT) && (seconds != INPUT_RESPONSE_GETNUMBER_TIMEOUT)) settings.periodicDisplayInterval = seconds * 1000; @@ -1301,6 +1359,8 @@ void menuPeriodicPrint() settings.enablePrintStates ^= 1; else if (incoming == 27) PERIODIC_TOGGLE(PD_CORRECTION_SOURCE); + else if (incoming == 28) + PERIODIC_TOGGLE(PD_FIRMWARE_MODE); else if (incoming == 40) PERIODIC_TOGGLE(PD_NTP_SERVER_DATA); @@ -1393,7 +1453,7 @@ void menuInstrument() systemPrintf("1) Set Antenna Height (a.k.a. Pole Length): %0.3lfm\r\n", settings.antennaHeight_mm / (double)1000.0); - systemPrintf("2) Set Antenna Phase Center (a.k.a. ARP): %0.1fmm\r\n", settings.antennaPhaseCenter_mm); + systemPrintf("2) Set Antenna Phase Center: %0.1fmm\r\n", settings.antennaPhaseCenter_mm); systemPrint("3) Report Tip Altitude: "); systemPrintf("%s\r\n", settings.outputTipAltitude ? "Enabled" : "Disabled"); diff --git a/Firmware/RTK_Everywhere/settings.h b/Firmware/RTK_Everywhere/settings.h index 955af0f64..b99209dac 100644 --- a/Firmware/RTK_Everywhere/settings.h +++ b/Firmware/RTK_Everywhere/settings.h @@ -90,6 +90,8 @@ typedef enum RTK_TORCH = 3, // 0x03 RTK_FACET_V2_LBAND = 4, // 0x04 RTK_POSTCARD = 5, // 0x05 + RTK_FLEX = 6, // 0x06 + RTK_TORCH_X2 = 7, // 0x07 // Add new values above this line RTK_UNKNOWN } ProductVariant; @@ -104,6 +106,8 @@ const char * const productDisplayNames[] = "Torch", "Facet LB", "Postcard", + "Flex", + "Torch X2", // Add new values just above this line "Unknown" }; @@ -117,6 +121,8 @@ const char * const platformFilePrefixTable[] = "SFE_Torch", "SFE_Facet_v2_LBand", "SFE_Postcard", + "SFE_Flex", + "SFE_Torch_X2", // Add new values just above this line "SFE_Unknown" }; @@ -130,6 +136,8 @@ const char * const platformPrefixTable[] = "Torch", "Facet v2 LBand", "Postcard", + "Flex", + "Torch X2", // Add new values just above this line "Unknown" }; @@ -143,6 +151,8 @@ const char * const platformProvisionTable[] = "Torch", "Facet v2 LBand", "Postcard", + "Flex", + "Torch X2", // Add new values just above this line "Unknown" }; @@ -156,6 +166,8 @@ const char * const platformRegistrationPageTable[] = "https://www.sparkfun.com/rtk_torch_registration", "Unknown", "https://www.sparkfun.com/rtk_postcard_registration", + "https://www.sparkfun.com/rtk_flex_registration", + "https://www.sparkfun.com/rtk_torch_x2_registration", // Add new values just above this line "Unknown" }; @@ -184,7 +196,7 @@ const char * const correctionsSourceNames[CORR_NUM] = { // These must match correctionsSource above "External Radio", - "ESP-Now", + "ESP-NOW", "LoRa Radio", "Bluetooth", "USB Serial", @@ -211,6 +223,8 @@ const SystemState platformPreviousStateTable[] = STATE_ROVER_NOT_STARTED, // Torch STATE_ROVER_NOT_STARTED, // Facet v2 L-Band STATE_ROVER_NOT_STARTED, // Postcard + STATE_ROVER_NOT_STARTED, // Flex + STATE_ROVER_NOT_STARTED, // Torch X2 // Add new values above this line STATE_ROVER_NOT_STARTED // Unknown }; @@ -243,6 +257,17 @@ typedef enum MUX_ADC_DAC, } muxConnectionType_e; +// GNSS receiver type detected in Flex +typedef enum +{ + GNSS_RECEIVER_LG290P = 0, + GNSS_RECEIVER_MOSAIC_X5, + GNSS_RECEIVER_X20P, + GNSS_RECEIVER_UM980, + // Add new values above this line + GNSS_RECEIVER_UNKNOWN, +} gnssReceiverType_e; + // User can enter fixed base coordinates in ECEF or degrees typedef enum { @@ -347,6 +372,8 @@ enum PeriodDisplayValues PD_WEB_SERVER_STATE, // 39 PD_OTA_STATE, // 40 + + PD_FIRMWARE_MODE, // 41 // Add new values before this line }; @@ -359,33 +386,134 @@ enum PeriodDisplayValues #ifdef COMPILE_NETWORK // NTRIP Server data -typedef struct _NTRIP_SERVER_DATA +typedef struct { // Network connection used to push RTCM to NTRIP caster NetworkClient *networkClient; volatile uint8_t state; // Count of bytes sent by the NTRIP server to the NTRIP caster - uint32_t bytesSent; + volatile uint32_t bytesSent; // Throttle the time between connection attempts // ms - Max of 4,294,967,295 or 4.3M seconds or 71,000 minutes or 1193 hours or 49 days between attempts - uint32_t connectionAttemptTimeout; - uint32_t lastConnectionAttempt; - int connectionAttempts; // Count the number of connection attempts between restarts + volatile uint32_t connectionAttemptTimeout; + volatile int connectionAttempts; // Count the number of connection attempts between restarts // NTRIP server timer usage: // * Reconnection delay // * Measure the connection response time // * Receive RTCM correction data timeout // * Monitor last RTCM byte received for frame counting - uint32_t timer; - uint32_t startTime; - int connectionAttemptsTotal; // Count the number of connection attempts absolutely + volatile uint32_t timer; + volatile uint32_t startTime; + volatile int connectionAttemptsTotal; // Count the number of connection attempts absolutely // Better debug printing by ntripServerProcessRTCM - uint32_t rtcmBytesSent; - uint32_t previousMilliseconds; + volatile uint32_t rtcmBytesSent; + volatile uint32_t previousMilliseconds; + + + // Protect all methods that manipulate timer with a mutex - to avoid race conditions + // Remember that data is pushed to the servers by + // gnssReadTask -> processUart1Message -> processRTCM -> ntripServerProcessRTCM + SemaphoreHandle_t serverSemaphore = NULL; + + unsigned long millisSinceTimer() + { + unsigned long retVal = 0; + if (serverSemaphore == NULL) + serverSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(serverSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + retVal = millis() - timer; + xSemaphoreGive(serverSemaphore); + } + return retVal; + } + + unsigned long millisSinceStartTime() + { + unsigned long retVal = 0; + if (serverSemaphore == NULL) + serverSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(serverSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + retVal = millis() - startTime; + xSemaphoreGive(serverSemaphore); + } + return retVal; + } + + void updateTimerAndBytesSent() + { + if (serverSemaphore == NULL) + serverSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(serverSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + bytesSent = bytesSent + 1; + rtcmBytesSent = rtcmBytesSent + 1; + timer = millis(); + xSemaphoreGive(serverSemaphore); + } + } + + bool checkBytesSentAndReset(uint32_t timerLimit) + { + bool retVal = false; + if (serverSemaphore == NULL) + serverSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(serverSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + if (((millis() - timer) > timerLimit) && (bytesSent > 0)) + { + retVal = true; + bytesSent = 0; + } + xSemaphoreGive(serverSemaphore); + } + return retVal; + } + + unsigned long getUptime() + { + unsigned long retVal = 0; + if (serverSemaphore == NULL) + serverSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(serverSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + retVal = timer - startTime; + xSemaphoreGive(serverSemaphore); + } + return retVal; + } + + void setTimerToMillis() + { + if (serverSemaphore == NULL) + serverSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(serverSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + timer = millis(); + xSemaphoreGive(serverSemaphore); + } + } + + bool checkConnectionAttemptTimeout() + { + bool retVal = false; + if (serverSemaphore == NULL) + serverSemaphore = xSemaphoreCreateMutex(); + if (xSemaphoreTake(serverSemaphore, 10 / portTICK_PERIOD_MS) == pdPASS) + { + if ((millis() - timer) >= connectionAttemptTimeout) + { + retVal = true; + } + xSemaphoreGive(serverSemaphore); + } + return retVal; + } } NTRIP_SERVER_DATA; #endif // COMPILE_NETWORK @@ -407,6 +535,7 @@ typedef enum BLUETOOTH_RADIO_SPP = 0, BLUETOOTH_RADIO_BLE, BLUETOOTH_RADIO_SPP_AND_BLE, + BLUETOOTH_RADIO_SPP_ACCESSORY_MODE, BLUETOOTH_RADIO_OFF, } BluetoothRadioType_e; @@ -452,6 +581,7 @@ typedef enum PRINT_ENDPOINT_BLUETOOTH, PRINT_ENDPOINT_BLUETOOTH_COMMAND, PRINT_ENDPOINT_ALL, + PRINT_ENDPOINT_COUNT, } PrintEndpoint; PrintEndpoint printEndpoint = PRINT_ENDPOINT_SERIAL; // Controls where the configuration menu gets piped to @@ -495,6 +625,7 @@ typedef enum FUNCTION_LOG_CLOSURE, FUNCTION_PRINT_FILE_LIST, FUNCTION_NTPEVENT, + FUNCTION_ARPWRITE, } SemaphoreFunction; // Print the base coordinates in different formats, depending on the type the user has entered @@ -522,6 +653,8 @@ typedef enum SETTING_UNKNOWN = 0, SETTING_KNOWN, SETTING_KNOWN_STRING, + SETTING_KNOWN_READ_ONLY, + SETTING_KNOWN_WEB_CONFIG_INTERFACE_ELEMENT, } SettingValueResponse; #define INCHES_IN_A_METER 39.37007874 @@ -620,12 +753,12 @@ typedef uint16_t NETCONSUMER_MASK_t; enum PP_NickName { PP_NICKNAME_DISABLED = 0, - PP_NICKNAME_FLEX_RTCM, - PP_NICKNAME_FLEX_LBAND_NA, - PP_NICKNAME_GLOBAL, - PP_NICKNAME_LIVE, - PP_NICKNAME_IP_MQTT, - PP_NICKNAME_MAX, + PP_NICKNAME_FLEX_RTCM, // 1 + PP_NICKNAME_FLEX_LBAND_NA, // 2 + PP_NICKNAME_GLOBAL, // 3 + PP_NICKNAME_LIVE, // 4 + PP_NICKNAME_IP_MQTT, // 5 + PP_NICKNAME_MAX, // 6 }; // This is all the settings that can be set on RTK Product. It's recorded to NVM and the config file. @@ -635,6 +768,10 @@ struct Settings int sizeOfSettings = 0; // sizeOfSettings **must** be the first entry and must be int int rtkIdentifier = RTK_IDENTIFIER; // rtkIdentifier **must** be the second entry + //Once we detect the platform or receiver, no need to re-detect + //ProductVariant previouslyDetectedPlatform = RTK_UNKNOWN; //Because LFS is started after deviceID, this is mute + gnssReceiverType_e detectedGnssReceiver = GNSS_RECEIVER_UNKNOWN; + // Antenna int16_t antennaHeight_mm = 1800; // Aka Pole length float antennaPhaseCenter_mm = 0.0; // Aka ARP @@ -643,7 +780,7 @@ struct Settings // Base operation CoordinateInputType coordinateInputType = COORDINATE_INPUT_TYPE_DD; // Default DD.ddddddddd - double fixedAltitude = 1560.089; + double fixedAltitude = 1560.089; // m bool fixedBase = false; // Use survey-in by default bool fixedBaseCoordinateType = COORD_TYPE_ECEF; double fixedEcefX = -1280206.568; @@ -654,6 +791,15 @@ struct Settings int observationSeconds = 60; // Default survey in time of 60 seconds float observationPositionAccuracy = 5.0; // Default survey in pos accy of 5m float surveyInStartingAccuracy = 1.0; // Wait for this horizontal positional accuracy in meters before starting survey in + // Use MSM7 over MSM4: on platforms where that is possible and where it requires parameter selection + // Needed on: + // LG290P (PQTMCFGRTCM) + // Not needed on: + // mosaic-X5 (it has MSM4 and MSM7 message groups) + // ZED (it has separate messages for MSM4 vs. MSM7) + // UM980 (it has separate messages for MSM4 vs. MSM7) + bool useMSM7 = false; + int rtcmMinElev = -90; // LG290P - minimum elevation for RTCM (PQTMCFGRTCM) // Battery bool enablePrintBatteryMessages = true; @@ -666,6 +812,7 @@ struct Settings BluetoothRadioType_e bluetoothRadioType = BLUETOOTH_RADIO_SPP_AND_BLE; uint16_t sppRxQueueSize = 512 * 4; uint16_t sppTxQueueSize = 32; + bool clearBtPairings = true; // Clear MFi Accessory SSP pairings // Corrections int correctionsSourcesLifetime_s = 30; // Expire a corrections source if no data is seen for this many seconds @@ -714,22 +861,27 @@ struct Settings // GNSS UART uint16_t serialGNSSRxFullThreshold = 50; // RX FIFO full interrupt. Max of ~128. See pinUART2Task(). - int uartReceiveBufferSize = 1024 * 2; // This buffer is filled automatically as the UART receives characters. + int uartReceiveBufferSize = 1024 * 4; // This buffer is filled automatically as the UART receives characters. EVK needs 4K // Hardware - bool enableExternalHardwareEventLogging = false; // Log when INT/TM2 pin goes low - uint16_t spiFrequency = 16; // By default, use 16MHz SPI + bool enableExternalHardwareEventLogging = false; // Log when INT/TM2 pin goes low + uint16_t spiFrequency = 16; // By default, use 16MHz SPI // HTTP bool debugHttpClientData = false; // Debug the HTTP Client (ZTP) data flow bool debugHttpClientState = false; // Debug the HTTP Client state machine + // IMU + bool detectedTilt = false; + bool testedTilt = false; + // Log file - bool enableLogging = true; // If an SD card is present, log default sentences + bool alignedLogFiles = false; // If true, align log files as per #630 + bool enableLogging = true; // If an SD card is present, log default sentences bool enablePrintLogFileMessages = false; bool enablePrintLogFileStatus = true; int maxLogLength_minutes = 60 * 24; // Default to 24 hours - int maxLogTime_minutes = 60 * 24; // Default to 24 hours + int maxLogTime_minutes = 60 * 24; // Default to 24 hours // MQTT bool debugMqttClientData = false; // Debug the MQTT SPARTAN data flow @@ -823,7 +975,8 @@ struct Settings 1; // Core where hardware is started and interrupts are assigned to, 0=core, 1=Arduino uint8_t btReadTaskCore = 1; // Core where task should run, 0=core, 1=Arduino uint8_t btReadTaskPriority = 1; // Read from BT SPP and Write to GNSS. 3 being the highest, and 0 being the lowest - bool enableHeapReport = false; // Turn on to display free heap + bool debugMalloc = false; + bool enableHeapReport = false; // Turn on to display free heap bool enablePrintIdleTime = false; bool enablePsram = true; // Control the use on onboard PSRAM. Used for testing behavior when PSRAM is not available. bool enableTaskReports = false; // Turn on to display task high water marks @@ -832,6 +985,7 @@ struct Settings 1; // Read from GNSS and Write to circular buffer (SD, TCP, BT). 3 being the highest, and 0 being the lowest uint8_t gnssUartInterruptsCore = 1; // Core where hardware is started and interrupts are assigned to, 0=core, 1=Arduino + bool haltOnPanic = false; // Halt after beginVersion if the reset reason was panic uint8_t handleGnssDataTaskCore = 1; // Core where task should run, 0=core, 1=Arduino uint8_t handleGnssDataTaskPriority = 1; // Read from the circular buffer and dole out to end points (SD, TCP, BT). uint8_t i2cInterruptsCore = 1; // Core where hardware is started and interrupts are assigned to, 0=core, 1=Arduino @@ -895,8 +1049,10 @@ struct Settings // Rover operation uint8_t dynamicModel = 254; // Default will be applied by checkGNSSArrayDefaults bool enablePrintRoverAccuracy = true; - int16_t minCNO = 6; // Minimum satellite signal level for navigation. ZED-F9P default is 6 dBHz - uint8_t minElev = 10; // Minimum elevation (in deg) for a GNSS satellite to be used in NAV + int16_t minCNO = 6; // Minimum satellite signal level for navigation. ZED-F9P default is 6 dBHz + // Minimum elevation (in deg) for a GNSS satellite to be used in NAV + // Note: we use 8-bit unsigned here, but some platforms (ZED, mosaic-X5) support negative elevation limits + uint8_t minElev = 10; // RTC (Real Time Clock) bool enablePrintRtcSync = false; @@ -935,7 +1091,8 @@ struct Settings bool debugTcpServer = false; bool enableTcpServer = false; uint16_t tcpServerPort = 2948; // TCP server port, 2948 is GPS Daemon: http://tcp-udp-ports.com/port-2948.htm - bool tcpUdpOverWiFiStation = true; // Controls if TCP/UDP settings should use Station or AP + bool tcpOverWiFiStation = true; // Should TCP server use Station (true) or AP (false) + bool udpOverWiFiStation = true; // Should UDP server use Station (true) or AP (false) // Time Zone - Default to UTC int8_t timeZoneHours = 0; @@ -969,7 +1126,7 @@ struct Settings bool enableImuCompensationDebug = false; bool enableImuDebug = false; // Turn on to display IMU library debug messages bool enableTiltCompensation = true; // Allow user to disable tilt compensation on the models that have an IMU - bool enableGalileoHas = true; // Allow E6 corrections if possible + bool enableGalileoHas = true; // Allow E6 corrections if possible. Also needed on LG290P #ifdef COMPILE_UM980 uint8_t um980Constellations[MAX_UM980_CONSTELLATIONS] = {254}; // Mark first record with key so defaults will be applied. float um980MessageRatesNMEA[MAX_UM980_NMEA_MSG] = {254}; // Mark first record with key so defaults will be applied. @@ -1029,7 +1186,7 @@ struct Settings {"", ""}, {"", ""}, }; - uint32_t wifiConnectTimeoutMs = 20000; // Wait this long for a WiFiMulti connection + uint32_t wifiConnectTimeoutMs = 10000; // Wait this long for a WiFiMulti connection bool outputTipAltitude = false; // If enabled, subtract the pole length and APC from the GNSS receiver's reported altitude @@ -1056,13 +1213,14 @@ struct Settings 254}; // Mark first record with key so defaults will be applied. Int value for each supported message - Report // rates for RTCM Base. Default to Quectel recommended rates. int lg290pMessageRatesPQTM[MAX_LG290P_PQTM_MSG] = {254}; // Mark first record with key so defaults will be applied. + char configurePPP[30] = "2 1 120 0.10 0.15"; // PQTMCFGPPP: 2,1,120,0.10,0.15 ** Use spaces, not commas! ** #endif // COMPILE_LG290P bool debugSettings = false; bool enableNtripCaster = false; //When true, respond as a faux NTRIP Caster to incoming TCP connections bool baseCasterOverride = false; //When true, user has put device into 'BaseCast' mode. Change settings, but don't save to NVM. - - bool debugMalloc = false; + bool debugCLI = false; //When true, output BLE CLI interactions over serial + uint16_t cliBlePrintDelay_ms = 50; // Time delayed between prints during a LIST command to avoid overwhelming the BLE connection // Add new settings to appropriate group above or create new group // Then also add to the same group in rtkSettingsEntries below @@ -1128,32 +1286,69 @@ typedef enum { tLgMRBaRT, tLgMRPqtm, tLgConst, + tGnssReceiver, + + tCmnCnst, + tCmnRtNm, + tCnRtRtB, + tCnRtRtR, // Add new settings types above <----------------> // (Maintain the enum of existing settings types!) } RTK_Settings_Types; +typedef enum +{ + NON = 0, // NONE - must be first + L29 = (1 << 0), // LG290P - No Tilt + MX5 = (1 << 1), // mosaic-X5 - No Tilt + U98 = (1 << 2), // UM980 - Tilt TBC + ZF9 = (1 << 3), // ZED-F9P - Tilt TBC + ZX2 = (1 << 4), // ZED-X20P - Tilt TBC + ALL = (1 << 5) - 1, // ALL - must be the highest single variant + ZED = ZF9 | ZX2, // Hybrids are possible (enums don't have to be consecutive) + MSM = L29, // Platforms which require parameter selection of MSM7 over MSM4 + HAS = L29, // Platforms which support Galileo HAS +} Facet_Flex_Variant; + +typedef bool (* AFTER_CMD)(int cmdIndex); + +// Forward routines +bool wifiAfterCommand(int cmdIndex); + typedef struct { bool inWebConfig; //This setting is exposed during WiFi/Eth config - bool inCommands; //This setting is exposer over CLI - bool useSuffix; // Split command at underscore, use suffix in alternate command table + bool inCommands; //This setting is exposer over CLI + bool useSuffix; // Split command at underscore, use suffix in alternate command table bool platEvk; bool platFacetV2; bool platFacetMosaic; bool platTorch; bool platFacetV2LBand; bool platPostcard; + Facet_Flex_Variant platFlex; + bool platTorchX2; RTK_Settings_Types type; int qualifier; void *var; const char *name; + AFTER_CMD afterSetCmd; // Functions to execute after the set command successfully completes } RTK_Settings_Entry; -#define COMMAND_PROFILE_0_INDEX -1 -#define COMMAND_PROFILE_NUMBER (COMMAND_PROFILE_0_INDEX - MAX_PROFILE_COUNT) -#define COMMAND_DEVICE_ID (COMMAND_PROFILE_NUMBER - 1) -#define COMMAND_UNKNOWN (COMMAND_DEVICE_ID - 1) -#define COMMAND_COUNT (-(COMMAND_UNKNOWN)) +#define COMMAND_PROFILE_0_INDEX -1 +#define COMMAND_PROFILE_NUMBER (COMMAND_PROFILE_0_INDEX - MAX_PROFILE_COUNT) // -1 - 8 = -9 +#define COMMAND_FIRMWARE_VERSION (COMMAND_PROFILE_NUMBER - 1) // -9 - 1 = -10 +#define COMMAND_REMOTE_FIRMWARE_VERSION (COMMAND_FIRMWARE_VERSION - 1) // -10 - 1 = -11 +#define COMMAND_ENABLE_RC_FIRMWARE (COMMAND_REMOTE_FIRMWARE_VERSION - 1) // -11 - 1 = -12 +#define COMMAND_GNSS_MODULE_INFO (COMMAND_ENABLE_RC_FIRMWARE - 1) // -12 - 1 = -13 +#define COMMAND_BATTERY_LEVEL_PERCENT (COMMAND_GNSS_MODULE_INFO - 1) // -13 - 1 = -14 +#define COMMAND_BATTERY_VOLTAGE (COMMAND_BATTERY_LEVEL_PERCENT - 1) // -13 - 1 = -14 +#define COMMAND_BATTERY_CHARGING_PERCENT (COMMAND_BATTERY_VOLTAGE - 1) // -13 - 1 = -14 +#define COMMAND_BLUETOOTH_ID (COMMAND_BATTERY_CHARGING_PERCENT - 1) // -13 - 1 = -14 +#define COMMAND_DEVICE_NAME (COMMAND_BLUETOOTH_ID - 1) // -14 - 1 = -15 +#define COMMAND_DEVICE_ID (COMMAND_DEVICE_NAME - 1) // -15 - 1 = -16 +#define COMMAND_UNKNOWN (COMMAND_DEVICE_ID - 1) // -16 - 1 = -17 +#define COMMAND_COUNT (-(COMMAND_UNKNOWN)) // 17 // Exit types for processCommand typedef enum @@ -1163,6 +1358,7 @@ typedef enum CLI_OK, // 2 CLI_BAD_FORMAT, CLI_UNKNOWN_SETTING, + CLI_SETTING_READ_ONLY, CLI_UNKNOWN_COMMAND, CLI_EXIT, CLI_LIST, @@ -1173,7 +1369,7 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // inWebConfig = Should this setting be sent to the WiFi/Eth Config page // inCommands = Should this setting be exposed over the CLI // useSuffix = Setting has an additional array to search -// EVK/Facet V2/Facet mosaic/Torch/Facet V2 L-Band = Is this setting supported on X platform +// EVK/Facet V2/Facet mosaic/Torch/Facet V2 L-Band/Postcard/Flex = Is this setting supported on X platform // F // a @@ -1181,38 +1377,87 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + + // ======================================================================================================= + // Priority Settings which are not alphabetized in commandIndex + // ======================================================================================================= + + // Detected GNSS Receiver - only for Flex. Save / load first so settingAvailableOnPlatform is correct on Flex + { 0, 0, 0, 0, 0, 0, 0, 0, 0, ALL, 0, tGnssReceiver, 0, & settings.detectedGnssReceiver, "detectedGnssReceiver", nullptr, }, + + // Common settings which use the same name on multiple Flex platforms + // We need these - for Flex - because: + // During setup, the settings are loaded before we know which GNSS is present + // Previously, the setting would be applied to whichever GNSS is matched first alphabetically + // We need to apply these settings to all GNSS initially so that when we + // write the actual settings (vs the possible settings), the settings for + // that GNSS are correct + // (recordSystemSettings is called in multiple places: beginVersion, gnssDetectReceiverType, etc.) + // constellation_ is common to all GNSS, but not all support (e.g.) NavIC + // messageRateNMEA_, messageRateRTCMBase_, and messageRateRTCMRover_ are common to UM980 and LG290P + // The qualifier is defined inside updateSettingWithValue, parseLine + { 0, 0, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tCmnCnst, 0, nullptr, "constellation_", gnssCmdUpdateConstellations, }, + { 0, 0, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tCmnRtNm, 0, nullptr, "messageRateNMEA_", gnssCmdUpdateMessageRates, }, + { 0, 0, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tCnRtRtB, 0, nullptr, "messageRateRTCMBase_", gnssCmdUpdateMessageRates, }, + { 0, 0, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tCnRtRtR, 0, nullptr, "messageRateRTCMRover_", gnssCmdUpdateMessageRates, }, + + // <--- Insert any new essential "priority" (non-sorted) settings above this line ---> + + // endOfPrioritySettings is a special 'null' entry which does not appear in commandIndex + { 0, 0, 0, 0, 0, 0, 0, 0, 0, NON, 0, _bool, 0, nullptr, "endOfPrioritySettings", nullptr, }, + + // ======================================================================================================= + // Everything below here will be sorted (alphabetized) in commandIndex + // ======================================================================================================= + +// F +// a +// F c +// i a e +// n i c t +// W n u e +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd // Antenna - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _int16_t, 0, & settings.antennaHeight_mm, "antennaHeight_mm", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _float, 2, & settings.antennaPhaseCenter_mm, "antennaPhaseCenter_mm" }, - { 1, 1, 0, 1, 1, 1, 0, 1, 1, _uint16_t, 0, & settings.ARPLoggingInterval_s, "ARPLoggingInterval", }, - { 1, 1, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enableARPLogging, "enableARPLogging", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int16_t, 0, & settings.antennaHeight_mm, "antennaHeight_mm", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _float, 2, & settings.antennaPhaseCenter_mm, "antennaPhaseCenter_mm", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 1, ALL, 1, _uint16_t, 0, & settings.ARPLoggingInterval_s, "ARPLoggingInterval", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 1, ALL, 1, _bool, 0, & settings.enableARPLogging, "enableARPLogging", nullptr, }, // Base operation - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCoordInp, 0, & settings.coordinateInputType, "coordinateInputType", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _double, 4, & settings.fixedAltitude, "fixedAltitude", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.fixedBase, "fixedBase", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.fixedBaseCoordinateType, "fixedBaseCoordinateType", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _double, 3, & settings.fixedEcefX, "fixedEcefX", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _double, 3, & settings.fixedEcefY, "fixedEcefY", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _double, 3, & settings.fixedEcefZ, "fixedEcefZ", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _double, 9, & settings.fixedLat, "fixedLat", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _double, 9, & settings.fixedLong, "fixedLong", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _int, 0, & settings.observationSeconds, "observationSeconds", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _float, 2, & settings.observationPositionAccuracy, "observationPositionAccuracy", }, - { 0, 1, 0, 1, 1, 0, 1, 1, 1, _float, 1, & settings.surveyInStartingAccuracy, "surveyInStartingAccuracy", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCoordInp, 0, & settings.coordinateInputType, "coordinateInputType", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _double, 4, & settings.fixedAltitude, "fixedAltitude", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.fixedBase, "fixedBase", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.fixedBaseCoordinateType, "fixedBaseCoordinateType", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _double, 3, & settings.fixedEcefX, "fixedEcefX", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _double, 3, & settings.fixedEcefY, "fixedEcefY", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _double, 3, & settings.fixedEcefZ, "fixedEcefZ", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _double, 9, & settings.fixedLat, "fixedLat", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _double, 9, & settings.fixedLong, "fixedLong", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int, 0, & settings.observationSeconds, "observationSeconds", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _float, 2, & settings.observationPositionAccuracy, "observationPositionAccuracy", nullptr, }, + { 0, 1, 0, 1, 1, 0, 1, 1, 1, ALL, 1, _float, 1, & settings.surveyInStartingAccuracy, "surveyInStartingAccuracy", nullptr, }, + { 1, 1, 0, 0, 0, 0, 0, 0, 1, MSM, 1, _bool, 0, & settings.useMSM7, "useMSM7", nullptr, }, + { 1, 1, 0, 0, 0, 0, 0, 0, 1, MSM, 1, _int, 0, & settings.rtcmMinElev, "rtcmMinElev", nullptr, }, // Battery - { 0, 0, 0, 0, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePrintBatteryMessages, "enablePrintBatteryMessages", }, - { 1, 1, 0, 0, 1, 1, 1, 1, 1, _uint32_t, 0, & settings.shutdownNoChargeTimeoutMinutes, "shutdownNoChargeTimeoutMinutes", }, + { 0, 0, 0, 0, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePrintBatteryMessages, "enablePrintBatteryMessages", nullptr, }, + { 1, 1, 0, 0, 1, 1, 1, 1, 1, ALL, 1, _uint32_t, 0, & settings.shutdownNoChargeTimeoutMinutes, "shutdownNoChargeTimeoutMinutes", nullptr, }, // F // a @@ -1220,29 +1465,31 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + // Beeper - { 1, 1, 0, 0, 0, 0, 1, 0, 0, _bool, 0, & settings.enableBeeper, "enableBeeper", }, + { 1, 1, 0, 0, 0, 0, 1, 0, 0, ALL, 1, _bool, 0, & settings.enableBeeper, "enableBeeper", nullptr, }, // Bluetooth - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tBtRadio, 0, & settings.bluetoothRadioType, "bluetoothRadioType", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.sppRxQueueSize, "sppRxQueueSize", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.sppTxQueueSize, "sppTxQueueSize", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tBtRadio, 0, & settings.bluetoothRadioType, "bluetoothRadioType", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.sppRxQueueSize, "sppRxQueueSize", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.sppTxQueueSize, "sppTxQueueSize", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.clearBtPairings, "clearBtPairings", nullptr, }, // Corrections - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _int, 0, & settings.correctionsSourcesLifetime_s, "correctionsSourcesLifetime", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tCorrSPri, CORR_NUM, & settings.correctionsSourcesPriority, "correctionsPriority_", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugCorrections, "debugCorrections", }, - { 1, 1, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enableExtCorrRadio, "enableExtCorrRadio", }, - { 1, 1, 0, 1, 1, 0, 0, 1, 0, _uint8_t, 0, & settings.extCorrRadioSPARTNSource, "extCorrRadioSPARTNSource", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int, 0, & settings.correctionsSourcesLifetime_s, "correctionsSourcesLifetime", nullptr, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tCorrSPri, CORR_NUM, & settings.correctionsSourcesPriority, "correctionsPriority_", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugCorrections, "debugCorrections", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _uint8_t, 0, & settings.enableExtCorrRadio, "enableExtCorrRadio", nullptr, }, // uint8_t needed for 254 + { 1, 1, 0, 1, 1, 0, 0, 1, 0, NON, 0, _uint8_t, 0, & settings.extCorrRadioSPARTNSource, "extCorrRadioSPARTNSource", nullptr, }, // F // a @@ -1250,26 +1497,27 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + // Data Port Multiplexer - { 1, 1, 0, 0, 1, 1, 0, 1, 0, tMuxConn, 0, & settings.dataPortChannel, "dataPortChannel", }, + { 1, 1, 0, 0, 1, 1, 0, 1, 0, NON, 0, tMuxConn, 0, & settings.dataPortChannel, "dataPortChannel", nullptr, }, // Display - { 0, 0, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enableResetDisplay, "enableResetDisplay", }, + { 0, 0, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.enableResetDisplay, "enableResetDisplay", nullptr, }, // ESP Now - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugEspNow, "debugEspNow", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableEspNow, "enableEspNow", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.espnowPeerCount, "espnowPeerCount", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tEspNowPr, ESPNOW_MAX_PEERS, & settings.espnowPeers[0][0], "espnowPeer_", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugEspNow, "debugEspNow", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableEspNow, "enableEspNow", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.espnowPeerCount, "espnowPeerCount", nullptr, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tEspNowPr, ESPNOW_MAX_PEERS, & settings.espnowPeers[0][0], "espnowPeer_", nullptr, }, // F // a @@ -1277,48 +1525,53 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + // Ethernet - { 0, 0, 0, 1, 0, 0, 0, 0, 0, _bool, 0, & settings.enablePrintEthernetDiag, "enablePrintEthernetDiag", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _bool, 0, & settings.ethernetDHCP, "ethernetDHCP", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _IPString, 0, & settings.ethernetDNS, "ethernetDNS", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _IPString, 0, & settings.ethernetGateway, "ethernetGateway", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _IPString, 0, & settings.ethernetIP, "ethernetIP", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _IPString, 0, & settings.ethernetSubnet, "ethernetSubnet", }, + { 0, 0, 0, 1, 0, 0, 0, 0, 0, NON, 0, _bool, 0, & settings.enablePrintEthernetDiag, "enablePrintEthernetDiag", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _bool, 0, & settings.ethernetDHCP, "ethernetDHCP", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _IPString, 0, & settings.ethernetDNS, "ethernetDNS", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _IPString, 0, & settings.ethernetGateway, "ethernetGateway", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _IPString, 0, & settings.ethernetIP, "ethernetIP", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _IPString, 0, & settings.ethernetSubnet, "ethernetSubnet", nullptr, }, // Firmware - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint32_t, 0, & settings.autoFirmwareCheckMinutes, "autoFirmwareCheckMinutes", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugFirmwareUpdate, "debugFirmwareUpdate", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableAutoFirmwareUpdate, "enableAutoFirmwareUpdate", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint32_t, 0, & settings.autoFirmwareCheckMinutes, "autoFirmwareCheckMinutes", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugFirmwareUpdate, "debugFirmwareUpdate", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableAutoFirmwareUpdate, "enableAutoFirmwareUpdate", nullptr, }, // GNSS UART - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.serialGNSSRxFullThreshold, "serialGNSSRxFullThreshold", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _int, 0, & settings.uartReceiveBufferSize, "uartReceiveBufferSize", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.serialGNSSRxFullThreshold, "serialGNSSRxFullThreshold", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int, 0, & settings.uartReceiveBufferSize, "uartReceiveBufferSize", nullptr, }, // GNSS Receiver - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugGnss, "debugGnss", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePrintPosition, "enablePrintPosition", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.measurementRateMs, "measurementRateMs", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.navigationRate, "navigationRate", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.gnssConfiguredOnce, "gnssConfiguredOnce", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.gnssConfiguredBase, "gnssConfiguredBase", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.gnssConfiguredRover, "gnssConfiguredRover", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugGnss, "debugGnss", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePrintPosition, "enablePrintPosition", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.measurementRateMs, "measurementRateMs", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.navigationRate, "navigationRate", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.gnssConfiguredOnce, "gnssConfiguredOnce", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.gnssConfiguredBase, "gnssConfiguredBase", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.gnssConfiguredRover, "gnssConfiguredRover", nullptr, }, // Hardware - { 1, 1, 0, 1, 1, 1, 0, 1, 0, _bool, 0, & settings.enableExternalHardwareEventLogging, "enableExternalHardwareEventLogging", }, - { 0, 0, 0, 1, 1, 1, 0, 1, 1, _uint16_t, 0, & settings.spiFrequency, "spiFrequency", }, + { 1, 1, 0, 1, 1, 1, 0, 1, 0, NON, 0, _bool, 0, & settings.enableExternalHardwareEventLogging, "enableExternalHardwareEventLogging", nullptr, }, + { 0, 0, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _uint16_t, 0, & settings.spiFrequency, "spiFrequency", nullptr, }, // HTTP - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugHttpClientData, "debugHttpClientData", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugHttpClientState, "debugHttpClientState", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugHttpClientData, "debugHttpClientData", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugHttpClientState, "debugHttpClientState", nullptr, }, + + // IMU + { 0, 0, 0, 0, 0, 0, 0, 0, 0, ALL, 0, _bool, 0, & settings.detectedTilt, "detectedTilt", nullptr, }, + { 0, 0, 0, 0, 0, 0, 0, 0, 0, ALL, 0, _bool, 0, & settings.testedTilt, "testedTilt", nullptr, }, // F // a @@ -1326,49 +1579,100 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + // Log file - { 1, 1, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enableLogging, "enableLogging", }, - { 0, 0, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enablePrintLogFileMessages, "enablePrintLogFileMessages", }, - { 0, 0, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enablePrintLogFileStatus, "enablePrintLogFileStatus", }, - { 1, 1, 0, 1, 1, 1, 0, 1, 1, _int, 0, & settings.maxLogLength_minutes, "maxLogLength", }, - { 1, 1, 0, 1, 1, 1, 0, 1, 1, _int, 0, & settings.maxLogTime_minutes, "maxLogTime"}, + { 1, 1, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.alignedLogFiles, "alignedLogFiles", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.enableLogging, "enableLogging", nullptr, }, + { 0, 0, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.enablePrintLogFileMessages, "enablePrintLogFileMessages", nullptr, }, + { 0, 0, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.enablePrintLogFileStatus, "enablePrintLogFileStatus", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _int, 0, & settings.maxLogLength_minutes, "maxLogLength", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _int, 0, & settings.maxLogTime_minutes, "maxLogTime", nullptr, }, // Mosaic - #ifdef COMPILE_MOSAICX5 - { 1, 1, 1, 0, 0, 1, 0, 0, 0, tMosaicConst, MAX_MOSAIC_CONSTELLATIONS, & settings.mosaicConstellations, "constellation_", }, - { 1, 1, 1, 0, 0, 1, 0, 0, 0, tMosaicMSNmea, MAX_MOSAIC_NMEA_MSG, & settings.mosaicMessageStreamNMEA, "messageStreamNMEA_", }, - { 1, 1, 1, 0, 0, 1, 0, 0, 0, tMosaicSINmea, MOSAIC_NUM_NMEA_STREAMS, & settings.mosaicStreamIntervalsNMEA, "streamIntervalNMEA_", }, - { 1, 1, 1, 0, 0, 1, 0, 0, 0, tMosaicMIRvRT, MAX_MOSAIC_RTCM_V3_INTERVAL_GROUPS, & settings.mosaicMessageIntervalsRTCMv3Rover, "messageIntervalRTCMRover_", }, - { 1, 1, 1, 0, 0, 1, 0, 0, 0, tMosaicMIBaRT, MAX_MOSAIC_RTCM_V3_INTERVAL_GROUPS, & settings.mosaicMessageIntervalsRTCMv3Base, "messageIntervalRTCMBase_", }, - { 1, 1, 1, 0, 0, 1, 0, 0, 0, tMosaicMERvRT, MAX_MOSAIC_RTCM_V3_MSG, & settings.mosaicMessageEnabledRTCMv3Rover, "messageEnabledRTCMRover_", }, - { 1, 1, 1, 0, 0, 1, 0, 0, 0, tMosaicMEBaRT, MAX_MOSAIC_RTCM_V3_MSG, & settings.mosaicMessageEnabledRTCMv3Base, "messageEnabledRTCMBase_", }, - { 1, 1, 0, 0, 0, 1, 0, 0, 0, _bool, 0, & settings.enableLoggingRINEX, "enableLoggingRINEX", }, - { 1, 1, 0, 0, 0, 1, 0, 0, 0, _uint8_t, 0, & settings.RINEXFileDuration, "RINEXFileDuration", }, - { 1, 1, 0, 0, 0, 1, 0, 0, 0, _uint8_t, 0, & settings.RINEXObsInterval, "RINEXObsInterval", }, - { 1, 1, 0, 0, 0, 1, 0, 0, 0, _bool, 0, & settings.externalEventPolarity, "externalEventPolarity", }, + { 1, 1, 1, 0, 0, 1, 0, 0, 0, MX5, 0, tMosaicConst, MAX_MOSAIC_CONSTELLATIONS, & settings.mosaicConstellations, "constellation_", gnssCmdUpdateConstellations, }, + { 1, 1, 1, 0, 0, 1, 0, 0, 0, MX5, 0, tMosaicMSNmea, MAX_MOSAIC_NMEA_MSG, & settings.mosaicMessageStreamNMEA, "messageStreamNMEA_", gnssCmdUpdateMessageRates, }, + { 1, 1, 1, 0, 0, 1, 0, 0, 0, MX5, 0, tMosaicSINmea, MOSAIC_NUM_NMEA_STREAMS, & settings.mosaicStreamIntervalsNMEA, "streamIntervalNMEA_", gnssCmdUpdateMessageRates, }, + { 1, 1, 1, 0, 0, 1, 0, 0, 0, MX5, 0, tMosaicMIRvRT, MAX_MOSAIC_RTCM_V3_INTERVAL_GROUPS, & settings.mosaicMessageIntervalsRTCMv3Rover, "messageIntervalRTCMRover_", gnssCmdUpdateMessageRates, }, + { 1, 1, 1, 0, 0, 1, 0, 0, 0, MX5, 0, tMosaicMIBaRT, MAX_MOSAIC_RTCM_V3_INTERVAL_GROUPS, & settings.mosaicMessageIntervalsRTCMv3Base, "messageIntervalRTCMBase_", gnssCmdUpdateMessageRates, }, + { 1, 1, 1, 0, 0, 1, 0, 0, 0, MX5, 0, tMosaicMERvRT, MAX_MOSAIC_RTCM_V3_MSG, & settings.mosaicMessageEnabledRTCMv3Rover, "messageEnabledRTCMRover_", gnssCmdUpdateMessageRates, }, + { 1, 1, 1, 0, 0, 1, 0, 0, 0, MX5, 0, tMosaicMEBaRT, MAX_MOSAIC_RTCM_V3_MSG, & settings.mosaicMessageEnabledRTCMv3Base, "messageEnabledRTCMBase_", gnssCmdUpdateMessageRates, }, + { 1, 1, 0, 0, 0, 1, 0, 0, 0, MX5, 0, _bool, 0, & settings.enableLoggingRINEX, "enableLoggingRINEX", nullptr, }, + { 1, 1, 0, 0, 0, 1, 0, 0, 0, MX5, 0, _uint8_t, 0, & settings.RINEXFileDuration, "RINEXFileDuration", nullptr, }, + { 1, 1, 0, 0, 0, 1, 0, 0, 0, MX5, 0, _uint8_t, 0, & settings.RINEXObsInterval, "RINEXObsInterval", nullptr, }, + { 1, 1, 0, 0, 0, 1, 0, 0, 0, NON, 0, _bool, 0, & settings.externalEventPolarity, "externalEventPolarity", nullptr, }, #endif // COMPILE_MOSAICX5 // MQTT - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugMqttClientData, "debugMqttClientData", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugMqttClientState, "debugMqttClientState", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugMqttClientData, "debugMqttClientData", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugMqttClientState, "debugMqttClientState", nullptr, }, // Multicast DNS - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.mdnsEnable, "mdnsEnable", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.mdnsHostName), & settings.mdnsHostName, "mdnsHostName", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.mdnsEnable, "mdnsEnable", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.mdnsHostName), & settings.mdnsHostName, "mdnsHostName", nullptr, }, // Network layer - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugNetworkLayer, "debugNetworkLayer", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.printNetworkStatus, "printNetworkStatus", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugNetworkLayer, "debugNetworkLayer", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.printNetworkStatus, "printNetworkStatus", nullptr, }, + +// F +// a +// F c +// i a e +// n i c t +// W n u e +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + + + // NTP (Ethernet Only) + { 0, 0, 0, 1, 0, 0, 0, 0, 0, NON, 0, _bool, 0, & settings.debugNtp, "debugNtp", nullptr, }, + { 0, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _bool, 0, & settings.enableNTPFile, "enableNTPFile", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _uint16_t, 0, & settings.ethernetNtpPort, "ethernetNtpPort", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _uint8_t, 0, & settings.ntpPollExponent, "ntpPollExponent", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _int8_t, 0, & settings.ntpPrecision, "ntpPrecision", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, tCharArry, sizeof(settings.ntpReferenceId), & settings.ntpReferenceId, "ntpReferenceId", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _uint32_t, 0, & settings.ntpRootDelay, "ntpRootDelay", nullptr, }, + { 1, 1, 0, 1, 0, 0, 0, 0, 0, NON, 0, _uint32_t, 0, & settings.ntpRootDispersion, "ntpRootDispersion", nullptr, }, + + // NTRIP Client + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugNtripClientRtcm, "debugNtripClientRtcm", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugNtripClientState, "debugNtripClientState", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableNtripClient, "enableNtripClient", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.ntripClient_CasterHost), & settings.ntripClient_CasterHost, "ntripClientCasterHost", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.ntripClient_CasterPort, "ntripClientCasterPort", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.ntripClient_CasterUser), & settings.ntripClient_CasterUser, "ntripClientCasterUser", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.ntripClient_CasterUserPW), & settings.ntripClient_CasterUserPW, "ntripClientCasterUserPW", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.ntripClient_MountPoint), & settings.ntripClient_MountPoint, "ntripClientMountPoint", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.ntripClient_MountPointPW), & settings.ntripClient_MountPointPW, "ntripClientMountPointPW", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.ntripClient_TransmitGGA, "ntripClientTransmitGGA", nullptr, }, + + // NTRIP Server + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugNtripServerRtcm, "debugNtripServerRtcm", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugNtripServerState, "debugNtripServerState", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableNtripServer, "enableNtripServer", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableRtcmMessageChecking, "enableRtcmMessageChecking", nullptr, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tNSCHost, NTRIP_SERVER_MAX, & settings.ntripServer_CasterHost[0], "ntripServerCasterHost_", nullptr, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tNSCPort, NTRIP_SERVER_MAX, & settings.ntripServer_CasterPort[0], "ntripServerCasterPort_", nullptr, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tNSCUser, NTRIP_SERVER_MAX, & settings.ntripServer_CasterUser[0], "ntripServerCasterUser_", nullptr, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tNSCUsrPw, NTRIP_SERVER_MAX, & settings.ntripServer_CasterUserPW[0], "ntripServerCasterUserPW_", nullptr, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tNSMtPt, NTRIP_SERVER_MAX, & settings.ntripServer_MountPoint[0], "ntripServerMountPoint_", nullptr, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tNSMtPtPw, NTRIP_SERVER_MAX, & settings.ntripServer_MountPointPW[0], "ntripServerMountPointPW_", nullptr, }, // F // a @@ -1383,91 +1687,58 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // n a f t s o B c // f n f E a r a a // i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name - - // NTP (Ethernet Only) - { 0, 0, 0, 1, 0, 0, 0, 0, 0, _bool, 0, & settings.debugNtp, "debugNtp", }, - { 0, 1, 0, 1, 0, 0, 0, 0, 0, _bool, 0, & settings.enableNTPFile, "enableNTPFile", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _uint16_t, 0, & settings.ethernetNtpPort, "ethernetNtpPort", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _uint8_t, 0, & settings.ntpPollExponent, "ntpPollExponent", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _int8_t, 0, & settings.ntpPrecision, "ntpPrecision", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, tCharArry, sizeof(settings.ntpReferenceId), & settings.ntpReferenceId, "ntpReferenceId", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _uint32_t, 0, & settings.ntpRootDelay, "ntpRootDelay", }, - { 1, 1, 0, 1, 0, 0, 0, 0, 0, _uint32_t, 0, & settings.ntpRootDispersion, "ntpRootDispersion", }, - - // NTRIP Client - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugNtripClientRtcm, "debugNtripClientRtcm", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugNtripClientState, "debugNtripClientState", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableNtripClient, "enableNtripClient", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.ntripClient_CasterHost), & settings.ntripClient_CasterHost, "ntripClientCasterHost", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.ntripClient_CasterPort, "ntripClientCasterPort", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.ntripClient_CasterUser), & settings.ntripClient_CasterUser, "ntripClientCasterUser", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.ntripClient_CasterUserPW), & settings.ntripClient_CasterUserPW, "ntripClientCasterUserPW", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.ntripClient_MountPoint), & settings.ntripClient_MountPoint, "ntripClientMountPoint", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.ntripClient_MountPointPW), & settings.ntripClient_MountPointPW, "ntripClientMountPointPW", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.ntripClient_TransmitGGA, "ntripClientTransmitGGA", }, - - // NTRIP Server - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugNtripServerRtcm, "debugNtripServerRtcm", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugNtripServerState, "debugNtripServerState", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableNtripServer, "enableNtripServer", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableRtcmMessageChecking, "enableRtcmMessageChecking", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tNSCHost, NTRIP_SERVER_MAX, & settings.ntripServer_CasterHost[0], "ntripServerCasterHost_", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tNSCPort, NTRIP_SERVER_MAX, & settings.ntripServer_CasterPort[0], "ntripServerCasterPort_", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tNSCUser, NTRIP_SERVER_MAX, & settings.ntripServer_CasterUser[0], "ntripServerCasterUser_", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tNSCUsrPw, NTRIP_SERVER_MAX, & settings.ntripServer_CasterUserPW[0], "ntripServerCasterUserPW_", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tNSMtPt, NTRIP_SERVER_MAX, & settings.ntripServer_MountPoint[0], "ntripServerMountPoint_", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tNSMtPtPw, NTRIP_SERVER_MAX, & settings.ntripServer_MountPointPW[0], "ntripServerMountPointPW_", }, +// g s x k 2 c h d d Type Qual Variable Name afterSetCmd // OS - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.bluetoothInterruptsCore, "bluetoothInterruptsCore", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.btReadTaskCore, "btReadTaskCore", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.btReadTaskPriority, "btReadTaskPriority", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugMalloc, "debugMalloc", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableHeapReport, "enableHeapReport", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePrintIdleTime, "enablePrintIdleTime", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePsram, "enablePsram", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableTaskReports, "enableTaskReports", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.gnssReadTaskCore, "gnssReadTaskCore", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.gnssReadTaskPriority, "gnssReadTaskPriority", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.gnssUartInterruptsCore, "gnssUartInterruptsCore", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.handleGnssDataTaskCore, "handleGnssDataTaskCore", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.handleGnssDataTaskPriority, "handleGnssDataTaskPriority", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.i2cInterruptsCore, "i2cInterruptsCore", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.measurementScale, "measurementScale", }, //Don't show on Config - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.printBootTimes, "printBootTimes", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.printPartitionTable, "printPartitionTable", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.printTaskStartStop, "printTaskStartStop", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.psramMallocLevel, "psramMallocLevel", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint32_t, 0, & settings.rebootMinutes, "rebootMinutes", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _int, 0, & settings.resetCount, "resetCount", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.bluetoothInterruptsCore, "bluetoothInterruptsCore", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.btReadTaskCore, "btReadTaskCore", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.btReadTaskPriority, "btReadTaskPriority", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugMalloc, "debugMalloc", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableHeapReport, "enableHeapReport", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePrintIdleTime, "enablePrintIdleTime", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePsram, "enablePsram", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableTaskReports, "enableTaskReports", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.gnssReadTaskCore, "gnssReadTaskCore", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.gnssReadTaskPriority, "gnssReadTaskPriority", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.gnssUartInterruptsCore, "gnssUartInterruptsCore", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.haltOnPanic, "haltOnPanic", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.handleGnssDataTaskCore, "handleGnssDataTaskCore", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.handleGnssDataTaskPriority, "handleGnssDataTaskPriority", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.i2cInterruptsCore, "i2cInterruptsCore", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.measurementScale, "measurementScale", nullptr, }, //Don't show on Config + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.printBootTimes, "printBootTimes", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.printPartitionTable, "printPartitionTable", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.printTaskStartStop, "printTaskStartStop", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.psramMallocLevel, "psramMallocLevel", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint32_t, 0, & settings.rebootMinutes, "rebootMinutes", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int, 0, & settings.resetCount, "resetCount", nullptr, }, // Periodic Display - { 0, 0, 0, 1, 1, 1, 1, 1, 1, tPerDisp, 0, & settings.periodicDisplay, "periodicDisplay", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint32_t, 0, & settings.periodicDisplayInterval, "periodicDisplayInterval", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tPerDisp, 0, & settings.periodicDisplay, "periodicDisplay", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint32_t, 0, & settings.periodicDisplayInterval, "periodicDisplayInterval", nullptr, }, // Point Perfect - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.autoKeyRenewal, "autoKeyRenewal", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugPpCertificate, "debugPpCertificate", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _int, 0, & settings.geographicRegion, "geographicRegion", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint64_t, 0, & settings.lastKeyAttempt, "lastKeyAttempt", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.lbandFixTimeout_seconds, "lbandFixTimeout", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.pointPerfectBrokerHost), & settings.pointPerfectBrokerHost, "pointPerfectBrokerHost", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.pointPerfectClientID), & settings.pointPerfectClientID, "pointPerfectClientID", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.pointPerfectCurrentKey), & settings.pointPerfectCurrentKey, "pointPerfectCurrentKey", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint64_t, 0, & settings.pointPerfectCurrentKeyDuration, "pointPerfectCurrentKeyDuration", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint64_t, 0, & settings.pointPerfectCurrentKeyStart, "pointPerfectCurrentKeyStart", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.pointPerfectDeviceProfileToken), & settings.pointPerfectDeviceProfileToken, "pointPerfectDeviceProfileToken", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.pointPerfectKeyDistributionTopic), & settings.pointPerfectKeyDistributionTopic, "pointPerfectKeyDistributionTopic", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.pointPerfectNextKey), & settings.pointPerfectNextKey, "pointPerfectNextKey", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint64_t, 0, & settings.pointPerfectNextKeyDuration, "pointPerfectNextKeyDuration", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint64_t, 0, & settings.pointPerfectNextKeyStart, "pointPerfectNextKeyStart", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.pplFixTimeoutS, "pplFixTimeoutS", }, - { 0, 0, 1, 1, 1, 1, 1, 1, 1, tRegCorTp, numRegionalAreas, & settings.regionalCorrectionTopics, "regionalCorrectionTopics_", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.pointPerfectService, "pointPerfectService", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.autoKeyRenewal, "autoKeyRenewal", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugPpCertificate, "debugPpCertificate", nullptr, }, + { 1, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int, 0, & settings.geographicRegion, "geographicRegion", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint64_t, 0, & settings.lastKeyAttempt, "lastKeyAttempt", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.lbandFixTimeout_seconds, "lbandFixTimeout", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.pointPerfectBrokerHost), & settings.pointPerfectBrokerHost, "pointPerfectBrokerHost", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.pointPerfectClientID), & settings.pointPerfectClientID, "pointPerfectClientID", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.pointPerfectCurrentKey), & settings.pointPerfectCurrentKey, "pointPerfectCurrentKey", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint64_t, 0, & settings.pointPerfectCurrentKeyDuration, "pointPerfectCurrentKeyDuration", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint64_t, 0, & settings.pointPerfectCurrentKeyStart, "pointPerfectCurrentKeyStart", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.pointPerfectDeviceProfileToken), & settings.pointPerfectDeviceProfileToken, "pointPerfectDeviceProfileToken", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.pointPerfectKeyDistributionTopic), & settings.pointPerfectKeyDistributionTopic, "pointPerfectKeyDistributionTopic", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.pointPerfectNextKey), & settings.pointPerfectNextKey, "pointPerfectNextKey", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint64_t, 0, & settings.pointPerfectNextKeyDuration, "pointPerfectNextKeyDuration", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint64_t, 0, & settings.pointPerfectNextKeyStart, "pointPerfectNextKeyStart", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.pplFixTimeoutS, "pplFixTimeoutS", nullptr, }, + { 0, 0, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tRegCorTp, numRegionalAreas, & settings.regionalCorrectionTopics, "regionalCorrectionTopics_", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.pointPerfectService, "pointPerfectService", nullptr, }, // Profiles - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.profileName), & settings.profileName, "profileName", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.profileName), & settings.profileName, "profileName", nullptr, }, // F // a @@ -1475,33 +1746,34 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + // Pulse Per Second - { 1, 1, 0, 1, 1, 1, 0, 1, 0, _bool, 0, & settings.enableExternalPulse, "enableExternalPulse", }, - { 1, 1, 0, 1, 1, 1, 0, 1, 0, _uint64_t, 0, & settings.externalPulseLength_us, "externalPulseLength", }, - { 1, 1, 0, 1, 1, 1, 0, 1, 0, tPulseEdg, 0, & settings.externalPulsePolarity, "externalPulsePolarity", }, - { 1, 1, 0, 1, 1, 1, 0, 1, 0, _uint64_t, 0, & settings.externalPulseTimeBetweenPulse_us, "externalPulseTimeBetweenPulse", }, + { 1, 1, 0, 1, 1, 1, 0, 1, 0, NON, 0, _bool, 0, & settings.enableExternalPulse, "enableExternalPulse", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 0, NON, 0, _uint64_t, 0, & settings.externalPulseLength_us, "externalPulseLength", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 0, NON, 0, tPulseEdg, 0, & settings.externalPulsePolarity, "externalPulsePolarity", nullptr, }, + { 1, 1, 0, 1, 1, 1, 0, 1, 0, NON, 0, _uint64_t, 0, & settings.externalPulseTimeBetweenPulse_us, "externalPulseTimeBetweenPulse", nullptr, }, // Ring Buffer - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePrintRingBufferOffsets, "enablePrintRingBufferOffsets", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _int, 0, & settings.gnssHandlerBufferSize, "gnssHandlerBufferSize", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePrintRingBufferOffsets, "enablePrintRingBufferOffsets", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int, 0, & settings.gnssHandlerBufferSize, "gnssHandlerBufferSize", nullptr, }, // Rover operation - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.dynamicModel, "dynamicModel", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePrintRoverAccuracy, "enablePrintRoverAccuracy", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _int16_t, 0, & settings.minCNO, "minCNO", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.minElev, "minElev", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 0, ALL, 0, _uint8_t, 0, & settings.dynamicModel, "dynamicModel", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePrintRoverAccuracy, "enablePrintRoverAccuracy", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int16_t, 0, & settings.minCNO, "minCNO", nullptr, }, // Not inWebConfig - createSettingsString gets from GNSS + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.minElev, "minElev", nullptr, }, // RTC (Real Time Clock) - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePrintRtcSync, "enablePrintRtcSync", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePrintRtcSync, "enablePrintRtcSync", nullptr, }, // F // a @@ -1509,28 +1781,29 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + // SD Card - { 0, 0, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enablePrintBufferOverrun, "enablePrintBufferOverrun", }, - { 0, 0, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enablePrintSDBuffers, "enablePrintSDBuffers", }, - { 0, 0, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.enableSD, "enableSD"}, - { 0, 0, 0, 1, 1, 1, 0, 1, 1, _bool, 0, & settings.forceResetOnSDFail, "forceResetOnSDFail", }, + { 0, 0, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.enablePrintBufferOverrun, "enablePrintBufferOverrun", nullptr, }, + { 0, 0, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.enablePrintSDBuffers, "enablePrintSDBuffers", nullptr, }, + { 0, 0, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.enableSD, "enableSD", nullptr, }, + { 0, 0, 0, 1, 1, 1, 0, 1, 1, ALL, 0, _bool, 0, & settings.forceResetOnSDFail, "forceResetOnSDFail", nullptr, }, // Serial - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint32_t, 0, & settings.dataPortBaud, "dataPortBaud", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.echoUserInput, "echoUserInput", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableGnssToUsbSerial, "enableGnssToUsbSerial", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint32_t, 0, & settings.radioPortBaud, "radioPortBaud", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _int16_t, 0, & settings.serialTimeoutGNSS, "serialTimeoutGNSS", }, - { 1, 1, 0, 0, 0, 1, 0, 0, 1, _bool, 0, & settings.enableNmeaOnRadio, "enableNmeaOnRadio", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint32_t, 0, & settings.dataPortBaud, "dataPortBaud", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.echoUserInput, "echoUserInput", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableGnssToUsbSerial, "enableGnssToUsbSerial", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint32_t, 0, & settings.radioPortBaud, "radioPortBaud", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int16_t, 0, & settings.serialTimeoutGNSS, "serialTimeoutGNSS", nullptr, }, + { 1, 1, 0, 0, 0, 1, 0, 0, 1, ALL, 0, _bool, 0, & settings.enableNmeaOnRadio, "enableNmeaOnRadio", nullptr, }, // F // a @@ -1538,39 +1811,40 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + // Setup Button - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.disableSetupButton, "disableSetupButton", }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.disableSetupButton, "disableSetupButton", nullptr, }, // State - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePrintDuplicateStates, "enablePrintDuplicateStates", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enablePrintStates, "enablePrintStates", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tSysState, 0, & settings.lastState, "lastState", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePrintDuplicateStates, "enablePrintDuplicateStates", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enablePrintStates, "enablePrintStates", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tSysState, 0, & settings.lastState, "lastState", nullptr, }, // Not inWebConfig - must be changed to 0:3 by createSettingsString // TCP Client - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugTcpClient, "debugTcpClient", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableTcpClient, "enableTcpClient", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, tCharArry, sizeof(settings.tcpClientHost), & settings.tcpClientHost, "tcpClientHost", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.tcpClientPort, "tcpClientPort", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugTcpClient, "debugTcpClient", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableTcpClient, "enableTcpClient", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, tCharArry, sizeof(settings.tcpClientHost), & settings.tcpClientHost, "tcpClientHost", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.tcpClientPort, "tcpClientPort", nullptr, }, // TCP Server - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugTcpServer, "debugTcpServer", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableTcpServer, "enableTcpServer", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.tcpServerPort, "tcpServerPort", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.tcpUdpOverWiFiStation, "tcpUdpOverWiFiStation", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugTcpServer, "debugTcpServer", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableTcpServer, "enableTcpServer", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.tcpServerPort, "tcpServerPort", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.tcpOverWiFiStation, "tcpOverWiFiStation", nullptr, }, // Time Zone - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _int8_t, 0, & settings.timeZoneHours, "timeZoneHours", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _int8_t, 0, & settings.timeZoneMinutes, "timeZoneMinutes", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _int8_t, 0, & settings.timeZoneSeconds, "timeZoneSeconds", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int8_t, 0, & settings.timeZoneHours, "timeZoneHours", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int8_t, 0, & settings.timeZoneMinutes, "timeZoneMinutes", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _int8_t, 0, & settings.timeZoneSeconds, "timeZoneSeconds", nullptr, }, // F // a @@ -1578,26 +1852,28 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + // ublox GNSS Receiver #ifdef COMPILE_ZED - { 1, 1, 1, 1, 1, 0, 0, 1, 0, tUbxConst, MAX_UBX_CONSTELLATIONS, & settings.ubxConstellations[0], "constellation_", }, - { 0, 1, 1, 1, 1, 0, 0, 1, 0, tUbxMsgRt, MAX_UBX_MSG, & settings.ubxMessageRates[0], "ubxMessageRate_", }, - { 0, 1, 1, 1, 1, 0, 0, 1, 0, tUbMsgRtb, MAX_UBX_MSG_RTCM, & settings.ubxMessageRatesBase[0], "ubxMessageRateBase_", }, + { 1, 1, 1, 1, 1, 0, 0, 1, 0, ZED, 0, tUbxConst, MAX_UBX_CONSTELLATIONS, & settings.ubxConstellations[0], "constellation_", gnssCmdUpdateConstellations, }, + { 0, 1, 1, 1, 1, 0, 0, 1, 0, ZED, 0, tUbxMsgRt, MAX_UBX_MSG, & settings.ubxMessageRates[0], "ubxMessageRate_", gnssCmdUpdateMessageRates, }, + { 0, 1, 1, 1, 1, 0, 0, 1, 0, ZED, 0, tUbMsgRtb, MAX_UBX_MSG_RTCM, & settings.ubxMessageRatesBase[0], "ubxMessageRateBase_", gnssCmdUpdateMessageRates, }, #endif // COMPILE_ZED // UDP Server - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugUdpServer, "debugUdpServer", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableUdpServer, "enableUdpServer", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.udpServerPort, "udpServerPort", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugUdpServer, "debugUdpServer", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableUdpServer, "enableUdpServer", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.udpServerPort, "udpServerPort", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.udpOverWiFiStation, "udpOverWiFiStation", nullptr, }, // F // a @@ -1605,53 +1881,55 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd + + // UM980 GNSS Receiver - TODO these apply to more than UM980 + { 1, 1, 0, 0, 0, 0, 1, 0, 1, HAS, 1, _bool, 0, & settings.enableGalileoHas, "enableGalileoHas", nullptr, }, + { 1, 1, 0, 0, 0, 0, 1, 0, 0, ALL, 0, _bool, 3, & settings.enableMultipathMitigation, "enableMultipathMitigation", nullptr, }, + { 0, 0, 0, 0, 0, 0, 1, 0, 0, ALL, 0, _bool, 0, & settings.enableImuCompensationDebug, "enableImuCompensationDebug", nullptr, }, + { 0, 0, 0, 0, 0, 0, 1, 0, 0, ALL, 0, _bool, 0, & settings.enableImuDebug, "enableImuDebug", nullptr, }, + { 1, 1, 0, 0, 0, 0, 1, 0, 0, ALL, 0, _bool, 0, & settings.enableTiltCompensation, "enableTiltCompensation", nullptr, }, - // UM980 GNSS Receiver - { 1, 1, 0, 0, 0, 0, 1, 0, 0, _bool, 0, & settings.enableGalileoHas, "enableGalileoHas", }, - { 0, 0, 0, 0, 0, 0, 1, 0, 0, _bool, 0, & settings.enableImuCompensationDebug, "enableImuCompensationDebug", }, - { 0, 0, 0, 0, 0, 0, 1, 0, 0, _bool, 0, & settings.enableImuDebug, "enableImuDebug", }, - { 1, 1, 0, 0, 0, 0, 1, 0, 0, _bool, 0, & settings.enableTiltCompensation, "enableTiltCompensation", }, #ifdef COMPILE_UM980 - { 1, 1, 1, 0, 0, 0, 1, 0, 0, tUmConst, MAX_UM980_CONSTELLATIONS, & settings.um980Constellations, "constellation_", }, - { 0, 1, 1, 0, 0, 0, 1, 0, 0, tUmMRNmea, MAX_UM980_NMEA_MSG, & settings.um980MessageRatesNMEA, "messageRateNMEA_", }, - { 0, 1, 1, 0, 0, 0, 1, 0, 0, tUmMRBaRT, MAX_UM980_RTCM_MSG, & settings.um980MessageRatesRTCMBase, "messageRateRTCMBase_", }, - { 0, 1, 1, 0, 0, 0, 1, 0, 0, tUmMRRvRT, MAX_UM980_RTCM_MSG, & settings.um980MessageRatesRTCMRover, "messageRateRTCMRover_", }, + { 1, 1, 1, 0, 0, 0, 1, 0, 0, U98, 0, tUmConst, MAX_UM980_CONSTELLATIONS, & settings.um980Constellations, "constellation_", gnssCmdUpdateConstellations, }, + { 0, 1, 1, 0, 0, 0, 1, 0, 0, U98, 0, tUmMRNmea, MAX_UM980_NMEA_MSG, & settings.um980MessageRatesNMEA, "messageRateNMEA_", gnssCmdUpdateMessageRates, }, + { 0, 1, 1, 0, 0, 0, 1, 0, 0, U98, 0, tUmMRBaRT, MAX_UM980_RTCM_MSG, & settings.um980MessageRatesRTCMBase, "messageRateRTCMBase_", gnssCmdUpdateMessageRates, }, + { 0, 1, 1, 0, 0, 0, 1, 0, 0, U98, 0, tUmMRRvRT, MAX_UM980_RTCM_MSG, & settings.um980MessageRatesRTCMRover, "messageRateRTCMRover_", gnssCmdUpdateMessageRates, }, #endif // COMPILE_UM980 // Web Server - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint16_t, 0, & settings.httpPort, "httpPort", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.httpPort, "httpPort", nullptr, }, // WiFi - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugWebServer, "debugWebServer", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugWifiState, "debugWifiState", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableCaptivePortal, "enableCaptivePortal", }, - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _uint8_t, 0, & settings.wifiChannel, "wifiChannel", }, - { 1, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.wifiConfigOverAP, "wifiConfigOverAP", }, - { 1, 1, 1, 1, 1, 1, 1, 1, 1, tWiFiNet, MAX_WIFI_NETWORKS, & settings.wifiNetworks, "wifiNetwork_", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _uint32_t, 0, & settings.wifiConnectTimeoutMs, "wifiConnectTimeoutMs", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugWebServer, "debugWebServer", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugWifiState, "debugWifiState", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableCaptivePortal, "enableCaptivePortal", wifiAfterCommand, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.wifiChannel, "wifiChannel", wifiAfterCommand, }, + { 1, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.wifiConfigOverAP, "wifiConfigOverAP", wifiAfterCommand, }, + { 1, 1, 1, 1, 1, 1, 1, 1, 1, ALL, 1, tWiFiNet, MAX_WIFI_NETWORKS, & settings.wifiNetworks, "wifiNetwork_", wifiAfterCommand, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint32_t, 0, & settings.wifiConnectTimeoutMs, "wifiConnectTimeoutMs", nullptr, }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _uint32_t, 0, & settings.outputTipAltitude, "outputTipAltitude", }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.outputTipAltitude, "outputTipAltitude", nullptr, }, // Localized distribution - { 1, 1, 0, 1, 1, 0, 1, 1, 1, _bool, 0, & settings.useLocalizedDistribution, "useLocalizedDistribution", }, - { 1, 1, 0, 1, 1, 0, 1, 1, 1, _uint8_t, 0, & settings.localizedDistributionTileLevel, "localizedDistributionTileLevel", }, - { 1, 1, 0, 1, 1, 0, 1, 1, 1, _bool, 0, & settings.useAssistNow, "useAssistNow", }, + { 1, 0, 0, 1, 1, 0, 1, 1, 1, ALL, 1, _bool, 0, & settings.useLocalizedDistribution, "useLocalizedDistribution", nullptr, }, + { 1, 0, 0, 1, 1, 0, 1, 1, 1, ALL, 1, _uint8_t, 0, & settings.localizedDistributionTileLevel, "localizedDistributionTileLevel", nullptr, }, + { 1, 0, 0, 1, 1, 0, 1, 1, 1, ALL, 1, _bool, 0, & settings.useAssistNow, "useAssistNow", nullptr, }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.requestKeyUpdate, "requestKeyUpdate", }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.requestKeyUpdate, "requestKeyUpdate", nullptr, }, - { 1, 1, 0, 0, 0, 0, 1, 0, 0, _bool, 0, & settings.enableLora, "enableLora", }, - { 1, 1, 0, 0, 0, 0, 1, 0, 0, _float, 3, & settings.loraCoordinationFrequency, "loraCoordinationFrequency", }, - { 0, 0, 0, 0, 0, 0, 1, 0, 0, _bool, 3, & settings.debugLora, "debugLora", }, - { 1, 1, 0, 0, 0, 0, 1, 0, 0, _int, 3, & settings.loraSerialInteractionTimeout_s, "loraSerialInteractionTimeout_s", }, - { 1, 1, 0, 0, 0, 0, 1, 0, 0, _bool, 3, & settings.enableMultipathMitigation, "enableMultipathMitigation", }, + // LoRa + { 1, 1, 0, 0, 0, 0, 1, 0, 0, ALL, 0, _bool, 0, & settings.enableLora, "enableLora", nullptr, }, + { 1, 1, 0, 0, 0, 0, 1, 0, 0, ALL, 0, _float, 3, & settings.loraCoordinationFrequency, "loraCoordinationFrequency", nullptr, }, + { 0, 0, 0, 0, 0, 0, 1, 0, 0, ALL, 0, _bool, 3, & settings.debugLora, "debugLora", nullptr, }, + { 1, 1, 0, 0, 0, 0, 1, 0, 0, ALL, 0, _int, 3, & settings.loraSerialInteractionTimeout_s, "loraSerialInteractionTimeout_s", nullptr, }, // F // a @@ -1659,26 +1937,30 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd #ifdef COMPILE_LG290P - { 1, 1, 1, 0, 0, 0, 0, 0, 1, tLgConst, MAX_LG290P_CONSTELLATIONS, & settings.lg290pConstellations, "constellation_", }, - { 0, 1, 1, 0, 0, 0, 0, 0, 1, tLgMRNmea, MAX_LG290P_NMEA_MSG, & settings.lg290pMessageRatesNMEA, "messageRateNMEA_", }, - { 0, 1, 1, 0, 0, 0, 0, 0, 1, tLgMRBaRT, MAX_LG290P_RTCM_MSG, & settings.lg290pMessageRatesRTCMBase, "messageRateRTCMBase_", }, - { 0, 1, 1, 0, 0, 0, 0, 0, 1, tLgMRRvRT, MAX_LG290P_RTCM_MSG, & settings.lg290pMessageRatesRTCMRover, "messageRateRTCMRover_", }, - { 0, 1, 1, 0, 0, 0, 0, 0, 1, tLgMRPqtm, MAX_LG290P_PQTM_MSG, & settings.lg290pMessageRatesPQTM, "messageRatePQTM_", }, + { 1, 1, 1, 0, 0, 0, 0, 0, 1, L29, 1, tLgConst, MAX_LG290P_CONSTELLATIONS, & settings.lg290pConstellations, "constellation_", gnssCmdUpdateConstellations, }, + { 0, 1, 1, 0, 0, 0, 0, 0, 1, L29, 1, tLgMRNmea, MAX_LG290P_NMEA_MSG, & settings.lg290pMessageRatesNMEA, "messageRateNMEA_", gnssCmdUpdateMessageRates, }, + { 0, 1, 1, 0, 0, 0, 0, 0, 1, L29, 1, tLgMRBaRT, MAX_LG290P_RTCM_MSG, & settings.lg290pMessageRatesRTCMBase, "messageRateRTCMBase_", gnssCmdUpdateMessageRates, }, + { 0, 1, 1, 0, 0, 0, 0, 0, 1, L29, 1, tLgMRRvRT, MAX_LG290P_RTCM_MSG, & settings.lg290pMessageRatesRTCMRover, "messageRateRTCMRover_", gnssCmdUpdateMessageRates, }, + { 0, 1, 1, 0, 0, 0, 0, 0, 1, L29, 1, tLgMRPqtm, MAX_LG290P_PQTM_MSG, & settings.lg290pMessageRatesPQTM, "messageRatePQTM_", gnssCmdUpdateMessageRates, }, + { 1, 1, 0, 0, 0, 0, 0, 0, 1, L29, 1, tCharArry, sizeof(settings.configurePPP), & settings.configurePPP, "configurePPP", nullptr, }, #endif // COMPILE_LG290P - { 0, 0, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.debugSettings, "debugSettings", }, - { 1, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.enableNtripCaster, "enableNtripCaster", }, - { 0, 1, 0, 1, 1, 1, 1, 1, 1, _bool, 0, & settings.baseCasterOverride, "baseCasterOverride", }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugSettings, "debugSettings", nullptr, }, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.enableNtripCaster, "enableNtripCaster", nullptr, }, + { 0, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.baseCasterOverride, "baseCasterOverride", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _bool, 0, & settings.debugCLI, "debugCLI", nullptr, }, + { 0, 0, 0, 1, 1, 1, 1, 1, 1, ALL, 1, _uint16_t, 0, & settings.cliBlePrintDelay_ms, "cliBlePrintDelay_ms", nullptr, }, + // Add new settings to appropriate group above or create new group // Then also add to the same group in settings above @@ -1688,17 +1970,17 @@ const RTK_Settings_Entry rtkSettingsEntries[] = // i a e // n i c t // W n u e -// e C s F t V P -// b o e a 2 o -// C m S c M s -// o m u e o T L t -// n a f t s o B c -// f n f E a r a a -// i d i v V i c n r -// g s x k 2 c h d d Type Qual Variable Name +// e C s F t V P T +// b o e a 2 o o +// C m S c M s r +// o m u e o T L t c +// n a f t s o B c F h +// f n f E a r a a l +// i d i v V i c n r e X +// g s x k 2 c h d d x 2 Type Qual Variable Name afterSetCmd /* - { 1, 1, 0, 1, 1, 1, 1, 1, , 0, & settings., ""}, + { 1, 1, 0, 1, 1, 1, 1, 1, 1, ALL, 1, 0, & settings., ""}, */ }; @@ -1762,6 +2044,7 @@ struct struct_present bool gnss_zedf9p = false; bool gnss_mosaicX5 = false; // L-Band is implicit bool gnss_lg290p = false; + bool gnss_zedx20p = false; // A GNSS TP interrupt - for accurate clock setting // The GNSS UBX PVT message is sent ahead of the top-of-second @@ -1772,6 +2055,7 @@ struct struct_present bool imu_zedf9r = false; bool microSd = false; + bool mosaicMicroSd = false; bool microSdCardDetectLow = false; // Card detect low = SD in place bool microSdCardDetectHigh = false; // Card detect high = SD in place bool microSdCardDetectGpioExpanderHigh = false; // Card detect on GPIO5, high = SD in place @@ -1782,6 +2066,7 @@ struct struct_present bool display_i2c0 = false; bool display_i2c1 = false; DisplayType display_type = DISPLAY_MAX_NONE; + bool displayInverted = false; bool fuelgauge_max17048 = false; bool fuelgauge_bq40z50 = false; @@ -1798,7 +2083,7 @@ struct struct_present bool button_mode = false; bool button_powerHigh = false; // Button is pressed when high bool button_powerLow = false; // Button is pressed when low - bool gpioExpander = false; // Available on Portability shield + bool gpioExpanderButtons = false; // Available on Portability shield bool fastPowerOff = false; bool invertedFastPowerOff = false; // Needed for Facet mosaic v11 @@ -1810,6 +2095,8 @@ struct struct_present bool minCno = false; // ZED, mosaic, UM980 have minCN0. LG290P does on version >= v5. bool minElevation = false; // ZED, mosaic, UM980 have minElevation. LG290P does on versions >= v5. bool dynamicModel = false; // ZED, mosaic, UM980 have dynamic models. LG290P does not. + bool gpioExpanderSwitches = false; // Used on Flex + bool tiltPossible = false; //Flex may have a tilt IMU } present; // Monitor which devices on the device are on or offline. @@ -1823,7 +2110,8 @@ struct struct_online bool ethernetNTPServer = false; // EthernetUDP bool fs = false; bool gnss = false; - bool gpioExpander = false; + bool gpioExpanderButtons = false; + bool gpioExpanderSwitches = false; bool httpClient = false; bool i2c = false; bool lband_gnss = false; @@ -1844,6 +2132,7 @@ struct struct_online bool tcpServer = false; bool udpServer = false; bool webServer = false; + bool authenticationCoPro = false; // MFi authentication } online; typedef uint8_t NetIndex_t; // Index into the networkInterfaceTable @@ -1961,6 +2250,8 @@ struct struct_tasks bool sdSizeCheckTaskStopRequest = false; bool updatePplTaskStopRequest = false; bool updateWebServerTaskStopRequest = false; + + volatile bool endDirectConnectMode = false; // Set true by e.g. button task } task; #ifdef COMPILE_NETWORK @@ -2194,15 +2485,20 @@ class RTK_WIFI const char * fileName, int lineNumber); - // Get the ESP-NOW status + // Get the ESP-NOW channel // Outputs: - // Returns true when ESP-NOW is online and ready for use - bool espNowOnline(); + // Returns the requested ESP-NOW channel + WIFI_CHANNEL_t espNowChannelGet(); // Set the ESP-NOW channel // Inputs: // channel: New ESP-NOW channel number - void espNowSetChannel(WIFI_CHANNEL_t channel); + void espNowChannelSet(WIFI_CHANNEL_t channel); + + // Get the ESP-NOW status + // Outputs: + // Returns true when ESP-NOW is online and ready for use + bool espNowOnline(); // Handle the WiFi event // Inputs: @@ -2217,6 +2513,16 @@ class RTK_WIFI // Returns the current WiFi channel number WIFI_CHANNEL_t getChannel(); + // Get the soft AP channel + // Outputs: + // Returns the requested soft AP channel + WIFI_CHANNEL_t softApChannelGet(); + + // Set the soft AP channel + // Inputs: + // channel: Request the channel for WiFi soft AP + void softApChannelSet(WIFI_CHANNEL_t channel); + // Configure the soft AP // Inputs: // ipAddress: IP address of the soft AP @@ -2255,6 +2561,16 @@ class RTK_WIFI // otherwise bool startAp(bool forceAP); + // Get the station channel + // Outputs: + // Returns the requested station channel + WIFI_CHANNEL_t stationChannelGet(); + + // Set the station channel + // Inputs: + // channel: Request the channel for WiFi station + void stationChannelSet(WIFI_CHANNEL_t channel); + // Get the WiFi station IP address // Returns the IP address of the WiFi station IPAddress stationIpAddress(); diff --git a/Firmware/RTK_Everywhere/src/BluetoothSerial/BluetoothSerial.cpp b/Firmware/RTK_Everywhere/src/BluetoothSerial/BluetoothSerial.cpp index e941a8ca7..a8d2ccb48 100644 --- a/Firmware/RTK_Everywhere/src/BluetoothSerial/BluetoothSerial.cpp +++ b/Firmware/RTK_Everywhere/src/BluetoothSerial/BluetoothSerial.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" #include "sdkconfig.h" #include #include #include #include -#include "freertos/FreeRTOS.h" -#include "freertos/task.h" #if defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) @@ -26,13 +26,13 @@ #include "esp32-hal-log.h" #endif -#include "BluetoothSerial.h" #include "BTAdvertisedDevice.h" +#include "BluetoothSerial.h" #include "esp_bt.h" +#include "esp_bt_device.h" #include "esp_bt_main.h" #include "esp_gap_bt_api.h" -#include "esp_bt_device.h" #include "esp_spp_api.h" #include @@ -42,8 +42,8 @@ const char *_spp_server_name = "ESP32SPP"; // #define RX_QUEUE_SIZE 512 // #define TX_QUEUE_SIZE 32 -#define SPP_TX_QUEUE_TIMEOUT 1000 -#define SPP_TX_DONE_TIMEOUT 1000 +#define SPP_TX_QUEUE_TIMEOUT 1000 +#define SPP_TX_DONE_TIMEOUT 1000 #define SPP_CONGESTED_TIMEOUT 1000 static uint32_t _spp_client = 0; @@ -63,10 +63,10 @@ static AuthCompleteCb auth_complete_callback = NULL; static bool _rmt_name_valid = false; static uint8_t _rmt_name[ESP_BT_GAP_MAX_BDNAME_LEN + 1] = {0}; -#define INQ_LEN 0x10 -#define INQ_NUM_RSPS 20 +#define INQ_LEN 0x10 +#define INQ_NUM_RSPS 20 #define READY_TIMEOUT (10 * 1000) -#define SCAN_TIMEOUT (INQ_LEN * 2 * 1000) +#define SCAN_TIMEOUT (INQ_LEN * 2 * 1000) static esp_bd_addr_t _peer_bd_addr; static char _remote_name[ESP_BT_GAP_MAX_BDNAME_LEN + 1]; static bool _isRemoteAddressSet; @@ -77,7 +77,7 @@ static bool _IO_CAP_INPUT; static bool _IO_CAP_OUTPUT; #endif esp_bt_pin_code_t _pin_code = {0}; -uint8_t _pin_code_len = 0; // Number of valid Bytes in the esp_bt_pin_code_t array +uint8_t _pin_code_len = 0; // Number of valid Bytes in the esp_bt_pin_code_t array static esp_spp_sec_t _sec_mask; static esp_spp_role_t _role; // start connect on ESP_SPP_DISCOVERY_COMP_EVT or save entry for getChannels @@ -87,8 +87,11 @@ static std::map sdpRecords; static BTScanResultsSet scanResults; static BTAdvertisedDeviceCb advertisedDeviceCb = nullptr; +static bool _aclConnected; +static uint8_t _aclAddress[ESP_BD_ADDR_LEN]; + // _spp_event_group -#define SPP_RUNNING 0x01 +#define SPP_RUNNING 0x01 #define SPP_CONNECTED 0x02 #define SPP_CONGESTED 0x04 // true until OPEN successful, changes to false on CLOSE @@ -97,846 +100,1090 @@ static BTAdvertisedDeviceCb advertisedDeviceCb = nullptr; #define SPP_CLOSED 0x10 // _bt_event_group -#define BT_DISCOVERY_RUNNING 0x01 +#define BT_DISCOVERY_RUNNING 0x01 #define BT_DISCOVERY_COMPLETED 0x02 -#define BT_SDP_RUNNING 0x04 +#define BT_SDP_RUNNING 0x04 #define BT_SDP_COMPLETED 0x08 -typedef struct { - size_t len; - uint8_t data[]; +typedef struct +{ + size_t len; + uint8_t data[]; } spp_packet_t; -#if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) -static char *bda2str(esp_bd_addr_t bda, char *str, size_t size) { - if (bda == NULL || str == NULL || size < 18) { - return NULL; - } - - uint8_t *p = bda; - snprintf(str, size, "%02x:%02x:%02x:%02x:%02x:%02x", p[0], p[1], p[2], p[3], p[4], p[5]); - return str; +char *bda2str(esp_bd_addr_t bda, char *str, size_t size) +{ + if (bda == NULL || str == NULL || size < 18) + { + return NULL; + } + + uint8_t *p = bda; + snprintf(str, size, "%02x:%02x:%02x:%02x:%02x:%02x", p[0], p[1], p[2], p[3], p[4], p[5]); + return str; } -#endif -static bool get_name_from_eir(uint8_t *eir, char *bdname, uint8_t *bdname_len) { - if (!eir || !bdname || !bdname_len) { +static bool get_name_from_eir(uint8_t *eir, char *bdname, uint8_t *bdname_len) +{ + if (!eir || !bdname || !bdname_len) + { + return false; + } + + uint8_t *rmt_bdname, rmt_bdname_len; + *bdname = *bdname_len = rmt_bdname_len = 0; + + rmt_bdname = esp_bt_gap_resolve_eir_data(eir, ESP_BT_EIR_TYPE_CMPL_LOCAL_NAME, &rmt_bdname_len); + if (!rmt_bdname) + { + rmt_bdname = esp_bt_gap_resolve_eir_data(eir, ESP_BT_EIR_TYPE_SHORT_LOCAL_NAME, &rmt_bdname_len); + } + if (rmt_bdname) + { + rmt_bdname_len = rmt_bdname_len > ESP_BT_GAP_MAX_BDNAME_LEN ? ESP_BT_GAP_MAX_BDNAME_LEN : rmt_bdname_len; + memcpy(bdname, rmt_bdname, rmt_bdname_len); + bdname[rmt_bdname_len] = 0; + *bdname_len = rmt_bdname_len; + return true; + } return false; - } - - uint8_t *rmt_bdname, rmt_bdname_len; - *bdname = *bdname_len = rmt_bdname_len = 0; - - rmt_bdname = esp_bt_gap_resolve_eir_data(eir, ESP_BT_EIR_TYPE_CMPL_LOCAL_NAME, &rmt_bdname_len); - if (!rmt_bdname) { - rmt_bdname = esp_bt_gap_resolve_eir_data(eir, ESP_BT_EIR_TYPE_SHORT_LOCAL_NAME, &rmt_bdname_len); - } - if (rmt_bdname) { - rmt_bdname_len = rmt_bdname_len > ESP_BT_GAP_MAX_BDNAME_LEN ? ESP_BT_GAP_MAX_BDNAME_LEN : rmt_bdname_len; - memcpy(bdname, rmt_bdname, rmt_bdname_len); - bdname[rmt_bdname_len] = 0; - *bdname_len = rmt_bdname_len; - return true; - } - return false; } -static esp_err_t _spp_queue_packet(uint8_t *data, size_t len) { - if (!data || !len) { - log_w("No data provided"); +static esp_err_t _spp_queue_packet(uint8_t *data, size_t len) +{ + if (!data || !len) + { + log_w("No data provided"); + return ESP_OK; + } + spp_packet_t *packet = (spp_packet_t *)malloc(sizeof(spp_packet_t) + len); + if (!packet) + { + log_e("SPP TX Packet Malloc Failed!"); + return ESP_FAIL; + } + packet->len = len; + memcpy(packet->data, data, len); + if (!_spp_tx_queue || xQueueSend(_spp_tx_queue, &packet, SPP_TX_QUEUE_TIMEOUT) != pdPASS) + { + log_e("SPP TX Queue Send Failed!"); + free(packet); + return ESP_FAIL; + } return ESP_OK; - } - spp_packet_t *packet = (spp_packet_t *)malloc(sizeof(spp_packet_t) + len); - if (!packet) { - log_e("SPP TX Packet Malloc Failed!"); - return ESP_FAIL; - } - packet->len = len; - memcpy(packet->data, data, len); - if (!_spp_tx_queue || xQueueSend(_spp_tx_queue, &packet, SPP_TX_QUEUE_TIMEOUT) != pdPASS) { - log_e("SPP TX Queue Send Failed!"); - free(packet); - return ESP_FAIL; - } - return ESP_OK; } const uint16_t SPP_TX_MAX = 330; static uint8_t _spp_tx_buffer[SPP_TX_MAX]; static uint16_t _spp_tx_buffer_len = 0; -static bool _spp_send_buffer() { - if ((xEventGroupWaitBits(_spp_event_group, SPP_CONGESTED, pdFALSE, pdTRUE, SPP_CONGESTED_TIMEOUT) & SPP_CONGESTED) != 0) { - if (!_spp_client) { - log_v("SPP Client Gone!"); - return false; - } - log_v("SPP Write %u", _spp_tx_buffer_len); - esp_err_t err = esp_spp_write(_spp_client, _spp_tx_buffer_len, _spp_tx_buffer); - if (err != ESP_OK) { - log_e("SPP Write Failed! [0x%X]", err); - return false; - } - _spp_tx_buffer_len = 0; - if (xSemaphoreTake(_spp_tx_done, SPP_TX_DONE_TIMEOUT) != pdTRUE) { - log_e("SPP Ack Failed!"); - return false; +static bool _spp_send_buffer() +{ + if ((xEventGroupWaitBits(_spp_event_group, SPP_CONGESTED, pdFALSE, pdTRUE, SPP_CONGESTED_TIMEOUT) & + SPP_CONGESTED) != 0) + { + if (!_spp_client) + { + log_v("SPP Client Gone!"); + return false; + } + log_v("SPP Write %u", _spp_tx_buffer_len); + esp_err_t err = esp_spp_write(_spp_client, _spp_tx_buffer_len, _spp_tx_buffer); + if (err != ESP_OK) + { + log_e("SPP Write Failed! [0x%X]", err); + return false; + } + _spp_tx_buffer_len = 0; + if (xSemaphoreTake(_spp_tx_done, SPP_TX_DONE_TIMEOUT) != pdTRUE) + { + log_e("SPP Ack Failed!"); + return false; + } + return true; } - return true; - } - log_e("SPP Write Congested!"); - return false; + log_e("SPP Write Congested!"); + return false; } -static void _spp_tx_task(void *arg) { - spp_packet_t *packet = NULL; - size_t len = 0, to_send = 0; - uint8_t *data = NULL; - for (;;) { - if (_spp_tx_queue && xQueueReceive(_spp_tx_queue, &packet, portMAX_DELAY) == pdTRUE && packet) { - if (packet->len <= (SPP_TX_MAX - _spp_tx_buffer_len)) { - memcpy(_spp_tx_buffer + _spp_tx_buffer_len, packet->data, packet->len); - _spp_tx_buffer_len += packet->len; - free(packet); - packet = NULL; - if (SPP_TX_MAX == _spp_tx_buffer_len || uxQueueMessagesWaiting(_spp_tx_queue) == 0) { - _spp_send_buffer(); - } - } else { - len = packet->len; - data = packet->data; - to_send = SPP_TX_MAX - _spp_tx_buffer_len; - memcpy(_spp_tx_buffer + _spp_tx_buffer_len, data, to_send); - _spp_tx_buffer_len = SPP_TX_MAX; - data += to_send; - len -= to_send; - if (!_spp_send_buffer()) { - len = 0; - } - while (len >= SPP_TX_MAX) { - memcpy(_spp_tx_buffer, data, SPP_TX_MAX); - _spp_tx_buffer_len = SPP_TX_MAX; - data += SPP_TX_MAX; - len -= SPP_TX_MAX; - if (!_spp_send_buffer()) { - len = 0; - break; - } +static void _spp_tx_task(void *arg) +{ + spp_packet_t *packet = NULL; + size_t len = 0, to_send = 0; + uint8_t *data = NULL; + for (;;) + { + if (_spp_tx_queue && xQueueReceive(_spp_tx_queue, &packet, portMAX_DELAY) == pdTRUE && packet) + { + if (packet->len <= (SPP_TX_MAX - _spp_tx_buffer_len)) + { + memcpy(_spp_tx_buffer + _spp_tx_buffer_len, packet->data, packet->len); + _spp_tx_buffer_len += packet->len; + free(packet); + packet = NULL; + if (SPP_TX_MAX == _spp_tx_buffer_len || uxQueueMessagesWaiting(_spp_tx_queue) == 0) + { + _spp_send_buffer(); + } + } + else + { + len = packet->len; + data = packet->data; + to_send = SPP_TX_MAX - _spp_tx_buffer_len; + memcpy(_spp_tx_buffer + _spp_tx_buffer_len, data, to_send); + _spp_tx_buffer_len = SPP_TX_MAX; + data += to_send; + len -= to_send; + if (!_spp_send_buffer()) + { + len = 0; + } + while (len >= SPP_TX_MAX) + { + memcpy(_spp_tx_buffer, data, SPP_TX_MAX); + _spp_tx_buffer_len = SPP_TX_MAX; + data += SPP_TX_MAX; + len -= SPP_TX_MAX; + if (!_spp_send_buffer()) + { + len = 0; + break; + } + } + if (len) + { + memcpy(_spp_tx_buffer, data, len); + _spp_tx_buffer_len += len; + if (uxQueueMessagesWaiting(_spp_tx_queue) == 0) + { + _spp_send_buffer(); + } + } + free(packet); + packet = NULL; + } } - if (len) { - memcpy(_spp_tx_buffer, data, len); - _spp_tx_buffer_len += len; - if (uxQueueMessagesWaiting(_spp_tx_queue) == 0) { - _spp_send_buffer(); - } + else + { + log_e("BluetoothSerial _spp_tx_task: something went horribly wrong"); } - free(packet); - packet = NULL; - } - } else { - log_e("Something went horribly wrong"); - } - } - vTaskDelete(NULL); - _spp_task_handle = NULL; + } + vTaskDelete(NULL); + _spp_task_handle = NULL; } -static void esp_spp_cb(esp_spp_cb_event_t event, esp_spp_cb_param_t *param) { - switch (event) { - case ESP_SPP_INIT_EVT: // Enum 0 - When SPP is initialized - log_i("ESP_SPP_INIT_EVT"); +static void esp_spp_cb(esp_spp_cb_event_t event, esp_spp_cb_param_t *param) +{ + switch (event) + { + case ESP_SPP_INIT_EVT: // Enum 0 - When SPP is initialized + log_i("ESP_SPP_INIT_EVT"); #ifdef ESP_IDF_VERSION_MAJOR - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); + esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); #else - esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); + esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); #endif - log_i("ESP_SPP_INIT_EVT: %s: start", _isMaster ? "master" : "slave"); - esp_spp_start_srv(ESP_SPP_SEC_NONE, _isMaster ? ESP_SPP_ROLE_MASTER : ESP_SPP_ROLE_SLAVE, 0, _spp_server_name); - xEventGroupSetBits(_spp_event_group, SPP_RUNNING); - break; - - case ESP_SPP_UNINIT_EVT: // Enum 1 - When SPP is deinitialized - log_i("ESP_SPP_UNINIT_EVT: SPP is deinitialized"); - break; - - case ESP_SPP_DISCOVERY_COMP_EVT: // Enum 8 - When SDP discovery complete - log_i("ESP_SPP_DISCOVERY_COMP_EVT num=%d", param->disc_comp.scn_num); - if (param->disc_comp.status == ESP_SPP_SUCCESS) { - for (int i = 0; i < param->disc_comp.scn_num; i++) { - log_d("ESP_SPP_DISCOVERY_COMP_EVT: spp [%d] channel: %d service name:%s", i, param->disc_comp.scn[i], param->disc_comp.service_name[0]); - } - if (_doConnect) { - if (param->disc_comp.scn_num > 0) { + log_i("ESP_SPP_INIT_EVT: %s: start", _isMaster ? "master" : "slave"); + esp_spp_start_srv(ESP_SPP_SEC_NONE, _isMaster ? ESP_SPP_ROLE_MASTER : ESP_SPP_ROLE_SLAVE, 0, _spp_server_name); + xEventGroupSetBits(_spp_event_group, SPP_RUNNING); + break; + + case ESP_SPP_UNINIT_EVT: // Enum 1 - When SPP is deinitialized + log_i("ESP_SPP_UNINIT_EVT: SPP is deinitialized"); + break; + + case ESP_SPP_DISCOVERY_COMP_EVT: // Enum 8 - When SDP discovery complete + log_i("ESP_SPP_DISCOVERY_COMP_EVT num=%d", param->disc_comp.scn_num); + if (param->disc_comp.status == ESP_SPP_SUCCESS) + { + for (int i = 0; i < param->disc_comp.scn_num; i++) + { + log_d("ESP_SPP_DISCOVERY_COMP_EVT: spp [%d] channel: %d service name:%s", i, param->disc_comp.scn[i], + param->disc_comp.service_name[0]); + } + if (_doConnect) + { + if (param->disc_comp.scn_num > 0) + { #if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) - char bda_str[18]; - log_i("ESP_SPP_DISCOVERY_COMP_EVT: spp connect to remote %s channel %d", bda2str(_peer_bd_addr, bda_str, sizeof(bda_str)), param->disc_comp.scn[0]); + char bda_str[18]; + log_i("ESP_SPP_DISCOVERY_COMP_EVT: spp connect to remote %s channel %d", + bda2str(_peer_bd_addr, bda_str, sizeof(bda_str)), param->disc_comp.scn[0]); #endif - xEventGroupClearBits(_spp_event_group, SPP_CLOSED); - if (esp_spp_connect(_sec_mask, _role, param->disc_comp.scn[0], _peer_bd_addr) != ESP_OK) { - log_e("ESP_SPP_DISCOVERY_COMP_EVT connect failed"); - xEventGroupSetBits(_spp_event_group, SPP_CLOSED); + xEventGroupClearBits(_spp_event_group, SPP_CLOSED); + if (esp_spp_connect(_sec_mask, _role, param->disc_comp.scn[0], _peer_bd_addr) != ESP_OK) + { + log_e("ESP_SPP_DISCOVERY_COMP_EVT connect failed"); + xEventGroupSetBits(_spp_event_group, SPP_CLOSED); + } + } + else + { + log_e("ESP_SPP_DISCOVERY_COMP_EVT remote doesn't offer an SPP channel"); + xEventGroupSetBits(_spp_event_group, SPP_CLOSED); + } + } + else + { + for (int i = 0; i < param->disc_comp.scn_num; i++) + { + sdpRecords[param->disc_comp.scn[i]] = param->disc_comp.service_name[0]; + } } - } else { - log_e("ESP_SPP_DISCOVERY_COMP_EVT remote doesn't offer an SPP channel"); - xEventGroupSetBits(_spp_event_group, SPP_CLOSED); - } - } else { - for (int i = 0; i < param->disc_comp.scn_num; i++) { - sdpRecords[param->disc_comp.scn[i]] = param->disc_comp.service_name[0]; - } - } - } else { - log_e("ESP_SPP_DISCOVERY_COMP_EVT failed!, status:%d", param->disc_comp.status); - } - xEventGroupSetBits(_bt_event_group, BT_SDP_COMPLETED); - break; - - case ESP_SPP_OPEN_EVT: // Enum 26 - When SPP Client connection open - log_i("ESP_SPP_OPEN_EVT"); - if (!_spp_client) { - _spp_client = param->open.handle; - } else { - secondConnectionAttempt = true; - esp_spp_disconnect(param->open.handle); - } - xEventGroupClearBits(_spp_event_group, SPP_DISCONNECTED); - xEventGroupSetBits(_spp_event_group, SPP_CONNECTED); - xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); - break; - - case ESP_SPP_CLOSE_EVT: // Enum 27 - When SPP connection closed - if ((param->close.async == false && param->close.status == ESP_SPP_SUCCESS) || param->close.async) { - log_i( - "ESP_SPP_CLOSE_EVT status:%d handle:%d close_by_remote:%d attempt %u", param->close.status, param->close.handle, param->close.async, - secondConnectionAttempt - ); - if (secondConnectionAttempt) { - secondConnectionAttempt = false; - } else { - _spp_client = 0; - xEventGroupSetBits(_spp_event_group, SPP_DISCONNECTED); - xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); - xEventGroupSetBits(_spp_event_group, SPP_CLOSED); - xEventGroupClearBits(_spp_event_group, SPP_CONNECTED); } - } else { - log_e("ESP_SPP_CLOSE_EVT failed!, status:%d", param->close.status); - } - break; - - case ESP_SPP_START_EVT: // Enum 28 - When SPP server started - log_i("ESP_SPP_START_EVT"); - break; - - case ESP_SPP_CL_INIT_EVT: // Enum 29 - When SPP client initiated a connection - if (param->cl_init.status == ESP_SPP_SUCCESS) { - log_i("ESP_SPP_CL_INIT_EVT handle:%d sec_id:%d", param->cl_init.handle, param->cl_init.sec_id); - } else { - log_i("ESP_SPP_CL_INIT_EVT status:%d", param->cl_init.status); - } - break; - - case ESP_SPP_DATA_IND_EVT: // Enum 30 - When SPP connection received data, only for ESP_SPP_MODE_CB - log_v("ESP_SPP_DATA_IND_EVT len=%d handle=%d", param->data_ind.len, param->data_ind.handle); - //esp_log_buffer_hex("",param->data_ind.data,param->data_ind.len); //for low level debug - //ets_printf("r:%u\n", param->data_ind.len); - - if (custom_data_callback) { - custom_data_callback(param->data_ind.data, param->data_ind.len); - } else if (_spp_rx_queue != NULL) { - for (int i = 0; i < param->data_ind.len; i++) { - if (xQueueSend(_spp_rx_queue, param->data_ind.data + i, (TickType_t)0) != pdTRUE) { - Serial.printf("RX Full! Discarding %u bytes\r\n", param->data_ind.len - i); - break; - } + else + { + log_e("ESP_SPP_DISCOVERY_COMP_EVT failed!, status:%d", param->disc_comp.status); } - } - break; - - case ESP_SPP_CONG_EVT: // Enum 31 - When SPP connection congestion status changed, only for ESP_SPP_MODE_CB - if (param->cong.cong) { - xEventGroupClearBits(_spp_event_group, SPP_CONGESTED); - } else { - xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); - } - log_v("ESP_SPP_CONG_EVT: %s", param->cong.cong ? "CONGESTED" : "FREE"); - break; - - case ESP_SPP_WRITE_EVT: // Enum 33 - When SPP write operation completes, only for ESP_SPP_MODE_CB - if (param->write.status == ESP_SPP_SUCCESS) { - if (param->write.cong) { - xEventGroupClearBits(_spp_event_group, SPP_CONGESTED); + xEventGroupSetBits(_bt_event_group, BT_SDP_COMPLETED); + break; + + case ESP_SPP_OPEN_EVT: // Enum 26 - When SPP Client connection open + log_i("ESP_SPP_OPEN_EVT"); + if (!_spp_client) + { + _spp_client = param->open.handle; } - log_v("ESP_SPP_WRITE_EVT: %u %s", param->write.len, param->write.cong ? "CONGESTED" : ""); - } else { - log_e("ESP_SPP_WRITE_EVT failed!, status:%d", param->write.status); - } - xSemaphoreGive(_spp_tx_done); //we can try to send another packet - break; - - case ESP_SPP_SRV_OPEN_EVT: // Enum 34 - When SPP Server connection open - if (param->srv_open.status == ESP_SPP_SUCCESS) { - log_i("ESP_SPP_SRV_OPEN_EVT: %u", _spp_client); - if (!_spp_client) { - _spp_client = param->srv_open.handle; - _spp_tx_buffer_len = 0; - } else { - secondConnectionAttempt = true; - esp_spp_disconnect(param->srv_open.handle); + else + { + secondConnectionAttempt = true; + esp_spp_disconnect(param->open.handle); } xEventGroupClearBits(_spp_event_group, SPP_DISCONNECTED); xEventGroupSetBits(_spp_event_group, SPP_CONNECTED); - } else { - log_e("ESP_SPP_SRV_OPEN_EVT Failed!, status:%d", param->srv_open.status); - } - break; - - case ESP_SPP_SRV_STOP_EVT: // Enum 35 - When SPP server stopped - log_i("ESP_SPP_SRV_STOP_EVT"); - break; - - case ESP_SPP_VFS_REGISTER_EVT: // Enum 36 - When SPP VFS register - log_i("ESP_SPP_VFS_REGISTER_EVT"); - break; - - case ESP_SPP_VFS_UNREGISTER_EVT: // Enum 37 - When SPP VFS unregister - log_i("ESP_SPP_VFS_UNREGISTER_EVT"); - break; - - default: log_i("ESP_SPP_* event #%d unhandled", event); break; - } - if (custom_spp_callback) { - (*custom_spp_callback)(event, param); - } + xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); + break; + + case ESP_SPP_CLOSE_EVT: // Enum 27 - When SPP connection closed + if ((param->close.async == false && param->close.status == ESP_SPP_SUCCESS) || param->close.async) + { + log_i("ESP_SPP_CLOSE_EVT status:%d handle:%d close_by_remote:%d attempt %u", param->close.status, + param->close.handle, param->close.async, secondConnectionAttempt); + if (secondConnectionAttempt) + { + secondConnectionAttempt = false; + } + else + { + _spp_client = 0; + xEventGroupSetBits(_spp_event_group, SPP_DISCONNECTED); + xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); + xEventGroupSetBits(_spp_event_group, SPP_CLOSED); + xEventGroupClearBits(_spp_event_group, SPP_CONNECTED); + } + } + else + { + log_e("ESP_SPP_CLOSE_EVT failed!, status:%d", param->close.status); + } + + break; + + case ESP_SPP_START_EVT: // Enum 28 - When SPP server started + log_i("ESP_SPP_START_EVT"); + break; + + case ESP_SPP_CL_INIT_EVT: // Enum 29 - When SPP client initiated a connection + if (param->cl_init.status == ESP_SPP_SUCCESS) + { + log_i("ESP_SPP_CL_INIT_EVT handle:%d sec_id:%d", param->cl_init.handle, param->cl_init.sec_id); + } + else + { + log_i("ESP_SPP_CL_INIT_EVT status:%d", param->cl_init.status); + } + break; + + case ESP_SPP_DATA_IND_EVT: // Enum 30 - When SPP connection received data, only for ESP_SPP_MODE_CB + log_v("ESP_SPP_DATA_IND_EVT len=%d handle=%d", param->data_ind.len, param->data_ind.handle); + // esp_log_buffer_hex("",param->data_ind.data,param->data_ind.len); //for low level debug + // ets_printf("r:%u\n", param->data_ind.len); + + if (custom_data_callback) + { + custom_data_callback(param->data_ind.data, param->data_ind.len); + } + else if (_spp_rx_queue != NULL) + { + for (int i = 0; i < param->data_ind.len; i++) + { + if (xQueueSend(_spp_rx_queue, param->data_ind.data + i, (TickType_t)0) != pdTRUE) + { + Serial.printf("BluetoothSerial RX Full! Discarding %u bytes\r\n", param->data_ind.len - i); + break; + } + } + } + break; + + case ESP_SPP_CONG_EVT: // Enum 31 - When SPP connection congestion status changed, only for ESP_SPP_MODE_CB + if (param->cong.cong) + { + xEventGroupClearBits(_spp_event_group, SPP_CONGESTED); + } + else + { + xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); + } + log_v("ESP_SPP_CONG_EVT: %s", param->cong.cong ? "CONGESTED" : "FREE"); + break; + + case ESP_SPP_WRITE_EVT: // Enum 33 - When SPP write operation completes, only for ESP_SPP_MODE_CB + if (param->write.status == ESP_SPP_SUCCESS) + { + if (param->write.cong) + { + xEventGroupClearBits(_spp_event_group, SPP_CONGESTED); + } + log_v("ESP_SPP_WRITE_EVT: %u %s", param->write.len, param->write.cong ? "CONGESTED" : ""); + } + else + { + log_e("ESP_SPP_WRITE_EVT failed!, status:%d", param->write.status); + } + xSemaphoreGive(_spp_tx_done); // we can try to send another packet + break; + + case ESP_SPP_SRV_OPEN_EVT: // Enum 34 - When SPP Server connection open + if (param->srv_open.status == ESP_SPP_SUCCESS) + { + log_i("ESP_SPP_SRV_OPEN_EVT: %u", _spp_client); + if (!_spp_client) + { + _spp_client = param->srv_open.handle; + _spp_tx_buffer_len = 0; + } + else + { + secondConnectionAttempt = true; + esp_spp_disconnect(param->srv_open.handle); + } + xEventGroupClearBits(_spp_event_group, SPP_DISCONNECTED); + xEventGroupSetBits(_spp_event_group, SPP_CONNECTED); + } + else + { + log_e("ESP_SPP_SRV_OPEN_EVT Failed!, status:%d", param->srv_open.status); + } + break; + + case ESP_SPP_SRV_STOP_EVT: // Enum 35 - When SPP server stopped + log_i("ESP_SPP_SRV_STOP_EVT"); + break; + + case ESP_SPP_VFS_REGISTER_EVT: // Enum 36 - When SPP VFS register + log_i("ESP_SPP_VFS_REGISTER_EVT"); + break; + + case ESP_SPP_VFS_UNREGISTER_EVT: // Enum 37 - When SPP VFS unregister + log_i("ESP_SPP_VFS_UNREGISTER_EVT"); + break; + + default: + log_i("ESP_SPP_* event #%d unhandled", event); + break; + } + if (custom_spp_callback) + { + (*custom_spp_callback)(event, param); + } } -void BluetoothSerial::onData(BluetoothSerialDataCb cb) { - custom_data_callback = cb; +void BluetoothSerial::onData(BluetoothSerialDataCb cb) +{ + custom_data_callback = cb; } -static void esp_bt_gap_cb(esp_bt_gap_cb_event_t event, esp_bt_gap_cb_param_t *param) { - switch (event) { - case ESP_BT_GAP_DISC_RES_EVT: - { // Enum 0 - Device discovery result event - log_i("ESP_BT_GAP_DISC_RES_EVT properties=%d", param->disc_res.num_prop); +static void esp_bt_gap_cb(esp_bt_gap_cb_event_t event, esp_bt_gap_cb_param_t *param) +{ + switch (event) + { + case ESP_BT_GAP_DISC_RES_EVT: { // Enum 0 - Device discovery result event + log_i("ESP_BT_GAP_DISC_RES_EVT properties=%d", param->disc_res.num_prop); #if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) - char bda_str[18]; - log_i("Scanned device: %s", bda2str(param->disc_res.bda, bda_str, 18)); + char bda_str[18]; + log_i("Scanned device: %s", bda2str(param->disc_res.bda, bda_str, 18)); #endif - BTAdvertisedDeviceSet advertisedDevice; - uint8_t peer_bdname_len = 0; - char peer_bdname[ESP_BT_GAP_MAX_BDNAME_LEN + 1]; - for (int i = 0; i < param->disc_res.num_prop; i++) { - switch (param->disc_res.prop[i].type) { - case ESP_BT_GAP_DEV_PROP_BDNAME: // Enum 1 - Bluetooth device name, value type is int8_t [] - peer_bdname_len = param->disc_res.prop[i].len; - memcpy(peer_bdname, param->disc_res.prop[i].val, peer_bdname_len); - peer_bdname_len--; // len includes 0 terminator - log_v("ESP_BT_GAP_DISC_RES_EVT : BDNAME : %s : %d", peer_bdname, peer_bdname_len); - if (strlen(_remote_name) == peer_bdname_len && strncmp(peer_bdname, _remote_name, peer_bdname_len) == 0) { - log_i("ESP_BT_GAP_DISC_RES_EVT : SPP_START_DISCOVERY_BDNAME : %s", peer_bdname); - _isRemoteAddressSet = true; - memcpy(_peer_bd_addr, param->disc_res.bda, ESP_BD_ADDR_LEN); - esp_bt_gap_cancel_discovery(); - esp_spp_start_discovery(_peer_bd_addr); + BTAdvertisedDeviceSet advertisedDevice; + uint8_t peer_bdname_len = 0; + char peer_bdname[ESP_BT_GAP_MAX_BDNAME_LEN + 1]; + for (int i = 0; i < param->disc_res.num_prop; i++) + { + switch (param->disc_res.prop[i].type) + { + case ESP_BT_GAP_DEV_PROP_BDNAME: // Enum 1 - Bluetooth device name, value type is int8_t [] + peer_bdname_len = param->disc_res.prop[i].len; + memcpy(peer_bdname, param->disc_res.prop[i].val, peer_bdname_len); + peer_bdname_len--; // len includes 0 terminator + log_v("ESP_BT_GAP_DISC_RES_EVT : BDNAME : %s : %d", peer_bdname, peer_bdname_len); + if (strlen(_remote_name) == peer_bdname_len && strncmp(peer_bdname, _remote_name, peer_bdname_len) == 0) + { + log_i("ESP_BT_GAP_DISC_RES_EVT : SPP_START_DISCOVERY_BDNAME : %s", peer_bdname); + _isRemoteAddressSet = true; + memcpy(_peer_bd_addr, param->disc_res.bda, ESP_BD_ADDR_LEN); + esp_bt_gap_cancel_discovery(); + esp_spp_start_discovery(_peer_bd_addr); + } + break; + + case ESP_BT_GAP_DEV_PROP_COD: // Enum 2 - Class of Device, value type is uint32_t + if (param->disc_res.prop[i].len <= sizeof(int)) + { + uint32_t cod = 0; + memcpy(&cod, param->disc_res.prop[i].val, param->disc_res.prop[i].len); + advertisedDevice.setCOD(cod); + log_d("ESP_BT_GAP_DEV_PROP_COD 0x%x", cod); + } + else + { + log_d("ESP_BT_GAP_DEV_PROP_COD invalid COD: Value size larger than integer"); + } + break; + + case ESP_BT_GAP_DEV_PROP_RSSI: // Enum 3 - Received Signal strength Indication, value type is int8_t, + // ranging from -128 to 127 + if (param->disc_res.prop[i].len <= sizeof(int)) + { + uint8_t rssi = 0; + memcpy(&rssi, param->disc_res.prop[i].val, param->disc_res.prop[i].len); + log_d("ESP_BT_GAP_DEV_PROP_RSSI %d", rssi); + advertisedDevice.setRSSI(rssi); + } + else + { + log_d("ESP_BT_GAP_DEV_PROP_RSSI invalid RSSI: Value size larger than integer"); + } + break; + + case ESP_BT_GAP_DEV_PROP_EIR: // Enum 4 - Extended Inquiry Response, value type is uint8_t [] + if (get_name_from_eir((uint8_t *)param->disc_res.prop[i].val, peer_bdname, &peer_bdname_len)) + { + log_i("ESP_BT_GAP_DISC_RES_EVT : EIR : %s : %d", peer_bdname, peer_bdname_len); + if (strlen(_remote_name) == peer_bdname_len && + strncmp(peer_bdname, _remote_name, peer_bdname_len) == 0) + { + log_v("ESP_BT_GAP_DISC_RES_EVT : SPP_START_DISCOVERY_EIR : %s", peer_bdname, peer_bdname_len); + _isRemoteAddressSet = true; + memcpy(_peer_bd_addr, param->disc_res.bda, ESP_BD_ADDR_LEN); + esp_bt_gap_cancel_discovery(); + esp_spp_start_discovery(_peer_bd_addr); + } + } + break; + + default: + log_i("ESP_BT_GAP_DISC_RES_EVT unknown property [%d]:type:%d", i, param->disc_res.prop[i].type); + break; } - break; - - case ESP_BT_GAP_DEV_PROP_COD: // Enum 2 - Class of Device, value type is uint32_t - if (param->disc_res.prop[i].len <= sizeof(int)) { - uint32_t cod = 0; - memcpy(&cod, param->disc_res.prop[i].val, param->disc_res.prop[i].len); - advertisedDevice.setCOD(cod); - log_d("ESP_BT_GAP_DEV_PROP_COD 0x%x", cod); - } else { - log_d("ESP_BT_GAP_DEV_PROP_COD invalid COD: Value size larger than integer"); + if (_isRemoteAddressSet) + { + break; } - break; - - case ESP_BT_GAP_DEV_PROP_RSSI: // Enum 3 - Received Signal strength Indication, value type is int8_t, ranging from -128 to 127 - if (param->disc_res.prop[i].len <= sizeof(int)) { - uint8_t rssi = 0; - memcpy(&rssi, param->disc_res.prop[i].val, param->disc_res.prop[i].len); - log_d("ESP_BT_GAP_DEV_PROP_RSSI %d", rssi); - advertisedDevice.setRSSI(rssi); - } else { - log_d("ESP_BT_GAP_DEV_PROP_RSSI invalid RSSI: Value size larger than integer"); - } - break; - - case ESP_BT_GAP_DEV_PROP_EIR: // Enum 4 - Extended Inquiry Response, value type is uint8_t [] - if (get_name_from_eir((uint8_t *)param->disc_res.prop[i].val, peer_bdname, &peer_bdname_len)) { - log_i("ESP_BT_GAP_DISC_RES_EVT : EIR : %s : %d", peer_bdname, peer_bdname_len); - if (strlen(_remote_name) == peer_bdname_len && strncmp(peer_bdname, _remote_name, peer_bdname_len) == 0) { - log_v("ESP_BT_GAP_DISC_RES_EVT : SPP_START_DISCOVERY_EIR : %s", peer_bdname, peer_bdname_len); - _isRemoteAddressSet = true; - memcpy(_peer_bd_addr, param->disc_res.bda, ESP_BD_ADDR_LEN); - esp_bt_gap_cancel_discovery(); - esp_spp_start_discovery(_peer_bd_addr); - } + } + if (peer_bdname_len) + { + advertisedDevice.setName(peer_bdname); + } + esp_bd_addr_t addr; + memcpy(addr, param->disc_res.bda, ESP_BD_ADDR_LEN); + advertisedDevice.setAddress(BTAddress(addr)); + if (scanResults.add(advertisedDevice) && advertisedDeviceCb) + { + advertisedDeviceCb(&advertisedDevice); + } + } + break; + + case ESP_BT_GAP_DISC_STATE_CHANGED_EVT: // Enum 1 - Discovery state changed event + if (param->disc_st_chg.state == ESP_BT_GAP_DISCOVERY_STOPPED) + { + log_i("ESP_BT_GAP_DISC_STATE_CHANGED_EVT stopped"); + xEventGroupClearBits(_bt_event_group, BT_DISCOVERY_RUNNING); + xEventGroupSetBits(_bt_event_group, BT_DISCOVERY_COMPLETED); + } + else + { // ESP_BT_GAP_DISCOVERY_STARTED + log_i("ESP_BT_GAP_DISC_STATE_CHANGED_EVT started"); + xEventGroupClearBits(_bt_event_group, BT_DISCOVERY_COMPLETED); + xEventGroupSetBits(_bt_event_group, BT_DISCOVERY_RUNNING); + } + break; + + case ESP_BT_GAP_RMT_SRVCS_EVT: // Enum 2 - Get remote services event + log_i("ESP_BT_GAP_RMT_SRVCS_EVT: status = %d, num_uuids = %d", param->rmt_srvcs.stat, + param->rmt_srvcs.num_uuids); + break; + + case ESP_BT_GAP_RMT_SRVC_REC_EVT: // Enum 3 - Get remote service record event + log_i("ESP_BT_GAP_RMT_SRVC_REC_EVT: status = %d", param->rmt_srvc_rec.stat); + break; + + case ESP_BT_GAP_AUTH_CMPL_EVT: // Enum 4 - Authentication complete event + if (param->auth_cmpl.stat == ESP_BT_STATUS_SUCCESS) + { + log_v("ESP_BT_GAP_AUTH_CMPL_EVT authentication success: %s", param->auth_cmpl.device_name); + if (auth_complete_callback) + { + auth_complete_callback(true); } - break; - - default: log_i("ESP_BT_GAP_DISC_RES_EVT unknown property [%d]:type:%d", i, param->disc_res.prop[i].type); break; } - if (_isRemoteAddressSet) { - break; + else + { + log_e("ESP_BT_GAP_AUTH_CMPL_EVT authentication failed, status:%d", param->auth_cmpl.stat); + if (auth_complete_callback) + { + auth_complete_callback(false); + } } - } - if (peer_bdname_len) { - advertisedDevice.setName(peer_bdname); - } - esp_bd_addr_t addr; - memcpy(addr, param->disc_res.bda, ESP_BD_ADDR_LEN); - advertisedDevice.setAddress(BTAddress(addr)); - if (scanResults.add(advertisedDevice) && advertisedDeviceCb) { - advertisedDeviceCb(&advertisedDevice); - } - } break; - - case ESP_BT_GAP_DISC_STATE_CHANGED_EVT: // Enum 1 - Discovery state changed event - if (param->disc_st_chg.state == ESP_BT_GAP_DISCOVERY_STOPPED) { - log_i("ESP_BT_GAP_DISC_STATE_CHANGED_EVT stopped"); - xEventGroupClearBits(_bt_event_group, BT_DISCOVERY_RUNNING); - xEventGroupSetBits(_bt_event_group, BT_DISCOVERY_COMPLETED); - } else { // ESP_BT_GAP_DISCOVERY_STARTED - log_i("ESP_BT_GAP_DISC_STATE_CHANGED_EVT started"); - xEventGroupClearBits(_bt_event_group, BT_DISCOVERY_COMPLETED); - xEventGroupSetBits(_bt_event_group, BT_DISCOVERY_RUNNING); - } - break; - - case ESP_BT_GAP_RMT_SRVCS_EVT: // Enum 2 - Get remote services event - log_i("ESP_BT_GAP_RMT_SRVCS_EVT: status = %d, num_uuids = %d", param->rmt_srvcs.stat, param->rmt_srvcs.num_uuids); - break; - - case ESP_BT_GAP_RMT_SRVC_REC_EVT: // Enum 3 - Get remote service record event - log_i("ESP_BT_GAP_RMT_SRVC_REC_EVT: status = %d", param->rmt_srvc_rec.stat); - break; - - case ESP_BT_GAP_AUTH_CMPL_EVT: // Enum 4 - Authentication complete event - if (param->auth_cmpl.stat == ESP_BT_STATUS_SUCCESS) { - log_v("authentication success: %s", param->auth_cmpl.device_name); - if (auth_complete_callback) { - auth_complete_callback(true); + break; + case ESP_BT_GAP_PIN_REQ_EVT: // Enum 5 - Legacy Pairing Pin code request + log_i("ESP_BT_GAP_PIN_REQ_EVT (min_16_digit=%d)", param->pin_req.min_16_digit); + if (param->pin_req.min_16_digit && _pin_code_len < 16) + { + esp_bt_gap_pin_reply(param->pin_req.bda, false, 0, NULL); } - } else { - log_e("authentication failed, status:%d", param->auth_cmpl.stat); - if (auth_complete_callback) { - auth_complete_callback(false); + else + { + // log_i("Input pin code: \"%s\"=0x%x", _pin_code); + log_i("Input pin code: \"%.*s\"=0x%x", _pin_code_len, _pin_code, *(int *)_pin_code); + esp_bt_gap_pin_reply(param->pin_req.bda, true, _pin_code_len, _pin_code); } - } - break; - case ESP_BT_GAP_PIN_REQ_EVT: // Enum 5 - Legacy Pairing Pin code request - log_i("ESP_BT_GAP_PIN_REQ_EVT (min_16_digit=%d)", param->pin_req.min_16_digit); - if (param->pin_req.min_16_digit && _pin_code_len < 16) { - esp_bt_gap_pin_reply(param->pin_req.bda, false, 0, NULL); - } else { - //log_i("Input pin code: \"%s\"=0x%x", _pin_code); - log_i("Input pin code: \"%.*s\"=0x%x", _pin_code_len, _pin_code, *(int *)_pin_code); - esp_bt_gap_pin_reply(param->pin_req.bda, true, _pin_code_len, _pin_code); - } - break; + break; #ifdef CONFIG_BT_SSP_ENABLED - case ESP_BT_GAP_CFM_REQ_EVT: // Enum 6 - Security Simple Pairing User Confirmation request. - log_i("ESP_BT_GAP_CFM_REQ_EVT Please compare the numeric value: %d", param->cfm_req.num_val); - if (confirm_request_callback) { - memcpy(current_bd_addr, param->cfm_req.bda, sizeof(esp_bd_addr_t)); - confirm_request_callback(param->cfm_req.num_val); - } else { - log_w("ESP_BT_GAP_CFM_REQ_EVT: confirm_request_callback does not exist - refusing pairing"); - esp_bt_gap_ssp_confirm_reply(param->cfm_req.bda, false); - } - break; + case ESP_BT_GAP_CFM_REQ_EVT: // Enum 6 - Security Simple Pairing User Confirmation request. +#if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) + char bda_str[18]; + log_i("ESP_BT_GAP_CFM_REQ_EVT from %s. Please compare the numeric value: %d", + bda2str(param->cfm_req.bda, bda_str, 18), param->cfm_req.num_val); +#endif + if (confirm_request_callback) + { + memcpy(current_bd_addr, param->cfm_req.bda, sizeof(esp_bd_addr_t)); + confirm_request_callback(param->cfm_req.num_val); + } + else + { + // log_w("ESP_BT_GAP_CFM_REQ_EVT: confirm_request_callback does not exist - refusing pairing"); + // esp_bt_gap_ssp_confirm_reply(param->cfm_req.bda, false); + log_w("ESP_BT_GAP_CFM_REQ_EVT: confirming reply"); + esp_bt_gap_ssp_confirm_reply(param->cfm_req.bda, true); + } + break; #endif - case ESP_BT_GAP_KEY_NOTIF_EVT: // Enum 7 - Security Simple Pairing Passkey Notification - log_i("ESP_BT_GAP_KEY_NOTIF_EVT passkey:%d", param->key_notif.passkey); - break; + case ESP_BT_GAP_KEY_NOTIF_EVT: // Enum 7 - Security Simple Pairing Passkey Notification + log_i("ESP_BT_GAP_KEY_NOTIF_EVT passkey:%d", param->key_notif.passkey); + break; #ifdef CONFIG_BT_SSP_ENABLED - case ESP_BT_GAP_KEY_REQ_EVT: // Enum 8 - Security Simple Pairing Passkey request - log_i("ESP_BT_GAP_KEY_REQ_EVT Please enter passkey!"); - if (key_request_callback) { - memcpy(current_bd_addr, param->cfm_req.bda, sizeof(esp_bd_addr_t)); - key_request_callback(); - } else { - log_w("ESP_BT_GAP_KEY_REQ_EVT: key_request_callback does not exist - refuseing pairing"); - esp_bt_gap_ssp_confirm_reply(param->cfm_req.bda, false); - } - break; + case ESP_BT_GAP_KEY_REQ_EVT: // Enum 8 - Security Simple Pairing Passkey request + log_i("ESP_BT_GAP_KEY_REQ_EVT Please enter passkey!"); + if (key_request_callback) + { + memcpy(current_bd_addr, param->cfm_req.bda, sizeof(esp_bd_addr_t)); + key_request_callback(); + } + else + { + log_w("ESP_BT_GAP_KEY_REQ_EVT: key_request_callback does not exist - refuseing pairing"); + esp_bt_gap_ssp_confirm_reply(param->cfm_req.bda, false); + } + break; #endif - case ESP_BT_GAP_READ_RSSI_DELTA_EVT: // Enum 9 - Read rssi event - log_i("ESP_BT_GAP_READ_RSSI_DELTA_EVT Read rssi event"); - break; - case ESP_BT_GAP_CONFIG_EIR_DATA_EVT: // Enum 10 - Config EIR data event - log_i("ESP_BT_GAP_CONFIG_EIR_DATA_EVT: stat:%d num:%d", param->config_eir_data.stat, param->config_eir_data.eir_type_num); - break; - - case ESP_BT_GAP_SET_AFH_CHANNELS_EVT: // Enum 11 - Set AFH channels event - log_i("ESP_BT_GAP_SET_AFH_CHANNELS_EVT Set AFH channels event"); - break; - - case ESP_BT_GAP_READ_REMOTE_NAME_EVT: // Enum 12 - Read Remote Name event - if (param->read_rmt_name.stat == ESP_BT_STATUS_SUCCESS) { - log_i("ESP_BT_GAP_READ_REMOTE_NAME_EVT: %s", param->read_rmt_name.rmt_name); - memcpy(_rmt_name, param->read_rmt_name.rmt_name, ESP_BT_GAP_MAX_BDNAME_LEN + 1); - _rmt_name_valid = true; - } else { - log_i("ESP_BT_GAP_READ_REMOTE_NAME_EVT: no success stat:%d", param->read_rmt_name.stat); - } - break; - - case ESP_BT_GAP_MODE_CHG_EVT: // Enum 13 - log_i("ESP_BT_GAP_MODE_CHG_EVT: mode: %d", param->mode_chg.mode); - break; - - case ESP_BT_GAP_REMOVE_BOND_DEV_COMPLETE_EVT: // Enum - 14 remove bond device complete event - log_i("ESP_BT_GAP_REMOVE_BOND_DEV_COMPLETE_EVT remove bond device complete event"); - break; - - case ESP_BT_GAP_QOS_CMPL_EVT: // Enum 15 - QOS complete event - log_i("ESP_BT_GAP_QOS_CMPL_EVT QOS complete event"); - break; - - case ESP_BT_GAP_ACL_CONN_CMPL_STAT_EVT: // Enum 16 - ACL connection complete status event - log_i("ESP_BT_GAP_ACL_CONN_CMPL_STAT_EVT ACL connection complete status event"); - break; - - case ESP_BT_GAP_ACL_DISCONN_CMPL_STAT_EVT: // Enum 17 - ACL disconnection complete status event - log_i( - "ESP_BT_GAP_ACL_DISCONN_CMPL_STAT_EVT ACL disconnection complete status event: reason %d, handle %d", param->acl_disconn_cmpl_stat.reason, - param->acl_disconn_cmpl_stat.handle - ); - break; - - default: log_i("ESP-BT_GAP_* unknown message: %d", event); break; - } + case ESP_BT_GAP_READ_RSSI_DELTA_EVT: // Enum 9 - Read rssi event + log_i("ESP_BT_GAP_READ_RSSI_DELTA_EVT Read rssi event"); + break; + case ESP_BT_GAP_CONFIG_EIR_DATA_EVT: // Enum 10 - Config EIR data event + log_i("ESP_BT_GAP_CONFIG_EIR_DATA_EVT: stat:%d num:%d", param->config_eir_data.stat, + param->config_eir_data.eir_type_num); + break; + + case ESP_BT_GAP_SET_AFH_CHANNELS_EVT: // Enum 11 - Set AFH channels event + log_i("ESP_BT_GAP_SET_AFH_CHANNELS_EVT Set AFH channels event"); + break; + + case ESP_BT_GAP_READ_REMOTE_NAME_EVT: // Enum 12 - Read Remote Name event + if (param->read_rmt_name.stat == ESP_BT_STATUS_SUCCESS) + { + log_i("ESP_BT_GAP_READ_REMOTE_NAME_EVT: %s", param->read_rmt_name.rmt_name); + memcpy(_rmt_name, param->read_rmt_name.rmt_name, ESP_BT_GAP_MAX_BDNAME_LEN + 1); + _rmt_name_valid = true; + } + else + { + log_i("ESP_BT_GAP_READ_REMOTE_NAME_EVT: no success stat:%d", param->read_rmt_name.stat); + } + break; + + case ESP_BT_GAP_MODE_CHG_EVT: // Enum 13 + log_i("ESP_BT_GAP_MODE_CHG_EVT: mode: %d", param->mode_chg.mode); + break; + + case ESP_BT_GAP_REMOVE_BOND_DEV_COMPLETE_EVT: // Enum - 14 remove bond device complete event + log_i("ESP_BT_GAP_REMOVE_BOND_DEV_COMPLETE_EVT remove bond device complete event"); + break; + + case ESP_BT_GAP_QOS_CMPL_EVT: // Enum 15 - QOS complete event + log_i("ESP_BT_GAP_QOS_CMPL_EVT QOS complete event"); + break; + + case ESP_BT_GAP_ACL_CONN_CMPL_STAT_EVT: // Enum 16 - ACL connection complete status event + { +#if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) + char bda_str[18]; + log_i("ESP_BT_GAP_ACL_CONN_CMPL_STAT_EVT ACL connection from: %s", + bda2str(param->acl_conn_cmpl_stat.bda, bda_str, 18)); +#endif + + memcpy(_aclAddress, param->acl_conn_cmpl_stat.bda, ESP_BD_ADDR_LEN); + + _aclConnected = true; + } + break; + + case ESP_BT_GAP_ACL_DISCONN_CMPL_STAT_EVT: // Enum 17 - ACL disconnection complete status event + log_i("ESP_BT_GAP_ACL_DISCONN_CMPL_STAT_EVT ACL disconnection complete status event: reason %d, handle %d", + param->acl_disconn_cmpl_stat.reason, param->acl_disconn_cmpl_stat.handle); + break; + +#if false + case ESP_BT_GAP_ENC_CHG_EVT: // Enum 21 + log_i("ESP_BT_GAP_ENC_CHG_EVT"); + break; +#endif + + default: + log_i("ESP-BT_GAP_* unknown message: %d", event); + break; + } } -static bool _init_bt(const char *deviceName, bt_mode mode, uint16_t rxQueueSize, uint16_t txQueueSize) { - if (!_bt_event_group) { - _bt_event_group = xEventGroupCreate(); - if (!_bt_event_group) { - log_e("BT Event Group Create Failed!"); - return false; - } - xEventGroupClearBits(_bt_event_group, 0xFFFFFF); - } - if (!_spp_event_group) { - _spp_event_group = xEventGroupCreate(); - if (!_spp_event_group) { - log_e("SPP Event Group Create Failed!"); - return false; - } - xEventGroupClearBits(_spp_event_group, 0xFFFFFF); - xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); - xEventGroupSetBits(_spp_event_group, SPP_DISCONNECTED); - xEventGroupSetBits(_spp_event_group, SPP_CLOSED); - } - if (_spp_rx_queue == NULL) { - //_spp_rx_queue = xQueueCreate(RX_QUEUE_SIZE, sizeof(uint8_t)); //initialize the queue - _spp_rx_queue = xQueueCreate(rxQueueSize, sizeof(uint8_t)); //initialize the queue - if (_spp_rx_queue == NULL) { - log_e("RX Queue Create Failed"); - return false; - } - } - if (_spp_tx_queue == NULL) { - //_spp_tx_queue = xQueueCreate(TX_QUEUE_SIZE, sizeof(spp_packet_t *)); //initialize the queue - _spp_tx_queue = xQueueCreate(txQueueSize, sizeof(spp_packet_t*)); //initialize the queue - if (_spp_tx_queue == NULL) { - log_e("TX Queue Create Failed"); - return false; - } - } - if (_spp_tx_done == NULL) { - _spp_tx_done = xSemaphoreCreateBinary(); - if (_spp_tx_done == NULL) { - log_e("TX Semaphore Create Failed"); - return false; - } - xSemaphoreTake(_spp_tx_done, 0); - } - - if (!_spp_task_handle) { - xTaskCreatePinnedToCore(_spp_tx_task, "spp_tx", 4096, NULL, configMAX_PRIORITIES - 1, &_spp_task_handle, 0); - if (!_spp_task_handle) { - log_e("Network Event Task Start Failed!"); - return false; - } - } - - if (!btStarted() && !btStartMode(mode)) { - log_e("initialize controller failed"); - return false; - } +static bool _init_bt(const char *deviceName, bt_mode mode, uint16_t rxQueueSize, uint16_t txQueueSize) +{ + if (!_bt_event_group) + { + _bt_event_group = xEventGroupCreate(); + if (!_bt_event_group) + { + log_e("BT Event Group Create Failed!"); + return false; + } + xEventGroupClearBits(_bt_event_group, 0xFFFFFF); + } + if (!_spp_event_group) + { + _spp_event_group = xEventGroupCreate(); + if (!_spp_event_group) + { + log_e("SPP Event Group Create Failed!"); + return false; + } + xEventGroupClearBits(_spp_event_group, 0xFFFFFF); + xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); + xEventGroupSetBits(_spp_event_group, SPP_DISCONNECTED); + xEventGroupSetBits(_spp_event_group, SPP_CLOSED); + } + if (_spp_rx_queue == NULL) + { + //_spp_rx_queue = xQueueCreate(RX_QUEUE_SIZE, sizeof(uint8_t)); //initialize the queue + _spp_rx_queue = xQueueCreate(rxQueueSize, sizeof(uint8_t)); // initialize the queue + if (_spp_rx_queue == NULL) + { + log_e("RX Queue Create Failed"); + return false; + } + } + if (_spp_tx_queue == NULL) + { + //_spp_tx_queue = xQueueCreate(TX_QUEUE_SIZE, sizeof(spp_packet_t *)); //initialize the queue + _spp_tx_queue = xQueueCreate(txQueueSize, sizeof(spp_packet_t *)); // initialize the queue + if (_spp_tx_queue == NULL) + { + log_e("TX Queue Create Failed"); + return false; + } + } + if (_spp_tx_done == NULL) + { + _spp_tx_done = xSemaphoreCreateBinary(); + if (_spp_tx_done == NULL) + { + log_e("TX Semaphore Create Failed"); + return false; + } + xSemaphoreTake(_spp_tx_done, 0); + } - esp_bluedroid_status_t bt_state = esp_bluedroid_get_status(); - if (bt_state == ESP_BLUEDROID_STATUS_UNINITIALIZED) { - if (esp_bluedroid_init()) { - log_e("initialize bluedroid failed"); - return false; + if (!_spp_task_handle) + { + xTaskCreatePinnedToCore(_spp_tx_task, "spp_tx", 4096, NULL, configMAX_PRIORITIES - 1, &_spp_task_handle, 0); + if (!_spp_task_handle) + { + log_e("Network Event Task Start Failed!"); + return false; + } } - } - if (bt_state != ESP_BLUEDROID_STATUS_ENABLED) { - if (esp_bluedroid_enable()) { - log_e("enable bluedroid failed"); - return false; + if (!btStarted() && !btStartMode(mode)) + { + log_e("initialize controller failed"); + return false; } - } - if (esp_bt_gap_register_callback(esp_bt_gap_cb) != ESP_OK) { - log_e("gap register failed"); - return false; - } + esp_bluedroid_status_t bt_state = esp_bluedroid_get_status(); + if (bt_state == ESP_BLUEDROID_STATUS_UNINITIALIZED) + { +// #ifdef CONFIG_BT_SSP_ENABLED +#if false + // Start with SSP + esp_bluedroid_config_t bluedroid_cfg = BT_BLUEDROID_INIT_CONFIG_DEFAULT(); + if (_enableSSP == false) + bluedroid_cfg.ssp_en = false; + + if (esp_bluedroid_init_with_cfg(&bluedroid_cfg)) // *** Not supported by IDF5.1 *** + { + log_e("initialize bluedroid failed"); + return false; + } +#else + if (esp_bluedroid_init()) + { + log_e("initialize bluedroid failed"); + return false; + } +#endif + } - if (esp_spp_register_callback(esp_spp_cb) != ESP_OK) { - log_e("spp register failed"); - return false; - } + if (bt_state != ESP_BLUEDROID_STATUS_ENABLED) + { + if (esp_bluedroid_enable()) + { + log_e("enable bluedroid failed"); + return false; + } + } - esp_spp_cfg_t cfg = BT_SPP_DEFAULT_CONFIG(); - cfg.mode = ESP_SPP_MODE_CB; - if (esp_spp_enhanced_init(&cfg) != ESP_OK) { - log_e("spp init failed"); - return false; - } + if (esp_bt_gap_register_callback(esp_bt_gap_cb) != ESP_OK) + { + log_e("gap register failed"); + return false; + } + + if (esp_spp_register_callback(esp_spp_cb) != ESP_OK) + { + log_e("spp register failed"); + return false; + } + + esp_spp_cfg_t cfg = BT_SPP_DEFAULT_CONFIG(); + cfg.mode = ESP_SPP_MODE_CB; + if (esp_spp_enhanced_init(&cfg) != ESP_OK) + { + log_e("spp init failed"); + return false; + } - log_i("device name set"); - esp_bt_dev_set_device_name(deviceName); + log_i("device name set"); + esp_bt_dev_set_device_name(deviceName); + // Note: in later cores, this changes to: + // esp_bt_gap_set_device_name(deviceName); #ifdef CONFIG_BT_SSP_ENABLED - if (_enableSSP) { - log_i("Simple Secure Pairing"); - esp_bt_sp_param_t param_type = ESP_BT_SP_IOCAP_MODE; - esp_bt_io_cap_t iocap; - if (_IO_CAP_INPUT && _IO_CAP_OUTPUT) { - iocap = ESP_BT_IO_CAP_IO; // Display with prompt - } else if (!_IO_CAP_INPUT && _IO_CAP_OUTPUT) { - iocap = ESP_BT_IO_CAP_OUT; // DisplayOnly - } else if (_IO_CAP_INPUT && !_IO_CAP_OUTPUT) { - iocap = ESP_BT_IO_CAP_IN; // Input only - } else if (!_IO_CAP_INPUT && !_IO_CAP_OUTPUT) { - iocap = ESP_BT_IO_CAP_NONE; // No input/output - } - esp_bt_gap_set_security_param(param_type, &iocap, sizeof(uint8_t)); - } + if (_enableSSP) + { + log_i("Simple Secure Pairing"); + esp_bt_sp_param_t param_type = ESP_BT_SP_IOCAP_MODE; + esp_bt_io_cap_t iocap; + if (_IO_CAP_INPUT && _IO_CAP_OUTPUT) + { + iocap = ESP_BT_IO_CAP_IO; // Display with prompt + } + else if (!_IO_CAP_INPUT && _IO_CAP_OUTPUT) + { + iocap = ESP_BT_IO_CAP_OUT; // DisplayOnly + } + else if (_IO_CAP_INPUT && !_IO_CAP_OUTPUT) + { + iocap = ESP_BT_IO_CAP_IN; // Input only + } + else if (!_IO_CAP_INPUT && !_IO_CAP_OUTPUT) + { + iocap = ESP_BT_IO_CAP_NONE; // No input/output + } + esp_bt_gap_set_security_param(param_type, &iocap, sizeof(uint8_t)); + } #endif - // the default BTA_DM_COD_LOUDSPEAKER does not work with the macOS BT stack - esp_bt_cod_t cod; - cod.major = 0b00001; - cod.minor = 0b000100; - cod.service = 0b00000010110; - if (esp_bt_gap_set_cod(cod, ESP_BT_INIT_COD) != ESP_OK) { - log_e("set cod failed"); - return false; - } - return true; + _aclConnected = false; + + // the default BTA_DM_COD_LOUDSPEAKER does not work with the macOS BT stack + esp_bt_cod_t cod; + cod.major = 0b00001; + cod.minor = 0b000100; + cod.service = 0b00000010110; + if (esp_bt_gap_set_cod(cod, ESP_BT_INIT_COD) != ESP_OK) + { + log_e("set cod failed"); + return false; + } + return true; } -static bool _stop_bt() { - if (btStarted()) { - if (_spp_client) { - esp_spp_disconnect(_spp_client); - } - esp_spp_deinit(); - esp_bluedroid_disable(); - esp_bluedroid_deinit(); - btStop(); - } - _spp_client = 0; - if (_spp_task_handle) { - vTaskDelete(_spp_task_handle); - _spp_task_handle = NULL; - } - if (_spp_event_group) { - vEventGroupDelete(_spp_event_group); - _spp_event_group = NULL; - } - if (_spp_rx_queue) { - vQueueDelete(_spp_rx_queue); - //ToDo: clear RX queue when in packet mode - _spp_rx_queue = NULL; - } - if (_spp_tx_queue) { - spp_packet_t *packet = NULL; - while (xQueueReceive(_spp_tx_queue, &packet, 0) == pdTRUE) { - free(packet); - } - vQueueDelete(_spp_tx_queue); - _spp_tx_queue = NULL; - } - if (_spp_tx_done) { - vSemaphoreDelete(_spp_tx_done); - _spp_tx_done = NULL; - } - if (_bt_event_group) { - vEventGroupDelete(_bt_event_group); - _bt_event_group = NULL; - } - return true; +static bool _stop_bt() +{ + if (btStarted()) + { + if (_spp_client) + { + esp_spp_disconnect(_spp_client); + } + esp_spp_deinit(); + esp_bluedroid_disable(); + esp_bluedroid_deinit(); + btStop(); + } + _spp_client = 0; + if (_spp_task_handle) + { + vTaskDelete(_spp_task_handle); + _spp_task_handle = NULL; + } + if (_spp_event_group) + { + vEventGroupDelete(_spp_event_group); + _spp_event_group = NULL; + } + if (_spp_rx_queue) + { + vQueueDelete(_spp_rx_queue); + // ToDo: clear RX queue when in packet mode + _spp_rx_queue = NULL; + } + if (_spp_tx_queue) + { + spp_packet_t *packet = NULL; + while (xQueueReceive(_spp_tx_queue, &packet, 0) == pdTRUE) + { + free(packet); + } + vQueueDelete(_spp_tx_queue); + _spp_tx_queue = NULL; + } + if (_spp_tx_done) + { + vSemaphoreDelete(_spp_tx_done); + _spp_tx_done = NULL; + } + if (_bt_event_group) + { + vEventGroupDelete(_bt_event_group); + _bt_event_group = NULL; + } + return true; } -static bool waitForConnect(int timeout) { - TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; - // wait for connected or closed - EventBits_t rc = xEventGroupWaitBits(_spp_event_group, SPP_CONNECTED | SPP_CLOSED, pdFALSE, pdFALSE, xTicksToWait); - if ((rc & SPP_CONNECTED) != 0) { - return true; - } else if ((rc & SPP_CLOSED) != 0) { +static bool waitForConnect(int timeout) +{ + TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; + // wait for connected or closed + EventBits_t rc = xEventGroupWaitBits(_spp_event_group, SPP_CONNECTED | SPP_CLOSED, pdFALSE, pdFALSE, xTicksToWait); + if ((rc & SPP_CONNECTED) != 0) + { + return true; + } + else if ((rc & SPP_CLOSED) != 0) + { + if (timeout > 0) + log_d("connection closed!"); + return false; + } if (timeout > 0) - log_d("connection closed!"); + log_d("timeout"); return false; - } - if (timeout > 0) - log_d("timeout"); - return false; } -static bool waitForDiscovered(int timeout) { - TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; - return (xEventGroupWaitBits(_spp_event_group, BT_DISCOVERY_COMPLETED, pdFALSE, pdTRUE, xTicksToWait) & BT_DISCOVERY_COMPLETED) != 0; +static bool waitForDiscovered(int timeout) +{ + TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; + return (xEventGroupWaitBits(_spp_event_group, BT_DISCOVERY_COMPLETED, pdFALSE, pdTRUE, xTicksToWait) & + BT_DISCOVERY_COMPLETED) != 0; } -static bool waitForSDPRecord(int timeout) { - TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; - return (xEventGroupWaitBits(_bt_event_group, BT_SDP_COMPLETED, pdFALSE, pdTRUE, xTicksToWait) & BT_SDP_COMPLETED) != 0; +static bool waitForSDPRecord(int timeout) +{ + log_i("waiting for SDP record"); + TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; + return (xEventGroupWaitBits(_bt_event_group, BT_SDP_COMPLETED, pdFALSE, pdTRUE, xTicksToWait) & BT_SDP_COMPLETED) != + 0; } /** * Serial Bluetooth Arduino * */ -BluetoothSerial::BluetoothSerial() { - local_name = "ESP32"; //default bluetooth name +BluetoothSerial::BluetoothSerial() +{ + local_name = "ESP32"; // default bluetooth name } -BluetoothSerial::~BluetoothSerial(void) { - _stop_bt(); +BluetoothSerial::~BluetoothSerial(void) +{ + _stop_bt(); } /** * @param isMaster set to true if you want to connect to an other device * @param disableBLE if BLE is not used, its ram can be freed to get +10kB free ram */ -//bool BluetoothSerial::begin(String localName, bool isMaster, bool disableBLE) { -bool BluetoothSerial::begin(String localName, bool isMaster, bool disableBLE, uint16_t rxQueueSize, uint16_t txQueueSize) { - _isMaster = isMaster; - if (localName.length()) { - local_name = localName; - } - return _init_bt(local_name.c_str(), disableBLE ? BT_MODE_CLASSIC_BT : BT_MODE_BTDM, rxQueueSize, txQueueSize); +// bool BluetoothSerial::begin(String localName, bool isMaster, bool disableBLE) { +bool BluetoothSerial::begin(String localName, bool isMaster, bool disableBLE, uint16_t rxQueueSize, + uint16_t txQueueSize) +{ + _isMaster = isMaster; + if (localName.length()) + { + local_name = localName; + } + return _init_bt(local_name.c_str(), disableBLE ? BT_MODE_CLASSIC_BT : BT_MODE_BTDM, rxQueueSize, txQueueSize); } -int BluetoothSerial::available(void) { - if (_spp_rx_queue == NULL) { - return 0; - } - return uxQueueMessagesWaiting(_spp_rx_queue); +int BluetoothSerial::available(void) +{ + if (_spp_rx_queue == NULL) + { + return 0; + } + return uxQueueMessagesWaiting(_spp_rx_queue); } -int BluetoothSerial::peek(void) { - uint8_t c; - if (_spp_rx_queue && xQueuePeek(_spp_rx_queue, &c, this->timeoutTicks)) { - return c; - } - return -1; +int BluetoothSerial::peek(void) +{ + uint8_t c; + if (_spp_rx_queue && xQueuePeek(_spp_rx_queue, &c, this->timeoutTicks)) + { + return c; + } + return -1; } -bool BluetoothSerial::hasClient(void) { - return _spp_client > 0; +bool BluetoothSerial::hasClient(void) +{ + return _spp_client > 0; } -int BluetoothSerial::read() { +int BluetoothSerial::read() +{ - uint8_t c = 0; - if (_spp_rx_queue && xQueueReceive(_spp_rx_queue, &c, this->timeoutTicks)) { - return c; - } - return -1; + uint8_t c = 0; + if (_spp_rx_queue && xQueueReceive(_spp_rx_queue, &c, this->timeoutTicks)) + { + return c; + } + return -1; } /** * Set timeout for read / peek */ -void BluetoothSerial::setTimeout(int timeoutMS) { - Stream::setTimeout(timeoutMS); - this->timeoutTicks = timeoutMS / portTICK_PERIOD_MS; +void BluetoothSerial::setTimeout(int timeoutMS) +{ + Stream::setTimeout(timeoutMS); + this->timeoutTicks = timeoutMS / portTICK_PERIOD_MS; } -size_t BluetoothSerial::write(uint8_t c) { - return write(&c, 1); +size_t BluetoothSerial::write(uint8_t c) +{ + return write(&c, 1); } -size_t BluetoothSerial::write(const uint8_t *buffer, size_t size) { - if (!_spp_client) { - return 0; - } - return (_spp_queue_packet((uint8_t *)buffer, size) == ESP_OK) ? size : 0; +size_t BluetoothSerial::write(const uint8_t *buffer, size_t size) +{ + if (!_spp_client) + { + return 0; + } + return (_spp_queue_packet((uint8_t *)buffer, size) == ESP_OK) ? size : 0; } -void BluetoothSerial::flush() { - if (_spp_tx_queue != NULL) { - while (uxQueueMessagesWaiting(_spp_tx_queue) > 0) { - delay(2); // https://github.com/espressif/arduino-esp32/pull/9905 +void BluetoothSerial::flush() +{ + if (_spp_tx_queue != NULL) + { + while (uxQueueMessagesWaiting(_spp_tx_queue) > 0) + { + delay(2); // https://github.com/espressif/arduino-esp32/pull/9905 + } } - } } -void BluetoothSerial::end() { - _stop_bt(); +void BluetoothSerial::end() +{ + _stop_bt(); } /** * free additional ~30kB ram, reset is required to enable BT again */ -void BluetoothSerial::memrelease() { - esp_bt_mem_release(ESP_BT_MODE_BTDM); +void BluetoothSerial::memrelease() +{ + esp_bt_mem_release(ESP_BT_MODE_BTDM); } #ifdef CONFIG_BT_SSP_ENABLED -void BluetoothSerial::onConfirmRequest(ConfirmRequestCb cb) { - confirm_request_callback = cb; +void BluetoothSerial::onConfirmRequest(ConfirmRequestCb cb) +{ + confirm_request_callback = cb; } -void BluetoothSerial::onKeyRequest(KeyRequestCb cb) { - key_request_callback = cb; +void BluetoothSerial::onKeyRequest(KeyRequestCb cb) +{ + key_request_callback = cb; } -void BluetoothSerial::respondPasskey(uint32_t passkey) { - esp_bt_gap_ssp_passkey_reply(current_bd_addr, true, passkey); +void BluetoothSerial::respondPasskey(uint32_t passkey) +{ + esp_bt_gap_ssp_passkey_reply(current_bd_addr, true, passkey); } #endif -void BluetoothSerial::onAuthComplete(AuthCompleteCb cb) { - auth_complete_callback = cb; +void BluetoothSerial::onAuthComplete(AuthCompleteCb cb) +{ + auth_complete_callback = cb; } -void BluetoothSerial::confirmReply(boolean confirm) { - esp_bt_gap_ssp_confirm_reply(current_bd_addr, confirm); +void BluetoothSerial::confirmReply(boolean confirm) +{ +#if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) + char bda_str[18]; + log_i("BluetoothSerial::confirmReply : %s : %s", + bda2str(current_bd_addr, bda_str, 18), confirm ? "true" : "false"); +#endif + esp_bt_gap_ssp_confirm_reply(current_bd_addr, confirm); } -esp_err_t BluetoothSerial::register_callback(esp_spp_cb_t callback) { - custom_spp_callback = callback; - return ESP_OK; +esp_err_t BluetoothSerial::register_callback(esp_spp_cb_t callback) +{ + custom_spp_callback = callback; + return ESP_OK; } #ifdef CONFIG_BT_SSP_ENABLED // Enable Simple Secure Pairing (using generated PIN) // This must be called before calling begin, otherwise has no effect! -void BluetoothSerial::enableSSP() { - if (isReady(false, READY_TIMEOUT)) { - log_i("Attempted to enable SSP for already initialized driver. Restart to take effect with end() followed by begin()"); - return; - } - _enableSSP = true; - _IO_CAP_INPUT = true; - _IO_CAP_OUTPUT = true; +void BluetoothSerial::enableSSP() +{ + if (isReady(false, READY_TIMEOUT)) + { + log_i("Attempted to enable SSP for already initialized driver. Restart to take effect with end() followed by " + "begin()"); + return; + } + _enableSSP = true; + _IO_CAP_INPUT = true; + _IO_CAP_OUTPUT = true; } // Enable Simple Secure Pairing (using generated PIN) @@ -944,69 +1191,82 @@ void BluetoothSerial::enableSSP() { // Behavior description: // When both Input and Output are false only the other device authenticates pairing without any pin. // When Output is true and Input is false only the other device authenticates pairing without any pin. -// When both Input and Output are true both devices display randomly generated code and if they match authenticate pairing on both devices -// - This must be implemented by registering callback via onConfirmRequest() and in this callback request user input and call confirmReply(true); if the authenticated +// When both Input and Output are true both devices display randomly generated code and if they match authenticate +// pairing on both devices +// - This must be implemented by registering callback via onConfirmRequest() and in this callback request user input +// and call confirmReply(true); if the authenticated // otherwise call `confirmReply(false)` to reject the pairing. -// When Input is true and Output is false User will be required to input the passkey to the ESP32 device to authenticate. -// - This must be implemented by registering callback via onKeyRequest() and in this callback the entered passkey will be responded via respondPasskey(passkey); -void BluetoothSerial::enableSSP(bool inputCpability, bool outputCapability) { - log_i("Enabling SSP: input capability=%d; output capability=%d", inputCpability, outputCapability); - _enableSSP = true; - _IO_CAP_INPUT = inputCpability; - _IO_CAP_OUTPUT = outputCapability; +// When Input is true and Output is false User will be required to input the passkey to the ESP32 device to +// authenticate. +// - This must be implemented by registering callback via onKeyRequest() and in this callback the entered passkey will +// be responded via respondPasskey(passkey); +void BluetoothSerial::enableSSP(bool inputCpability, bool outputCapability) +{ + log_i("Enabling SSP: input capability=%d; output capability=%d", inputCpability, outputCapability); + _enableSSP = true; + _IO_CAP_INPUT = inputCpability; + _IO_CAP_OUTPUT = outputCapability; } // Disable Simple Secure Pairing (using generated PIN) // This must be called before calling begin, otherwise has no effect! -void BluetoothSerial::disableSSP() { - _enableSSP = false; +void BluetoothSerial::disableSSP() +{ + _enableSSP = false; } #else -bool BluetoothSerial::setPin(const char *pin, uint8_t pin_code_len) { - if (pin_code_len == 0 || pin_code_len > 16) { - log_e("PIN code must be 1-16 Bytes long! Called with length %d", pin_code_len); - return false; - } - _pin_code_len = pin_code_len; - memcpy(_pin_code, pin, pin_code_len); - return (esp_bt_gap_set_pin(ESP_BT_PIN_TYPE_FIXED, _pin_code_len, _pin_code) == ESP_OK); +bool BluetoothSerial::setPin(const char *pin, uint8_t pin_code_len) +{ + if (pin_code_len == 0 || pin_code_len > 16) + { + log_e("PIN code must be 1-16 Bytes long! Called with length %d", pin_code_len); + return false; + } + _pin_code_len = pin_code_len; + memcpy(_pin_code, pin, pin_code_len); + return (esp_bt_gap_set_pin(ESP_BT_PIN_TYPE_FIXED, _pin_code_len, _pin_code) == ESP_OK); } #endif -bool BluetoothSerial::connect(String remoteName) { - bool retval = false; +bool BluetoothSerial::connect(String remoteName) +{ + bool retval = false; - if (!isReady(true, READY_TIMEOUT)) { - return false; - } - if (remoteName && remoteName.length() < 1) { - log_e("No remote name is provided"); - return false; - } - disconnect(); - _doConnect = true; - _isRemoteAddressSet = true; - _sec_mask = ESP_SPP_SEC_ENCRYPT | ESP_SPP_SEC_AUTHENTICATE; - _role = ESP_SPP_ROLE_MASTER; - strncpy(_remote_name, remoteName.c_str(), ESP_BT_GAP_MAX_BDNAME_LEN); - _remote_name[ESP_BT_GAP_MAX_BDNAME_LEN] = 0; - log_i("master : remoteName"); - // will first resolve name to address + if (!isReady(true, READY_TIMEOUT)) + { + return false; + } + if (remoteName && remoteName.length() < 1) + { + log_e("No remote name is provided"); + return false; + } + disconnect(); + _doConnect = true; + _isRemoteAddressSet = true; + _sec_mask = ESP_SPP_SEC_ENCRYPT | ESP_SPP_SEC_AUTHENTICATE; + _role = ESP_SPP_ROLE_MASTER; + strncpy(_remote_name, remoteName.c_str(), ESP_BT_GAP_MAX_BDNAME_LEN); + _remote_name[ESP_BT_GAP_MAX_BDNAME_LEN] = 0; + log_i("master : remoteName"); + // will first resolve name to address #ifdef ESP_IDF_VERSION_MAJOR - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); + esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); #else - esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); + esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); #endif - xEventGroupClearBits(_spp_event_group, SPP_CLOSED); - if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, INQ_LEN, INQ_NUM_RSPS) == ESP_OK) { - retval = waitForConnect(SCAN_TIMEOUT); - } - if (retval == false) { - _isRemoteAddressSet = false; - } - return retval; + xEventGroupClearBits(_spp_event_group, SPP_CLOSED); + if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, INQ_LEN, INQ_NUM_RSPS) == ESP_OK) + { + retval = waitForConnect(SCAN_TIMEOUT); + } + if (retval == false) + { + _isRemoteAddressSet = false; + } + return retval; } /** @@ -1020,127 +1280,161 @@ bool BluetoothSerial::connect(String remoteName) { * ESP_SPP_ROLE_MASTER master can handle up to 7 connections to slaves * ESP_SPP_ROLE_SLAVE can only have one connection to a master */ -bool BluetoothSerial::connect(uint8_t remoteAddress[], int channel, esp_spp_sec_t sec_mask, esp_spp_role_t role) { - bool retval = false; - if (!isReady(true, READY_TIMEOUT)) { - return false; - } - if (!remoteAddress) { - log_e("No remote address is provided"); - return false; - } - disconnect(); - _doConnect = true; - _remote_name[0] = 0; - _isRemoteAddressSet = true; - _sec_mask = sec_mask; - _role = role; - memcpy(_peer_bd_addr, remoteAddress, ESP_BD_ADDR_LEN); - log_i("master : remoteAddress"); - xEventGroupClearBits(_spp_event_group, SPP_CLOSED); - if (channel > 0) { +bool BluetoothSerial::connect(uint8_t remoteAddress[], int channel, esp_spp_sec_t sec_mask, esp_spp_role_t role) +{ + bool retval = false; + if (!isReady(true, READY_TIMEOUT)) + { + return false; + } + if (!remoteAddress) + { + log_e("No remote address is provided"); + return false; + } + disconnect(); + _doConnect = true; + _remote_name[0] = 0; + _isRemoteAddressSet = true; + _sec_mask = sec_mask; + _role = role; + memcpy(_peer_bd_addr, remoteAddress, ESP_BD_ADDR_LEN); + log_i("master : remoteAddress"); + xEventGroupClearBits(_spp_event_group, SPP_CLOSED); + if (channel > 0) + { #if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) - char bda_str[18]; - log_i("spp connect to remote %s channel %d", bda2str(_peer_bd_addr, bda_str, sizeof(bda_str)), channel); + char bda_str[18]; + log_i("spp connect to remote %s channel %d", bda2str(_peer_bd_addr, bda_str, sizeof(bda_str)), channel); #endif - if (esp_spp_connect(sec_mask, role, channel, _peer_bd_addr) != ESP_OK) { - log_e("spp connect failed"); - retval = false; - } else { - retval = waitForConnect(READY_TIMEOUT); - if (retval) { - log_i("connected"); - } else { - if (this->isClosed()) { - log_e("connect failed"); - } else { - log_e("connect timed out after %dms", READY_TIMEOUT); + if (esp_spp_connect(sec_mask, role, channel, _peer_bd_addr) != ESP_OK) + { + log_e("spp connect failed"); + retval = false; + } + else + { + retval = waitForConnect(READY_TIMEOUT); + if (retval) + { + log_i("connected"); + } + else + { + if (this->isClosed()) + { + log_e("connect failed"); + } + else + { + log_e("connect timed out after %dms", READY_TIMEOUT); + } + } } - } } - } else if (esp_spp_start_discovery(_peer_bd_addr) == ESP_OK) { - retval = waitForConnect(READY_TIMEOUT); - } + else if (esp_spp_start_discovery(_peer_bd_addr) == ESP_OK) + { + retval = waitForConnect(READY_TIMEOUT); + } - if (!retval) { - _isRemoteAddressSet = false; - } - return retval; + if (!retval) + { + _isRemoteAddressSet = false; + } + return retval; } -bool BluetoothSerial::connect() { - if (!isReady(true, READY_TIMEOUT)) { - return false; - } - _doConnect = true; - if (_isRemoteAddressSet) { - disconnect(); - // use resolved or set address first - log_i("master : remoteAddress"); - if (esp_spp_start_discovery(_peer_bd_addr) == ESP_OK) { - return waitForConnect(READY_TIMEOUT); +bool BluetoothSerial::connect() +{ + if (!isReady(true, READY_TIMEOUT)) + { + return false; } - return false; - } else if (_remote_name[0]) { - disconnect(); - log_i("master : remoteName"); - // will resolve name to address first - it may take a while + _doConnect = true; + if (_isRemoteAddressSet) + { + disconnect(); + // use resolved or set address first + log_i("master : remoteAddress"); + if (esp_spp_start_discovery(_peer_bd_addr) == ESP_OK) + { + return waitForConnect(READY_TIMEOUT); + } + return false; + } + else if (_remote_name[0]) + { + disconnect(); + log_i("master : remoteName"); + // will resolve name to address first - it may take a while #ifdef ESP_IDF_VERSION_MAJOR - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); + esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); #else - esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); + esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); #endif - if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, INQ_LEN, INQ_NUM_RSPS) == ESP_OK) { - return waitForConnect(SCAN_TIMEOUT); + if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, INQ_LEN, INQ_NUM_RSPS) == ESP_OK) + { + return waitForConnect(SCAN_TIMEOUT); + } + return false; } + log_e("Neither Remote name nor address was provided"); return false; - } - log_e("Neither Remote name nor address was provided"); - return false; } -bool BluetoothSerial::disconnect() { - if (_spp_client) { - flush(); - log_i("disconnecting"); - if (esp_spp_disconnect(_spp_client) == ESP_OK) { - TickType_t xTicksToWait = READY_TIMEOUT / portTICK_PERIOD_MS; - return (xEventGroupWaitBits(_spp_event_group, SPP_DISCONNECTED, pdFALSE, pdTRUE, xTicksToWait) & SPP_DISCONNECTED) != 0; +bool BluetoothSerial::disconnect() +{ + if (_spp_client) + { + flush(); + log_i("disconnecting"); + if (esp_spp_disconnect(_spp_client) == ESP_OK) + { + TickType_t xTicksToWait = READY_TIMEOUT / portTICK_PERIOD_MS; + return (xEventGroupWaitBits(_spp_event_group, SPP_DISCONNECTED, pdFALSE, pdTRUE, xTicksToWait) & + SPP_DISCONNECTED) != 0; + } } - } - return false; + return false; } -bool BluetoothSerial::unpairDevice(uint8_t remoteAddress[]) { - if (isReady(false, READY_TIMEOUT)) { - log_i("removing bonded device"); - return (esp_bt_gap_remove_bond_device(remoteAddress) == ESP_OK); - } - return false; +bool BluetoothSerial::unpairDevice(uint8_t remoteAddress[]) +{ + if (isReady(false, READY_TIMEOUT)) + { + log_i("removing bonded device"); + return (esp_bt_gap_remove_bond_device(remoteAddress) == ESP_OK); + } + return false; } -bool BluetoothSerial::connected(int timeout) { - return waitForConnect(timeout); +bool BluetoothSerial::connected(int timeout) +{ + return waitForConnect(timeout); } /** * true if a connection terminated or a connection attempt failed */ -bool BluetoothSerial::isClosed() { - return xEventGroupGetBits(_spp_event_group) & SPP_CLOSED; +bool BluetoothSerial::isClosed() +{ + return xEventGroupGetBits(_spp_event_group) & SPP_CLOSED; } -bool BluetoothSerial::isReady(bool checkMaster, int timeout) { - if (checkMaster && !_isMaster) { - log_e("Master mode is not active. Call begin(localName, true) to enable Master mode"); - return false; - } - if (!btStarted()) { - log_e("BT is not initialized. Call begin() first"); - return false; - } - TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; - return (xEventGroupWaitBits(_spp_event_group, SPP_RUNNING, pdFALSE, pdTRUE, xTicksToWait) & SPP_RUNNING) != 0; +bool BluetoothSerial::isReady(bool checkMaster, int timeout) +{ + if (checkMaster && !_isMaster) + { + log_e("Master mode is not active. Call begin(localName, true) to enable Master mode"); + return false; + } + if (!btStarted()) + { + log_e("BT is not initialized. Call begin() first"); + return false; + } + TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; + return (xEventGroupWaitBits(_spp_event_group, SPP_RUNNING, pdFALSE, pdTRUE, xTicksToWait) & SPP_RUNNING) != 0; } /** @@ -1149,24 +1443,27 @@ bool BluetoothSerial::isReady(bool checkMaster, int timeout) { * @param[in] timeoutMs can range from MIN_INQ_TIME to MAX_INQ_TIME * @return in case of Error immediately Empty ScanResults. */ -BTScanResults *BluetoothSerial::discover(int timeoutMs) { - scanResults.clear(); - if (timeoutMs < MIN_INQ_TIME || timeoutMs > MAX_INQ_TIME) { - log_e("Timeout out of bounds: MIN=%d; MAX=%d; requested=%d", MIN_INQ_TIME, MAX_INQ_TIME, timeoutMs); - return nullptr; - } - int timeout = timeoutMs / INQ_TIME; - log_i("discover::disconnect"); - disconnect(); - log_i("discovering"); - // will resolve name to address first - it may take a while - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); - if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, timeout, 0) == ESP_OK) { - waitForDiscovered(timeoutMs); - log_i("gap_cancel_discovery()"); - esp_bt_gap_cancel_discovery(); - } - return &scanResults; +BTScanResults *BluetoothSerial::discover(int timeoutMs) +{ + scanResults.clear(); + if (timeoutMs < MIN_INQ_TIME || timeoutMs > MAX_INQ_TIME) + { + log_e("Timeout out of bounds: MIN=%d; MAX=%d; requested=%d", MIN_INQ_TIME, MAX_INQ_TIME, timeoutMs); + return nullptr; + } + int timeout = timeoutMs / INQ_TIME; + log_i("discover::disconnect"); + disconnect(); + log_i("discovering"); + // will resolve name to address first - it may take a while + esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); + if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, timeout, 0) == ESP_OK) + { + waitForDiscovered(timeoutMs); + log_i("gap_cancel_discovery()"); + esp_bt_gap_cancel_discovery(); + } + return &scanResults; } /** @@ -1177,33 +1474,40 @@ BTScanResults *BluetoothSerial::discover(int timeoutMs) { * * @return Whether start was successful or problems with params */ -bool BluetoothSerial::discoverAsync(BTAdvertisedDeviceCb cb, int timeoutMs) { - scanResults.clear(); - if (strlen(_remote_name) || _isRemoteAddressSet) { - return false; - } - int timeout = timeoutMs / INQ_TIME; - disconnect(); - advertisedDeviceCb = cb; - log_i("discovering"); - // will resolve name to address first - it may take a while - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); - if (timeout > 0) { - return esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, timeout, 0) == ESP_OK; - } else { - return esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, ESP_BT_GAP_MAX_INQ_LEN, 0) == ESP_OK; - } +bool BluetoothSerial::discoverAsync(BTAdvertisedDeviceCb cb, int timeoutMs) +{ + scanResults.clear(); + if (strlen(_remote_name) || _isRemoteAddressSet) + { + return false; + } + int timeout = timeoutMs / INQ_TIME; + disconnect(); + advertisedDeviceCb = cb; + log_i("discovering"); + // will resolve name to address first - it may take a while + esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); + if (timeout > 0) + { + return esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, timeout, 0) == ESP_OK; + } + else + { + return esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, ESP_BT_GAP_MAX_INQ_LEN, 0) == ESP_OK; + } } /** @brief Stops the asynchronous discovery and clears the callback */ -void BluetoothSerial::discoverAsyncStop() { - esp_bt_gap_cancel_discovery(); - advertisedDeviceCb = nullptr; +void BluetoothSerial::discoverAsyncStop() +{ + esp_bt_gap_cancel_discovery(); + advertisedDeviceCb = nullptr; } /** @brief Clears scanResult entries */ -void BluetoothSerial::discoverClear() { - scanResults.clear(); +void BluetoothSerial::discoverClear() +{ + scanResults.clear(); } /** @brief Can be used while discovering asynchronously @@ -1211,38 +1515,46 @@ void BluetoothSerial::discoverClear() { * * @return BTScanResults contains several information of found devices */ -BTScanResults *BluetoothSerial::getScanResults() { - return &scanResults; +BTScanResults *BluetoothSerial::getScanResults() +{ + return &scanResults; } -BluetoothSerial::operator bool() const { - return true; +BluetoothSerial::operator bool() const +{ + return true; } /** * SDP scan address * esp_spp_start_discovery doesn't tell us the btAddress in the callback, so we have to wait until it's finished */ -std::map BluetoothSerial::getChannels(const BTAddress &remoteAddress) { - if (xEventGroupGetBits(_bt_event_group) & BT_SDP_RUNNING) { - log_e("getChannels failed - already running"); - } - xEventGroupSetBits(_bt_event_group, BT_SDP_RUNNING); - xEventGroupClearBits(_bt_event_group, BT_SDP_COMPLETED); - _doConnect = false; - sdpRecords.clear(); - log_d("esp_spp_start_discovery"); - if (esp_spp_start_discovery(*remoteAddress.getNative()) != ESP_OK) { - log_e("esp_spp_start_discovery failed"); - } else { - if (!waitForSDPRecord(READY_TIMEOUT)) { - log_e("getChannels failed timeout"); - } - log_d("esp_spp_start_discovery wait for BT_SDP_COMPLETED done (%dms)", READY_TIMEOUT); - } - log_d("esp_spp_start_discovery done, found %d services", sdpRecords.size()); - xEventGroupClearBits(_bt_event_group, BT_SDP_RUNNING); - return sdpRecords; +std::map BluetoothSerial::getChannels(const BTAddress &remoteAddress) +{ + if (xEventGroupGetBits(_bt_event_group) & BT_SDP_RUNNING) + { + log_e("getChannels failed - already running"); + } + xEventGroupSetBits(_bt_event_group, BT_SDP_RUNNING); + xEventGroupClearBits(_bt_event_group, BT_SDP_COMPLETED); + _doConnect = false; + sdpRecords.clear(); + log_d("esp_spp_start_discovery"); + if (esp_spp_start_discovery(*remoteAddress.getNative()) != ESP_OK) + { + log_e("esp_spp_start_discovery failed"); + } + else + { + if (!waitForSDPRecord(READY_TIMEOUT)) + { + log_e("getChannels failed timeout"); + } + log_d("esp_spp_start_discovery wait for BT_SDP_COMPLETED done (%dms)", READY_TIMEOUT); + } + log_d("esp_spp_start_discovery done, found %d services", sdpRecords.size()); + xEventGroupClearBits(_bt_event_group, BT_SDP_RUNNING); + return sdpRecords; } /** @@ -1250,130 +1562,178 @@ std::map BluetoothSerial::getChannels(const BTAddress &remoteA * * @param mac [out] The mac */ -void BluetoothSerial::getBtAddress(uint8_t *mac) { - const uint8_t *dev_mac = esp_bt_dev_get_address(); - memcpy(mac, dev_mac, ESP_BD_ADDR_LEN); +void BluetoothSerial::getBtAddress(uint8_t *mac) +{ + const uint8_t *dev_mac = esp_bt_dev_get_address(); + memcpy(mac, dev_mac, ESP_BD_ADDR_LEN); } /** * @brief Gets the MAC address of local BT device as BTAddress object. * * @return The BTAddress object. */ -BTAddress BluetoothSerial::getBtAddressObject() { - uint8_t mac_arr[ESP_BD_ADDR_LEN]; - getBtAddress(mac_arr); - return BTAddress(mac_arr); +BTAddress BluetoothSerial::getBtAddressObject() +{ + uint8_t mac_arr[ESP_BD_ADDR_LEN]; + getBtAddress(mac_arr); + return BTAddress(mac_arr); } /** * @brief Gets the MAC address of local BT device as string. * * @return The BT MAC address string. */ -String BluetoothSerial::getBtAddressString() { - return getBtAddressObject().toString(true); +String BluetoothSerial::getBtAddressString() +{ + return getBtAddressObject().toString(true); } // Send a request to the remote device defined by the remoteAddress to send back its name. // The name will be read by background task and stored. It can be later read with radRemoteName() -void BluetoothSerial::requestRemoteName(uint8_t remoteAddress[]) { - if (isReady(false, READY_TIMEOUT)) { - esp_bt_gap_read_remote_name(remoteAddress); - } +void BluetoothSerial::requestRemoteName(uint8_t remoteAddress[]) +{ + if (isReady(false, READY_TIMEOUT)) + { + esp_bt_gap_read_remote_name(remoteAddress); + } } // If remote name is valid (was already received) this function will copy the name to the aprameter rmt_name // The buffer must have size at least ESP_BT_GAP_MAX_BDNAME_LEN + 1 // If the name is valid the function will return true // If the name is not valid (was not read yet) returns false -bool BluetoothSerial::readRemoteName(char rmt_name[ESP_BT_GAP_MAX_BDNAME_LEN + 1]) { - if (_rmt_name_valid) { - memcpy(rmt_name, _rmt_name, ESP_BT_GAP_MAX_BDNAME_LEN + 1); - return true; - } - return false; +bool BluetoothSerial::readRemoteName(char rmt_name[ESP_BT_GAP_MAX_BDNAME_LEN + 1]) +{ + if (_rmt_name_valid) + { + memcpy(rmt_name, _rmt_name, ESP_BT_GAP_MAX_BDNAME_LEN + 1); + return true; + } + return false; } // Set validity of remote name before reading name from different device -void BluetoothSerial::invalidateRemoteName() { - _rmt_name_valid = false; +void BluetoothSerial::invalidateRemoteName() +{ + _rmt_name_valid = false; } -int BluetoothSerial::getNumberOfBondedDevices() { - return esp_bt_gap_get_bond_device_num(); +int BluetoothSerial::getNumberOfBondedDevices() +{ + return esp_bt_gap_get_bond_device_num(); } // Accepts the maximum number of devices that can fit in given array dev_list. // Create you list this way: esp_bd_addr_t dev_list[dev_num]; // Returns number of retrieved devices (on error returns 0) -int BluetoothSerial::getBondedDevices(uint dev_num, esp_bd_addr_t *dev_list) { - // typedef uint8_t esp_bd_addr_t[ESP_BD_ADDR_LEN] - if (dev_list == NULL) { - log_e("Device list is NULL"); - return 0; - } - if (dev_num == 0) { - log_e("Device number must be larger than 0!"); - return 0; - } - int _dev_num = dev_num; - esp_bt_gap_get_bond_device_list(&_dev_num, dev_list); - return _dev_num; +int BluetoothSerial::getBondedDevices(uint dev_num, esp_bd_addr_t *dev_list) +{ + // typedef uint8_t esp_bd_addr_t[ESP_BD_ADDR_LEN] + if (dev_list == NULL) + { + log_e("Device list is NULL"); + return 0; + } + if (dev_num == 0) + { + log_e("Device number must be larger than 0!"); + return 0; + } + int _dev_num = dev_num; + esp_bt_gap_get_bond_device_list(&_dev_num, dev_list); + return _dev_num; } -bool BluetoothSerial::deleteBondedDevice(uint8_t *remoteAddress) { - esp_err_t ret = esp_bt_gap_remove_bond_device(remoteAddress); - if (ret == ESP_OK) { - return true; - } else { +bool BluetoothSerial::deleteBondedDevice(uint8_t *remoteAddress) +{ + esp_err_t ret = esp_bt_gap_remove_bond_device(remoteAddress); + if (ret == ESP_OK) + { + return true; + } + else + { + return false; + } +} + +void BluetoothSerial::deleteAllBondedDevices() +{ + if (!isReady(false, READY_TIMEOUT)) + { + log_w("Attempted to drop cache for uninitialized driver. First call begin()"); + return; + } + + int expected_dev_num = esp_bt_gap_get_bond_device_num(); + if (expected_dev_num == 0) + { + log_i("No devices in cache."); + return; + } + else + { + log_d("Found %d bonded devices", expected_dev_num); + } + esp_err_t ret; + + // typedef uint8_t esp_bd_addr_t[ESP_BD_ADDR_LEN] // ESP_BD_ADDR_LEN = 6 + esp_bd_addr_t *dev_list = NULL; + log_d("Allocate buffer: sizeof(esp_bd_addr_t)=%d * expected_dev_num=%d", sizeof(esp_bd_addr_t), expected_dev_num); + dev_list = (esp_bd_addr_t *)malloc(sizeof(esp_bd_addr_t) * expected_dev_num); + if (dev_list == NULL) + { + log_e("Could not allocated BT device buffer!"); + return; + } + // uint8_t dev_list [20][6]; + + int dev_num; + ret = esp_bt_gap_get_bond_device_list(&dev_num, dev_list); + log_d("esp_bt_gap_get_bond_device_list ret = %d", ret); + if (ret == ESP_OK) + { + if (dev_num != expected_dev_num) + { + log_w("Inconsistent number of bonded devices. Expected %d; returned %d", expected_dev_num, dev_num); + } + for (int i = 0; i < dev_num; ++i) + { + ret = esp_bt_gap_remove_bond_device(dev_list[i]); + log_d("esp_bt_gap_remove_bond_device ret = %d", ret); + if (ret == ESP_OK) + { + log_d("Removed bonded device #%d", i); + } + else + { + log_w("Failed to removed bonded device #%d", i); + } + // btc_storage_remove_bonded_device(dev_list[i]); + } + log_d("device num after delete = %d", esp_bt_gap_get_bond_device_num()); + } + else + { + log_w("Function esp_bt_gap_get_bond_device_list() returned code %d", ret); + } +} + +// aclConnected() is a one-shot. __aclConnected is cleared when returning true +bool BluetoothSerial::aclConnected() +{ + if (_aclConnected) + { + _aclConnected = false; + return true; + } + return false; - } } -void BluetoothSerial::deleteAllBondedDevices() { - if (!isReady(false, READY_TIMEOUT)) { - log_w("Attempted to drop cache for uninitialized driver. First call begin()"); - return; - } - - int expected_dev_num = esp_bt_gap_get_bond_device_num(); - if (expected_dev_num == 0) { - log_i("No devices in cache."); - return; - } else { - log_d("Found %d bonded devices", expected_dev_num); - } - esp_err_t ret; - - // typedef uint8_t esp_bd_addr_t[ESP_BD_ADDR_LEN] // ESP_BD_ADDR_LEN = 6 - esp_bd_addr_t *dev_list = NULL; - log_d("Allocate buffer: sizeof(esp_bd_addr_t)=%d * expected_dev_num=%d", sizeof(esp_bd_addr_t), expected_dev_num); - dev_list = (esp_bd_addr_t *)malloc(sizeof(esp_bd_addr_t) * expected_dev_num); - if (dev_list == NULL) { - log_e("Could not allocated BT device buffer!"); - return; - } - //uint8_t dev_list [20][6]; - - int dev_num; - ret = esp_bt_gap_get_bond_device_list(&dev_num, dev_list); - log_d("esp_bt_gap_get_bond_device_list ret = %d", ret); - if (ret == ESP_OK) { - if (dev_num != expected_dev_num) { - log_w("Inconsistent number of bonded devices. Expected %d; returned %d", expected_dev_num, dev_num); - } - for (int i = 0; i < dev_num; ++i) { - ret = esp_bt_gap_remove_bond_device(dev_list[i]); - log_d("esp_bt_gap_remove_bond_device ret = %d", ret); - if (ret == ESP_OK) { - log_d("Removed bonded device #%d", i); - } else { - log_w("Failed to removed bonded device #%d", i); - } - //btc_storage_remove_bonded_device(dev_list[i]); - } - log_d("device num after delete = %d", esp_bt_gap_get_bond_device_num()); - } else { - log_w("Function esp_bt_gap_get_bond_device_list() returned code %d", ret); - } +uint8_t *BluetoothSerial::aclGetAddress() +{ + return (&_aclAddress[0]); } -#endif // defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) + +#endif // defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) diff --git a/Firmware/RTK_Everywhere/src/BluetoothSerial/BluetoothSerial.h b/Firmware/RTK_Everywhere/src/BluetoothSerial/BluetoothSerial.h index 8845d254b..c1cfb4e5f 100644 --- a/Firmware/RTK_Everywhere/src/BluetoothSerial/BluetoothSerial.h +++ b/Firmware/RTK_Everywhere/src/BluetoothSerial/BluetoothSerial.h @@ -114,6 +114,9 @@ class BluetoothSerial : public Stream { bool deleteBondedDevice(uint8_t *remoteAddress); void deleteAllBondedDevices(); + bool aclConnected(); // One-shot + uint8_t *aclGetAddress(); + private: String local_name; int timeoutTicks = 0; diff --git a/Firmware/RTK_Everywhere/support.ino b/Firmware/RTK_Everywhere/support.ino index 8d0f67a84..5240641bb 100644 --- a/Firmware/RTK_Everywhere/support.ino +++ b/Firmware/RTK_Everywhere/support.ino @@ -14,7 +14,7 @@ int systemAvailable() return (Serial.available()); } -// If we are printing to all endpoints, BT gets priority +// If we are reading from all endpoints, BT gets priority int systemRead() { if (printEndpoint == PRINT_ENDPOINT_BLUETOOTH || printEndpoint == PRINT_ENDPOINT_ALL) @@ -60,6 +60,12 @@ void systemWrite(const uint8_t *buffer, uint16_t length) { bluetoothCommandWrite(buffer, length); } + + // We're just adding up the size of the list, don't pass along to serial port + else if (printEndpoint == PRINT_ENDPOINT_COUNT) + { + systemWriteCounts++; + } } // Forward GNSS data to the USB serial port @@ -293,7 +299,7 @@ InputResponse getUserInputString(char *userString, uint16_t stringSize, bool loc uint8_t spot = 0; bool echo = localEcho && settings.echoUserInput; - while ((millis() - startTime) / 1000 <= menuTimeout) + while (((millis() - startTime) / 1000) <= menuTimeout) { delay(1); // Yield to processor @@ -302,6 +308,14 @@ InputResponse getUserInputString(char *userString, uint16_t stringSize, bool loc gnss->update(); // Regularly poll to get latest data + // Keep the ntripClient alive by pushing GPGGA. + // I'm not sure if we want / need to do this, but that's how it was when + // the GPGGA push was performed from processUart1Message from gnssReadTask. + // Doing it here keeps the user experience the same. It is safe to do it here + // because the loop is suspended and networkUpdate / ntripClientUpdate aren't + // being called. Maybe we _should_ call networkUpdate() here? Just sayin'... + pushGPGGA(nullptr); + // Keep processing NTP requests if (online.ethernetNTPServer) { @@ -475,23 +489,33 @@ void printElapsedTime(const char *title) #define TIMESTAMP_INTERVAL 1000 // Milliseconds +// Get the timestamp +const char *getTimeStamp() +{ + static char theTime[30]; + + // 1 2 3 + // 123456789012345678901234567890 + // YYYY-mm-dd HH:MM:SS.xxxrn0 + struct tm timeinfo = rtc.getTimeStruct(); + char timestamp[30]; + strftime(timestamp, sizeof(timestamp), "%Y-%m-%d %H:%M:%S", &timeinfo); + snprintf(theTime, sizeof(theTime), "%s.%03ld", timestamp, rtc.getMillis()); + + return (const char *)theTime; +} + // Print the timestamp -void printTimeStamp() +void printTimeStamp(bool always) { uint32_t currentMilliseconds; static uint32_t previousMilliseconds; // Timestamp the messages currentMilliseconds = millis(); - if ((currentMilliseconds - previousMilliseconds) >= TIMESTAMP_INTERVAL) + if (always || ((currentMilliseconds - previousMilliseconds) >= TIMESTAMP_INTERVAL)) { - // 1 2 3 - // 123456789012345678901234567890 - // YYYY-mm-dd HH:MM:SS.xxxrn0 - struct tm timeinfo = rtc.getTimeStruct(); - char timestamp[30]; - strftime(timestamp, sizeof(timestamp), "%Y-%m-%d %H:%M:%S", &timeinfo); - systemPrintf("%s.%03ld\r\n", timestamp, rtc.getMillis()); + systemPrintln(getTimeStamp()); // Select the next time to display the timestamp previousMilliseconds = currentMilliseconds; @@ -1185,3 +1209,12 @@ void WeekToWToUnixEpoch(uint64_t *unixEpoch, uint16_t GPSWeek, uint32_t GPSToW) *unixEpoch += 315964800; } +const char *configPppSpacesToCommas(const char *config) +{ + static char commas[sizeof(settings.configurePPP)]; + snprintf(commas, sizeof(commas), "%s", config); + for (size_t i = 0; i < strlen(commas); i++) + if (commas[i] == ' ') + commas[i] = ','; + return (const char *)commas; +} diff --git a/Firmware/Test Sketches/ESPNOW_Receive/ESPNOW_Receive.ino b/Firmware/Test Sketches/ESPNOW_Receive/ESPNOW_Receive.ino index 6a1acbf2f..42edfdf28 100644 --- a/Firmware/Test Sketches/ESPNOW_Receive/ESPNOW_Receive.ino +++ b/Firmware/Test Sketches/ESPNOW_Receive/ESPNOW_Receive.ino @@ -6,46 +6,56 @@ A receiver does not need to have the broadcastMac added to its peer list. It will receive a broadcast no matter what. - If desired, onDataRecieve should check the received MAC against the list of friendly/paired MACs - in order to throw out broadcasted packets that may not be valid data. + Interestingly, the receiver does not have peers added. It will 'receive' packets that either have + its MAC address or the broadcast MAC address in the packet. + + The transmitter needs to have either this remote's MAC address added as a peer, or the broadcast MAC added as a peer. */ #include -#include +#include //Needed for esp_read_mac() +#include //Needed because ESP-NOW requires WiFi.mode() -void onDataRecieve(const uint8_t *mac_addr, const uint8_t *incomingData, int len) +void onDataReceive(const esp_now_recv_info *mac, const uint8_t *incomingData, int len) { - Serial.printf("Bytes received: %d", len); - Serial.printf(" from peer: 0x%02X%02X%02X%02X%02X%02X\r\n", mac_addr[0], mac_addr[1], mac_addr[2], mac_addr[3], mac_addr[4], mac_addr[5]); + // typedef struct esp_now_recv_info { + // uint8_t * src_addr; // Source address of ESPNOW packet + // uint8_t * des_addr; // Destination address of ESPNOW packet + // wifi_pkt_rx_ctrl_t * rx_ctrl; // Rx control info of ESPNOW packet + // } esp_now_recv_info_t; + + // Display the packet info + Serial.printf( + "RX from MAC %02X:%02X:%02X:%02X:%02X:%02X, %d bytes - ", + mac->des_addr[0], mac->des_addr[1], mac->des_addr[2], mac->des_addr[3], mac->des_addr[4], mac->des_addr[5], + len); + + //Print what was received - it might be binary gobbly-de-gook + char toPrint[len + 1]; + snprintf(toPrint, sizeof(toPrint), "%s", incomingData); + Serial.println(toPrint); } void setup() { Serial.begin(115200); - delay(500); - Serial.println("Point to Point Receiver - No WiFi"); + delay(250); + Serial.println("ESP-NOW Example - This device is the receiver"); - uint8_t unitMACAddress[6]; //Use MAC address in BT broadcast and display + uint8_t unitMACAddress[6]; esp_read_mac(unitMACAddress, ESP_MAC_WIFI_STA); - Serial.print("WiFi MAC Address:"); - for (int x = 0 ; x < 6 ; x++) - { - Serial.print(" 0x"); - if (unitMACAddress[x] < 0x10) Serial.print("0"); - Serial.print(unitMACAddress[x], HEX); - } - Serial.println(); + Serial.printf("Hi! My MAC address is: {0x%02X, 0x%02X, 0x%02X, 0x%02X, 0x%02X, 0x%02X}\r\n", + unitMACAddress[0], unitMACAddress[1], unitMACAddress[2], unitMACAddress[3], unitMACAddress[4], unitMACAddress[5]); - // Set device as a Wi-Fi Station + //ESP-NOW must have WiFi initialized WiFi.mode(WIFI_STA); - if (esp_now_init() != ESP_OK) { + if (esp_now_init() != ESP_OK) Serial.println("Error initializing ESP-NOW"); - return; - } - - esp_now_register_recv_cb(onDataRecieve); + else + Serial.println("ESP-NOW started"); + esp_now_register_recv_cb((esp_now_recv_cb_t)onDataReceive); } void loop() @@ -60,29 +70,3 @@ void loop() } } } - -// Add a given MAC address to the peer list -esp_err_t espnowAddPeer(uint8_t *peerMac) -{ - return (espnowAddPeer(peerMac, true)); // Encrypt by default -} - -esp_err_t espnowAddPeer(uint8_t *peerMac, bool encrypt) -{ - esp_now_peer_info_t peerInfo; - - memcpy(peerInfo.peer_addr, peerMac, 6); - peerInfo.channel = 0; - peerInfo.ifidx = WIFI_IF_STA; - // memcpy(peerInfo.lmk, "RTKProductsLMK56", 16); - // peerInfo.encrypt = encrypt; - peerInfo.encrypt = false; - - esp_err_t result = esp_now_add_peer(&peerInfo); - if (result != ESP_OK) - { - Serial.printf("Failed to add peer: 0x%02X%02X%02X%02X%02X%02X\r\n", peerMac[0], peerMac[1], peerMac[2], - peerMac[3], peerMac[4], peerMac[5]); - } - return (result); -} diff --git a/Firmware/Test Sketches/ESPNOW_Transmit/ESPNOW_Transmit.ino b/Firmware/Test Sketches/ESPNOW_Transmit/ESPNOW_Transmit.ino index 2045dad09..f4dd5e3c3 100644 --- a/Firmware/Test Sketches/ESPNOW_Transmit/ESPNOW_Transmit.ino +++ b/Firmware/Test Sketches/ESPNOW_Transmit/ESPNOW_Transmit.ino @@ -1,25 +1,32 @@ /* - Transmit dummy data over ESP-NOW - - In this example, we don't have a paired MAC, this example simply broadcasts. - - To send a broadcast, the 0xFF broadcastMac has to be added to the peer list, *and* - we have to address the message to the broadcastMac, *not* 0 to send to all peers on the list. - - A receiver does not need to have the broadcastMac added to its peer list. It will receive a broadcast - no matter what. + ESP-NOW transmit to a specific peer + By: Nathan Seidle + SparkFun Electronics + Date: September 25th, 2025 + License: Public domain / don't care. + + In this example we transmit 'This is test #1' to a specified peer or broadcast. + + Run ESPNOW_Transmit and ESPNOW_Recieve on two ESP32s. + + The remote will print its MAC address. Reload this transmit example with that remote's MAC address. + + The transmit unit must have the remote MAC or the broadcast MAC added to the peer list. + + If the broadcast MAC is added to the peer list, then any device will receive data sent to the broadcast MAC. + + Interestingly, the remote devices don't have to have peers added. A remote will 'receive' packets that either + have its MAC address or the broadcast MAC address in the packet. */ #include -#include +#include //Needed for esp_read_mac() +#include //Needed because ESP-NOW requires WiFi.mode() uint8_t broadcastMac[] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; -uint8_t roverMac[] = {0x64, 0xB7, 0x08, 0x3D, 0xFD, 0xAC}; -uint8_t mockMac[] = {0xAA, 0xBB, 0xCC, 0xDD, 0xEE, 0xFF}; //Dummy MAC for testing +uint8_t remoteMac[] = {0x64, 0xB7, 0x08, 0x86, 0xA4, 0xD0}; //Modify this with the MAC address of the remote unit you want to transmit to -esp_now_peer_info_t peerInfo; - -unsigned long lastSend = 0; +uint8_t packetCounter = 0; // Intentionally 8-bit so it rolls over void onDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) { @@ -33,9 +40,15 @@ void onDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) void setup() { Serial.begin(115200); - delay(500); - Serial.println("Point to Point - Base Transmitter"); + delay(250); + Serial.println("ESP-NOW Example - This device is the transmitter"); + + uint8_t unitMACAddress[6]; + esp_read_mac(unitMACAddress, ESP_MAC_WIFI_STA); + Serial.printf("Hi! My MAC address is: {0x%02X, 0x%02X, 0x%02X, 0x%02X, 0x%02X, 0x%02X}\r\n", + unitMACAddress[0], unitMACAddress[1], unitMACAddress[2], unitMACAddress[3], unitMACAddress[4], unitMACAddress[5]); + //ESP-NOW must have WiFi initialized WiFi.mode(WIFI_STA); if (esp_now_init() != ESP_OK) { @@ -43,33 +56,19 @@ void setup() return; } - esp_now_register_send_cb(onDataSent); + esp_now_register_send_cb((esp_now_send_cb_t)onDataSent); - //espnowAddPeer(roverMac); // Register a remote address if we want to deliver data there - espnowAddPeer(mockMac); - espnowAddPeer(broadcastMac); + Serial.println(); + Serial.println("a) Add remote MAC to the peer list"); + Serial.println("b) Add broadcast MAC to the peer list"); + Serial.println("c) Clear the peer list"); + Serial.println("1) Send data to remote MAC"); + Serial.println("2) Send data to broadcast MAC"); + Serial.println("r) Reset"); } void loop() { - if (millis() - lastSend > 500) - { - lastSend = millis(); - - uint8_t espnowData[] = "This is the test string."; - - esp_err_t result = ESP_OK; - - result = esp_now_send(0, (uint8_t *)&espnowData, sizeof(espnowData)); // Send packet to all peers on the list, excluding broadcast peer. - //result = esp_now_send(broadcastMac, (uint8_t *)&espnowData, sizeof(espnowData)); // Send packet over broadcast - //result = esp_now_send(roverMac, (uint8_t *)&espnowData, sizeof(espnowData)); // Send packet to a specific peer - - if (result == ESP_OK) - Serial.println("Sent with success"); - else - Serial.println("Error sending the data"); - } - if (Serial.available()) { byte incoming = Serial.read(); @@ -78,31 +77,101 @@ void loop() Serial.println("Reset"); ESP.restart(); } + else if (incoming == 'a') + { + Serial.println("Adding peer to list"); + espnowAddPeer(remoteMac); // Register a remote address to deliver data to + } + else if (incoming == 'b') + { + Serial.println("Adding broadcast to list"); + espnowAddPeer(broadcastMac); // Register a remote address to deliver data to + } + else if (incoming == 'c') + { + Serial.println("Clearing broadcast list"); + espnowClearPeerList(); + } + else if (incoming == '1') + { + Serial.println("Send to peer list"); + espnowSendMessage(0); // Send packet to all peers on the list, excluding broadcast peer. + } + else if (incoming == '2') + { + Serial.println("Send via broadcast"); + espnowSendMessage(broadcastMac);// Send packet over broadcast + } } } -// Add a given MAC address to the peer list esp_err_t espnowAddPeer(uint8_t *peerMac) -{ - return (espnowAddPeer(peerMac, true)); // Encrypt by default -} - -esp_err_t espnowAddPeer(uint8_t *peerMac, bool encrypt) { esp_now_peer_info_t peerInfo; memcpy(peerInfo.peer_addr, peerMac, 6); peerInfo.channel = 0; peerInfo.ifidx = WIFI_IF_STA; - // memcpy(peerInfo.lmk, "RTKProductsLMK56", 16); - // peerInfo.encrypt = encrypt; peerInfo.encrypt = false; esp_err_t result = esp_now_add_peer(&peerInfo); if (result != ESP_OK) { - Serial.printf("Failed to add peer: 0x%02X%02X%02X%02X%02X%02X\r\n", peerMac[0], peerMac[1], peerMac[2], - peerMac[3], peerMac[4], peerMac[5]); + Serial.printf("Failed to add peer: 0x%02X%02X%02X%02X%02X%02X\r\n", peerMac[0], peerMac[1], peerMac[2], peerMac[3], peerMac[4], peerMac[5]); } return (result); } + +// Send data packet to a given MAC +void espnowSendMessage(const uint8_t *sendToMac) +{ + char espnowData[100]; + sprintf(espnowData, "This is test #: %d", packetCounter++); + + esp_err_t result = esp_now_send(sendToMac, (uint8_t *)&espnowData, sizeof(espnowData)); // Send packet to a specific peer + + if (result == ESP_OK) + Serial.println("Sent with success"); // We will always get a success with broadcastMac packets, presumably because they do not have delivery confirmation. + else + Serial.println("Error sending the data"); +} + +void espnowClearPeerList() +{ +// if (esp_now_is_peer_exist(broadcastMac)) +// { +// status = espNowRemovePeer(broadcastMac); +// if (status != ESP_OK) +// Serial.printf("ERROR: Failed to delete broadcast peer, status: %d\r\n", status); +// else +// Serial.printf("ESP-NOW removed broadcast peer\r\n"); +// } + + // Remove all peers + while (1) + { + esp_now_peer_info_t peerInfo; + + // Get the next peer + esp_err_t status = esp_now_fetch_peer(true, &peerInfo); + if (status != ESP_OK) + { + Serial.println("All done!"); + break; + } + + // Remove the unicast peer + status = esp_now_del_peer(peerInfo.peer_addr); + if (status != ESP_OK) + { + Serial.printf("ERROR: Failed to delete peer %02X:%02X:%02X:%02X:%02X:%02X, status: %d\r\n", + peerInfo.peer_addr[0], peerInfo.peer_addr[1], peerInfo.peer_addr[2], peerInfo.peer_addr[3], + peerInfo.peer_addr[4], peerInfo.peer_addr[5], status); + break; + } + + Serial.printf("ESP-NOW removed peer %02X:%02X:%02X:%02X:%02X:%02X\r\n", peerInfo.peer_addr[0], + peerInfo.peer_addr[1], peerInfo.peer_addr[2], peerInfo.peer_addr[3], peerInfo.peer_addr[4], + peerInfo.peer_addr[5]); + } +} diff --git a/Firmware/Test Sketches/Hookup_Display/Display.ino b/Firmware/Test Sketches/Hookup_Display/Display.ino index 4fb46fdc2..939f94b3c 100644 --- a/Firmware/Test Sketches/Hookup_Display/Display.ino +++ b/Firmware/Test Sketches/Hookup_Display/Display.ino @@ -474,8 +474,8 @@ void updateDisplay(bool doUpdate) //Allowed icon combinations: //Bluetooth + Rover/Base //WiFi + Bluetooth + Rover/Base - //ESP-Now + Bluetooth + Rover/Base - //ESP-Now + Bluetooth + WiFi + //ESP-NOW + Bluetooth + Rover/Base + //ESP-NOW + Bluetooth + WiFi //See setRadioIcons() for the icon selection logic //Left spot @@ -2102,14 +2102,14 @@ void displayBitmap(uint8_t x, uint8_t y, uint8_t imageWidth, uint8_t imageHeight oled.bitmap(x, y, x + imageWidth, y + imageHeight, (uint8_t *)imageData, imageWidth, imageHeight); } -//Show screen while ESP-Now is pairing +//Show screen while ESP-NOW is pairing void paintEspNowPairing() { - displayMessage("ESP-Now Pairing", 0); + displayMessage("ESP-NOW Pairing", 0); } void paintEspNowPaired() { - displayMessage("ESP-Now Paired", 2000); + displayMessage("ESP-NOW Paired", 2000); } void displayNtpStart(uint16_t displayTime) diff --git a/Firmware/Test Sketches/OTA_Update_With_AP/OTA_Update_With_AP.ino b/Firmware/Test Sketches/OTA_Update_With_AP/OTA_Update_With_AP.ino new file mode 100644 index 000000000..8abb4af95 --- /dev/null +++ b/Firmware/Test Sketches/OTA_Update_With_AP/OTA_Update_With_AP.ino @@ -0,0 +1,173 @@ +/* + 1) Enable hotspot on your phone - set the credentials below to match your hot spot + 2) Set "Core Debug Level" to Debug + 3) Load this code onto any old ESP32 (classic, not S3, C6, etc) + 4) Press 'u' to access firmware update over the internet <- Should work + 5) Now connect to 'RTK Test' WiFi network from your phone + 6) Press 'u' to access firmware update, fails with the following output + + [ 18127][D][NetworkManager.cpp:127] hostByName(): DNS found IPv4 185.199.108.133 + [ 23136][I][ssl_client.cpp:133] start_ssl_client(): select returned due to timeout 5000 ms for fd 48 + + Fails using Arduino core v3.0.1, 3.0.7, 3.2.1 <- You pick the one you want. We use 3.0.7 a lot. + + Why does connecting to the ESP32's AP cause the ESP32 to be unable to do HTTP Gets? + + We have seen this work before on a large codebase using the ESP32 Arduino v3.0.1 core but I can no longer + replicate that success locally compiling the source. The compiled binary works, the locally compiled binary fails. +*/ + +#include +#include + +#define R4A_MILLISECONDS_IN_A_SECOND 1000 + +#include "Secrets.h" +#include "Telnet.h" + +#define JSON_URL "https://raw.githubusercontent.com/sparkfun/SparkFun_RTK_Everywhere_Firmware_Binaries/main/RTK-Everywhere-Firmware.json" +#define VERSION "1.0.0" + +bool RTK_CONFIG_MBEDTLS_EXTERNAL_MEM_ALLOC = + false; // Flag used by the special build of libmbedtls (libmbedcrypto) to select external memory + +ESP32OTAPull ota; + +R4A_TELNET_SERVER telnet; + +void setup() +{ + Serial.begin(115200); + delay(200); + + // Enable both AP and Station modes + WiFi.mode(WIFI_AP_STA); + + // Start the Soft AP + WiFi.softAP("RTK Test"); + printChannel(&Serial); + Serial.print("Soft AP Created with IP Gateway "); + Serial.println(WiFi.softAPIP()); + + // Connect to the phone's hot spot + WiFi.begin(ssid, password); + Serial.print("Connecting to WiFi .."); + while (WiFi.status() != WL_CONNECTED) { + Serial.print('.'); + delay(250); + } + Serial.println(); + + // Display the WiFi information + wifiDisplayInfo(&Serial); + + printMenu(&Serial); +} + +void loop() +{ + r4aSerialMenu(); + telnet.update(true); +} + +void processMenu(const char * command, Print * display) +{ + if (command[0] == 'r') + { + ESP.restart(); + } + else if (command[0] == 'c') + { + printChannel(display); + } + else if (command[0] == 'u') + { + WiFi.STA.setDefault(); + display->printf("Check for update, but don't download it.\r\n"); + int ret = ota.CheckForOTAUpdate(JSON_URL, VERSION, ESP32OTAPull::DONT_DO_UPDATE); + display->printf("CheckForOTAUpdate returned %d (%s)\r\n\n", ret, errtext(ret)); + + String otaVersion = ota.GetVersion(); + display->printf("OTA Version Available: %s\r\n", otaVersion.c_str()); + } + else if (command[0] == 'w') + { + wifiDisplayInfo(display); + } + printMenu(display); +} + +void printMenu(Print * display) +{ + display->printf("r - ESP32 reboot\r\n"); + display->printf("c - Display the channels\r\n"); + display->printf("u - Check for firmware version\r\n"); + display->printf("w - Display WiFi information\r\n"); +} + +void printSoftApChannel(Print * display) +{ + NetworkInterface * interface; + + interface = Network.getDefaultInterface(); + WiFi.AP.setDefault(); + display->printf("WiFi AP Channel: %d\r\n", WiFi.channel()); + if (interface) + Network.setDefaultInterface(*interface); +} + +void printStationChannel(Print * display) +{ + NetworkInterface * interface; + + interface = Network.getDefaultInterface(); + WiFi.STA.setDefault(); + display->printf("WiFi STA Channel: %d\r\n", WiFi.channel()); + if (interface) + Network.setDefaultInterface(*interface); +} + +void printChannel(Print * display) +{ + printSoftApChannel(display); + printStationChannel(display); +} + +void wifiDisplayInfo(Print * display) +{ + printSoftApChannel(display); + display->printf("Soft AP IP: %s\r\n", WiFi.AP.localIP().toString().c_str()); + display->printf("SSID: %s\r\n", ssid); + display->printf("Password: %s\r\n", password); + printStationChannel(display); + display->printf("Station IP: %s\r\n", WiFi.STA.localIP().toString().c_str()); + display->println(); +} + +const char *errtext(int code) +{ + switch (code) + { + case ESP32OTAPull::UPDATE_AVAILABLE: + return "An update is available but wasn't installed"; + case ESP32OTAPull::NO_UPDATE_PROFILE_FOUND: + return "No profile matches"; + case ESP32OTAPull::NO_UPDATE_AVAILABLE: + return "Profile matched, but update not applicable"; + case ESP32OTAPull::UPDATE_OK: + return "An update was done, but no reboot"; + case ESP32OTAPull::HTTP_FAILED: + return "HTTP GET failure"; + case ESP32OTAPull::WRITE_ERROR: + return "Write error"; + case ESP32OTAPull::JSON_PROBLEM: + return "Invalid JSON"; + case ESP32OTAPull::OTA_UPDATE_FAIL: + return "Update fail (no OTA partition?)"; + default: + if (code > 0) + return "Unexpected HTTP response code"; + break; + } + return "Unknown error"; +} diff --git a/Firmware/Test Sketches/OTA_Update_With_AP/Secrets.h b/Firmware/Test Sketches/OTA_Update_With_AP/Secrets.h new file mode 100644 index 000000000..302a075ae --- /dev/null +++ b/Firmware/Test Sketches/OTA_Update_With_AP/Secrets.h @@ -0,0 +1,8 @@ +#ifndef __SECRETS.H__ +#define __SECRETS.H__ + +//SSID for phone's hot spot +const char ssid[] = "Phone SSID"; +const char password[] = "Phone Password"; + +#endif // __SECRETS.H__ diff --git a/Firmware/Test Sketches/OTA_Update_With_AP/Serial.ino b/Firmware/Test Sketches/OTA_Update_With_AP/Serial.ino new file mode 100644 index 000000000..230eb34f5 --- /dev/null +++ b/Firmware/Test Sketches/OTA_Update_With_AP/Serial.ino @@ -0,0 +1,109 @@ +/********************************************************************** + Serial.ino + + Robots-For-All (R4A) + Serial stream support +**********************************************************************/ + +#include "Telnet.h" + +//********************************************************************* +// Read a line of input from a Serial port into a String +String * r4aReadLine(bool echo, String * buffer, HardwareSerial * port) +{ + char data; + String * line; + + // Wait for an input character + line = nullptr; + while (port->available()) + { + // Get the input character + data = port->read(); + if ((data != '\r') && (data != '\n')) + { + // Handle backspace + if (data == 8) + { + // Output a bell when the buffer is empty + if (buffer->length() <= 0) + port->write(7); + else + { + // Remove the character from the line + port->write(data); + port->write(' '); + port->write(data); + + // Remove the character from the buffer + *buffer = buffer->substring(0, buffer->length() - 1); + } + } + else + { + // Echo the character + if (echo) + port->write(data); + + // Add the character to the line + *buffer += data; + } + } + + // Echo a carriage return and linefeed + else if (data == '\r') + { + if (echo) + port->println(); + line = buffer; + break; + } + + // Echo the linefeed + else if (echo && (data == '\n')) + port->println(); + } + + // Return the line when it is complete + return line; +} + +//********************************************************************* +// Repeatedly display a fatal error message +void r4aReportFatalError(const char * errorMessage, + Print * display) +{ + static uint32_t lastDisplayMsec; + + while (true) + { + if ((millis() - lastDisplayMsec) >= (15 * R4A_MILLISECONDS_IN_A_SECOND)) + { + lastDisplayMsec = millis(); + display->printf("ERROR: %s\r\n", errorMessage); + } + } +} + +//********************************************************************* +// Process serial menu item +void r4aSerialMenu() +{ + const char * command; + String * line; + static String serialBuffer; + + // Process input from the serial port + line = r4aReadLine(true, &serialBuffer, &Serial); + if (line) + { + // Get the command + command = line->c_str(); + + // Process the command + processMenu(command, &Serial); + + // Start building the next command + serialBuffer = ""; + } +} diff --git a/Firmware/Test Sketches/OTA_Update_With_AP/Telnet.h b/Firmware/Test Sketches/OTA_Update_With_AP/Telnet.h new file mode 100644 index 000000000..a5b3f3004 --- /dev/null +++ b/Firmware/Test Sketches/OTA_Update_With_AP/Telnet.h @@ -0,0 +1,120 @@ +/********************************************************************** + Telnet.h + + Robots-For-All (R4A) + Telnet client and server declarations + See: https://www.rfc-editor.org/rfc/pdfrfc/rfc854.txt.pdf +**********************************************************************/ + +#ifndef __TELNET_H__ +#define __TELNET_H__ + +#include +#include + +//**************************************** +// Telnet Client API +//**************************************** + +// Forward declaration +class R4A_TELNET_SERVER; + +//********************************************************************* +// Telnet client +class R4A_TELNET_CLIENT : public WiFiClient +{ +private: + R4A_TELNET_CLIENT * _nextClient; // Next client in the server's client list + String _command; // User command received via telnet + + // Allow the server to access the command string + friend R4A_TELNET_SERVER; + +public: + + // Constructor + R4A_TELNET_CLIENT() + { + } + + // Allow the R4A_TELNET_SERVER access to the private members + friend class R4A_TELNET_SERVER; +}; + +//**************************************** +// Telnet Server API +//**************************************** + +// Telnet server +class R4A_TELNET_SERVER : WiFiServer +{ +private: + enum R4A_TELNET_SERVER_STATE + { + R4A_TELNET_STATE_OFF = 0, + R4A_TELNET_STATE_ALLOCATE_CLIENT, + R4A_TELNET_STATE_LISTENING, + R4A_TELNET_STATE_SHUTDOWN, + }; + uint8_t _state; // Telnet server state + uint16_t _port; // Port number for the telnet server + bool _echo; + R4A_TELNET_CLIENT * _newClient; // New client object, ready for listen call + R4A_TELNET_CLIENT * _clientList; // Singlely linked list of telnet clients + +public: + + Print * _debugState; // Address of Print object to display telnet server state changes + Print * _displayOptions; // Address of Print object to display telnet options + + // Constructor + // Inputs: + // menuTable: Address of table containing the menu descriptions, the + // main menu must be the first entry in the table. + // menuEntries: Number of entries in the menu table + // blankLineBeforePreMenu: Display a blank line before the preMenu + // blankLineBeforeMenuHeader: Display a blank line before the menu header + // blankLineAfterMenuHeader: Display a blank line after the menu header + // alignCommands: Align the commands + // blankLineAfterMenu: Display a blank line after the menu + // port: Port number for internet connection + // echo: When true causes the input characters to be echoed + R4A_TELNET_SERVER(uint16_t port = 23, + bool echo = false) + : _state{0}, _port{port}, _echo{echo}, _newClient{nullptr}, + _clientList{nullptr}, _debugState{nullptr}, _displayOptions{nullptr}, + WiFiServer() + { + } + + // Destructor + ~R4A_TELNET_SERVER() + { + if (_newClient) + delete _newClient; + while (_clientList) + { + R4A_TELNET_CLIENT * client = _clientList; + _clientList = client->_nextClient; + client->stop(); + delete client; + } + } + + // Display the client list + void displayClientList(Print * display = &Serial); + + // Get the telnet port number + // Returns the telnet port number set during initalization + uint16_t port(); + + // Start and update the telnet server + // Inputs: + // wifiConnected: Set true when WiFi is connected to an access point + // and false otherwise + void update(bool wifiConnected); +}; + +extern class R4A_TELNET_SERVER telnet; // Server providing telnet access + +#endif // __TELNET_H__ diff --git a/Firmware/Test Sketches/OTA_Update_With_AP/Telnet.ino b/Firmware/Test Sketches/OTA_Update_With_AP/Telnet.ino new file mode 100644 index 000000000..68c72a147 --- /dev/null +++ b/Firmware/Test Sketches/OTA_Update_With_AP/Telnet.ino @@ -0,0 +1,314 @@ +/********************************************************************** + Telnet.ino + + Robots-For-All (R4A) + Telnet client and server support + See: https://www.rfc-editor.org/rfc/pdfrfc/rfc854.txt.pdf +**********************************************************************/ + +#include "Telnet.h" + +//********************************************************************* +// Read a line of input from a WiFi client into a String +String * r4aReadLine(bool echo, String * buffer, WiFiClient * port) +{ + char data; + String * line; + + // Wait for an input character + line = nullptr; + while (port->available()) + { + // Get the input character + data = port->read(); + if ((data != '\r') && (data != '\n')) + { + // Handle backspace + if (data == 8) + { + // Output a bell when the buffer is empty + if (buffer->length() <= 0) + port->write(7); + else + { + // Remove the character from the line + port->write(data); + port->write(' '); + port->write(data); + + // Remove the character from the buffer + *buffer = buffer->substring(0, buffer->length() - 1); + } + } + else + { + // Echo the character + if (echo) + port->write(data); + + // Add the character to the line + *buffer += data; + } + } + + // Echo a carriage return and linefeed + else if (data == '\r') + { + if (echo) + port->println(); + line = buffer; + break; + } + + // Echo the linefeed + else if (echo && (data == '\n')) + port->println(); + } + + // Return the line when it is complete + return line; +} + +//********************************************************************* +// Display the client list +void R4A_TELNET_SERVER::displayClientList(Print * display) +{ + R4A_TELNET_CLIENT * client; + + // Display the list header + display->println(); + display->println("Telnet Server Client List"); + client = _clientList; + + // Walk the list of clients + while (client) + { + // Display the client + display->println(" |"); + display->println(" V"); + display->printf("Telnet Client IP Address: %s:%d\r\n", + client->remoteIP().toString().c_str(), + client->remotePort()); + + // Get the next client + client = client->_nextClient; + } + + // Display the end of the list + display->println(" |"); + display->println(" V"); + display->println("nullptr - End of List"); + display->println(); +} + +//********************************************************************* +// Get the telnet port number +// Returns the telnet port number set during initalization +uint16_t R4A_TELNET_SERVER::port() +{ + return _port; +} + +//********************************************************************* +// Start and update the telnet server +void R4A_TELNET_SERVER::update(bool wifiConnected) +{ + R4A_TELNET_CLIENT * client; + bool clientDone; + bool debugState; + bool displayOptions; + R4A_TELNET_CLIENT ** previousClient; + + debugState = _debugState; + displayOptions = _displayOptions; + switch (_state) + { + case R4A_TELNET_STATE_OFF: + // Wait until WiFi is available + if (wifiConnected) + { + // Start the server + _clientList = nullptr; + _newClient = nullptr; + WiFiServer(port); + begin(_port); + if (debugState) + Serial.println("Telnet Server: OFF --> ALLOCATE_CLIENT"); + _state = R4A_TELNET_STATE_ALLOCATE_CLIENT; + } + break; + + case R4A_TELNET_STATE_ALLOCATE_CLIENT: + // Check for WiFi failure + if (!wifiConnected) + { + // Wifi has failed + if (debugState) + Serial.println("Telnet Server: ALLOCATE_CLIENT --> SHUTDOWN"); + _state = R4A_TELNET_STATE_SHUTDOWN; + } + else + { + // Wifi still connected to an access point + // Allocate the next client heap is available + _newClient = new R4A_TELNET_CLIENT(); + + // Display the newClient + if (debugState) + Serial.printf("Telnet Client %p allocated\r\n", _newClient); + + // Enter listening state when memory is available + if (_newClient) + { + if (debugState) + Serial.println("Telnet Server: ALLOCATE_CLIENT --> LISTENING"); + _state = R4A_TELNET_STATE_LISTENING; + } + } + break; + + case R4A_TELNET_STATE_LISTENING: + if (!wifiConnected) + { + // Wifi has failed + if (debugState) + Serial.println("Telnet Server: LISTENING --> SHUTDOWN"); + _state = R4A_TELNET_STATE_SHUTDOWN; + } + else + { + WiFiClient * wifiClient; + + // Wifi still connected to an access point + // Wait for a client connection + wifiClient = _newClient; + *wifiClient = accept(); + if (*wifiClient) + { + if (debugState) + Serial.printf("Telnet Client %s:%d connected\r\n", + _newClient->remoteIP().toString().c_str(), + _newClient->remotePort()); + + // Display the main menu + printMenu(_newClient); + + // Add this client to the list of clients + _newClient->_nextClient = _clientList; + _clientList = _newClient; + _newClient = nullptr; + + // Allocate another client + if (debugState) + Serial.println("Telnet Server: LISTENING --> ALLOCATE_CLIENT"); + _state = R4A_TELNET_STATE_ALLOCATE_CLIENT; + } + } + break; + + case R4A_TELNET_STATE_SHUTDOWN: + // Release the next client + if (_newClient) + { + delete _newClient; + if (_debugState) + Serial.printf("Telnet Client %p deleted\r\n", _newClient); + _newClient = nullptr; + } + + // Shutdown the telnet server + stop(); + if (debugState) + Serial.println("Telnet Server: SHUTDOWN --> OFF"); + _state = R4A_TELNET_STATE_OFF; + break; + } + + // Walk the list of telnet clients + previousClient = &_clientList; + for (client = _clientList; client != nullptr; client = *previousClient) + { + // Check for network failure + clientDone = false; + if ((!wifiConnected) || (!client->connected())) + // Break the client connection + clientDone = true; + else + { + uint8_t buffer[16]; + const char * command; + String * line; + uint8_t option; + uint8_t parameter; + + // Wait for data + if (client->available()) + { + // Strip any telnet header + while (client->peek() == 0xff) + { + // Discard the leading character + client->read(); + + // Get the option byte : WILL, WON'T, DO, DON'T + // See: https://www.iana.org/assignments/telnet-options/telnet-options.xhtml + option = client->read(); + if (option >= 0xfb) + { + // Discard the option parameter + // See: + // https://www.rfc-editor.org/rfc/pdfrfc/rfc855.txt.pdf, page 3 + // https://www.iana.org/assignments/telnet-options/telnet-options.xhtml + parameter = client->read(); + if (parameter == 0xff) + parameter = client->read(); + + // Display the option + if (displayOptions) + Serial.printf("Telnet Client %s:%d ignoring option 0xff 0x%02x 0x%02x\r\n", + client->remoteIP().toString().c_str(), + client->remotePort(), option, parameter); + } + } + + // Get a command from this client + line = r4aReadLine(_echo, &client->_command, client); + + // If a command is available, process it + if (line) + { + // Process the command + command = line->c_str(); + clientDone = false; + processMenu(command, client); + + // Start building the next command + client->_command = ""; + } + } + + // Check the next client + if (!clientDone) + previousClient = &client->_nextClient; + } + + // Check for done or broken client connection + if (clientDone) + { + // Break the client connection + if (debugState) + Serial.printf("Telnet Client %s:%d stopping\r\n", + client->remoteIP().toString().c_str(), + client->remotePort()); + client->stop(); + + // Remove the client from the list + *previousClient = client->_nextClient; + + // Free this client + delete client; + if (_debugState) + Serial.printf("Telnet Client %p deleted\r\n", client); + } + } +} diff --git a/Firmware/Test Sketches/OTA_Update_With_AP/makefile b/Firmware/Test Sketches/OTA_Update_With_AP/makefile new file mode 100644 index 000000000..92d4b2e09 --- /dev/null +++ b/Firmware/Test Sketches/OTA_Update_With_AP/makefile @@ -0,0 +1,195 @@ +###################################################################### +# makefile +# +# Builds the example +###################################################################### + +########## +# Source files +########## + +EXAMPLE_SKETCH=OTA_Update_With_AP + +EXECUTABLES += example + +PARTITION_CSV_FILE=RTKEverywhere + +########## +# Windows NT utilities +########## +ifeq ($(OS),Windows_NT) + +CLEAR=cls +COPY=copy +DELETE=rmdir /s +DIR_LISTING=dir + +# Terminal settings +TERMINAL_APP= +TERMINAL_PORT="COM3" +TERMINAL_PARAMS= + +# Windows NT generic paths +USER_DIRECTORY_PATH=C:\Users\$(USERNAME)\ +ARDUINO_LIBRARY_PATH=$(USER_DIRECTORY_PATH)\Documents\Arduino\libraries\ +HOME_BOARD_PATH=$(USER_DIRECTORY_PATH)\AppData\Local\Arduino15\packages\esp32\ +BUILD_PATH=build\esp32.esp32.esp32\ + +########## +# Linux utilities +########## +else + +CLEAR=clear +COPY=cp +DELETE=rm -Rf +DIR_LISTING=ls +TERMINAL_APP=minicom + +# Terminal settings +TERMINAL_PORT=/dev/ttyUSB0 +TERMINAL_PORT_LG290P=/dev/ttyACM0 +TERMINAL_PORT_TORCH=/dev/ttyACM1 +TERMINAL_PARAMS=-b 115200 -8 < /dev/tty + +# Linux generic paths +USER_DIRECTORY_PATH=~/ +ARDUINO_LIBRARY_PATH=$(USER_DIRECTORY_PATH)/Arduino/libraries/ +BUILD_PATH=build/esp32.esp32.esp32/ +ESP_IDF_PATH=$(HOME_BOARD_PATH)/tools/esp32-arduino-libs/ +HOME_BOARD_PATH=$(USER_DIRECTORY_PATH)/.arduino15/packages/esp32/ +ESPTOOL_PATH=~/Arduino/hardware/espressif/esp32/tools/esptool/ +BOOT_LOADER_PATH=~/SparkFun/SparkFun_RTK_Firmware_Uploader/RTK_Firmware_Uploader/resource/ + +endif + +########## +# Buid all the sources - must be first +########## + +.PHONY: all + +all: $(EXECUTABLES) + +########## +# Add ESP32 board support +########## + +.PHONY: arduino-config + +arduino-config: + arduino-cli config init --overwrite --additional-urls "https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json,https://espressif.github.io/arduino-esp32/package_esp32_dev_index.json" + +########## +# Build the example +########## + +.PHONY: example + +example: $(BUILD_PATH)$(EXAMPLE_SKETCH).ino.bin + +DEBUG_LEVEL=none +#DEBUG_LEVEL=debug + +$(BUILD_PATH)$(EXAMPLE_SKETCH).ino.bin: $(EXAMPLE_SKETCH).ino *.ino *.h makefile + $(CLEAR) + arduino-cli compile --fqbn "esp32:esp32:esp32":DebugLevel=$(DEBUG_LEVEL),PSRAM=enabled $< \ + --warnings default \ + --build-property build.partitions=$(PARTITION_CSV_FILE) \ + --build-property upload.maximum_size=6291456 \ + --build-property "compiler.cpp.extra_flags=-MMD -c \"-DPOINTPERFECT_TOKEN=$(POINTPERFECT_TOKEN)\" \"-DFIRMWARE_VERSION_MAJOR=$(FIRMWARE_VERSION_MAJOR)\" \"-DFIRMWARE_VERSION_MINOR=$(FIRMWARE_VERSION_MINOR)\" \"-DENABLE_DEVELOPER=$(ENABLE_DEVELOPER)\"" \ + --export-binaries + +########## +# EVK +########## + +.PHONY: upload + +upload: $(BUILD_PATH)$(EXAMPLE_SKETCH).ino.bin + python3 $(ESPTOOL_PATH)esptool.py \ + --chip esp32 \ + --port $(TERMINAL_PORT) \ + --baud 921600 \ + --before default_reset \ + --after hard_reset \ + write_flash \ + --flash_mode dio \ + --flash_freq 80m \ + --flash_size detect \ + --compress \ + 0x1000 $(BOOT_LOADER_PATH)RTK_Surveyor.ino.bootloader.bin \ + 0x8000 $(BOOT_LOADER_PATH)RTK_Surveyor_Partitions_16MB.bin \ + 0xe000 $(BOOT_LOADER_PATH)boot_app0.bin \ + 0x10000 $< + $(TERMINAL_APP) -D $(TERMINAL_PORT) $(TERMINAL_PARAMS) + +.PHONY: terminal + +terminal: + $(TERMINAL_APP) -D $(TERMINAL_PORT) $(TERMINAL_PARAMS) + +########## +# LG290P +########## + +.PHONY: upload_lg290p + +upload_lg290p: $(BUILD_PATH)$(EXAMPLE_SKETCH).ino.bin + python3 $(ESPTOOL_PATH)esptool.py \ + --chip esp32 \ + --port $(TERMINAL_PORT_LG290P) \ + --baud 460800 \ + --before default_reset \ + --after hard_reset \ + write_flash \ + --flash_mode dio \ + --flash_freq 80m \ + --flash_size detect \ + --compress \ + 0x1000 $(BOOT_LOADER_PATH)RTK_Surveyor.ino.bootloader.bin \ + 0x8000 $(BOOT_LOADER_PATH)RTK_Everywhere_Partitions_8MB.bin \ + 0xe000 $(BOOT_LOADER_PATH)boot_app0.bin \ + 0x10000 $< + $(TERMINAL_APP) -D $(TERMINAL_PORT_LG290P) $(TERMINAL_PARAMS) + +.PHONY: terminal_lg290p + +terminal_lg290p: + $(TERMINAL_APP) -D $(TERMINAL_PORT_LG290P) $(TERMINAL_PARAMS) + +########## +# Torch +########## + +.PHONY: upload_torch + +upload_torch: $(BUILD_PATH)$(EXAMPLE_SKETCH).ino.bin + python3 $(ESPTOOL_PATH)esptool.py \ + --chip esp32 \ + --port $(TERMINAL_PORT_TORCH) \ + --baud 460800 \ + --before default_reset \ + --after hard_reset \ + write_flash \ + --flash_mode dio \ + --flash_freq 80m \ + --flash_size detect \ + --compress \ + 0x1000 $(BOOT_LOADER_PATH)RTK_Surveyor.ino.bootloader.bin \ + 0x8000 $(BOOT_LOADER_PATH)RTK_Surveyor_Partitions_16MB.bin \ + 0xe000 $(BOOT_LOADER_PATH)boot_app0.bin \ + 0x10000 $< + $(TERMINAL_APP) -D $(TERMINAL_PORT_TORCH) $(TERMINAL_PARAMS) + +.PHONY: terminal_torch + +terminal_torch: + $(TERMINAL_APP) -D $(TERMINAL_PORT_TORCH) $(TERMINAL_PARAMS) + +########## +# Clean up the example +########## + +clean: + $(DELETE) build diff --git a/Firmware/Tools/Settings_Diff.py b/Firmware/Tools/Settings_Diff.py new file mode 100644 index 000000000..b25fcaa43 --- /dev/null +++ b/Firmware/Tools/Settings_Diff.py @@ -0,0 +1,118 @@ +# Performs a 'diff' on two RTK (Everywhere) Firmware settings CSV files +# +# E.g. the settings CSVs passed between the firmware and the web config javascript +# The order of the settings going in one direction is very different to the other direction, +# making it tricky to compare them directly +# This code performs an exhaustive diff: looking for differences between the two; +# any duplicates; and finding any settings present in one but not the other + +import sys +import os + +class RTK_Settings_Diff(): + + def __init__(self, File1:str = None, File2:str = None): + self.filename1 = File1 + self.filename2 = File2 + + def setFilename1(self, File:str): + self.filename1 = File + + def setFilename2(self, File:str): + self.filename2 = File + + def readByte(self, fi): + fileBytes = fi.read(1) + if (len(fileBytes) == 0): + return None + #print(chr(fileBytes[0])) + return chr(fileBytes[0]) + + def readFile(self, filename): + print('Processing',filename) + print() + filesize = os.path.getsize(filename) # Record the file size + + # Try to open file for reading + try: + fi = open(filename,"rb") + except: + raise Exception('Invalid file!') + + # Read the file + firstThing = '' + secondThing = '' + isFirstThing = True + things = {} + + while filesize > 0: + c = self.readByte(fi) + if c == None: + fi.close() + return things + elif c == ',': + isFirstThing = not isFirstThing + if isFirstThing: + if firstThing in things.keys(): # Seen it before? + print('Duplicate setting: {},{} : {}'.format(firstThing, things[firstThing], secondThing)) + things[firstThing] = secondThing + firstThing = '' + secondThing = '' + #print(firstThing, secondThing) + elif c == '\r': + pass + elif c == '\n': + pass + else: + if isFirstThing: + firstThing = firstThing + str(c) + else: + secondThing = secondThing + str(c) + filesize = filesize - 1 + + fi.close() + return things + + def diff(self): + + print() + + things1 = self.readFile(self.filename1) + #print(things1) + + print() + + things2 = self.readFile(self.filename2) + #print(things2) + + print() + + for thing1 in things1.keys(): + if thing1 not in things2.keys(): + print('Only found in file 1 : {},{}'.format(thing1,things1[thing1])) + + print() + + for thing2 in things2.keys(): + if thing2 not in things1.keys(): + print('Only found in file 2 : {},{}'.format(thing2,things2[thing2])) + + print() + + for thing1 in things1.keys(): + if thing1 in things2.keys(): + if things1[thing1] != things2[thing1]: + print('Diff: {},{} : {}'.format(thing1,things1[thing1],things2[thing1])) + +if __name__ == '__main__': + + import argparse + + parser = argparse.ArgumentParser(description='SparkFun RTK Firmware Settings CSV Diff') + parser.add_argument('File1', metavar='File1', type=str, help='The path to the first settings CSV file') + parser.add_argument('File2', metavar='File2', type=str, help='The path to the second settings CSV file') + args = parser.parse_args() + + diff = RTK_Settings_Diff(args.File1, args.File2) + + diff.diff() diff --git a/Firmware/compile_with_docker.bat b/Firmware/compile_with_docker.bat new file mode 100644 index 000000000..e3a34af0b --- /dev/null +++ b/Firmware/compile_with_docker.bat @@ -0,0 +1,6 @@ +docker build -t rtk_everywhere_firmware --no-cache-filter deployment . +docker create --name=rtk_everywhere rtk_everywhere_firmware:latest +docker cp rtk_everywhere:/RTK_Everywhere.ino.bin . +docker cp rtk_everywhere:/RTK_Everywhere.ino.elf . +docker cp rtk_everywhere:/RTK_Everywhere.ino.bootloader.bin . +docker container rm rtk_everywhere diff --git a/Issue_Template.md b/Issue_Template.md index 055a4de4c..89ad1ee2d 100644 --- a/Issue_Template.md +++ b/Issue_Template.md @@ -3,7 +3,7 @@ Describe your issue here. Additionally, screenshots are easy to paste into githu ### Your workbench - What version of RTK firmware are you running? This can be found when the serial menu is opened (also in the settings.txt file, and in the serial output at power up). -- What radios are you using: Bluetooth, WiFi, and/or ESP-Now? What app are you using to connect over Bluetooth? Are you transmitting NTRIP back to the device? +- What radios are you using: Bluetooth, WiFi, and/or ESP-NOW? What app are you using to connect over Bluetooth? Are you transmitting NTRIP back to the device? - Are there any additional details that may help us help you? ### Steps to reproduce diff --git a/docs/displays.md b/docs/displays.md index 733ba2d74..b03dd672c 100644 --- a/docs/displays.md +++ b/docs/displays.md @@ -249,7 +249,7 @@ RTK Everywhere - with NTRIP (RTK2go / SNIP) corrections Each corrections source has a unique icon: -From left to right: External Radio; ESP-Now; LoRa Radio; Bluetooth +From left to right: External Radio; ESP-NOW; LoRa Radio; Bluetooth
![RTK Everywhere corrections source icons](./img/Corrections/SparkFun%20RTK%20Corrections%20Source%20Icons%201.png) diff --git a/docs/firmware_compile.md b/docs/firmware_compile.md index 1c9ce8ca6..4b6edd83d 100644 --- a/docs/firmware_compile.md +++ b/docs/firmware_compile.md @@ -2,9 +2,233 @@ This is information about how to compile the RTK Everywhere firmware from source. This is for advanced users who would like to modify the functionality of the RTK products. -Please see the [compilation workflow](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/.github/workflows/compile-rtk-everywhere.yml#L77) on Github for the latest core and library versions. +* [How SparkFun does it](#how-sparkfun-does-it) +* [Using Docker](#using-docker) +* [Compiling on Windows (Deprecated)](#compiling-on-windows-deprecated) -## Windows +## How SparkFun does it + +At SparkFun, we use GitHub Actions and a Workflow to compile each release of RTK Everywhere. We run the [compilation workflow](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/.github/workflows/compile-rtk-everywhere.yml) directly on GitHub. A virtual ubuntu machine installs the [Arduino CLI](https://github.com/arduino/arduino-cli/releases), installs the ESP32 Arduino core, patches the core in a couple of places, installs all the required libraries at the required version, converts the embedded HTML and Bootstrap JavaScript to binary zip format, and generates the firmware binary for the ESP32. That binary is either uploaded as an Artifact (by [non-release-build](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/.github/workflows/non-release-build.yml)) or pushed to the [SparkFun RTK Everywhere Firmware Binaries](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware_Binaries) repo (by [compilation workflow](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/.github/workflows/compile-rtk-everywhere.yml)). + +You are welcome to clone or fork this repo and do the exact same thing yourself. But you may need a paid GitHub Pro account to run the GitHub Actions, especially if you keep your clone / fork private. + +If you run the [compilation workflow](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/.github/workflows/compile-rtk-everywhere.yml), it will compile the firmware and attempt to push the binary to the Binaries repo. This will fail as your account won't have the right permissions. The [non-release-build](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/.github/workflows/non-release-build.yml) is the one for you. The firmware binary will be attached as an Artifact to the workflow run. Navigate to Actions \ Non-Release Build, select the latest run of Non-Release Build, the binary is in the Artifacts. + +You can then use (e.g.) the [SparkFun RTK Firmware Uploader](https://github.com/sparkfun/SparkFun_RTK_Firmware_Uploader) to upload the binary onto the ESP32. + +## Using Docker + +Installing the correct version of the ESP32 core and of each required Arduino library, is tedious and error-prone. Especially on Windows. We've lost count of the number of times code compilation fails on our local machines, because we had the wrong ESP32 core installed, or forgot to patch libbt or libmbedcrypto... It is much easier to sandbox the firmware compilation using an environment like [Docker](https://www.docker.com/). + +Docker is open-source. It is our new favourite thing! + +Here is a step-by-step guide for how to install Docker and compile the firmware from scratch: + +### Clone, fork or download the RTK Everywhere Firmware repo + +To build the RTK Everywhere Firmware, you obviously need a copy of the source code. + +If you are familiar with Git and GitHub Desktop, you can clone the RTK Everywhere Firmware repo directly into GitHub Desktop: + +![Clone RTK Everywhere with GitHub Desktop](./img/CompileSource/Clone_Repo_To_GitHub_Desktop.png) + +If you want to _contribute_ to RTK Everywhere, and already have a GitHub account, you can Fork the repo: + +![Fork RTK Everywhere](./img/CompileSource/Fork_Repo.png) + +Clone your fork to your local machine, make changes, and send us a Pull Request. This is exactly what the SparkFun Team do when developing the code. Please use the `release_candidate` branch for any such changes. We are very unlikely to merge anything directly into `main`, unless it is (e.g.) docs corrections or improvements. + +If you don't want to do either of those, you can simply Download a Zip copy of the repo instead. You will receive a complete copy as a Zip file. You can do this from the green **Code** button, or click on the icon below to download a copy of the main (released) branch: + +[![Download ZIP](./img/CompileSource/Download_Zip.png)](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/archive/refs/heads/main.zip "Download ZIP (main branch)") + +For the real Wild West experience, you can also download a copy of the `release_candidate` code branch. This is where the team is actively changing and testing the code, before it becomes a full release. The code there will _usually_ compile and will _usually_ work, but we don't guarantee it! We may be part way through implementing some breaking changes at the time of your download... + +[![Download ZIP - release candidate](./img/CompileSource/Download_Zip.png)](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/archive/refs/heads/release_candidate.zip "Download ZIP (release_candidate branch)") + +### Install Docker Desktop + +* **(Optional)** Head to [Docker](https://www.docker.com/) and create an account. A free "Personal" account will cover occasional compilations of the firmware +* Download and install [Docker Desktop](https://docs.docker.com/get-started/get-docker/) - there are versions for Mac, Windows and Linux. You may need to restart to complete the installation. +* Run the Desktop + * You don't _need_ to have an account and you don't _need_ to be signed in + * You only need to be signed in if you want to store or share your Container on Docker Hub + * If you don't sign in, Docker Desktop will run in Personal mode - which will cover local compilations of the firmware +* On Windows, you may see an error saying "**WSL needs updating** Your version of Windows Subsystem for Linux (WSL) is too old". If you do: + * Open a command prompt + * Type `wsl --update` to update WSL. At the time of writing, this installs Windows Subsystem for Linux 2.6.1 + * Restart the Docker Desktop +* If you are using Docker for the first time, the "What is a container?" and "How do I run a container?" demos are useful - _but not essential_ + * On Windows, you may want to give Docker Desktop permission to access to your Network, so it can access (e.g.) HTML ports + * You can Stop the container and Delete it when you are done +* You may want to prevent Docker from running when your machine starts up + * Uncheck "Start Docker Desktop when you sign in to your computer" in the Desktop settings + +### Using Docker to create the firmware binary + +* **Make sure you have Docker Desktop running.** You don't need to be signed in, but it needs to be running. +* Open a Command Prompt and `cd` into the SparkFun_RTK_Everywhere_Firmware folder +* Check you are in the right place. Type `dir` and hit enter. You should see the following files and folders: + +``` + .gitattributes + .github + .gitignore + docs + Firmware + Graphics + Issue_Template.md + License.md + README.md +``` + +* `cd Firmware` and then `dir` again. You should see: + +``` + compile_with_docker.bat + Dockerfile + readme.md + RTKEverywhere.csv + RTKEverywhere_8MB.csv + RTK_Everywhere +``` + +* The file that does most of the work is the `Dockerfile` + +* But, if you're short on time, run `compile_with_docker.bat`. It does everything for you: + +![Output of the compile batch file](./img/CompileSource/compile_me_batch_file.png) + +* Hey presto! You have your newly compiled firmware binary! + +You can then use (e.g.) the [SparkFun RTK Firmware Uploader](https://github.com/sparkfun/SparkFun_RTK_Firmware_Uploader) to upload the binary onto the ESP32. + +### Running the Dockerfile manually + +If you want to see and understand what's going on under the hood with the Dockerfile, Image and Container: + +Here is how to perform each step manually: + +* To begin, run the Dockerfile. Type: + +``` +docker build -t rtk_everywhere_firmware . +``` + +![Dockerfile starting](./img/CompileSource/Dockerfile_starting.png) + +![Dockerfile complete](./img/CompileSource/Dockerfile_complete.png) + +* If you want to see the full build progress including the output of echo or ls, use: + +``` +docker build -t rtk_everywhere_firmware --progress=plain . +``` + +* If you want to rebuild the image completely from scratch, without using the cache, use: + +``` +docker build -t rtk_everywhere_firmware --progress=plain --no-cache . +``` + +Building the full Image from scratch is slow, taking several minutes. You should only need to do it once - unless you make any changes to the Dockerfile. + +* **When you make changes to the source code and want to recompile, use:** + +``` +docker build -t rtk_everywhere_firmware --no-cache-filter deployment . +``` + +This uses the cache for the `upstream` stage and avoids recreating the full ubuntu machine. But it ignores the cache for the `deployment` stage, ensuring the code is recompiled. + +### Access the firmware binary by running the Image + +In Docker Desktop, in the Images tab, you should now be able to see an Image named `rtk_everywhere_firmware`. We now need to Run that Image to access the firmware binary. Click the triangular Run icon under Actions: + +![Docker image ready to run](./img/CompileSource/Docker_Image.png) + +Running the Image will create a Container, through which we can access the output of the arduino-cli code compilation. + +By default, the Container name is random. To avoid this, we define one in the **Optional settings** : + +![Docker Container - named rtk_everywhere](./img/CompileSource/Docker_Container.png) + +Run the Container and you should see: + +![Container is complete](./img/CompileSource/Container_complete.png) + +In the Command Prompt, type the following : + +``` +docker cp rtk_everywhere:/RTK_Everywhere.ino.bin . +``` + +Hey presto! A file called `RTK_Everywhere.ino.bin` appears in the current directory. That's the firmware binary we are going to upload to the ESP32. + +![Firmware binary](./img/CompileSource/Firmware_binary.png) + +If you need the `.elf` file so you can debug code crashes with me-no-dev's [ESP ExceptionDecoder](https://github.com/me-no-dev/EspExceptionDecoder): + +``` +docker cp rtk_everywhere:/RTK_Everywhere.ino.elf . +``` + +If you need the `.bootloader.bin` file so you can upload it with esptool: + +``` +docker cp rtk_everywhere:/RTK_Everywhere.ino.bootloader.bin . +``` + +If you want the files to appear in a more convenient directory, replace the single `.` with a folder path. + +Delete the `rtk_everywhere` container afterwards, to save disk space and so you can reuse the same container name next time. If you forget, you will see an error: + +```Conflict. The container name "/rtk_everywhere" is already in use by container. You have to remove (or rename) that container to be able to reuse that name.``` + +* **Remember:** when you make changes to the source code and want to recompile, use: + +``` +docker build -t rtk_everywhere_firmware --no-cache-filter deployment . +``` + +#### Shortcut: compile_with_docker.bat + +**Shortcut:** the `compile_with_docker.bat` batch file does everything for you: + +``` +docker build -t rtk_everywhere_firmware --no-cache-filter deployment . +docker create --name=rtk_everywhere rtk_everywhere_firmware:latest +docker cp rtk_everywhere:/RTK_Everywhere.ino.bin . +docker cp rtk_everywhere:/RTK_Everywhere.ino.elf . +docker cp rtk_everywhere:/RTK_Everywhere.ino.bootloader.bin . +docker container rm rtk_everywhere +``` + +#### Changing the build properties + +**Changing the build properties:** if you want to change the build properties and (e.g.) include your own PointPerfect token, paste the following into a .bat file or shell script: + +``` +docker build -t rtk_everywhere_firmware --no-cache-filter deployment^ + --build-arg FIRMWARE_VERSION_MAJOR=99^ + --build-arg FIRMWARE_VERSION_MINOR=99^ + --build-arg POINTPERFECT_LBAND_TOKEN="0xAA,0xBB,<<=YOUR TOKEN IN C HEX FORMAT=>>,0x02,0x03"^ + --build-arg POINTPERFECT_IP_TOKEN="0xAA,0xBB,<<=YOUR TOKEN IN C HEX FORMAT=>>,0x02,0x03"^ + --build-arg POINTPERFECT_LBAND_IP_TOKEN="0xAA,0xBB,<<=YOUR TOKEN IN C HEX FORMAT=>>,0x02,0x03"^ + --build-arg POINTPERFECT_RTCM_TOKEN="0xAA,0xBB,<<=YOUR TOKEN IN C HEX FORMAT=>>,0x02,0x03"^ + --build-arg ENABLE_DEVELOPER=false^ + --build-arg DEBUG_LEVEL=none^ + . +docker create --name=rtk_everywhere rtk_everywhere_firmware:latest +docker cp rtk_everywhere:/RTK_Everywhere.ino.bin . +docker cp rtk_everywhere:/RTK_Everywhere.ino.elf . +docker cp rtk_everywhere:/RTK_Everywhere.ino.bootloader.bin . +docker container rm rtk_everywhere +``` + +## Compiling on Windows (Deprecated) + +**Note: we recommend using the Docker method. It is far easier and much less error-prone...** The SparkFun RTK Everywhere Firmware is compiled using Arduino CLI (currently [v1.0.4](https://github.com/arduino/arduino-cli/releases)). To compile: @@ -23,17 +247,33 @@ The SparkFun RTK Everywhere Firmware is compiled using Arduino CLI (currently [v 4. RTK Everywhere uses a custom partition file. Download the [RTKEverywhere.csv](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/Firmware/RTKEverywhere.csv) or [RTKEverywhere_8MB.csv](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/Firmware/RTKEverywhere_8MB.csv) for the RTK Postcard. 5. Add *RTKEverywhere.csv* partition table to the Arduino partitions folder. It should look something like - C:\Users\\[user name]\AppData\Local\Arduino15\packages\esp32\hardware\esp32\3.0.7\tools\partitions\RTKEverywhere.csv + C:\Users\[user name]\AppData\Local\Arduino15\packages\esp32\hardware\esp32\3.0.7\tools\partitions\RTKEverywhere.csv This will increase the program partitions, as well as the SPIFFs partition to utilize the full 16MB of flash (8MB in the case of the Postcard). -6. Compile using the following command +6. Patch the core (libmbedtls, NetworkEvents and libbt) - as shown in the workflow + +7. Update the web config `form.h` by running the two python scripts in the `Tools` folder: + +``` +python index_html_zipper.py ../RTK_Everywhere/AP-Config/index.html ../RTK_Everywhere/form.h +python main_js_zipper.py ../RTK_Everywhere/AP-Config/src/main.js ../RTK_Everywhere/form.h +``` + +8. Compile using the following command + +``` + arduino-cli compile --fqbn "esp32:esp32:esp32":DebugLevel=none,PSRAM=enabled ./Firmware/RTK_Everywhere/RTK_Everywhere.ino --build-property build.partitions=RTKEverywhere --build-property upload.maximum_size=4055040 --build-property "compiler.cpp.extra_flags=-MMD -c" --export-binaries +``` + +9. Once compiled, upload to the device using the following two commands. Replace `COM4` with the COM port on which the RTK device is located. - arduino-cli compile 'Firmware/RTK_Everywhere' --build-property build.partitions=RTKEverywhere --build-property upload.maximum_size=4055040 --fqbn esp32:esp32:esp32:FlashSize=16M,PSRAM=enabled +``` + esptool.exe --chip esp32 --port \\.\COM4 --baud 460800 --before default_reset --after no_reset write_flash -z --flash_mode dio --flash_freq 80m --flash_size detect 0x1000 RTK_Surveyor.ino.bootloader.bin 0x8000 RTK_Surveyor_Partitions_16MB.bin 0xe000 boot_app0.bin 0x10000 RTK_Surveyor.ino.bin -8. Once compiled, upload to the device using the following command where `[COM_PORT]` is the COM port on which the RTK device is located (ie `COM42`). + esptool.exe --chip esp32 --port \\.\COM4 --before default_reset run - arduino-cli upload -p [COM_PORT] --fqbn esp32:esp32:esp32:UploadSpeed=512000,FlashSize=16M 'Firmware/RTK_Everywhere' +``` If you are seeing the error: @@ -44,255 +284,3 @@ You have either not replaced the partition file correctly or failed to include t !!! note There are a variety of compile guards (COMPILE_WIFI, COMPILE_AP, etc) at the top of RTK_Everywhere.ino that can be commented out to remove them from compilation. This will greatly reduce the firmware size and allow for faster development of functions that do not rely on these features (serial menus, system configuration, logging, etc). -## Ubuntu 20.04 - -### Virtual Machine - -Execute the following commands to create the Linux virtual machine: - -1. Using a browser, download the Ubuntu 20.04 Desktop image -2. virtualbox - 1. Click on the new button - 2. Specify the machine Name, e.g.: Sparkfun_RTK_20.04 - 3. Select Type: Linux - 4. Select Version: Ubuntu (64-bit) - 5. Click the Next> button - 6. Select the memory size: 7168 - 7. Click the Next> button - 8. Click on Create a virtual hard disk now - 9. Click the Create button - 10. Select VDI (VirtualBox Disk Image) - 11. Click the Next> button - 12. Select Dynamically allocated - 13. Click the Next> button - 14. Select the disk size: 128 GB - 15. Click the Create button - 16. Click on Storage - 17. Click the empty CD icon - 18. On the right-hand side, click the CD icon - 19. Click on Choose a disk file... - 20. Choose the ubuntu-20.04... iso file - 21. Click the Open button - 22. Click on Network - 23. Under 'Attached to:' select Bridged Adapter - 24. Click the OK button - 25. Click the Start button -3. Install Ubuntu 20.04 -4. Log into Ubuntu -5. Click on Activities -6. Type terminal into the search box -7. Optionally install the SSH server - 1. In the terminal window - 1. sudo apt install -y net-tools openssh-server - 2. ifconfig - - Write down the IP address - - 2. On the PC - 1. ssh-keygen -t rsa -f ~/.ssh/Sparkfun_RTK_20.04 - 2. ssh-copy-id -o IdentitiesOnly=yes -i ~/.ssh/Sparkfun_RTK_20.04 <username>@<IP address> - 3. ssh -Y <username>@<IP address> - -### Build Environment - -Execute the following commands to create the build environment for the SparkFun RTK Everywhere Firmware: - -1. sudo adduser $USER dialout -2. sudo shutdown -r 0 - - Reboot to ensure that the dialout privilege is available to the user - -3. sudo apt update -4. sudo apt install -y git gitk git-cola minicom python3-pip -5. sudo pip3 install pyserial -6. mkdir ~/SparkFun -7. mkdir ~/SparkFun/esptool -8. cd ~/SparkFun/esptool -9. git clone https://github.com/espressif/esptool . -10. cd ~/SparkFun -11. nano serial-port.sh - - Insert the following text into the file: - - ```C++ - #!/bin/bash - # serial-port.sh - # - # Shell script to read the serial data from the RTK Express ESP32 port - # - # Parameters: - # 1: ttyUSBn - # - sudo minicom -b 115200 -8 -D /dev/$1 < /dev/tty - ``` - -12. chmod +x serial-port.sh -13. nano new-firmware.sh - - Insert the following text into the file: - - ```C++ - #!/bin/bash - # new-firmware.sh - # - # Shell script to load firmware into the RTK Express via the ESP32 port - # - # Parameters: - # 1: ttyUSBn - # 2: Firmware file - # - sudo python3 ~/SparkFun/RTK_Binaries/Uploader_GUI/esptool.py --chip esp32 --port /dev/$1 --baud 921600 --before default_reset --after hard_reset write_flash -z --flash_mode dio --flash_freq 80m --flash_size detect \ - 0x1000 ~/SparkFun/RTK_Binaries/bin/RTK_Surveyor.ino.bootloader.bin \ - 0x8000 ~/SparkFun/RTK_Binaries/bin/RTK_Surveyor_Partitions_16MB.bin \ - 0xe000 ~/SparkFun/RTK_Binaries/bin/boot_app0.bin \ - 0x10000 $2 - ``` - -14. chmod +x new-firmware.sh -15. nano new-firmware-4mb.sh - - Insert the following text into the file: - - ```C++ - #!/bin/bash - # new-firmware-4mb.sh - # - # Shell script to load firmware into the 4MB RTK Express via the ESP32 port - # - # Parameters: - # 1: ttyUSBn - # 2: Firmware file - # - sudo python3 ~/SparkFun/RTK_Binaries/Uploader_GUI/esptool.py --chip esp32 --port /dev/$1 --baud 921600 --before default_reset --after hard_reset write_flash -z --flash_mode dio --flash_freq 80m --flash_size detect \ - 0x1000 ~/SparkFun/RTK_Binaries/bin/RTK_Surveyor.ino.bootloader.bin \ - 0x8000 ~/SparkFun/RTK_Binaries/bin/RTK_Surveyor_Partitions_4MB.bin \ - 0xe000 ~/SparkFun/RTK_Binaries/bin/boot_app0.bin \ - 0x10000 $2 - ``` - -16. chmod +x new-firmware-4mb.sh - - Get the SparkFun RTK Everywhere Firmware sources - -17. mkdir ~/SparkFun/RTK -18. cd ~/SparkFun/RTK -19. git clone https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware . - - Get the SparkFun RTK binaries - -20. mkdir ~/SparkFun/RTK_Binaries -21. cd ~/SparkFun/RTK_Binaries -22. git clone https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware_Binaries.git . - - Install the Arduino IDE - -23. mkdir ~/SparkFun/arduino -24. cd ~/SparkFun/arduino -25. wget https://downloads.arduino.cc/arduino-1.8.15-linux64.tar.xz -26. tar -xvf ./arduino-1.8.15-linux64.tar.xz -27. cd arduino-1.8.15/ -28. sudo ./install.sh - - Add the ESP32 support - -29. Arduino - - 1. Click on File in the menu bar - 2. Click on Preferences - 3. Go down to the Additional Boards Manager URLs text box - 4. Only if the textbox already has a value, go to the end of the value or values and add a comma - 5. Add the link: https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json - 6. Note the value in Sketchbook location - 7. Click the OK button - 8. Click on File in the menu bar - 9. Click on Quit - - Get the required external libraries, then add to the Sketchbook location from above - -30. cd ~/Arduino/libraries -31. mkdir AsyncTCP -32. cd AsyncTCP/ -33. git clone https://github.com/me-no-dev/AsyncTCP.git . -34. cd .. -35. mkdir ESPAsyncWebServer -36. cd ESPAsyncWebServer -37. git clone https://github.com/me-no-dev/ESPAsyncWebServer . - - Connect the Config ESP32 port of the RTK to a USB port on the computer - -38. ls /dev/ttyUSB* - - Enable the libraries in the Arduino IDE - -39. Arduino - - 1. From the menu, click on File - 2. Click on Open... - 3. Select the ~/SparkFun/RTK/Firmware/RTK_Surveyor/RTK_Surveyor.ino file - 4. Click on the Open button - - Select the ESP32 development module - - 5. From the menu, click on Tools - 6. Click on Board - 7. Click on Board Manager… - 8. Click on esp32 - 9. Select version 2.0.2 - 10. Click on the Install button in the lower right - 11. Close the Board Manager... - 12. From the menu, click on Tools - 13. Click on Board - 14. Click on ESP32 Arduino - 15. Click on ESP32 Dev Module - - Load the required libraries - - 16. From the menu, click on Tools - 17. Click on Manage Libraries… - 18. For each of the following libraries: - - 1. Locate the library - 2. Click on the library - 3. Select the version listed in the compile-rtk-firmware.yml file for the [main](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/main/.github/workflows/compile-rtk-firmware.yml) or the [release_candidate](https://github.com/sparkfun/SparkFun_RTK_Everywhere_Firmware/blob/release_candidate/.github/workflows/compile-rtk-firmware.yml) branch - 4. Click on the Install button in the lower right - - Library List: - - - ArduinoJson - - ESP32Time - - ESP32-OTA-Pull - - ESP32_BleSerial - - Ethernet - - JC_Button - - MAX17048 - Used for “Test Sketch/Batt_Monitor” - - PubSubClient - - SdFat - - SparkFun LIS2DH12 Arduino Library - - SparkFun MAX1704x Fuel Gauge Arduino Library - - SparkFun Qwiic OLED Graphics Library - - SparkFun u-blox GNSS v3 - - SparkFun_WebServer_ESP32_W5500 - - 19. Click on the Close button - - Select the terminal port - - 20. From the menu, click on Tools - 21. Click on Port, Select the port that was displayed in step 38 above - 22. Select /dev/ttyUSB0 - 23. Click on Upload Speed - 24. Select 230400 - - Setup the partitions for the 16 MB flash - - 25. From the menu, click on Tools - 26. Click on Flash Size - 27. Select 16MB - 28. From the menu, click on Tools - 29. Click on Partition Scheme - 30. Click on 16M Flash (3MB APP/9MB FATFS) - 31. From the menu click on File - 32. Click on Quit - -40. cd ~/SparkFun/RTK/ -41. cp Firmware/app3M_fat9M_16MB.csv ~/.arduino15/packages/esp32/hardware/esp32/2.0.2/tools/partitions/app3M_fat9M_16MB.csv diff --git a/docs/img/CompileSource/Clone_Repo_To_GitHub_Desktop.png b/docs/img/CompileSource/Clone_Repo_To_GitHub_Desktop.png new file mode 100644 index 000000000..86ee53682 Binary files /dev/null and b/docs/img/CompileSource/Clone_Repo_To_GitHub_Desktop.png differ diff --git a/docs/img/CompileSource/Container_complete.png b/docs/img/CompileSource/Container_complete.png new file mode 100644 index 000000000..661c61628 Binary files /dev/null and b/docs/img/CompileSource/Container_complete.png differ diff --git a/docs/img/CompileSource/Docker_Container.png b/docs/img/CompileSource/Docker_Container.png new file mode 100644 index 000000000..bca62cef0 Binary files /dev/null and b/docs/img/CompileSource/Docker_Container.png differ diff --git a/docs/img/CompileSource/Docker_Image.png b/docs/img/CompileSource/Docker_Image.png new file mode 100644 index 000000000..653f49699 Binary files /dev/null and b/docs/img/CompileSource/Docker_Image.png differ diff --git a/docs/img/CompileSource/Dockerfile_complete.png b/docs/img/CompileSource/Dockerfile_complete.png new file mode 100644 index 000000000..0d6d504a1 Binary files /dev/null and b/docs/img/CompileSource/Dockerfile_complete.png differ diff --git a/docs/img/CompileSource/Dockerfile_starting.png b/docs/img/CompileSource/Dockerfile_starting.png new file mode 100644 index 000000000..aa7bba139 Binary files /dev/null and b/docs/img/CompileSource/Dockerfile_starting.png differ diff --git a/docs/img/CompileSource/Download_Zip.png b/docs/img/CompileSource/Download_Zip.png new file mode 100644 index 000000000..00163c2f1 Binary files /dev/null and b/docs/img/CompileSource/Download_Zip.png differ diff --git a/docs/img/CompileSource/Firmware_binary.png b/docs/img/CompileSource/Firmware_binary.png new file mode 100644 index 000000000..2408d0b7a Binary files /dev/null and b/docs/img/CompileSource/Firmware_binary.png differ diff --git a/docs/img/CompileSource/Fork_Repo.png b/docs/img/CompileSource/Fork_Repo.png new file mode 100644 index 000000000..1a15eb90f Binary files /dev/null and b/docs/img/CompileSource/Fork_Repo.png differ diff --git a/docs/img/CompileSource/compile_me_batch_file.png b/docs/img/CompileSource/compile_me_batch_file.png new file mode 100644 index 000000000..80bec09c5 Binary files /dev/null and b/docs/img/CompileSource/compile_me_batch_file.png differ diff --git a/docs/menu_corrections_priorities.md b/docs/menu_corrections_priorities.md index 38c9a1e6d..81c7206fb 100644 --- a/docs/menu_corrections_priorities.md +++ b/docs/menu_corrections_priorities.md @@ -28,7 +28,7 @@ RTK Corrections Priorities Menu To achieve an RTK Fix, SparkFun RTK products must be provided with a correction source. An RTK device can obtain corrections from a variety of sources. Below is the list of possible sources (not all platforms support all sources) and their default priorities. These defaults generally follow the rule that a shorter baseline between Rover and Base leads to more accurate, and therefore more valuable, correction data: - External Radio (100m [OSR](https://docs.sparkfun.com/SparkFun_RTK_Everywhere_Firmware/correction_sources/#osr-vs-ssr) Baseline) - Two packet radios communicating directly between a Rover and Base -- ESP-Now (100m OSR Baseline) - Two RTK devices communicating directly between a Rover and Base over the built-in 2.4GHz radios +- ESP-NOW (100m OSR Baseline) - Two RTK devices communicating directly between a Rover and Base over the built-in 2.4GHz radios - LoRa Radio (1km OSR Baseline) - Two RTK devices communicating directly between a Rover and Base over the built-in LoRa radios (RTK Torch only) - Bluetooth (10+km OSR/SSR Baseline) - A Rover obtaining corrections over Bluetooth to a phone/tablet that has an NTRIP Client - USB (10+km OSR/SSR Baseline) - A Rover obtaining corrections over USB to a phone/tablet that has an NTRIP Client diff --git a/docs/menu_gnss.md b/docs/menu_gnss.md index 84c1a2675..f8e3c9ef1 100644 --- a/docs/menu_gnss.md +++ b/docs/menu_gnss.md @@ -39,7 +39,7 @@ Measurement Frequency can be set by either Hz or by seconds between measurements ## Dynamic Model -The Dynamic Model can be changed but it is recommended to leave it as *Survey*. For more information, please see the list of [reference documents](reference_documents.md) for your platform. +The Dynamic Model can be changed but it is recommended to leave it as *Portable*. For more information, please see the list of [reference documents](reference_documents.md) for your platform. ## Min SV Elevation and C/N0 diff --git a/docs/menu_system.md b/docs/menu_system.md index 5b3d269df..5db0dee57 100644 --- a/docs/menu_system.md +++ b/docs/menu_system.md @@ -77,7 +77,7 @@ System Menu Options serial menu The device can be in Rover, Base, or WiFi Config mode. The selected mode will be entered once the user exits the menu system. -- **B**ase - The device will reconfigure for base mode. It will begin transmitting corrections over Bluetooth, WiFi (NTRIP Server, TCP, etc), or other (ESP-Now, external radio if compatible, etc). +- **B**ase - The device will reconfigure for base mode. It will begin transmitting corrections over Bluetooth, WiFi (NTRIP Server, TCP, etc), or other (ESP-NOW, external radio if compatible, etc). - Base**C**aster - The device will reconfigure for base caster mode. It will broadcast a WiFi access point, allow incoming NTRIP Client connections on port 2101. See [BaseCast Mode](menu_base.md#base-cast). - **R**over - This is the default mode. The device transmits its NMEA and other messages (if enabled) over Bluetooth. It can receive corrections over Bluetooth (or other transport methods such as NTRIP Client) to achieve RTK Fix. - **W**eb Config - The device will shut down GNSS operations and serve a configuration web page over WiFi or ethernet. @@ -108,7 +108,7 @@ System Menu Options serial menu - **~** - If desired, the external button(s) can be disabled to prevent accidental mode changes. !!! note - Bluetooth SPP cannot operate concurrently with ESP-Now radio transmissions. Therefore, if you plan to use the ESP-Now radio system to connect RTK products, the BLE protocol must be used to communicate over Bluetooth to data collectors. Alternatively, ESP-Now works concurrently with WiFi so connecting to a data collector over WiFi can be used. + Bluetooth SPP cannot operate concurrently with ESP-NOW radio transmissions. Therefore, if you plan to use the ESP-NOW radio system to connect RTK products, the BLE protocol must be used to communicate over Bluetooth to data collectors. Alternatively, ESP-NOW works concurrently with WiFi so connecting to a data collector over WiFi can be used. ## Factory Reset