trunk roundhouse kick

pull/2187/head
Thomas Göttgens 2023-01-21 14:34:29 +01:00
rodzic 6cf18b7d07
commit 51b2c431d9
234 zmienionych plików z 4989 dodań i 5101 usunięć

3
.gitattributes vendored
Wyświetl plik

@ -1,3 +1,4 @@
* text=auto eol=lf
*.{cmd,[cC][mM][dD]} text eol=crlf
*.{bat,[bB][aA][tT]} text eol=crlf
*.{bat,[bB][aA][tT]} text eol=crlf
*.{sh,[sS][hH]} text eol=lf

Wyświetl plik

@ -2,8 +2,8 @@
set -e
VERSION=`bin/buildinfo.py long`
SHORT_VERSION=`bin/buildinfo.py short`
VERSION=$(bin/buildinfo.py long)
SHORT_VERSION=$(bin/buildinfo.py short)
OUTDIR=release/
@ -11,7 +11,7 @@ rm -f $OUTDIR/firmware*
rm -r $OUTDIR/* || true
# Important to pull latest version of libs into all device flavors, otherwise some devices might be stale
platformio pkg update
platformio pkg update
echo "Building for $1 with $PLATFORMIO_BUILD_FLAGS"
rm -f .pio/build/$1/firmware.*

Wyświetl plik

@ -2,8 +2,8 @@
set -e
VERSION=`bin/buildinfo.py long`
SHORT_VERSION=`bin/buildinfo.py short`
VERSION=$(bin/buildinfo.py long)
SHORT_VERSION=$(bin/buildinfo.py short)
OUTDIR=release/
@ -13,11 +13,10 @@ mkdir -p $OUTDIR/
rm -r $OUTDIR/* || true
# Important to pull latest version of libs into all device flavors, otherwise some devices might be stale
platformio pkg update
platformio pkg update
pio run --environment native
cp .pio/build/native/program $OUTDIR/meshtasticd_linux_amd64
cp bin/device-install.* $OUTDIR
cp bin/device-update.* $OUTDIR

Wyświetl plik

@ -2,8 +2,8 @@
set -e
VERSION=`bin/buildinfo.py long`
SHORT_VERSION=`bin/buildinfo.py short`
VERSION=$(bin/buildinfo.py long)
SHORT_VERSION=$(bin/buildinfo.py short)
OUTDIR=release/
@ -11,7 +11,7 @@ rm -f $OUTDIR/firmware*
rm -r $OUTDIR/* || true
# Important to pull latest version of libs into all device flavors, otherwise some devices might be stale
platformio pkg update
platformio pkg update
echo "Building for $1 with $PLATFORMIO_BUILD_FLAGS"
rm -f .pio/build/$1/firmware.*

Wyświetl plik

@ -2,8 +2,8 @@
set -e
VERSION=`bin/buildinfo.py long`
SHORT_VERSION=`bin/buildinfo.py short`
VERSION=$(bin/buildinfo.py long)
SHORT_VERSION=$(bin/buildinfo.py short)
OUTDIR=release/
@ -11,7 +11,7 @@ rm -f $OUTDIR/firmware*
rm -r $OUTDIR/* || true
# Important to pull latest version of libs into all device flavors, otherwise some devices might be stale
platformio pkg update
platformio pkg update
echo "Building for $1 with $PLATFORMIO_BUILD_FLAGS"
rm -f .pio/build/$1/firmware.*

Wyświetl plik

@ -4,23 +4,23 @@
set -e
VERSION=`bin/buildinfo.py long`
VERSION=$(bin/buildinfo.py long)
# The shell vars the build tool expects to find
export APP_VERSION=$VERSION
if [[ $# -gt 0 ]]; then
# can override which environment by passing arg
BOARDS="$@"
# can override which environment by passing arg
BOARDS="$@"
else
BOARDS="tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 rak4631 rak4631_eink rak11200 t-echo pca10059_diy_eink"
BOARDS="tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 rak4631 rak4631_eink rak11200 t-echo pca10059_diy_eink"
fi
echo "BOARDS:${BOARDS}"
CHECK=""
for BOARD in $BOARDS; do
CHECK="${CHECK} -e ${BOARD}"
CHECK="${CHECK} -e ${BOARD}"
done
pio check --flags "-DAPP_VERSION=${APP_VERSION} --suppressions-list=suppressions.txt" $CHECK --skip-packages --pattern="src/" --fail-on-defect=low --fail-on-defect=medium --fail-on-defect=high

Wyświetl plik

@ -5,17 +5,17 @@
set -e
if [[ $# -gt 0 ]]; then
# can override which environment by passing arg
BOARDS="$@"
# can override which environment by passing arg
BOARDS="$@"
else
BOARDS="rak4631 rak4631_eink t-echo pca10059_diy_eink pico rak11200 tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 nano-g1 station-g1 m5stack-core m5stack-coreink tbeam-s3-core"
BOARDS="rak4631 rak4631_eink t-echo pca10059_diy_eink pico rak11200 tlora-v2 tlora-v1 tlora_v1_3 tlora-v2-1-1.6 tbeam heltec-v1 heltec-v2.0 heltec-v2.1 tbeam0.7 meshtastic-diy-v1 nano-g1 station-g1 m5stack-core m5stack-coreink tbeam-s3-core"
fi
echo "BOARDS:${BOARDS}"
CHECK=""
for BOARD in $BOARDS; do
CHECK="${CHECK} -e ${BOARD}"
CHECK="${CHECK} -e ${BOARD}"
done
echo $CHECK

Wyświetl plik

@ -1,12 +1,12 @@
#!/bin/sh
PYTHON=${PYTHON:-$(which python3 python|head -n 1)}
PYTHON=${PYTHON:-$(which python3 python | head -n 1)}
set -e
# Usage info
show_help() {
cat << EOF
cat <<EOF
Usage: $(basename $0) [-h] [-p ESPTOOL_PORT] [-P PYTHON] [-f FILENAME|FILENAME]
Flash image file to device, but first erasing and writing system information"
@ -18,39 +18,41 @@ Flash image file to device, but first erasing and writing system information"
EOF
}
while getopts ":hp:P:f:" opt; do
case "${opt}" in
h)
show_help
exit 0
;;
p) export ESPTOOL_PORT=${OPTARG}
;;
P) PYTHON=${OPTARG}
;;
f) FILENAME=${OPTARG}
;;
*)
echo "Invalid flag."
show_help >&2
exit 1
;;
esac
case "${opt}" in
h)
show_help
exit 0
;;
p)
export ESPTOOL_PORT=${OPTARG}
;;
P)
PYTHON=${OPTARG}
;;
f)
FILENAME=${OPTARG}
;;
*)
echo "Invalid flag."
show_help >&2
exit 1
;;
esac
done
shift "$((OPTIND-1))"
shift "$((OPTIND - 1))"
[ -z "$FILENAME" -a -n "$1" ] && {
FILENAME=$1
shift
FILENAME=$1
shift
}
if [ -f "${FILENAME}" ] && [ ! -z "${FILENAME##*"update"*}" ]; then
echo "Trying to flash ${FILENAME}, but first erasing and writing system information"
"$PYTHON" -m esptool erase_flash
"$PYTHON" -m esptool write_flash 0x00 ${FILENAME}
"$PYTHON" -m esptool write_flash 0x260000 bleota.bin
"$PYTHON" -m esptool write_flash 0x300000 littlefs-*.bin
"$PYTHON" -m esptool erase_flash
"$PYTHON" -m esptool write_flash 0x00 ${FILENAME}
"$PYTHON" -m esptool write_flash 0x260000 bleota.bin
"$PYTHON" -m esptool write_flash 0x300000 littlefs-*.bin
else
show_help

Wyświetl plik

@ -1,10 +1,10 @@
#!/bin/sh
PYTHON=${PYTHON:-$(which python3 python|head -n 1)}
PYTHON=${PYTHON:-$(which python3 python | head -n 1)}
# Usage info
show_help() {
cat << EOF
cat <<EOF
Usage: $(basename $0) [-h] [-p ESPTOOL_PORT] [-P PYTHON] [-f FILENAME|FILENAME]
Flash image file to device, leave existing system intact."
@ -16,31 +16,33 @@ Flash image file to device, leave existing system intact."
EOF
}
while getopts ":hp:P:f:" opt; do
case "${opt}" in
h)
show_help
exit 0
;;
p) export ESPTOOL_PORT=${OPTARG}
;;
P) PYTHON=${OPTARG}
;;
f) FILENAME=${OPTARG}
;;
*)
echo "Invalid flag."
show_help >&2
exit 1
;;
esac
case "${opt}" in
h)
show_help
exit 0
;;
p)
export ESPTOOL_PORT=${OPTARG}
;;
P)
PYTHON=${OPTARG}
;;
f)
FILENAME=${OPTARG}
;;
*)
echo "Invalid flag."
show_help >&2
exit 1
;;
esac
done
shift "$((OPTIND-1))"
shift "$((OPTIND - 1))"
[ -z "$FILENAME" -a -n "$1" ] && {
FILENAME=$1
shift
FILENAME=$1
shift
}
if [ -f "${FILENAME}" ] && [ -z "${FILENAME##*"update"*}" ]; then

Wyświetl plik

@ -2,4 +2,4 @@
arm-none-eabi-readelf -s -e .pio/build/nrf52dk/firmware.elf | head -80
nm -CSr --size-sort .pio/build/nrf52dk/firmware.elf | grep '^200'
nm -CSr --size-sort .pio/build/nrf52dk/firmware.elf | grep '^200'

Wyświetl plik

@ -1,6 +1,6 @@
#!/usr/bin/env bash
set -e
set -e
# regen the design bins first
cd design

Wyświetl plik

@ -1,10 +1,10 @@
#!/usr/bin/env bash
set -e
set -e
echo "This script is only for developers who are publishing new builds on github. Most users don't need it"
VERSION=`bin/buildinfo.py long`
VERSION=$(bin/buildinfo.py long)
# Must have a V prefix to trigger github
git tag "v${VERSION}"

Wyświetl plik

@ -8,4 +8,3 @@ sleep 20 # 5 seconds was not enough
echo "Simulator started, launching python test..."
python3 -c 'from meshtastic.test import testSimulator; testSimulator()'

Wyświetl plik

@ -7,12 +7,7 @@
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_TTGO_EINK -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
[
"0x239A",
"0x4405"
]
],
"hwids": [["0x239A", "0x4405"]],
"usb_product": "TTGO_eink",
"mcu": "nrf52840",
"variant": "eink0.1",
@ -30,19 +25,13 @@
"settings_addr": "0xFF000"
}
},
"connectivity": [
"bluetooth"
],
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"onboard_tools": [
"jlink"
],
"onboard_tools": ["jlink"],
"svd_path": "nrf52840.svd"
},
"frameworks": [
"arduino"
],
"frameworks": ["arduino"],
"name": "TTGO eink (Adafruit BSP)",
"upload": {
"maximum_ram_size": 248832,
@ -50,12 +39,8 @@
"require_upload_port": true,
"speed": 115200,
"protocol": "jlink",
"protocols": [
"jlink",
"nrfjprog",
"stlink"
]
"protocols": ["jlink", "nrfjprog", "stlink"]
},
"url": "FIXME",
"vendor": "TTGO"
}
}

Wyświetl plik

@ -9,9 +9,7 @@
"product_line": "STM32WLE5xx"
},
"debug": {
"default_tools": [
"stlink"
],
"default_tools": ["stlink"],
"jlink_device": "STM32WLE5CC",
"openocd_target": "stm32wlx",
"svd_path": "STM32WLE5_CM4.svd"
@ -22,9 +20,7 @@
"maximum_ram_size": 65536,
"maximum_size": 262144,
"protocol": "cmsis-dap",
"protocols": [
"cmsis-dap"
]
"protocols": ["cmsis-dap"]
},
"url": "https://www.st.com/en/microcontrollers-microprocessors/stm32wl-series.html",
"vendor": "ST"

Wyświetl plik

@ -19,16 +19,12 @@
"sd_fwid": "0x00B7"
}
},
"connectivity": [
"bluetooth"
],
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52832_xxAA",
"svd_path": "nrf52.svd"
},
"frameworks": [
"arduino"
],
"frameworks": ["arduino"],
"name": "lora ISP4520",
"upload": {
"maximum_ram_size": 65536,
@ -36,13 +32,8 @@
"require_upload_port": true,
"speed": 115200,
"protocol": "nrfutil",
"protocols": [
"jlink",
"nrfjprog",
"nrfutil",
"stlink"
]
"protocols": ["jlink", "nrfjprog", "nrfutil", "stlink"]
},
"url": "",
"vendor": "PsiSoft"
}
}

Wyświetl plik

@ -1,72 +1,51 @@
{
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_FEATHER -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
[
"0x239A",
"0x8029"
],
[
"0x239A",
"0x0029"
],
[
"0x239A",
"0x002A"
],
[
"0x239A",
"0x802A"
]
],
"usb_product": "PCA10059",
"mcu": "nrf52840",
"variant": "nRF52840 Dongle",
"bsp": {
"name": "adafruit"
},
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
},
"bootloader": {
"settings_addr": "0xFF000"
}
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
},
"connectivity": [
"bluetooth"
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_FEATHER -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
["0x239A", "0x8029"],
["0x239A", "0x0029"],
["0x239A", "0x002A"],
["0x239A", "0x802A"]
],
"debug": {
"jlink_device": "nRF52840_xxAA",
"svd_path": "nrf52840.svd"
"usb_product": "PCA10059",
"mcu": "nrf52840",
"variant": "nRF52840 Dongle",
"bsp": {
"name": "adafruit"
},
"frameworks": [
"arduino"
],
"name": "nRF52840 Dongle",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": [
"jlink",
"nrfjprog",
"nrfutil",
"stlink"
],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
},
"url": "https://www.nordicsemi.com/Products/Development-hardware/nrf52840-dongle",
"vendor": "Nordic Semiconductor"
"bootloader": {
"settings_addr": "0xFF000"
}
},
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"svd_path": "nrf52840.svd"
},
"frameworks": ["arduino"],
"name": "nRF52840 Dongle",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": ["jlink", "nrfjprog", "nrfutil", "stlink"],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
},
"url": "https://www.nordicsemi.com/Products/Development-hardware/nrf52840-dongle",
"vendor": "Nordic Semiconductor"
}

Wyświetl plik

@ -1,47 +1,46 @@
{
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_PCA10056 -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [["0x239A", "0x4404"]],
"usb_product": "nrf52840dk",
"mcu": "nrf52840",
"variant": "pca10056",
"variants_dir": "variants",
"bsp": {
"name": "adafruit"
},
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
},
"bootloader": {
"settings_addr": "0xFF000"
}
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
},
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"onboard_tools": ["jlink"],
"svd_path": "nrf52840.svd"
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_PCA10056 -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [["0x239A", "0x4404"]],
"usb_product": "nrf52840dk",
"mcu": "nrf52840",
"variant": "pca10056",
"variants_dir": "variants",
"bsp": {
"name": "adafruit"
},
"frameworks": ["arduino"],
"name": "A modified NRF52840-DK devboard (Adafruit BSP)",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"require_upload_port": true,
"speed": 115200,
"protocol": "jlink",
"protocols": ["jlink", "nrfjprog", "stlink"]
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
},
"url": "https://meshtastic.org/",
"vendor": "Nordic Semi"
}
"bootloader": {
"settings_addr": "0xFF000"
}
},
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"onboard_tools": ["jlink"],
"svd_path": "nrf52840.svd"
},
"frameworks": ["arduino"],
"name": "A modified NRF52840-DK devboard (Adafruit BSP)",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"require_upload_port": true,
"speed": 115200,
"protocol": "jlink",
"protocols": ["jlink", "nrfjprog", "stlink"]
},
"url": "https://meshtastic.org/",
"vendor": "Nordic Semi"
}

Wyświetl plik

@ -7,12 +7,7 @@
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_TTGO_EINK -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
[
"0x239A",
"0x4405"
]
],
"hwids": [["0x239A", "0x4405"]],
"usb_product": "TTGO_eink",
"mcu": "nrf52840",
"variant": "t-echo",
@ -30,35 +25,24 @@
"settings_addr": "0xFF000"
}
},
"connectivity": [
"bluetooth"
],
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"onboard_tools": [
"jlink"
],
"onboard_tools": ["jlink"],
"svd_path": "nrf52840.svd"
},
"frameworks": [
"arduino"
],
"frameworks": ["arduino"],
"name": "TTGO eink (Adafruit BSP)",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": [
"jlink",
"nrfjprog",
"nrfutil",
"stlink"
],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": ["jlink", "nrfjprog", "nrfutil", "stlink"],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
},
"url": "FIXME",
"vendor": "TTGO"
}
}

Wyświetl plik

@ -15,24 +15,15 @@
"f_cpu": "240000000L",
"f_flash": "80000000L",
"flash_mode": "dio",
"hwids": [
[
"0X303A",
"0x1001"
]
],
"hwids": [["0X303A", "0x1001"]],
"mcu": "esp32s3",
"variant": "tbeam-s3-core"
},
"connectivity": [
"wifi"
],
"connectivity": ["wifi"],
"debug": {
"openocd_target": "esp32s3.cfg"
},
"frameworks": [
"arduino"
],
"frameworks": ["arduino"],
"name": "LilyGo TBeam-S3-Core",
"upload": {
"flash_size": "8MB",
@ -43,4 +34,4 @@
},
"url": "http://www.lilygo.cn/",
"vendor": "LilyGo"
}
}

Wyświetl plik

@ -14,25 +14,15 @@
"f_cpu": "240000000L",
"f_flash": "80000000L",
"flash_mode": "dio",
"hwids": [
[
"0X303A",
"0x1001"
]
],
"hwids": [["0X303A", "0x1001"]],
"mcu": "esp32s3",
"variant": "tlora-t3s3-v1"
},
"connectivity": [
"wifi"
],
"connectivity": ["wifi"],
"debug": {
"openocd_target": "esp32s3.cfg"
},
"frameworks": [
"arduino",
"espidf"
],
"frameworks": ["arduino", "espidf"],
"name": "LilyGo TLora-T3S3-V1",
"upload": {
"flash_size": "4MB",
@ -44,4 +34,4 @@
},
"url": "http://www.lilygo.cn/",
"vendor": "LilyGo"
}
}

Wyświetl plik

@ -1,6 +1,6 @@
{
"build": {
"arduino":{
"arduino": {
"ldscript": "esp32_out.ld"
},
"core": "esp32",
@ -11,26 +11,14 @@
"mcu": "esp32",
"variant": "WisCore_RAK11200_Board"
},
"connectivity": [
"wifi",
"bluetooth",
"ethernet",
"can"
],
"frameworks": [
"arduino",
"espidf"
],
"connectivity": ["wifi", "bluetooth", "ethernet", "can"],
"frameworks": ["arduino", "espidf"],
"name": "WisCore RAK11200 Board",
"upload": {
"flash_size": "4MB",
"maximum_ram_size": 327680,
"maximum_size": 4194304,
"protocols": [
"esptool",
"espota",
"ftdi"
],
"protocols": ["esptool", "espota", "ftdi"],
"require_upload_port": true,
"speed": 460800
},

Wyświetl plik

@ -8,22 +8,10 @@
"extra_flags": "-DNRF52832_XXAA -DNRF52",
"f_cpu": "64000000L",
"hwids": [
[
"0x239A",
"0x8029"
],
[
"0x239A",
"0x0029"
],
[
"0x239A",
"0x002A"
],
[
"0x239A",
"0x802A"
]
["0x239A", "0x8029"],
["0x239A", "0x0029"],
["0x239A", "0x002A"],
["0x239A", "0x802A"]
],
"usb_product": "Feather nRF52832 Express",
"mcu": "nrf52832",
@ -41,17 +29,12 @@
"variant": "nrf52_adafruit_feather"
}
},
"connectivity": [
"bluetooth"
],
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52832_xxAA",
"svd_path": "nrf52.svd"
},
"frameworks": [
"arduino",
"zephyr"
],
"frameworks": ["arduino", "zephyr"],
"name": "Adafruit Bluefruit nRF52832 Feather",
"upload": {
"maximum_ram_size": 65536,
@ -59,13 +42,8 @@
"require_upload_port": true,
"speed": 115200,
"protocol": "nrfutil",
"protocols": [
"jlink",
"nrfjprog",
"nrfutil",
"stlink"
]
"protocols": ["jlink", "nrfjprog", "nrfutil", "stlink"]
},
"url": "https://www.adafruit.com/product/3406",
"vendor": "Adafruit"
}
}

Wyświetl plik

@ -1,72 +1,51 @@
{
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_FEATHER -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
[
"0x239A",
"0x8029"
],
[
"0x239A",
"0x0029"
],
[
"0x239A",
"0x002A"
],
[
"0x239A",
"0x802A"
]
],
"usb_product": "WisCore RAK4631 Board",
"mcu": "nrf52840",
"variant": "WisCore_RAK4631_Board",
"bsp": {
"name": "adafruit"
},
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
},
"bootloader": {
"settings_addr": "0xFF000"
}
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
},
"connectivity": [
"bluetooth"
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_FEATHER -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
["0x239A", "0x8029"],
["0x239A", "0x0029"],
["0x239A", "0x002A"],
["0x239A", "0x802A"]
],
"debug": {
"jlink_device": "nRF52840_xxAA",
"svd_path": "nrf52840.svd"
"usb_product": "WisCore RAK4631 Board",
"mcu": "nrf52840",
"variant": "WisCore_RAK4631_Board",
"bsp": {
"name": "adafruit"
},
"frameworks": [
"arduino"
],
"name": "WisCore RAK4631 Board",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": [
"jlink",
"nrfjprog",
"nrfutil",
"stlink"
],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
},
"url": "https://www.rakwireless.com",
"vendor": "RAKwireless"
}
"bootloader": {
"settings_addr": "0xFF000"
}
},
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"svd_path": "nrf52840.svd"
},
"frameworks": ["arduino"],
"name": "WisCore RAK4631 Board",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": ["jlink", "nrfjprog", "nrfutil", "stlink"],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
},
"url": "https://www.rakwireless.com",
"vendor": "RAKwireless"
}

Wyświetl plik

@ -8,6 +8,6 @@ services:
replicas: 4
networks:
- mesh
networks:
mesh:
mesh:

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "BluetoothCommon.h"
#include "configuration.h"
// NRF52 wants these constants as byte arrays
// Generated here https://yupana-engineering.com/online-uuid-to-c-array-converter - but in REVERSE BYTE ORDER

Wyświetl plik

@ -1,26 +1,24 @@
#include "configuration.h"
#include "FSCommon.h"
#include "configuration.h"
#ifdef HAS_SDCARD
#include <SPI.h>
#include <SD.h>
#include <SPI.h>
#ifdef SDCARD_USE_SPI1
#ifdef SDCARD_USE_SPI1
SPIClass SPI1(HSPI);
#define SDHandler SPI1
#endif
#endif // HAS_SDCARD
#endif //HAS_SDCARD
bool copyFile(const char* from, const char* to)
bool copyFile(const char *from, const char *to)
{
#ifdef FSCom
unsigned char cbuffer[16];
File f1 = FSCom.open(from, FILE_O_READ);
if (!f1){
if (!f1) {
LOG_ERROR("Failed to open source file %s\n", from);
return false;
}
@ -30,55 +28,55 @@ bool copyFile(const char* from, const char* to)
LOG_ERROR("Failed to open destination file %s\n", to);
return false;
}
while (f1.available() > 0) {
byte i = f1.read(cbuffer, 16);
f2.write(cbuffer, i);
}
f2.close();
f1.close();
return true;
#endif
}
bool renameFile(const char* pathFrom, const char* pathTo)
bool renameFile(const char *pathFrom, const char *pathTo)
{
#ifdef FSCom
#ifdef ARCH_ESP32
// rename was fixed for ESP32 IDF LittleFS in April
return FSCom.rename(pathFrom, pathTo);
#else
if (copyFile(pathFrom, pathTo) && FSCom.remove(pathFrom) ) {
if (copyFile(pathFrom, pathTo) && FSCom.remove(pathFrom)) {
return true;
} else{
} else {
return false;
}
#endif
#endif
}
void listDir(const char * dirname, uint8_t levels, boolean del = false)
void listDir(const char *dirname, uint8_t levels, boolean del = false)
{
#ifdef FSCom
#if (defined(ARCH_ESP32) || defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
char buffer[255];
#endif
File root = FSCom.open(dirname, FILE_O_READ);
if(!root){
if (!root) {
return;
}
if(!root.isDirectory()){
if (!root.isDirectory()) {
return;
}
File file = root.openNextFile();
while(file){
if(file.isDirectory() && !String(file.name()).endsWith(".")) {
if(levels){
while (file) {
if (file.isDirectory() && !String(file.name()).endsWith(".")) {
if (levels) {
#ifdef ARCH_ESP32
listDir(file.path(), levels -1, del);
if(del) {
listDir(file.path(), levels - 1, del);
if (del) {
LOG_DEBUG("Removing %s\n", file.path());
strncpy(buffer, file.path(), sizeof(buffer));
file.close();
@ -87,33 +85,33 @@ void listDir(const char * dirname, uint8_t levels, boolean del = false)
file.close();
}
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
listDir(file.name(), levels -1, del);
if(del) {
listDir(file.name(), levels - 1, del);
if (del) {
LOG_DEBUG("Removing %s\n", file.name());
strncpy(buffer, file.name(), sizeof(buffer));
file.close();
FSCom.rmdir(buffer);
} else {
file.close();
}
}
#else
listDir(file.name(), levels -1, del);
listDir(file.name(), levels - 1, del);
file.close();
#endif
}
} else {
#ifdef ARCH_ESP32
if(del) {
if (del) {
LOG_DEBUG("Deleting %s\n", file.path());
strncpy(buffer, file.path(), sizeof(buffer));
file.close();
FSCom.remove(buffer);
} else {
LOG_DEBUG(" %s (%i Bytes)\n", file.path(), file.size());
LOG_DEBUG(" %s (%i Bytes)\n", file.path(), file.size());
file.close();
}
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
if(del) {
if (del) {
LOG_DEBUG("Deleting %s\n", file.name());
strncpy(buffer, file.name(), sizeof(buffer));
file.close();
@ -125,12 +123,12 @@ void listDir(const char * dirname, uint8_t levels, boolean del = false)
#else
LOG_DEBUG(" %s (%i Bytes)\n", file.name(), file.size());
file.close();
#endif
#endif
}
file = root.openNextFile();
}
#ifdef ARCH_ESP32
if(del) {
#ifdef ARCH_ESP32
if (del) {
LOG_DEBUG("Removing %s\n", root.path());
strncpy(buffer, root.path(), sizeof(buffer));
root.close();
@ -139,7 +137,7 @@ void listDir(const char * dirname, uint8_t levels, boolean del = false)
root.close();
}
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
if(del) {
if (del) {
LOG_DEBUG("Removing %s\n", root.name());
strncpy(buffer, root.name(), sizeof(buffer));
root.close();
@ -153,7 +151,7 @@ void listDir(const char * dirname, uint8_t levels, boolean del = false)
#endif
}
void rmDir(const char * dirname)
void rmDir(const char *dirname)
{
#ifdef FSCom
#if (defined(ARCH_ESP32) || defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
@ -168,8 +166,7 @@ void rmDir(const char * dirname)
void fsInit()
{
#ifdef FSCom
if (!FSBegin())
{
if (!FSBegin()) {
LOG_ERROR("Filesystem mount Failed.\n");
// assert(0); This auto-formats the partition, so no need to fail here.
}
@ -182,7 +179,6 @@ void fsInit()
#endif
}
void setupSDCard()
{
#ifdef HAS_SDCARD
@ -190,12 +186,12 @@ void setupSDCard()
if (!SD.begin(SDCARD_CS, SDHandler)) {
LOG_DEBUG("No SD_MMC card detected\n");
return ;
return;
}
uint8_t cardType = SD.cardType();
if (cardType == CARD_NONE) {
LOG_DEBUG("No SD_MMC card attached\n");
return ;
return;
}
LOG_DEBUG("SD_MMC Card Type: ");
if (cardType == CARD_MMC) {
@ -214,6 +210,3 @@ void setupSDCard()
LOG_DEBUG("Used space: %llu MB\n", SD.usedBytes() / (1024 * 1024));
#endif
}

Wyświetl plik

@ -40,8 +40,8 @@ using namespace Adafruit_LittleFS_Namespace;
#endif
void fsInit();
bool copyFile(const char* from, const char* to);
bool renameFile(const char* pathFrom, const char* pathTo);
void listDir(const char * dirname, uint8_t levels, boolean del);
void rmDir(const char * dirname);
bool copyFile(const char *from, const char *to);
bool renameFile(const char *pathFrom, const char *pathTo);
void listDir(const char *dirname, uint8_t levels, boolean del);
void rmDir(const char *dirname);
void setupSDCard();

Wyświetl plik

@ -20,7 +20,7 @@ class GPSStatus : public Status
bool hasLock = false; // default to false, until we complete our first read
bool isConnected = false; // Do we have a GPS we are talking to
bool isPowerSaving = false; //Are we in power saving state
bool isPowerSaving = false; // Are we in power saving state
Position p = Position_init_default;
@ -47,7 +47,7 @@ class GPSStatus : public Status
bool getIsConnected() const { return isConnected; }
bool getIsPowerSaving() const { return isPowerSaving;}
bool getIsPowerSaving() const { return isPowerSaving; }
int32_t getLatitude() const
{
@ -88,22 +88,31 @@ class GPSStatus : public Status
}
}
uint32_t getDOP() const { return p.PDOP; }
uint32_t getDOP() const
{
return p.PDOP;
}
uint32_t getHeading() const { return p.ground_track; }
uint32_t getHeading() const
{
return p.ground_track;
}
uint32_t getNumSatellites() const { return p.sats_in_view; }
uint32_t getNumSatellites() const
{
return p.sats_in_view;
}
bool matches(const GPSStatus *newStatus) const
{
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("GPSStatus.match() new pos@%x to old pos@%x\n", newStatus->p.pos_timestamp, p.pos_timestamp);
#endif
return (newStatus->hasLock != hasLock || newStatus->isConnected != isConnected || newStatus->isPowerSaving !=isPowerSaving ||
newStatus->p.latitude_i != p.latitude_i || newStatus->p.longitude_i != p.longitude_i ||
newStatus->p.altitude != p.altitude || newStatus->p.altitude_hae != p.altitude_hae ||
newStatus->p.PDOP != p.PDOP || newStatus->p.ground_track != p.ground_track ||
newStatus->p.ground_speed != p.ground_speed ||
return (newStatus->hasLock != hasLock || newStatus->isConnected != isConnected ||
newStatus->isPowerSaving != isPowerSaving || newStatus->p.latitude_i != p.latitude_i ||
newStatus->p.longitude_i != p.longitude_i || newStatus->p.altitude != p.altitude ||
newStatus->p.altitude_hae != p.altitude_hae || newStatus->p.PDOP != p.PDOP ||
newStatus->p.ground_track != p.ground_track || newStatus->p.ground_speed != p.ground_speed ||
newStatus->p.sats_in_view != p.sats_in_view);
}

Wyświetl plik

@ -1,83 +1,68 @@
#pragma once
#include <Arduino.h>
#include "Status.h"
#include "configuration.h"
#include <Arduino.h>
namespace meshtastic {
namespace meshtastic
{
/// Describes the state of the NodeDB system.
class NodeStatus : public Status
/// Describes the state of the NodeDB system.
class NodeStatus : public Status
{
private:
CallbackObserver<NodeStatus, const NodeStatus *> statusObserver =
CallbackObserver<NodeStatus, const NodeStatus *>(this, &NodeStatus::updateStatus);
uint8_t numOnline = 0;
uint8_t numTotal = 0;
uint8_t lastNumTotal = 0;
public:
bool forceUpdate = false;
NodeStatus() { statusType = STATUS_TYPE_NODE; }
NodeStatus(uint8_t numOnline, uint8_t numTotal, bool forceUpdate = false) : Status()
{
this->forceUpdate = forceUpdate;
this->numOnline = numOnline;
this->numTotal = numTotal;
}
NodeStatus(const NodeStatus &);
NodeStatus &operator=(const NodeStatus &);
private:
CallbackObserver<NodeStatus, const NodeStatus *> statusObserver = CallbackObserver<NodeStatus, const NodeStatus *>(this, &NodeStatus::updateStatus);
void observe(Observable<const NodeStatus *> *source) { statusObserver.observe(source); }
uint8_t numOnline = 0;
uint8_t numTotal = 0;
uint8_t getNumOnline() const { return numOnline; }
uint8_t lastNumTotal = 0;
uint8_t getNumTotal() const { return numTotal; }
public:
bool forceUpdate = false;
uint8_t getLastNumTotal() const { return lastNumTotal; }
NodeStatus() {
statusType = STATUS_TYPE_NODE;
}
NodeStatus( uint8_t numOnline, uint8_t numTotal, bool forceUpdate = false ) : Status()
bool matches(const NodeStatus *newStatus) const
{
return (newStatus->getNumOnline() != numOnline || newStatus->getNumTotal() != numTotal);
}
int updateStatus(const NodeStatus *newStatus)
{
// Only update the status if values have actually changed
lastNumTotal = numTotal;
bool isDirty;
{
this->forceUpdate = forceUpdate;
this->numOnline = numOnline;
this->numTotal = numTotal;
isDirty = matches(newStatus);
initialized = true;
numOnline = newStatus->getNumOnline();
numTotal = newStatus->getNumTotal();
}
NodeStatus(const NodeStatus &);
NodeStatus &operator=(const NodeStatus &);
void observe(Observable<const NodeStatus *> *source)
{
statusObserver.observe(source);
if (isDirty || newStatus->forceUpdate) {
LOG_DEBUG("Node status update: %d online, %d total\n", numOnline, numTotal);
onNewStatus.notifyObservers(this);
}
return 0;
}
};
uint8_t getNumOnline() const
{
return numOnline;
}
uint8_t getNumTotal() const
{
return numTotal;
}
uint8_t getLastNumTotal() const
{
return lastNumTotal;
}
bool matches(const NodeStatus *newStatus) const
{
return (
newStatus->getNumOnline() != numOnline ||
newStatus->getNumTotal() != numTotal
);
}
int updateStatus(const NodeStatus *newStatus) {
// Only update the status if values have actually changed
lastNumTotal = numTotal;
bool isDirty;
{
isDirty = matches(newStatus);
initialized = true;
numOnline = newStatus->getNumOnline();
numTotal = newStatus->getNumTotal();
}
if(isDirty || newStatus->forceUpdate) {
LOG_DEBUG("Node status update: %d online, %d total\n", numOnline, numTotal);
onNewStatus.notifyObservers(this);
}
return 0;
}
};
}
} // namespace meshtastic
extern meshtastic::NodeStatus *nodeStatus;

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "OSTimer.h"
#include "configuration.h"
/**
* Schedule a callback to run. The callback must _not_ block, though it is called from regular thread level (not ISR)

Wyświetl plik

@ -1,3 +1,2 @@
#include "configuration.h"
#include "Observer.h"
#include "configuration.h"

Wyświetl plik

@ -10,7 +10,7 @@ template <class T> class Observable;
*/
template <class T> class Observer
{
std::list<Observable<T> *> observed;
std::list<Observable<T> *> observed;
public:
virtual ~Observer();
@ -87,7 +87,7 @@ template <class T> class Observable
template <class T> Observer<T>::~Observer()
{
for (typename std::list<Observable<T> *>::const_iterator iterator = observed.begin(); iterator != observed.end();
++iterator) {
++iterator) {
(*iterator)->removeObserver(this);
}
observed.clear();

Wyświetl plik

@ -1,16 +1,16 @@
#include "power.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "buzz/buzz.h"
#include "configuration.h"
#include "main.h"
#include "sleep.h"
#include "utils.h"
#include "buzz/buzz.h"
#ifdef HAS_PMU
#include "XPowersLibInterface.hpp"
#include "XPowersAXP2101.tpp"
#include "XPowersAXP192.tpp"
#include "XPowersAXP2101.tpp"
#include "XPowersLibInterface.hpp"
XPowersLibInterface *PMU = NULL;
#else
// Copy of the base class defined in axp20x.h.
@ -108,20 +108,20 @@ class AnalogBatteryLevel : public HasBatteryLevel
#ifdef BATTERY_PIN
// Override variant or default ADC_MULTIPLIER if we have the override pref
float operativeAdcMultiplier = config.power.adc_multiplier_override > 0
? config.power.adc_multiplier_override
: ADC_MULTIPLIER;
float operativeAdcMultiplier =
config.power.adc_multiplier_override > 0 ? config.power.adc_multiplier_override : ADC_MULTIPLIER;
// Do not call analogRead() often.
const uint32_t min_read_interval = 5000;
if (millis() - last_read_time_ms > min_read_interval) {
last_read_time_ms = millis();
//Set the number of samples, it has an effect of increasing sensitivity, especially in complex electromagnetic environment.
// Set the number of samples, it has an effect of increasing sensitivity, especially in complex electromagnetic
// environment.
uint32_t raw = 0;
for(uint32_t i=0; i<BATTERY_SENSE_SAMPLES; i++){
for (uint32_t i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
raw += analogRead(BATTERY_PIN);
}
raw = raw/BATTERY_SENSE_SAMPLES;
raw = raw / BATTERY_SENSE_SAMPLES;
float scaled;
#ifndef VBAT_RAW_TO_SCALED
@ -143,15 +143,24 @@ class AnalogBatteryLevel : public HasBatteryLevel
/**
* return true if there is a battery installed in this unit
*/
virtual bool isBatteryConnect() override { return getBatteryPercent() != -1; }
virtual bool isBatteryConnect() override
{
return getBatteryPercent() != -1;
}
/// If we see a battery voltage higher than physics allows - assume charger is pumping
/// in power
virtual bool isVbusIn() override { return getBattVoltage() > chargingVolt; }
virtual bool isVbusIn() override
{
return getBattVoltage() > chargingVolt;
}
/// Assume charging if we have a battery and external power is connected.
/// we can't be smart enough to say 'full'?
virtual bool isCharging() override { return isBatteryConnect() && isVbusIn(); }
virtual bool isCharging() override
{
return isBatteryConnect() && isVbusIn();
}
private:
/// If we see a battery voltage higher than physics allows - assume charger is pumping
@ -159,16 +168,16 @@ class AnalogBatteryLevel : public HasBatteryLevel
#ifndef BAT_FULLVOLT
#define BAT_FULLVOLT 4200
#endif
#endif
#ifndef BAT_EMPTYVOLT
#define BAT_EMPTYVOLT 3270
#endif
#endif
#ifndef BAT_CHARGINGVOLT
#define BAT_CHARGINGVOLT 4210
#endif
#endif
#ifndef BAT_NOBATVOLT
#define BAT_NOBATVOLT 2230
#endif
#endif
/// For heltecs with no battery connected, the measured voltage is 2204, so raising to 2230 from 2100
const float fullVolt = BAT_FULLVOLT, emptyVolt = BAT_EMPTYVOLT, chargingVolt = BAT_CHARGINGVOLT, noBatVolt = BAT_NOBATVOLT;
@ -238,12 +247,12 @@ void Power::shutdown()
{
screen->setOn(false);
#if defined(USE_EINK) && defined(PIN_EINK_EN)
digitalWrite(PIN_EINK_EN, LOW); //power off backlight first
digitalWrite(PIN_EINK_EN, LOW); // power off backlight first
#endif
#ifdef HAS_PMU
LOG_INFO("Shutting down\n");
if(PMU) {
if (PMU) {
PMU->setChargingLedMode(XPOWERS_CHG_LED_OFF);
PMU->shutdown();
}
@ -290,15 +299,16 @@ void Power::readPowerStatus()
if (lastheap != ESP.getFreeHeap()) {
LOG_DEBUG("Threads running:");
int running = 0;
for(int i = 0; i < MAX_THREADS; i++){
for (int i = 0; i < MAX_THREADS; i++) {
auto thread = concurrency::mainController.get(i);
if((thread != nullptr) && (thread->enabled)) {
if ((thread != nullptr) && (thread->enabled)) {
LOG_DEBUG(" %s", thread->ThreadName.c_str());
running++;
}
}
LOG_DEBUG("\n");
LOG_DEBUG("Heap status: %d/%d bytes free (%d), running %d/%d threads\n", ESP.getFreeHeap(), ESP.getHeapSize(), ESP.getFreeHeap() - lastheap, running, concurrency::mainController.size(false));
LOG_DEBUG("Heap status: %d/%d bytes free (%d), running %d/%d threads\n", ESP.getFreeHeap(), ESP.getHeapSize(),
ESP.getFreeHeap() - lastheap, running, concurrency::mainController.size(false));
lastheap = ESP.getFreeHeap();
}
#endif
@ -312,7 +322,7 @@ void Power::readPowerStatus()
LOG_DEBUG("Warning RAK4631 Low voltage counter: %d/10\n", low_voltage_counter);
if (low_voltage_counter > 10) {
// We can't trigger deep sleep on NRF52, it's freezing the board
//powerFSM.trigger(EVENT_LOW_BATTERY);
// powerFSM.trigger(EVENT_LOW_BATTERY);
LOG_DEBUG("Low voltage detected, but not triggering deep sleep\n");
}
} else {
@ -338,11 +348,11 @@ int32_t Power::runOnce()
#ifdef HAS_PMU
// WE no longer use the IRQ line to wake the CPU (due to false wakes from sleep), but we do poll
// the IRQ status by reading the registers over I2C
if(PMU) {
if (PMU) {
PMU->getIrqStatus();
if(PMU->isVbusRemoveIrq()){
if (PMU->isVbusRemoveIrq()) {
LOG_INFO("USB unplugged\n");
powerFSM.trigger(EVENT_POWER_DISCONNECTED);
}
@ -388,24 +398,24 @@ int32_t Power::runOnce()
share the same i2c bus, instead use ssd1306 sleep mode DCDC2 -> unused DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this on!) LDO1
30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of days), can
not be turned off LDO2 200mA -> LORA LDO3 200mA -> GPS
*
*
*/
bool Power::axpChipInit()
{
#ifdef HAS_PMU
TwoWire * w = NULL;
TwoWire *w = NULL;
// Use macro to distinguish which wire is used by PMU
#ifdef PMU_USE_WIRE1
w = &Wire1;
w = &Wire1;
#else
w = &Wire;
w = &Wire;
#endif
/**
* It is not necessary to specify the wire pin,
* It is not necessary to specify the wire pin,
* just input the wire, because the wire has been initialized in main.cpp
*/
if (!PMU) {
@ -431,11 +441,11 @@ bool Power::axpChipInit()
}
if (!PMU) {
/*
* In XPowersLib, if the XPowersAXPxxx object is released, Wire.end() will be called at the same time.
* In order not to affect other devices, if the initialization of the PMU fails, Wire needs to be re-initialized once,
* if there are multiple devices sharing the bus.
* * */
/*
* In XPowersLib, if the XPowersAXPxxx object is released, Wire.end() will be called at the same time.
* In order not to affect other devices, if the initialization of the PMU fails, Wire needs to be re-initialized once,
* if there are multiple devices sharing the bus.
* * */
#ifndef PMU_USE_WIRE1
w->begin(I2C_SDA, I2C_SCL);
#endif
@ -445,48 +455,45 @@ bool Power::axpChipInit()
batteryLevel = PMU;
if (PMU->getChipModel() == XPOWERS_AXP192) {
// lora radio power channel
PMU->setPowerChannelVoltage(XPOWERS_LDO2, 3300);
PMU->enablePowerOutput(XPOWERS_LDO2);
// oled module power channel,
// disable it will cause abnormal communication between boot and AXP power supply,
// disable it will cause abnormal communication between boot and AXP power supply,
// do not turn it off
PMU->setPowerChannelVoltage(XPOWERS_DCDC1, 3300);
// enable oled power
PMU->enablePowerOutput(XPOWERS_DCDC1);
// gnss module power channel - now turned on in setGpsPower
PMU->setPowerChannelVoltage(XPOWERS_LDO3, 3300);
// PMU->enablePowerOutput(XPOWERS_LDO3);
//protected oled power source
// protected oled power source
PMU->setProtectedChannel(XPOWERS_DCDC1);
//protected esp32 power source
// protected esp32 power source
PMU->setProtectedChannel(XPOWERS_DCDC3);
//disable not use channel
// disable not use channel
PMU->disablePowerOutput(XPOWERS_DCDC2);
//disable all axp chip interrupt
// disable all axp chip interrupt
PMU->disableIRQ(XPOWERS_AXP192_ALL_IRQ);
// Set constant current charging current
PMU->setChargerConstantCurr(XPOWERS_AXP192_CHG_CUR_450MA);
//Set up the charging voltage
// Set up the charging voltage
PMU->setChargeTargetVoltage(XPOWERS_AXP192_CHG_VOL_4V2);
} else if (PMU->getChipModel() == XPOWERS_AXP2101) {
// t-beam s3 core
// t-beam s3 core
/**
* gnss module power channel
* gnss module power channel
* The default ALDO4 is off, you need to turn on the GNSS power first, otherwise it will be invalid during initialization
*/
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
@ -496,51 +503,50 @@ bool Power::axpChipInit()
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
PMU->enablePowerOutput(XPOWERS_ALDO3);
// m.2 interface
// m.2 interface
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
PMU->enablePowerOutput(XPOWERS_DCDC3);
/**
* ALDO2 cannot be turned off.
* It is a necessary condition for sensor communication.
* It must be turned on to properly access the sensor and screen
* It is also responsible for the power supply of PCF8563
*/
* ALDO2 cannot be turned off.
* It is a necessary condition for sensor communication.
* It must be turned on to properly access the sensor and screen
* It is also responsible for the power supply of PCF8563
*/
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
PMU->enablePowerOutput(XPOWERS_ALDO2);
// 6-axis , magnetometer ,bme280 , oled screen power channel
// 6-axis , magnetometer ,bme280 , oled screen power channel
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
PMU->enablePowerOutput(XPOWERS_ALDO1);
// sdcard power channle
// sdcard power channle
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
PMU->enablePowerOutput(XPOWERS_BLDO1);
// PMU->setPowerChannelVoltage(XPOWERS_DCDC4, 3300);
// PMU->enablePowerOutput(XPOWERS_DCDC4);
//not use channel
PMU->disablePowerOutput(XPOWERS_DCDC2); //not elicited
PMU->disablePowerOutput(XPOWERS_DCDC5); //not elicited
PMU->disablePowerOutput(XPOWERS_DLDO1); //Invalid power channel, it does not exist
PMU->disablePowerOutput(XPOWERS_DLDO2); //Invalid power channel, it does not exist
// not use channel
PMU->disablePowerOutput(XPOWERS_DCDC2); // not elicited
PMU->disablePowerOutput(XPOWERS_DCDC5); // not elicited
PMU->disablePowerOutput(XPOWERS_DLDO1); // Invalid power channel, it does not exist
PMU->disablePowerOutput(XPOWERS_DLDO2); // Invalid power channel, it does not exist
PMU->disablePowerOutput(XPOWERS_VBACKUP);
//disable all axp chip interrupt
// disable all axp chip interrupt
PMU->disableIRQ(XPOWERS_AXP2101_ALL_IRQ);
//Set the constant current charging current of AXP2101, temporarily use 500mA by default
// Set the constant current charging current of AXP2101, temporarily use 500mA by default
PMU->setChargerConstantCurr(XPOWERS_AXP2101_CHG_CUR_500MA);
//Set up the charging voltage
// Set up the charging voltage
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V2);
}
PMU->clearIrqStatus();
// TBeam1.1 /T-Beam S3-Core has no external TS detection,
// TBeam1.1 /T-Beam S3-Core has no external TS detection,
// it needs to be disabled, otherwise it will cause abnormal charging
PMU->disableTSPinMeasure();
@ -550,40 +556,52 @@ bool Power::axpChipInit()
LOG_DEBUG("=======================================================================\n");
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
LOG_DEBUG("DC1 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
LOG_DEBUG("DC1 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
}
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
LOG_DEBUG("DC2 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
LOG_DEBUG("DC2 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
}
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
LOG_DEBUG("DC3 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
LOG_DEBUG("DC3 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
}
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
LOG_DEBUG("DC4 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
LOG_DEBUG("DC4 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
}
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
LOG_DEBUG("LDO2 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
LOG_DEBUG("LDO2 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_LDO2));
}
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
LOG_DEBUG("LDO3 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
LOG_DEBUG("LDO3 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_LDO3));
}
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
LOG_DEBUG("ALDO1: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
LOG_DEBUG("ALDO1: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
}
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
LOG_DEBUG("ALDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
LOG_DEBUG("ALDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
}
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
LOG_DEBUG("ALDO3: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
LOG_DEBUG("ALDO3: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
}
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
LOG_DEBUG("ALDO4: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
LOG_DEBUG("ALDO4: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
}
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
LOG_DEBUG("BLDO1: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
LOG_DEBUG("BLDO1: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
}
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
LOG_DEBUG("BLDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
LOG_DEBUG("BLDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
}
LOG_DEBUG("=======================================================================\n");
@ -597,30 +615,29 @@ bool Power::axpChipInit()
PMU->setSysPowerDownVoltage(2600);
#endif
#ifdef PMU_IRQ
uint64_t pmuIrqMask = 0;
uint64_t pmuIrqMask = 0;
if (PMU->getChipModel() == XPOWERS_AXP192) {
pmuIrqMask = XPOWERS_AXP192_VBUS_INSERT_IRQ | XPOWERS_AXP192_BAT_INSERT_IRQ | XPOWERS_AXP192_PKEY_SHORT_IRQ;
} else if (PMU->getChipModel() == XPOWERS_AXP2101) {
pmuIrqMask = XPOWERS_AXP2101_VBUS_INSERT_IRQ | XPOWERS_AXP2101_BAT_INSERT_IRQ | XPOWERS_AXP2101_PKEY_SHORT_IRQ;
}
if (PMU->getChipModel() == XPOWERS_AXP192) {
pmuIrqMask = XPOWERS_AXP192_VBUS_INSERT_IRQ | XPOWERS_AXP192_BAT_INSERT_IRQ | XPOWERS_AXP192_PKEY_SHORT_IRQ;
} else if (PMU->getChipModel() == XPOWERS_AXP2101) {
pmuIrqMask = XPOWERS_AXP2101_VBUS_INSERT_IRQ | XPOWERS_AXP2101_BAT_INSERT_IRQ | XPOWERS_AXP2101_PKEY_SHORT_IRQ;
}
pinMode(PMU_IRQ, INPUT);
attachInterrupt(
PMU_IRQ, [] { pmu_irq = true; }, FALLING);
pinMode(PMU_IRQ, INPUT);
attachInterrupt(
PMU_IRQ, [] { pmu_irq = true; }, FALLING);
// we do not look for AXPXXX_CHARGING_FINISHED_IRQ & AXPXXX_CHARGING_IRQ because it occurs repeatedly while there is
// no battery also it could cause inadvertent waking from light sleep just because the battery filled
// we don't look for AXPXXX_BATT_REMOVED_IRQ because it occurs repeatedly while no battery installed
// we don't look at AXPXXX_VBUS_REMOVED_IRQ because we don't have anything hooked to vbus
PMU->enableIRQ(pmuIrqMask);
// we do not look for AXPXXX_CHARGING_FINISHED_IRQ & AXPXXX_CHARGING_IRQ because it occurs repeatedly while there is
// no battery also it could cause inadvertent waking from light sleep just because the battery filled
// we don't look for AXPXXX_BATT_REMOVED_IRQ because it occurs repeatedly while no battery installed
// we don't look at AXPXXX_VBUS_REMOVED_IRQ because we don't have anything hooked to vbus
PMU->enableIRQ(pmuIrqMask);
PMU->clearIrqStatus();
PMU->clearIrqStatus();
#endif /*PMU_IRQ*/
readPowerStatus();
readPowerStatus();
pmu_found = true;

Wyświetl plik

@ -11,10 +11,10 @@
/// Should we behave as if we have AC power now?
static bool isPowered()
{
// Circumvent the battery sensing logic and assumes constant power if no battery pin or power mgmt IC
#if !defined(BATTERY_PIN) && !defined(HAS_AXP192) && !defined(HAS_AXP2101)
return true;
#endif
// Circumvent the battery sensing logic and assumes constant power if no battery pin or power mgmt IC
#if !defined(BATTERY_PIN) && !defined(HAS_AXP192) && !defined(HAS_AXP2101)
return true;
#endif
bool isRouter = (config.device.role == Config_DeviceConfig_Role_ROUTER ? 1 : 0);
@ -199,7 +199,8 @@ static void onEnter()
uint32_t now = millis();
if ((now - lastPingMs) > 30 * 1000) { // if more than a minute since our last press, ask node we are looking at to update their state
if ((now - lastPingMs) >
30 * 1000) { // if more than a minute since our last press, ask node we are looking at to update their state
if (displayedNodeNum)
service.sendNetworkPing(displayedNodeNum, true); // Refresh the currently displayed node
lastPingMs = now;
@ -249,7 +250,8 @@ void PowerFSM_setup()
// We need this transition, because we might not transition if we were waiting to enter light-sleep, because when we wake from
// light sleep we _always_ transition to NB or dark and
powerFSM.add_transition(&stateLS, isRouter ? &stateNB : &stateDARK, EVENT_PACKET_FOR_PHONE, NULL, "Received packet, exiting light sleep");
powerFSM.add_transition(&stateLS, isRouter ? &stateNB : &stateDARK, EVENT_PACKET_FOR_PHONE, NULL,
"Received packet, exiting light sleep");
powerFSM.add_transition(&stateNB, &stateNB, EVENT_PACKET_FOR_PHONE, NULL, "Received packet, resetting win wake");
// Handle press events - note: we ignore button presses when in API mode
@ -258,7 +260,8 @@ void PowerFSM_setup()
powerFSM.add_transition(&stateDARK, &stateON, EVENT_PRESS, NULL, "Press");
powerFSM.add_transition(&statePOWER, &statePOWER, EVENT_PRESS, screenPress, "Press");
powerFSM.add_transition(&stateON, &stateON, EVENT_PRESS, screenPress, "Press"); // reenter On to restart our timers
powerFSM.add_transition(&stateSERIAL, &stateSERIAL, EVENT_PRESS, screenPress, "Press"); // Allow button to work while in serial API
powerFSM.add_transition(&stateSERIAL, &stateSERIAL, EVENT_PRESS, screenPress,
"Press"); // Allow button to work while in serial API
// Handle critically low power battery by forcing deep sleep
powerFSM.add_transition(&stateBOOT, &stateSDS, EVENT_LOW_BATTERY, NULL, "LowBat");
@ -324,7 +327,9 @@ void PowerFSM_setup()
powerFSM.add_transition(&stateDARK, &stateDARK, EVENT_CONTACT_FROM_PHONE, NULL, "Contact from phone");
powerFSM.add_timed_transition(&stateON, &stateDARK, getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout");
powerFSM.add_timed_transition(&stateON, &stateDARK,
getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL,
"Screen-on timeout");
#ifdef ARCH_ESP32
State *lowPowerState = &stateLS;
@ -332,14 +337,18 @@ void PowerFSM_setup()
// See: https://github.com/meshtastic/firmware/issues/1071
if (isRouter || config.power.is_power_saving) {
powerFSM.add_timed_transition(&stateNB, &stateLS, getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, "Min wake timeout");
powerFSM.add_timed_transition(&stateDARK, &stateLS, getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), NULL, "Bluetooth timeout");
powerFSM.add_timed_transition(&stateNB, &stateLS,
getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL,
"Min wake timeout");
powerFSM.add_timed_transition(&stateDARK, &stateLS,
getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs),
NULL, "Bluetooth timeout");
}
if (config.power.sds_secs != UINT32_MAX)
powerFSM.add_timed_transition(lowPowerState, &stateSDS, getConfiguredOrDefaultMs(config.power.sds_secs), NULL, "mesh timeout");
powerFSM.add_timed_transition(lowPowerState, &stateSDS, getConfiguredOrDefaultMs(config.power.sds_secs), NULL,
"mesh timeout");
#endif
powerFSM.run_machine(); // run one interation of the state machine, so we run our on enter tasks for the initial DARK state
}

Wyświetl plik

@ -19,8 +19,8 @@
#define EVENT_POWER_CONNECTED 13
#define EVENT_POWER_DISCONNECTED 14
#define EVENT_FIRMWARE_UPDATE 15 // We just received a new firmware update packet from the phone
#define EVENT_SHUTDOWN 16 //force a full shutdown now (not just sleep)
#define EVENT_INPUT 17 // input broker wants something, we need to wake up and enable screen
#define EVENT_SHUTDOWN 16 // force a full shutdown now (not just sleep)
#define EVENT_INPUT 17 // input broker wants something, we need to wake up and enable screen
extern Fsm powerFSM;
extern State statePOWER, stateSERIAL;

Wyświetl plik

@ -26,9 +26,10 @@ class PowerFSMThread : public OSThread
if (powerStatus->getHasUSB()) {
timeLastPowered = millis();
} else if (config.power.on_battery_shutdown_after_secs > 0 &&
config.power.on_battery_shutdown_after_secs != UINT32_MAX &&
millis() > (timeLastPowered + getConfiguredOrDefaultMs(config.power.on_battery_shutdown_after_secs))) { // shutdown after 30 minutes unpowered
} else if (config.power.on_battery_shutdown_after_secs > 0 && config.power.on_battery_shutdown_after_secs != UINT32_MAX &&
millis() > (timeLastPowered +
getConfiguredOrDefaultMs(
config.power.on_battery_shutdown_after_secs))) { // shutdown after 30 minutes unpowered
powerFSM.trigger(EVENT_SHUTDOWN);
}

Wyświetl plik

@ -1,12 +1,12 @@
#include "configuration.h"
#include "RedirectablePrint.h"
#include "RTC.h"
#include "NodeDB.h"
#include "RTC.h"
#include "concurrency/OSThread.h"
#include "configuration.h"
#include <assert.h>
#include <cstring>
#include <sys/time.h>
#include <time.h>
#include <cstring>
/**
* A printer that doesn't go anywhere
@ -42,7 +42,8 @@ size_t RedirectablePrint::vprintf(const char *format, va_list arg)
size_t len = vsnprintf(printBuf, sizeof(printBuf), format, copy);
va_end(copy);
// If the resulting string is longer than sizeof(printBuf)-1 characters, the remaining characters are still counted for the return value
// If the resulting string is longer than sizeof(printBuf)-1 characters, the remaining characters are still counted for the
// return value
if (len > sizeof(printBuf) - 1) {
len = sizeof(printBuf) - 1;
@ -104,30 +105,34 @@ size_t RedirectablePrint::log(const char *logLevel, const char *format, ...)
return r;
}
void RedirectablePrint::hexDump(const char *logLevel, unsigned char *buf, uint16_t len) {
const char alphabet[17] = "0123456789abcdef";
log(logLevel, " +------------------------------------------------+ +----------------+\n");
log(logLevel, " |.0 .1 .2 .3 .4 .5 .6 .7 .8 .9 .a .b .c .d .e .f | | ASCII |\n");
for (uint16_t i = 0; i < len; i += 16) {
if (i % 128 == 0)
log(logLevel, " +------------------------------------------------+ +----------------+\n");
char s[] = "| | | |\n";
uint8_t ix = 1, iy = 52;
for (uint8_t j = 0; j < 16; j++) {
if (i + j < len) {
uint8_t c = buf[i + j];
s[ix++] = alphabet[(c >> 4) & 0x0F];
s[ix++] = alphabet[c & 0x0F];
ix++;
if (c > 31 && c < 128) s[iy++] = c;
else s[iy++] = '.';
}
void RedirectablePrint::hexDump(const char *logLevel, unsigned char *buf, uint16_t len)
{
const char alphabet[17] = "0123456789abcdef";
log(logLevel, " +------------------------------------------------+ +----------------+\n");
log(logLevel, " |.0 .1 .2 .3 .4 .5 .6 .7 .8 .9 .a .b .c .d .e .f | | ASCII |\n");
for (uint16_t i = 0; i < len; i += 16) {
if (i % 128 == 0)
log(logLevel, " +------------------------------------------------+ +----------------+\n");
char s[] = "| | | |\n";
uint8_t ix = 1, iy = 52;
for (uint8_t j = 0; j < 16; j++) {
if (i + j < len) {
uint8_t c = buf[i + j];
s[ix++] = alphabet[(c >> 4) & 0x0F];
s[ix++] = alphabet[c & 0x0F];
ix++;
if (c > 31 && c < 128)
s[iy++] = c;
else
s[iy++] = '.';
}
}
uint8_t index = i / 16;
if (i < 256)
log(logLevel, " ");
log(logLevel, "%02x", index);
log(logLevel, ".");
log(logLevel, s);
}
uint8_t index = i / 16;
if (i < 256) log(logLevel, " ");
log(logLevel, "%02x",index);
log(logLevel, ".");
log(logLevel, s);
}
log(logLevel, " +------------------------------------------------+ +----------------+\n");
log(logLevel, " +------------------------------------------------+ +----------------+\n");
}

Wyświetl plik

@ -29,12 +29,12 @@ class RedirectablePrint : public Print
/**
* Debug logging print message
*
*
* If the provide format string ends with a newline we assume it is the final print of a single
* log message. Otherwise we assume more prints will come before the log message ends. This
* allows you to call logDebug a few times to build up a single log message line if you wish.
*/
size_t log(const char *logLevel, const char *format, ...) __attribute__ ((format (printf, 3, 4)));
size_t log(const char *logLevel, const char *format, ...) __attribute__((format(printf, 3, 4)));
/** like printf but va_list based */
size_t vprintf(const char *format, va_list arg);

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "SPILock.h"
#include "configuration.h"
#include <Arduino.h>
#include <assert.h>

Wyświetl plik

@ -49,7 +49,8 @@ int32_t SerialConsole::runOnce()
return runOncePart();
}
void SerialConsole::flush() {
void SerialConsole::flush()
{
Port.flush();
}
@ -74,7 +75,7 @@ bool SerialConsole::handleToRadio(const uint8_t *buf, size_t len)
canWrite = true;
return StreamAPI::handleToRadio(buf, len);
}else{
} else {
return false;
}
}

Wyświetl plik

@ -29,7 +29,6 @@ class SerialConsole : public StreamAPI, public RedirectablePrint, private concur
void flush();
protected:
/// Check the current underlying physical link to see if the client is currently connected
virtual bool checkIsConnected() override;
};

Wyświetl plik

@ -8,65 +8,49 @@
#define STATUS_TYPE_GPS 2
#define STATUS_TYPE_NODE 3
namespace meshtastic
{
// A base class for observable status
class Status
// A base class for observable status
class Status
{
protected:
// Allows us to observe an Observable
CallbackObserver<Status, const Status *> statusObserver =
CallbackObserver<Status, const Status *>(this, &Status::updateStatus);
bool initialized = false;
// Workaround for no typeid support
int statusType = 0;
public:
// Allows us to generate observable events
Observable<const Status *> onNewStatus;
// Enable polymorphism ?
virtual ~Status() = default;
Status()
{
protected:
// Allows us to observe an Observable
CallbackObserver<Status, const Status *> statusObserver = CallbackObserver<Status, const Status *>(this, &Status::updateStatus);
bool initialized = false;
// Workaround for no typeid support
int statusType = 0;
public:
// Allows us to generate observable events
Observable<const Status *> onNewStatus;
// Enable polymorphism ?
virtual ~Status() = default;
Status() {
if (!statusType)
{
statusType = STATUS_TYPE_BASE;
}
if (!statusType) {
statusType = STATUS_TYPE_BASE;
}
}
// Prevent object copy/move
Status(const Status &) = delete;
Status &operator=(const Status &) = delete;
// Prevent object copy/move
Status(const Status &) = delete;
Status &operator=(const Status &) = delete;
// Start observing a source of data
void observe(Observable<const Status *> *source)
{
statusObserver.observe(source);
}
// Start observing a source of data
void observe(Observable<const Status *> *source) { statusObserver.observe(source); }
// Determines whether or not existing data matches the data in another Status instance
bool matches(const Status *otherStatus) const
{
return true;
}
// Determines whether or not existing data matches the data in another Status instance
bool matches(const Status *otherStatus) const { return true; }
bool isInitialized() const
{
return initialized;
}
bool isInitialized() const { return initialized; }
int getStatusType() const
{
return statusType;
}
int getStatusType() const { return statusType; }
// Called when the Observable we're observing generates a new notification
int updateStatus(const Status *newStatus)
{
return 0;
}
};
// Called when the Observable we're observing generates a new notification
int updateStatus(const Status *newStatus) { return 0; }
};
}; // namespace meshtastic

Wyświetl plik

@ -34,11 +34,13 @@ uint8_t AirTime::currentPeriodIndex()
return ((getSecondsSinceBoot() / SECONDS_PER_PERIOD) % PERIODS_TO_LOG);
}
uint8_t AirTime::getPeriodUtilMinute() {
uint8_t AirTime::getPeriodUtilMinute()
{
return (getSecondsSinceBoot() / 10) % CHANNEL_UTILIZATION_PERIODS;
}
uint8_t AirTime::getPeriodUtilHour() {
uint8_t AirTime::getPeriodUtilHour()
{
return (getSecondsSinceBoot() / 60) % MINUTES_IN_HOUR;
}
@ -119,23 +121,23 @@ float AirTime::utilizationTXPercent()
bool AirTime::isTxAllowedChannelUtil(bool polite)
{
uint8_t percentage = (polite ? polite_channel_util_percent : max_channel_util_percent);
uint8_t percentage = (polite ? polite_channel_util_percent : max_channel_util_percent);
if (channelUtilizationPercent() < percentage) {
return true;
return true;
} else {
LOG_WARN("Channel utilization is >%d percent. Skipping this opportunity to send.\n", percentage);
return false;
}
}
bool AirTime::isTxAllowedAirUtil()
bool AirTime::isTxAllowedAirUtil()
{
if (!config.lora.override_duty_cycle && myRegion->dutyCycle < 100) {
if (utilizationTXPercent() < myRegion->dutyCycle * polite_duty_cycle_percent / 100) {
return true;
return true;
} else {
LOG_WARN("Tx air utilization is >%f percent. Skipping this opportunity to send.\n", myRegion->dutyCycle * polite_duty_cycle_percent / 100);
LOG_WARN("Tx air utilization is >%f percent. Skipping this opportunity to send.\n",
myRegion->dutyCycle * polite_duty_cycle_percent / 100);
return false;
}
}
@ -143,21 +145,19 @@ bool AirTime::isTxAllowedAirUtil()
}
// Get the amount of minutes we have to be silent before we can send again
uint8_t AirTime::getSilentMinutes(float txPercent, float dutyCycle)
{
float newTxPercent = txPercent;
for (int8_t i = MINUTES_IN_HOUR-1; i >= 0; --i) {
newTxPercent -= ((float)this->utilizationTX[i] / (MS_IN_MINUTE * MINUTES_IN_HOUR / 100));
if (newTxPercent < dutyCycle)
return MINUTES_IN_HOUR-1-i;
}
uint8_t AirTime::getSilentMinutes(float txPercent, float dutyCycle)
{
float newTxPercent = txPercent;
for (int8_t i = MINUTES_IN_HOUR - 1; i >= 0; --i) {
newTxPercent -= ((float)this->utilizationTX[i] / (MS_IN_MINUTE * MINUTES_IN_HOUR / 100));
if (newTxPercent < dutyCycle)
return MINUTES_IN_HOUR - 1 - i;
}
return MINUTES_IN_HOUR;
return MINUTES_IN_HOUR;
}
AirTime::AirTime() : concurrency::OSThread("AirTime"),airtimes({}) {
}
AirTime::AirTime() : concurrency::OSThread("AirTime"), airtimes({}) {}
int32_t AirTime::runOnce()
{
@ -213,14 +213,14 @@ int32_t AirTime::runOnce()
// Update channel_utilization every second.
myNodeInfo.air_util_tx = airTime->utilizationTXPercent();
}
/*
LOG_DEBUG("utilPeriodTX %d TX Airtime %3.2f%\n", utilPeriodTX, airTime->utilizationTXPercent());
for (uint32_t i = 0; i < MINUTES_IN_HOUR; i++) {
LOG_DEBUG(
"%d,", this->utilizationTX[i]
);
}
LOG_DEBUG("\n");
*/
/*
LOG_DEBUG("utilPeriodTX %d TX Airtime %3.2f%\n", utilPeriodTX, airTime->utilizationTXPercent());
for (uint32_t i = 0; i < MINUTES_IN_HOUR; i++) {
LOG_DEBUG(
"%d,", this->utilizationTX[i]
);
}
LOG_DEBUG("\n");
*/
return (1000 * 1);
}

Wyświetl plik

@ -1,10 +1,10 @@
#pragma once
#include "MeshRadio.h"
#include "concurrency/OSThread.h"
#include "configuration.h"
#include <Arduino.h>
#include <functional>
#include "MeshRadio.h"
/*
TX_LOG - Time on air this device has transmitted
@ -33,7 +33,6 @@
#define MS_IN_MINUTE (SECONDS_IN_MINUTE * 1000)
#define MS_IN_HOUR (MINUTES_IN_HOUR * SECONDS_IN_MINUTE * 1000)
enum reportTypes { TX_LOG, RX_LOG, RX_ALL_LOG };
void logAirtime(reportTypes reportType, uint32_t airtime_ms);
@ -60,7 +59,7 @@ class AirTime : private concurrency::OSThread
uint32_t getSecondsSinceBoot();
uint32_t *airtimeReport(reportTypes reportType);
uint8_t getSilentMinutes(float txPercent, float dutyCycle);
bool isTxAllowedChannelUtil(bool polite=false);
bool isTxAllowedChannelUtil(bool polite = false);
bool isTxAllowedAirUtil();
private:
@ -70,7 +69,7 @@ class AirTime : private concurrency::OSThread
uint32_t secSinceBoot = 0;
uint8_t max_channel_util_percent = 40;
uint8_t polite_channel_util_percent = 25;
uint8_t polite_duty_cycle_percent = 50; // half of Duty Cycle allowance is ok for metadata
uint8_t polite_duty_cycle_percent = 50; // half of Duty Cycle allowance is ok for metadata
struct airtimeStruct {
uint32_t periodTX[PERIODS_TO_LOG]; // AirTime transmitted

Wyświetl plik

@ -1,6 +1,6 @@
#include "buzz.h"
#include "configuration.h"
#include "NodeDB.h"
#include "configuration.h"
#if !defined(ARCH_ESP32) && !defined(ARCH_RP2040) && !defined(ARCH_PORTDUINO)
#include "Tone.h"
@ -11,8 +11,8 @@ extern "C" void delay(uint32_t dwMs);
#endif
struct ToneDuration {
int frequency_khz;
int duration_ms;
int frequency_khz;
int duration_ms;
};
// Some common frequencies.
@ -30,40 +30,39 @@ struct ToneDuration {
#define NOTE_B3 247
#define NOTE_CS4 277
const int DURATION_1_8 = 125; // 1/8 note
const int DURATION_1_4 = 250; // 1/4 note
const int DURATION_1_8 = 125; // 1/8 note
const int DURATION_1_4 = 250; // 1/4 note
void playTones(const ToneDuration *tone_durations, int size) {
void playTones(const ToneDuration *tone_durations, int size)
{
#ifdef PIN_BUZZER
if (!config.device.buzzer_gpio)
config.device.buzzer_gpio = PIN_BUZZER;
if (!config.device.buzzer_gpio)
config.device.buzzer_gpio = PIN_BUZZER;
#endif
if (config.device.buzzer_gpio) {
for (int i = 0; i < size; i++) {
const auto &tone_duration = tone_durations[i];
tone(config.device.buzzer_gpio, tone_duration.frequency_khz, tone_duration.duration_ms);
// to distinguish the notes, set a minimum time between them.
delay(1.3 * tone_duration.duration_ms);
if (config.device.buzzer_gpio) {
for (int i = 0; i < size; i++) {
const auto &tone_duration = tone_durations[i];
tone(config.device.buzzer_gpio, tone_duration.frequency_khz, tone_duration.duration_ms);
// to distinguish the notes, set a minimum time between them.
delay(1.3 * tone_duration.duration_ms);
}
}
}
}
void playBeep() {
ToneDuration melody[] = {{NOTE_B3, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
void playBeep()
{
ToneDuration melody[] = {{NOTE_B3, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
}
void playStartMelody() {
ToneDuration melody[] = {{NOTE_FS3, DURATION_1_8},
{NOTE_AS3, DURATION_1_8},
{NOTE_CS4, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
void playStartMelody()
{
ToneDuration melody[] = {{NOTE_FS3, DURATION_1_8}, {NOTE_AS3, DURATION_1_8}, {NOTE_CS4, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
}
void playShutdownMelody() {
ToneDuration melody[] = {{NOTE_CS4, DURATION_1_8},
{NOTE_AS3, DURATION_1_8},
{NOTE_FS3, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
void playShutdownMelody()
{
ToneDuration melody[] = {{NOTE_CS4, DURATION_1_8}, {NOTE_AS3, DURATION_1_8}, {NOTE_FS3, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
}

Wyświetl plik

@ -4,15 +4,15 @@
*/
enum class Cmd {
INVALID,
SET_ON,
SET_OFF,
ON_PRESS,
START_BLUETOOTH_PIN_SCREEN,
START_FIRMWARE_UPDATE_SCREEN,
STOP_BLUETOOTH_PIN_SCREEN,
STOP_BOOT_SCREEN,
PRINT,
START_SHUTDOWN_SCREEN,
START_REBOOT_SCREEN,
INVALID,
SET_ON,
SET_OFF,
ON_PRESS,
START_BLUETOOTH_PIN_SCREEN,
START_FIRMWARE_UPDATE_SCREEN,
STOP_BLUETOOTH_PIN_SCREEN,
STOP_BOOT_SCREEN,
PRINT,
START_SHUTDOWN_SCREEN,
START_REBOOT_SCREEN,
};

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "concurrency/BinarySemaphoreFreeRTOS.h"
#include "configuration.h"
#include <assert.h>
#ifdef HAS_FREE_RTOS

Wyświetl plik

@ -1,18 +1,14 @@
#include "configuration.h"
#include "concurrency/BinarySemaphorePosix.h"
#include "configuration.h"
#ifndef HAS_FREE_RTOS
namespace concurrency
{
BinarySemaphorePosix::BinarySemaphorePosix()
{
}
BinarySemaphorePosix::BinarySemaphorePosix() {}
BinarySemaphorePosix::~BinarySemaphorePosix()
{
}
BinarySemaphorePosix::~BinarySemaphorePosix() {}
/**
* Returns false if we timed out
@ -23,13 +19,9 @@ bool BinarySemaphorePosix::take(uint32_t msec)
return false;
}
void BinarySemaphorePosix::give()
{
}
void BinarySemaphorePosix::give() {}
IRAM_ATTR void BinarySemaphorePosix::giveFromISR(BaseType_t *pxHigherPriorityTaskWoken)
{
}
IRAM_ATTR void BinarySemaphorePosix::giveFromISR(BaseType_t *pxHigherPriorityTaskWoken) {}
} // namespace concurrency

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "concurrency/InterruptableDelay.h"
#include "configuration.h"
namespace concurrency
{

Wyświetl plik

@ -2,7 +2,6 @@
#include "../freertosinc.h"
#ifdef HAS_FREE_RTOS
#include "concurrency/BinarySemaphoreFreeRTOS.h"
#define BinarySemaphore BinarySemaphoreFreeRTOS

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "Lock.h"
#include "configuration.h"
#include <cassert>
namespace concurrency

Wyświetl plik

@ -1,7 +1,8 @@
#include "configuration.h"
#include "LockGuard.h"
#include "configuration.h"
namespace concurrency {
namespace concurrency
{
LockGuard::LockGuard(Lock *lock) : lock(lock)
{

Wyświetl plik

@ -2,7 +2,8 @@
#include "Lock.h"
namespace concurrency {
namespace concurrency
{
/**
* @brief RAII lock guard

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "NotifiedWorkerThread.h"
#include "configuration.h"
#include "main.h"
namespace concurrency
@ -80,11 +80,9 @@ void NotifiedWorkerThread::checkNotification()
}
}
int32_t NotifiedWorkerThread::runOnce()
{
enabled = false; // Only run once per notification
enabled = false; // Only run once per notification
checkNotification();
return RUN_SAME;

Wyświetl plik

@ -41,9 +41,9 @@ class NotifiedWorkerThread : public OSThread
/// just calls checkNotification()
virtual int32_t runOnce() override;
/// Sometimes we might want to check notifications independently of when our thread was getting woken up (i.e. if we are about to change
/// radio transmit/receive modes we want to handle any pending interrupts first). You can call this method and if any notifications are currently
/// pending they will be handled immediately.
/// Sometimes we might want to check notifications independently of when our thread was getting woken up (i.e. if we are about
/// to change radio transmit/receive modes we want to handle any pending interrupts first). You can call this method and if
/// any notifications are currently pending they will be handled immediately.
void checkNotification();
private:

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "OSThread.h"
#include "configuration.h"
#include <assert.h>
namespace concurrency
@ -76,7 +76,7 @@ void OSThread::run()
{
#ifdef DEBUG_HEAP
auto heap = ESP.getFreeHeap();
#endif
#endif
currentThread = this;
auto newDelay = runOnce();
#ifdef DEBUG_HEAP
@ -95,11 +95,11 @@ void OSThread::run()
currentThread = NULL;
}
int32_t OSThread::disable()
int32_t OSThread::disable()
{
enabled = false;
setInterval(INT32_MAX);
return INT32_MAX;
}

Wyświetl plik

@ -27,10 +27,10 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#include <Arduino.h>
#ifdef RV3028_RTC
#include "Melopero_RV3028.h"
#include "Melopero_RV3028.h"
#endif
#ifdef PCF8563_RTC
#include "pcf8563.h"
#include "pcf8563.h"
#endif
// -----------------------------------------------------------------------------
@ -42,7 +42,8 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#error APP_VERSION must be set by the build environment
#endif
// FIXME: This is still needed by the Bluetooth Stack and needs to be replaced by something better. Remnant of the old versioning system.
// FIXME: This is still needed by the Bluetooth Stack and needs to be replaced by something better. Remnant of the old versioning
// system.
#ifndef HW_VERSION
#define HW_VERSION "1.0"
#endif
@ -64,13 +65,13 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// Nop definition for these attributes that are specific to ESP32
#ifndef EXT_RAM_ATTR
#define EXT_RAM_ATTR
#define EXT_RAM_ATTR
#endif
#ifndef IRAM_ATTR
#define IRAM_ATTR
#define IRAM_ATTR
#endif
#ifndef RTC_DATA_ATTR
#define RTC_DATA_ATTR
#define RTC_DATA_ATTR
#endif
// -----------------------------------------------------------------------------
@ -80,7 +81,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// Disable use of the NTP library and related features
// #define DISABLE_NTP
// Disable the welcome screen and allow
// Disable the welcome screen and allow
//#define DISABLE_WELCOME_UNSET
// -----------------------------------------------------------------------------
@ -135,49 +136,49 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
/* Step #1: offer chance for variant-specific defines */
#include "variant.h"
/* Step #2: follow with defines common to the architecture;
/* Step #2: follow with defines common to the architecture;
also enable HAS_ option not specifically disabled by variant.h */
#include "architecture.h"
/* Step #3: mop up with disabled values for HAS_ options not handled by the above two */
#ifndef HAS_WIFI
#define HAS_WIFI 0
#define HAS_WIFI 0
#endif
#ifndef HAS_ETHERNET
#define HAS_ETHERNET 0
#define HAS_ETHERNET 0
#endif
#ifndef HAS_SCREEN
#define HAS_SCREEN 0
#define HAS_SCREEN 0
#endif
#ifndef HAS_WIRE
#define HAS_WIRE 0
#define HAS_WIRE 0
#endif
#ifndef HAS_GPS
#define HAS_GPS 0
#define HAS_GPS 0
#endif
#ifndef HAS_BUTTON
#define HAS_BUTTON 0
#define HAS_BUTTON 0
#endif
#ifndef HAS_TELEMETRY
#define HAS_TELEMETRY 0
#define HAS_TELEMETRY 0
#endif
#ifndef HAS_RADIO
#define HAS_RADIO 0
#define HAS_RADIO 0
#endif
#ifndef HAS_RTC
#define HAS_RTC 0
#define HAS_RTC 0
#endif
#ifndef HAS_CPU_SHUTDOWN
#define HAS_CPU_SHUTDOWN 0
#define HAS_CPU_SHUTDOWN 0
#endif
#ifndef HAS_BLUETOOTH
#define HAS_BLUETOOTH 0
#define HAS_BLUETOOTH 0
#endif
#include "RF95Configuration.h"
#include "DebugConfiguration.h"
#include "RF95Configuration.h"
#ifndef HW_VENDOR
#error HW_VENDOR must be defined
#error HW_VENDOR must be defined
#endif

Wyświetl plik

@ -6,42 +6,49 @@
void d_writeCommand(uint8_t c)
{
SPI1.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0));
if (PIN_EINK_DC >= 0) digitalWrite(PIN_EINK_DC, LOW);
if (PIN_EINK_CS >= 0) digitalWrite(PIN_EINK_CS, LOW);
SPI1.transfer(c);
if (PIN_EINK_CS >= 0) digitalWrite(PIN_EINK_CS, HIGH);
if (PIN_EINK_DC >= 0) digitalWrite(PIN_EINK_DC, HIGH);
SPI1.endTransaction();
SPI1.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0));
if (PIN_EINK_DC >= 0)
digitalWrite(PIN_EINK_DC, LOW);
if (PIN_EINK_CS >= 0)
digitalWrite(PIN_EINK_CS, LOW);
SPI1.transfer(c);
if (PIN_EINK_CS >= 0)
digitalWrite(PIN_EINK_CS, HIGH);
if (PIN_EINK_DC >= 0)
digitalWrite(PIN_EINK_DC, HIGH);
SPI1.endTransaction();
}
void d_writeData(uint8_t d)
{
SPI1.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0));
if (PIN_EINK_CS >= 0) digitalWrite(PIN_EINK_CS, LOW);
SPI1.transfer(d);
if (PIN_EINK_CS >= 0) digitalWrite(PIN_EINK_CS, HIGH);
SPI1.endTransaction();
SPI1.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0));
if (PIN_EINK_CS >= 0)
digitalWrite(PIN_EINK_CS, LOW);
SPI1.transfer(d);
if (PIN_EINK_CS >= 0)
digitalWrite(PIN_EINK_CS, HIGH);
SPI1.endTransaction();
}
unsigned long d_waitWhileBusy(uint16_t busy_time)
{
if (PIN_EINK_BUSY >= 0)
{
delay(1); // add some margin to become active
unsigned long start = micros();
while (1)
{
if (digitalRead(PIN_EINK_BUSY) != HIGH) break;
delay(1);
if (digitalRead(PIN_EINK_BUSY) != HIGH) break;
if (micros() - start > 10000000) break;
}
unsigned long elapsed = micros() - start;
(void) start;
return elapsed;
}
else return busy_time;
if (PIN_EINK_BUSY >= 0) {
delay(1); // add some margin to become active
unsigned long start = micros();
while (1) {
if (digitalRead(PIN_EINK_BUSY) != HIGH)
break;
delay(1);
if (digitalRead(PIN_EINK_BUSY) != HIGH)
break;
if (micros() - start > 10000000)
break;
}
unsigned long elapsed = micros() - start;
(void)start;
return elapsed;
} else
return busy_time;
}
void scanEInkDevice(void)
@ -51,10 +58,10 @@ void scanEInkDevice(void)
d_writeData(0x83);
d_writeCommand(0x20);
eink_found = (d_waitWhileBusy(150) > 0) ? true : false;
if(eink_found)
LOG_DEBUG("EInk display found\n");
if (eink_found)
LOG_DEBUG("EInk display found\n");
else
LOG_DEBUG("EInk display not found\n");
LOG_DEBUG("EInk display not found\n");
SPI1.end();
}
#endif

Wyświetl plik

@ -21,45 +21,45 @@ GPS *gps;
/// only init that port once.
static bool didSerialInit;
bool GPS::getACK(uint8_t c, uint8_t i) {
uint8_t b;
uint8_t ack = 0;
const uint8_t ackP[2] = {c, i};
uint8_t buf[10] = {0xB5, 0x62, 0x05, 0x01, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00};
unsigned long startTime = millis();
bool GPS::getACK(uint8_t c, uint8_t i)
{
uint8_t b;
uint8_t ack = 0;
const uint8_t ackP[2] = {c, i};
uint8_t buf[10] = {0xB5, 0x62, 0x05, 0x01, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00};
unsigned long startTime = millis();
for (int j = 2; j < 6; j++) {
buf[8] += buf[j];
buf[9] += buf[8];
}
for (int j = 2; j < 6; j++) {
buf[8] += buf[j];
buf[9] += buf[8];
}
for (int j = 0; j < 2; j++) {
buf[6 + j] = ackP[j];
buf[8] += buf[6 + j];
buf[9] += buf[8];
}
for (int j = 0; j < 2; j++) {
buf[6 + j] = ackP[j];
buf[8] += buf[6 + j];
buf[9] += buf[8];
}
while (1) {
if (ack > 9) {
return true;
while (1) {
if (ack > 9) {
return true;
}
if (millis() - startTime > 1000) {
return false;
}
if (_serial_gps->available()) {
b = _serial_gps->read();
if (b == buf[ack]) {
ack++;
} else {
ack = 0;
}
}
}
if (millis() - startTime > 1000) {
return false;
}
if (_serial_gps->available()) {
b = _serial_gps->read();
if (b == buf[ack]) {
ack++;
}
else {
ack = 0;
}
}
}
}
/**
* @brief
* @brief
* @note New method, this method can wait for the specified class and message ID, and return the payload
* @param *buffer: The message buffer, if there is a response payload message, it will be returned through the buffer parameter
* @param size: size of buffer
@ -69,22 +69,22 @@ bool GPS::getACK(uint8_t c, uint8_t i) {
*/
int GPS::getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t requestedID)
{
uint16_t ubxFrameCounter = 0;
uint32_t startTime = millis();
uint16_t needRead;
uint16_t ubxFrameCounter = 0;
uint32_t startTime = millis();
uint16_t needRead;
while (millis() - startTime < 800) {
while (_serial_gps->available()) {
int c = _serial_gps->read();
switch (ubxFrameCounter) {
case 0:
//ubxFrame 'μ'
if (c == 0xB5) {
// ubxFrame 'μ'
if (c == 0xB5) {
ubxFrameCounter++;
}
break;
case 1:
//ubxFrame 'b'
// ubxFrame 'b'
if (c == 0x62) {
ubxFrameCounter++;
} else {
@ -92,7 +92,7 @@ int GPS::getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
}
break;
case 2:
//Class
// Class
if (c == requestedClass) {
ubxFrameCounter++;
} else {
@ -100,7 +100,7 @@ int GPS::getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
}
break;
case 3:
//Message ID
// Message ID
if (c == requestedID) {
ubxFrameCounter++;
} else {
@ -108,13 +108,13 @@ int GPS::getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
}
break;
case 4:
//Payload lenght lsb
// Payload lenght lsb
needRead = c;
ubxFrameCounter++;
break;
case 5:
//Payload lenght msb
needRead |= (c << 8);
// Payload lenght msb
needRead |= (c << 8);
ubxFrameCounter++;
break;
case 6:
@ -145,41 +145,41 @@ bool GPS::setupGPS()
didSerialInit = true;
#ifdef ARCH_ESP32
// In esp32 framework, setRxBufferSize needs to be initialized before Serial
_serial_gps->setRxBufferSize(2048); // the default is 256
// In esp32 framework, setRxBufferSize needs to be initialized before Serial
_serial_gps->setRxBufferSize(2048); // the default is 256
#endif
// if the overrides are not dialled in, set them from the board definitions, if they exist
// if the overrides are not dialled in, set them from the board definitions, if they exist
#if defined(GPS_RX_PIN)
if (!config.position.rx_gpio)
config.position.rx_gpio = GPS_RX_PIN;
if (!config.position.rx_gpio)
config.position.rx_gpio = GPS_RX_PIN;
#endif
#if defined(GPS_TX_PIN)
if (!config.position.tx_gpio)
config.position.tx_gpio = GPS_TX_PIN;
if (!config.position.tx_gpio)
config.position.tx_gpio = GPS_TX_PIN;
#endif
// ESP32 has a special set of parameters vs other arduino ports
#if defined(ARCH_ESP32)
if(config.position.rx_gpio)
if (config.position.rx_gpio)
_serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, config.position.rx_gpio, config.position.tx_gpio);
#else
_serial_gps->begin(GPS_BAUDRATE);
#endif
/*
* T-Beam-S3-Core will be preset to use gps Probe here, and other boards will not be changed first
*/
gnssModel = probe();
* T-Beam-S3-Core will be preset to use gps Probe here, and other boards will not be changed first
*/
gnssModel = probe();
if(gnssModel == GNSS_MODEL_MTK){
if (gnssModel == GNSS_MODEL_MTK) {
/*
* t-beam-s3-core uses the same L76K GNSS module as t-echo.
* Unlike t-echo, L76K uses 9600 baud rate for communication by default.
* */
// _serial_gps->begin(9600); //The baud rate of 9600 has been initialized at the beginning of setupGPS, this line is the redundant part
// delay(250);
* t-beam-s3-core uses the same L76K GNSS module as t-echo.
* Unlike t-echo, L76K uses 9600 baud rate for communication by default.
* */
// _serial_gps->begin(9600); //The baud rate of 9600 has been initialized at the beginning of setupGPS, this line
// is the redundant part delay(250);
// Initialize the L76K Chip, use GPS + GLONASS
_serial_gps->write("$PCAS04,5*1C\r\n");
@ -191,10 +191,10 @@ if (!config.position.tx_gpio)
_serial_gps->write("$PCAS11,3*1E\r\n");
delay(250);
}else if(gnssModel == GNSS_MODEL_UBLOX){
} else if (gnssModel == GNSS_MODEL_UBLOX) {
/*
tips: NMEA Only should not be set here, otherwise initializing Ublox gnss module again after
tips: NMEA Only should not be set here, otherwise initializing Ublox gnss module again after
setting will not output command messages in UART1, resulting in unrecognized module information
// Set the UART port to output NMEA only
@ -204,13 +204,14 @@ if (!config.position.tx_gpio)
if (!getACK(0x06, 0x00)) {
LOG_WARN("Unable to enable NMEA Mode.\n");
return true;
}
}
*/
// ublox-M10S can be compatible with UBLOX traditional protocol, so the following sentence settings are also valid
// ublox-M10S can be compatible with UBLOX traditional protocol, so the following sentence settings are also valid
// disable GGL
byte _message_GGL[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x01, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x05, 0x3A};
byte _message_GGL[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x01,
0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x05, 0x3A};
_serial_gps->write(_message_GGL, sizeof(_message_GGL));
if (!getACK(0x06, 0x01)) {
LOG_WARN("Unable to disable NMEA GGL.\n");
@ -218,7 +219,8 @@ if (!config.position.tx_gpio)
}
// disable GSA
byte _message_GSA[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x02, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x06, 0x41};
byte _message_GSA[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x02,
0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x06, 0x41};
_serial_gps->write(_message_GSA, sizeof(_message_GSA));
if (!getACK(0x06, 0x01)) {
LOG_WARN("Unable to disable NMEA GSA.\n");
@ -226,7 +228,8 @@ if (!config.position.tx_gpio)
}
// disable GSV
byte _message_GSV[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x03, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x07, 0x48};
byte _message_GSV[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x03,
0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x07, 0x48};
_serial_gps->write(_message_GSV, sizeof(_message_GSV));
if (!getACK(0x06, 0x01)) {
LOG_WARN("Unable to disable NMEA GSV.\n");
@ -234,7 +237,8 @@ if (!config.position.tx_gpio)
}
// disable VTG
byte _message_VTG[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x05, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x09, 0x56};
byte _message_VTG[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x05,
0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x09, 0x56};
_serial_gps->write(_message_VTG, sizeof(_message_VTG));
if (!getACK(0x06, 0x01)) {
LOG_WARN("Unable to disable NMEA VTG.\n");
@ -242,7 +246,8 @@ if (!config.position.tx_gpio)
}
// enable RMC
byte _message_RMC[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x04, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x09, 0x54};
byte _message_RMC[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x04,
0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x09, 0x54};
_serial_gps->write(_message_RMC, sizeof(_message_RMC));
if (!getACK(0x06, 0x01)) {
LOG_WARN("Unable to enable NMEA RMC.\n");
@ -250,7 +255,8 @@ if (!config.position.tx_gpio)
}
// enable GGA
byte _message_GGA[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x05, 0x38};
byte _message_GGA[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x00,
0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x05, 0x38};
_serial_gps->write(_message_GGA, sizeof(_message_GGA));
if (!getACK(0x06, 0x01)) {
LOG_WARN("Unable to enable NMEA GGA.\n");
@ -270,9 +276,9 @@ bool GPS::setup()
#endif
#ifdef HAS_PMU
if(config.position.gps_enabled){
setGPSPower(true);
}
if (config.position.gps_enabled) {
setGPSPower(true);
}
#endif
#ifdef PIN_GPS_RESET
@ -289,7 +295,7 @@ if(config.position.gps_enabled){
notifyDeepSleepObserver.observe(&notifyDeepSleep);
notifyGPSSleepObserver.observe(&notifyGPSSleep);
}
if (config.position.gps_enabled==false) {
if (config.position.gps_enabled == false) {
setAwake(false);
doGPSpowersave(false);
}
@ -401,7 +407,7 @@ uint32_t GPS::getSleepTime() const
if (t == UINT32_MAX)
return t; // already maxint
return t * 1000;
}
@ -425,9 +431,9 @@ int32_t GPS::runOnce()
// if we have received valid NMEA claim we are connected
setConnected();
} else {
if((config.position.gps_enabled == 1) && (gnssModel == GNSS_MODEL_UBLOX)){
if ((config.position.gps_enabled == 1) && (gnssModel == GNSS_MODEL_UBLOX)) {
// reset the GPS on next bootup
if(devicestate.did_gps_reset && (millis() > 60000) && !hasFlow()) {
if (devicestate.did_gps_reset && (millis() > 60000) && !hasFlow()) {
LOG_DEBUG("GPS is not communicating, trying factory reset on next bootup.\n");
devicestate.did_gps_reset = false;
nodeDB.saveDeviceStateToDisk();
@ -544,10 +550,10 @@ GnssModel_t GPS::probe()
// we use autodetect, only T-BEAM S3 for now...
uint8_t buffer[256];
/*
* The GNSS module information variable is temporarily placed inside the function body,
* if it needs to be used elsewhere, it can be moved to the outside
* */
struct uBloxGnssModelInfo info ;
* The GNSS module information variable is temporarily placed inside the function body,
* if it needs to be used elsewhere, it can be moved to the outside
* */
struct uBloxGnssModelInfo info;
memset(&info, 0, sizeof(struct uBloxGnssModelInfo));
@ -561,10 +567,10 @@ GnssModel_t GPS::probe()
while (millis() < startTimeout) {
if (_serial_gps->available()) {
String ver = _serial_gps->readStringUntil('\r');
// Get module info , If the correct header is returned,
// Get module info , If the correct header is returned,
// it can be determined that it is the MTK chip
int index = ver.indexOf("$");
if(index != -1){
if (index != -1) {
ver = ver.substring(index);
if (ver.startsWith("$GPTXT,01,01,02")) {
LOG_INFO("L76K GNSS init succeeded, using L76K GNSS Module\n");
@ -573,7 +579,6 @@ GnssModel_t GPS::probe()
}
}
}
uint8_t cfg_rate[] = {0xB5, 0x62, 0x06, 0x08, 0x00, 0x00, 0x0E, 0x30};
_serial_gps->write(cfg_rate, sizeof(cfg_rate));
@ -581,10 +586,10 @@ GnssModel_t GPS::probe()
if (!getAck(buffer, 256, 0x06, 0x08)) {
LOG_WARN("Failed to find UBlox & MTK GNSS Module\n");
return GNSS_MODEL_UNKONW;
}
}
// Get Ublox gnss module hardware and software info
uint8_t cfg_get_hw[] = {0xB5, 0x62, 0x0A, 0x04, 0x00, 0x00, 0x0E, 0x34};
uint8_t cfg_get_hw[] = {0xB5, 0x62, 0x0A, 0x04, 0x00, 0x00, 0x0E, 0x34};
_serial_gps->write(cfg_get_hw, sizeof(cfg_get_hw));
uint16_t len = getAck(buffer, 256, 0x0A, 0x04);
@ -611,27 +616,27 @@ GnssModel_t GPS::probe()
}
LOG_DEBUG("Module Info : \n");
LOG_DEBUG("Soft version: %s\n",info.swVersion);
LOG_DEBUG("Hard version: %s\n",info.hwVersion);
LOG_DEBUG("Extensions:%d\n",info.extensionNo);
LOG_DEBUG("Soft version: %s\n", info.swVersion);
LOG_DEBUG("Hard version: %s\n", info.hwVersion);
LOG_DEBUG("Extensions:%d\n", info.extensionNo);
for (int i = 0; i < info.extensionNo; i++) {
LOG_DEBUG(" %s\n",info.extension[i]);
LOG_DEBUG(" %s\n", info.extension[i]);
}
memset(buffer,0,sizeof(buffer));
memset(buffer, 0, sizeof(buffer));
//tips: extensionNo field is 0 on some 6M GNSS modules
// tips: extensionNo field is 0 on some 6M GNSS modules
for (int i = 0; i < info.extensionNo; ++i) {
if (!strncmp(info.extension[i], "OD=", 3)) {
strncpy((char *)buffer, &(info.extension[i][3]), sizeof(buffer));
LOG_DEBUG("GetModel:%s\n",(char *)buffer);
LOG_DEBUG("GetModel:%s\n", (char *)buffer);
}
}
}
if (strlen((char*)buffer)) {
LOG_INFO("UBlox GNSS init succeeded, using UBlox %s GNSS Module\n" , buffer);
}else{
if (strlen((char *)buffer)) {
LOG_INFO("UBlox GNSS init succeeded, using UBlox %s GNSS Module\n", buffer);
} else {
LOG_INFO("UBlox GNSS init succeeded, using UBlox GNSS Module\n");
}
@ -662,8 +667,7 @@ GPS *createGps()
new_gps->setup();
return new_gps;
}
}
else{
} else {
GPS *new_gps = new NMEAGPS();
new_gps->setup();
return new_gps;

Wyświetl plik

@ -4,19 +4,18 @@
#include "Observer.h"
#include "concurrency/OSThread.h"
struct uBloxGnssModelInfo {
char swVersion[30];
char hwVersion[10];
struct uBloxGnssModelInfo {
char swVersion[30];
char hwVersion[10];
uint8_t extensionNo;
char extension[10][30];
} ;
char extension[10][30];
};
typedef enum{
GNSS_MODEL_MTK,
GNSS_MODEL_UBLOX,
GNSS_MODEL_UNKONW,
}GnssModel_t;
typedef enum {
GNSS_MODEL_MTK,
GNSS_MODEL_UBLOX,
GNSS_MODEL_UNKONW,
} GnssModel_t;
// Generate a string representation of DOP
const char *getDOPString(uint32_t dop);
@ -78,7 +77,7 @@ class GPS : private concurrency::OSThread
/// Return true if we are connected to a GPS
bool isConnected() const { return hasGPS; }
bool isPowerSaving() const { return !config.position.gps_enabled;}
bool isPowerSaving() const { return !config.position.gps_enabled; }
/**
* Restart our lock attempt - try to get and broadcast a GPS reading ASAP
@ -164,7 +163,7 @@ class GPS : private concurrency::OSThread
virtual int32_t runOnce() override;
// Get GNSS model
// Get GNSS model
GnssModel_t probe();
int getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t requestedID);
@ -173,8 +172,8 @@ class GPS : private concurrency::OSThread
GnssModel_t gnssModel = GNSS_MODEL_UNKONW;
};
// Creates an instance of the GPS class.
// Creates an instance of the GPS class.
// Returns the new instance or null if the GPS is not present.
GPS* createGps();
GPS *createGps();
extern GPS *gps;

Wyświetl plik

@ -1,21 +1,25 @@
#include "GeoCoord.h"
GeoCoord::GeoCoord() {
GeoCoord::GeoCoord()
{
_dirty = true;
}
GeoCoord::GeoCoord (int32_t lat, int32_t lon, int32_t alt) : _latitude(lat), _longitude(lon), _altitude(alt) {
GeoCoord::GeoCoord(int32_t lat, int32_t lon, int32_t alt) : _latitude(lat), _longitude(lon), _altitude(alt)
{
GeoCoord::setCoords();
}
GeoCoord::GeoCoord (float lat, float lon, int32_t alt) : _altitude(alt) {
GeoCoord::GeoCoord(float lat, float lon, int32_t alt) : _altitude(alt)
{
// Change decimial reprsentation to int32_t. I.e., 12.345 becomes 123450000
_latitude = int32_t(lat * 1e+7);
_longitude = int32_t(lon * 1e+7);
GeoCoord::setCoords();
}
GeoCoord::GeoCoord(double lat, double lon, int32_t alt): _altitude(alt) {
GeoCoord::GeoCoord(double lat, double lon, int32_t alt) : _altitude(alt)
{
// Change decimial reprsentation to int32_t. I.e., 12.345 becomes 123450000
_latitude = int32_t(lat * 1e+7);
_longitude = int32_t(lon * 1e+7);
@ -23,7 +27,8 @@ GeoCoord::GeoCoord(double lat, double lon, int32_t alt): _altitude(alt) {
}
// Initialize all the coordinate systems
void GeoCoord::setCoords() {
void GeoCoord::setCoords()
{
double lat = _latitude * 1e-7;
double lon = _longitude * 1e-7;
GeoCoord::latLongToDMS(lat, lon, _dms);
@ -34,9 +39,10 @@ void GeoCoord::setCoords() {
_dirty = false;
}
void GeoCoord::updateCoords(int32_t lat, int32_t lon, int32_t alt) {
void GeoCoord::updateCoords(int32_t lat, int32_t lon, int32_t alt)
{
// If marked dirty or new coordiantes
if(_dirty || _latitude != lat || _longitude != lon || _altitude != alt) {
if (_dirty || _latitude != lat || _longitude != lon || _altitude != alt) {
_dirty = true;
_latitude = lat;
_longitude = lon;
@ -45,25 +51,26 @@ void GeoCoord::updateCoords(int32_t lat, int32_t lon, int32_t alt) {
}
}
void GeoCoord::updateCoords(const double lat, const double lon, const int32_t alt) {
void GeoCoord::updateCoords(const double lat, const double lon, const int32_t alt)
{
int32_t iLat = lat * 1e+7;
int32_t iLon = lon * 1e+7;
// If marked dirty or new coordiantes
if(_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
if (_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
_dirty = true;
_latitude = iLat;
_longitude = iLon;
_altitude = alt;
setCoords();
}
}
void GeoCoord::updateCoords(const float lat, const float lon, const int32_t alt) {
void GeoCoord::updateCoords(const float lat, const float lon, const int32_t alt)
{
int32_t iLat = lat * 1e+7;
int32_t iLon = lon * 1e+7;
// If marked dirty or new coordiantes
if(_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
if (_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
_dirty = true;
_latitude = iLat;
_longitude = iLon;
@ -73,12 +80,15 @@ void GeoCoord::updateCoords(const float lat, const float lon, const int32_t alt)
}
/**
* Converts lat long coordinates from decimal degrees to degrees minutes seconds format.
* Converts lat long coordinates from decimal degrees to degrees minutes seconds format.
* DD°MM'SS"C DDD°MM'SS"C
*/
void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms) {
if (lat < 0) dms.latCP = 'S';
else dms.latCP = 'N';
void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms)
{
if (lat < 0)
dms.latCP = 'S';
else
dms.latCP = 'N';
double latDeg = lat;
@ -90,8 +100,10 @@ void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms) {
dms.latMin = floor(latMin);
dms.latSec = (latMin - dms.latMin) * 60;
if (lon < 0) dms.lonCP = 'W';
else dms.lonCP = 'E';
if (lon < 0)
dms.lonCP = 'W';
else
dms.lonCP = 'E';
double lonDeg = lon;
@ -108,52 +120,64 @@ void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms) {
* Converts lat long coordinates to UTM.
* based on this: https://github.com/walvok/LatLonToUTM/blob/master/latlon_utm.ino
*/
void GeoCoord::latLongToUTM(const double lat, const double lon, UTM &utm) {
void GeoCoord::latLongToUTM(const double lat, const double lon, UTM &utm)
{
const std::string latBands = "CDEFGHJKLMNPQRSTUVWXX";
utm.zone = int((lon + 180)/6 + 1);
utm.band = latBands[int(lat/8 + 10)];
double a = 6378137; // WGS84 - equatorial radius
double k0 = 0.9996; // UTM point scale on the central meridian
double eccSquared = 0.00669438; // eccentricity squared
double lonTemp = (lon + 180) - int((lon + 180)/360) * 360 - 180; //Make sure the longitude is between -180.00 .. 179.9
utm.zone = int((lon + 180) / 6 + 1);
utm.band = latBands[int(lat / 8 + 10)];
double a = 6378137; // WGS84 - equatorial radius
double k0 = 0.9996; // UTM point scale on the central meridian
double eccSquared = 0.00669438; // eccentricity squared
double lonTemp = (lon + 180) - int((lon + 180) / 360) * 360 - 180; // Make sure the longitude is between -180.00 .. 179.9
double latRad = toRadians(lat);
double lonRad = toRadians(lonTemp);
// Special Zones for Norway and Svalbard
if( lat >= 56.0 && lat < 64.0 && lonTemp >= 3.0 && lonTemp < 12.0 ) // Norway
if (lat >= 56.0 && lat < 64.0 && lonTemp >= 3.0 && lonTemp < 12.0) // Norway
utm.zone = 32;
if( lat >= 72.0 && lat < 84.0 ) { // Svalbard
if ( lonTemp >= 0.0 && lonTemp < 9.0 ) utm.zone = 31;
else if( lonTemp >= 9.0 && lonTemp < 21.0 ) utm.zone = 33;
else if( lonTemp >= 21.0 && lonTemp < 33.0 ) utm.zone = 35;
else if( lonTemp >= 33.0 && lonTemp < 42.0 ) utm.zone = 37;
if (lat >= 72.0 && lat < 84.0) { // Svalbard
if (lonTemp >= 0.0 && lonTemp < 9.0)
utm.zone = 31;
else if (lonTemp >= 9.0 && lonTemp < 21.0)
utm.zone = 33;
else if (lonTemp >= 21.0 && lonTemp < 33.0)
utm.zone = 35;
else if (lonTemp >= 33.0 && lonTemp < 42.0)
utm.zone = 37;
}
double lonOrigin = (utm.zone - 1)*6 - 180 + 3; // puts origin in middle of zone
double lonOrigin = (utm.zone - 1) * 6 - 180 + 3; // puts origin in middle of zone
double lonOriginRad = toRadians(lonOrigin);
double eccPrimeSquared = (eccSquared)/(1 - eccSquared);
double N = a/sqrt(1 - eccSquared*sin(latRad)*sin(latRad));
double T = tan(latRad)*tan(latRad);
double C = eccPrimeSquared*cos(latRad)*cos(latRad);
double A = cos(latRad)*(lonRad - lonOriginRad);
double M = a*((1 - eccSquared/4 - 3*eccSquared*eccSquared/64 - 5*eccSquared*eccSquared*eccSquared/256)*latRad
- (3*eccSquared/8 + 3*eccSquared*eccSquared/32 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(2*latRad)
+ (15*eccSquared*eccSquared/256 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(4*latRad)
- (35*eccSquared*eccSquared*eccSquared/3072)*sin(6*latRad));
utm.easting = (double)(k0*N*(A+(1-T+C)*pow(A, 3)/6 + (5-18*T+T*T+72*C-58*eccPrimeSquared)*A*A*A*A*A/120)
+ 500000.0);
utm.northing = (double)(k0*(M+N*tan(latRad)*(A*A/2+(5-T+9*C+4*C*C)*A*A*A*A/24
+ (61-58*T+T*T+600*C-330*eccPrimeSquared)*A*A*A*A*A*A/720)));
if(lat < 0)
utm.northing += 10000000.0; //10000000 meter offset for southern hemisphere
double eccPrimeSquared = (eccSquared) / (1 - eccSquared);
double N = a / sqrt(1 - eccSquared * sin(latRad) * sin(latRad));
double T = tan(latRad) * tan(latRad);
double C = eccPrimeSquared * cos(latRad) * cos(latRad);
double A = cos(latRad) * (lonRad - lonOriginRad);
double M =
a * ((1 - eccSquared / 4 - 3 * eccSquared * eccSquared / 64 - 5 * eccSquared * eccSquared * eccSquared / 256) * latRad -
(3 * eccSquared / 8 + 3 * eccSquared * eccSquared / 32 + 45 * eccSquared * eccSquared * eccSquared / 1024) *
sin(2 * latRad) +
(15 * eccSquared * eccSquared / 256 + 45 * eccSquared * eccSquared * eccSquared / 1024) * sin(4 * latRad) -
(35 * eccSquared * eccSquared * eccSquared / 3072) * sin(6 * latRad));
utm.easting = (double)(k0 * N *
(A + (1 - T + C) * pow(A, 3) / 6 +
(5 - 18 * T + T * T + 72 * C - 58 * eccPrimeSquared) * A * A * A * A * A / 120) +
500000.0);
utm.northing =
(double)(k0 * (M + N * tan(latRad) *
(A * A / 2 + (5 - T + 9 * C + 4 * C * C) * A * A * A * A / 24 +
(61 - 58 * T + T * T + 600 * C - 330 * eccPrimeSquared) * A * A * A * A * A * A / 720)));
if (lat < 0)
utm.northing += 10000000.0; // 10000000 meter offset for southern hemisphere
}
// Converts lat long coordinates to an MGRS.
void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs) {
const std::string e100kLetters[3] = { "ABCDEFGH", "JKLMNPQR", "STUVWXYZ" };
const std::string n100kLetters[2] = { "ABCDEFGHJKLMNPQRSTUV", "FGHJKLMNPQRSTUVABCDE" };
void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs)
{
const std::string e100kLetters[3] = {"ABCDEFGH", "JKLMNPQR", "STUVWXYZ"};
const std::string n100kLetters[2] = {"ABCDEFGHJKLMNPQRSTUV", "FGHJKLMNPQRSTUVABCDE"};
UTM utm;
latLongToUTM(lat, lon, utm);
mgrs.zone = utm.zone;
@ -161,7 +185,7 @@ void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs) {
double col = floor(utm.easting / 100000);
mgrs.east100k = e100kLetters[(mgrs.zone - 1) % 3][col - 1];
double row = (int32_t)floor(utm.northing / 100000.0) % 20;
mgrs.north100k = n100kLetters[(mgrs.zone-1)%2][row];
mgrs.north100k = n100kLetters[(mgrs.zone - 1) % 2][row];
mgrs.easting = (int32_t)utm.easting % 100000;
mgrs.northing = (int32_t)utm.northing % 100000;
}
@ -170,52 +194,54 @@ void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs) {
* Converts lat long coordinates to Ordnance Survey Grid Reference (UK National Grid Ref).
* Based on: https://www.movable-type.co.uk/scripts/latlong-os-gridref.html
*/
void GeoCoord::latLongToOSGR(const double lat, const double lon, OSGR &osgr) {
void GeoCoord::latLongToOSGR(const double lat, const double lon, OSGR &osgr)
{
const char letter[] = "ABCDEFGHJKLMNOPQRSTUVWXYZ"; // No 'I' in OSGR
double a = 6377563.396; // Airy 1830 semi-major axis
double b = 6356256.909; // Airy 1830 semi-minor axis
double f0 = 0.9996012717; // National Grid point scale factor on the central meridian
double phi0 = toRadians(49);
double a = 6377563.396; // Airy 1830 semi-major axis
double b = 6356256.909; // Airy 1830 semi-minor axis
double f0 = 0.9996012717; // National Grid point scale factor on the central meridian
double phi0 = toRadians(49);
double lambda0 = toRadians(-2);
double n0 = -100000;
double e0 = 400000;
double e2 = 1 - (b*b)/(a*a); // eccentricity squared
double n = (a - b)/(a + b);
double e2 = 1 - (b * b) / (a * a); // eccentricity squared
double n = (a - b) / (a + b);
double osgb_Latitude;
double osgb_Longitude;
convertWGS84ToOSGB36(lat, lon, osgb_Latitude, osgb_Longitude);
double phi = osgb_Latitude; // already in radians
double phi = osgb_Latitude; // already in radians
double lambda = osgb_Longitude; // already in radians
double v = a * f0 / sqrt(1 - e2 * sin(phi) * sin(phi));
double rho = a * f0 * (1 - e2) / pow(1 - e2 * sin(phi) * sin(phi), 1.5);
double eta2 = v / rho - 1;
double mA = (1 + n + (5/4)*n*n + (5/4)*n*n*n) * (phi - phi0);
double mB = (3*n + 3*n*n + (21/8)*n*n*n) * sin(phi - phi0) * cos(phi + phi0);
double mA = (1 + n + (5 / 4) * n * n + (5 / 4) * n * n * n) * (phi - phi0);
double mB = (3 * n + 3 * n * n + (21 / 8) * n * n * n) * sin(phi - phi0) * cos(phi + phi0);
// loss of precision in mC & mD due to floating point rounding can cause innaccuracy of northing by a few meters
double mC = (15/8*n*n + 15/8*n*n*n) * sin(2*(phi - phi0)) * cos(2*(phi + phi0));
double mD = (35/24)*n*n*n * sin(3*(phi - phi0)) * cos(3*(phi + phi0));
double m = b*f0*(mA - mB + mC - mD);
double mC = (15 / 8 * n * n + 15 / 8 * n * n * n) * sin(2 * (phi - phi0)) * cos(2 * (phi + phi0));
double mD = (35 / 24) * n * n * n * sin(3 * (phi - phi0)) * cos(3 * (phi + phi0));
double m = b * f0 * (mA - mB + mC - mD);
double cos3Phi = cos(phi)*cos(phi)*cos(phi);
double cos5Phi = cos3Phi*cos(phi)*cos(phi);
double tan2Phi = tan(phi)*tan(phi);
double tan4Phi = tan2Phi*tan2Phi;
double cos3Phi = cos(phi) * cos(phi) * cos(phi);
double cos5Phi = cos3Phi * cos(phi) * cos(phi);
double tan2Phi = tan(phi) * tan(phi);
double tan4Phi = tan2Phi * tan2Phi;
double I = m + n0;
double II = (v/2)*sin(phi)*cos(phi);
double III = (v/24)*sin(phi)*cos3Phi*(5 - tan2Phi + 9*eta2);
double IIIA = (v/720)*sin(phi)*cos5Phi*(61 - 58*tan2Phi + tan4Phi);
double IV = v*cos(phi);
double V = (v/6)*cos3Phi*(v/rho - tan2Phi);
double VI = (v/120)*cos5Phi*(5 - 18*tan2Phi + tan4Phi + 14*eta2 - 58*tan2Phi*eta2);
double II = (v / 2) * sin(phi) * cos(phi);
double III = (v / 24) * sin(phi) * cos3Phi * (5 - tan2Phi + 9 * eta2);
double IIIA = (v / 720) * sin(phi) * cos5Phi * (61 - 58 * tan2Phi + tan4Phi);
double IV = v * cos(phi);
double V = (v / 6) * cos3Phi * (v / rho - tan2Phi);
double VI = (v / 120) * cos5Phi * (5 - 18 * tan2Phi + tan4Phi + 14 * eta2 - 58 * tan2Phi * eta2);
double deltaLambda = lambda - lambda0;
double deltaLambda2 = deltaLambda*deltaLambda;
double northing = I + II*deltaLambda2 + III*deltaLambda2*deltaLambda2 + IIIA*deltaLambda2*deltaLambda2*deltaLambda2;
double easting = e0 + IV*deltaLambda + V*deltaLambda2*deltaLambda + VI*deltaLambda2*deltaLambda2*deltaLambda;
double deltaLambda2 = deltaLambda * deltaLambda;
double northing =
I + II * deltaLambda2 + III * deltaLambda2 * deltaLambda2 + IIIA * deltaLambda2 * deltaLambda2 * deltaLambda2;
double easting = e0 + IV * deltaLambda + V * deltaLambda2 * deltaLambda + VI * deltaLambda2 * deltaLambda2 * deltaLambda;
if (easting < 0 || easting > 700000 || northing < 0 || northing > 1300000) // Check if out of boundaries
osgr = { 'I', 'I', 0, 0 };
osgr = {'I', 'I', 0, 0};
else {
uint32_t e100k = floor(easting / 100000);
uint32_t n100k = floor(northing / 100000);
@ -232,7 +258,8 @@ void GeoCoord::latLongToOSGR(const double lat, const double lon, OSGR &osgr) {
* Converts lat long coordinates to Open Location Code.
* Based on: https://github.com/google/open-location-code/blob/main/c/src/olc.c
*/
void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc)
{
char tempCode[] = "1234567890abc";
const char kAlphabet[] = "23456789CFGHJMPQRVWX";
double latitude;
@ -258,7 +285,7 @@ void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
lat_val += latitude * 2.5e7;
lng_val += longitude * 8.192e6;
size_t pos = OLC_CODE_LEN;
if (OLC_CODE_LEN > 10) { // Compute grid part of code if needed
for (size_t i = 0; i < 5; i++) {
int lat_digit = lat_val % 5;
@ -272,9 +299,9 @@ void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
lat_val /= pow(5, 5);
lng_val /= pow(4, 5);
}
pos = 10;
for (size_t i = 0; i < 5; i++) { // Compute pair section of code
int lat_ndx = lat_val % 20;
int lng_ndx = lng_val % 20;
@ -286,7 +313,7 @@ void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
if (i == 0)
tempCode[pos--] = '+';
}
if (OLC_CODE_LEN < 9) { // Add padding if needed
for (size_t i = OLC_CODE_LEN; i < 9; i++)
tempCode[i] = '0';
@ -300,50 +327,52 @@ void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
for (size_t i = 0; i < char_count; i++) {
olc.code[i] = tempCode[i];
}
olc.code[char_count] = '\0';
olc.code[char_count] = '\0';
}
// Converts the coordinate in WGS84 datum to the OSGB36 datum.
void GeoCoord::convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude) {
void GeoCoord::convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude)
{
// Convert lat long to cartesian
double phi = toRadians(lat);
double lambda = toRadians(lon);
double h = 0.0; // No OSTN height data used, some loss of accuracy (up to 5m)
double wgsA = 6378137; // WGS84 datum semi major axis
double h = 0.0; // No OSTN height data used, some loss of accuracy (up to 5m)
double wgsA = 6378137; // WGS84 datum semi major axis
double wgsF = 1 / 298.257223563; // WGS84 datum flattening
double ecc = 2*wgsF - wgsF*wgsF;
double ecc = 2 * wgsF - wgsF * wgsF;
double vee = wgsA / sqrt(1 - ecc * pow(sin(phi), 2));
double wgsX = (vee + h) * cos(phi) * cos(lambda);
double wgsY = (vee + h) * cos(phi) * sin(lambda);
double wgsZ = ((1 - ecc) * vee + h) * sin(phi);
// 7-parameter Helmert transform
double tx = -446.448; // x shift in meters
double ty = 125.157; // y shift in meters
double tz = -542.060; // z shift in meters
double s = 20.4894/1e6 + 1; // scale normalized parts per million to (s + 1)
double rx = toRadians(-0.1502/3600); // x rotation normalize arcseconds to radians
double ry = toRadians(-0.2470/3600); // y rotation normalize arcseconds to radians
double rz = toRadians(-0.8421/3600); // z rotation normalize arcseconds to radians
double osgbX = tx + wgsX*s - wgsY*rz + wgsZ*ry;
double osgbY = ty + wgsX*rz + wgsY*s - wgsZ*rx;
double osgbZ = tz - wgsX*ry + wgsY*rx + wgsZ*s;
double tx = -446.448; // x shift in meters
double ty = 125.157; // y shift in meters
double tz = -542.060; // z shift in meters
double s = 20.4894 / 1e6 + 1; // scale normalized parts per million to (s + 1)
double rx = toRadians(-0.1502 / 3600); // x rotation normalize arcseconds to radians
double ry = toRadians(-0.2470 / 3600); // y rotation normalize arcseconds to radians
double rz = toRadians(-0.8421 / 3600); // z rotation normalize arcseconds to radians
double osgbX = tx + wgsX * s - wgsY * rz + wgsZ * ry;
double osgbY = ty + wgsX * rz + wgsY * s - wgsZ * rx;
double osgbZ = tz - wgsX * ry + wgsY * rx + wgsZ * s;
// Convert cartesian to lat long
double airyA = 6377563.396; // Airy1830 datum semi major axis
double airyB = 6356256.909; // Airy1830 datum semi minor axis
double airyF = 1/ 299.3249646; // Airy1830 datum flattening
double airyEcc = 2*airyF - airyF*airyF;
double airyA = 6377563.396; // Airy1830 datum semi major axis
double airyB = 6356256.909; // Airy1830 datum semi minor axis
double airyF = 1 / 299.3249646; // Airy1830 datum flattening
double airyEcc = 2 * airyF - airyF * airyF;
double airyEcc2 = airyEcc / (1 - airyEcc);
double p = sqrt(osgbX*osgbX + osgbY*osgbY);
double R = sqrt(p*p + osgbZ*osgbZ);
double tanBeta = (airyB*osgbZ) / (airyA*p) * (1 + airyEcc2*airyB/R);
double sinBeta = tanBeta / sqrt(1 + tanBeta*tanBeta);
double p = sqrt(osgbX * osgbX + osgbY * osgbY);
double R = sqrt(p * p + osgbZ * osgbZ);
double tanBeta = (airyB * osgbZ) / (airyA * p) * (1 + airyEcc2 * airyB / R);
double sinBeta = tanBeta / sqrt(1 + tanBeta * tanBeta);
double cosBeta = sinBeta / tanBeta;
osgb_Latitude = atan2(osgbZ + airyEcc2*airyB*sinBeta*sinBeta*sinBeta, p - airyEcc*airyA*cosBeta*cosBeta*cosBeta); // leave in radians
osgb_Longitude = atan2(osgbY, osgbX); // leave in radians
//osgb height = p*cos(osgb.latitude) + osgbZ*sin(osgb.latitude) -
//(airyA*airyA/(airyA / sqrt(1 - airyEcc*sin(osgb.latitude)*sin(osgb.latitude)))); // Not used, no OSTN data
osgb_Latitude = atan2(osgbZ + airyEcc2 * airyB * sinBeta * sinBeta * sinBeta,
p - airyEcc * airyA * cosBeta * cosBeta * cosBeta); // leave in radians
osgb_Longitude = atan2(osgbY, osgbX); // leave in radians
// osgb height = p*cos(osgb.latitude) + osgbZ*sin(osgb.latitude) -
//(airyA*airyA/(airyA / sqrt(1 - airyEcc*sin(osgb.latitude)*sin(osgb.latitude)))); // Not used, no OSTN data
}
/// Ported from my old java code, returns distance in meters along the globe
@ -397,12 +426,13 @@ float GeoCoord::bearing(double lat1, double lon1, double lat2, double lon2)
* @brief Convert from meters to range in radians on a great circle
* @param range_meters
* The range in meters
* @return range in radians on a great circle
* @return range in radians on a great circle
*/
float GeoCoord::rangeMetersToRadians(double range_meters) {
float GeoCoord::rangeMetersToRadians(double range_meters)
{
// 1 nm is 1852 meters
double distance_nm = range_meters * 1852;
return (PI / (180 * 60)) *distance_nm;
return (PI / (180 * 60)) * distance_nm;
}
/**
@ -410,22 +440,27 @@ float GeoCoord::rangeMetersToRadians(double range_meters) {
* @brief Convert from radians to range in meters on a great circle
* @param range_radians
* The range in radians
* @return Range in meters on a great circle
* @return Range in meters on a great circle
*/
float GeoCoord::rangeRadiansToMeters(double range_radians) {
float GeoCoord::rangeRadiansToMeters(double range_radians)
{
double distance_nm = ((180 * 60) / PI) * range_radians;
// 1 meter is 0.000539957 nm
return distance_nm * 0.000539957;
}
// Find distance from point to passed in point
int32_t GeoCoord::distanceTo(const GeoCoord& pointB) {
return latLongToMeter(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7, pointB.getLongitude() * 1e-7);
int32_t GeoCoord::distanceTo(const GeoCoord &pointB)
{
return latLongToMeter(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7,
pointB.getLongitude() * 1e-7);
}
// Find bearing from point to passed in point
int32_t GeoCoord::bearingTo(const GeoCoord& pointB) {
return bearing(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7, pointB.getLongitude() * 1e-7);
int32_t GeoCoord::bearingTo(const GeoCoord &pointB)
{
return bearing(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7,
pointB.getLongitude() * 1e-7);
}
/**
@ -436,8 +471,9 @@ int32_t GeoCoord::bearingTo(const GeoCoord& pointB) {
* @param range_meters
* range in meters
* @return GeoCoord object of point at bearing and range from initial point
*/
std::shared_ptr<GeoCoord> GeoCoord::pointAtDistance(double bearing, double range_meters) {
*/
std::shared_ptr<GeoCoord> GeoCoord::pointAtDistance(double bearing, double range_meters)
{
double range_radians = rangeMetersToRadians(range_meters);
double lat1 = this->getLatitude() * 1e-7;
double lon1 = this->getLongitude() * 1e-7;
@ -446,5 +482,4 @@ std::shared_ptr<GeoCoord> GeoCoord::pointAtDistance(double bearing, double range
double lon = fmod(lon1 - dlon + PI, 2 * PI) - PI;
return std::make_shared<GeoCoord>(double(lat), double(lon), this->getAltitude());
}

Wyświetl plik

@ -1,26 +1,27 @@
#pragma once
#include <algorithm>
#include <string>
#include <cstring>
#include <cstdint>
#include <cstring>
#include <math.h>
#include <stdint.h>
#include <stdexcept>
#include <memory>
#include <stdexcept>
#include <stdint.h>
#include <string>
#define PI 3.1415926535897932384626433832795
#define OLC_CODE_LEN 11
// Helper functions
// Raises a number to an exponent, handling negative exponents.
static inline double pow_neg(double base, double exponent) {
if (exponent == 0) {
return 1;
} else if (exponent > 0) {
return pow(base, exponent);
}
return 1 / pow(base, -exponent);
static inline double pow_neg(double base, double exponent)
{
if (exponent == 0) {
return 1;
} else if (exponent > 0) {
return pow(base, exponent);
}
return 1 / pow(base, -exponent);
}
static inline double toRadians(double deg)
@ -35,8 +36,7 @@ static inline double toDegrees(double r)
// GeoCoord structs/classes
// A struct to hold the data for a DMS coordinate.
struct DMS
{
struct DMS {
uint8_t latDeg;
uint8_t latMin;
uint32_t latSec;
@ -48,8 +48,7 @@ struct DMS
};
// A struct to hold the data for a UTM coordinate, this is also used when creating an MGRS coordinate.
struct UTM
{
struct UTM {
uint8_t zone;
char band;
uint32_t easting;
@ -57,8 +56,7 @@ struct UTM
};
// A struct to hold the data for a MGRS coordinate.
struct MGRS
{
struct MGRS {
uint8_t zone;
char band;
char east100k;
@ -80,85 +78,85 @@ struct OLC {
char code[OLC_CODE_LEN + 1]; // +1 for null termination
};
class GeoCoord {
private:
int32_t _latitude = 0;
int32_t _longitude = 0;
int32_t _altitude = 0;
class GeoCoord
{
private:
int32_t _latitude = 0;
int32_t _longitude = 0;
int32_t _altitude = 0;
DMS _dms = {};
UTM _utm = {};
MGRS _mgrs = {};
OSGR _osgr = {};
OLC _olc = {};
DMS _dms = {};
UTM _utm = {};
MGRS _mgrs = {};
OSGR _osgr = {};
OLC _olc = {};
bool _dirty = true;
bool _dirty = true;
void setCoords();
void setCoords();
public:
GeoCoord();
GeoCoord(int32_t lat, int32_t lon, int32_t alt);
GeoCoord(double lat, double lon, int32_t alt);
GeoCoord(float lat, float lon, int32_t alt);
public:
GeoCoord();
GeoCoord(int32_t lat, int32_t lon, int32_t alt);
GeoCoord(double lat, double lon, int32_t alt);
GeoCoord(float lat, float lon, int32_t alt);
void updateCoords(const int32_t lat, const int32_t lon, const int32_t alt);
void updateCoords(const double lat, const double lon, const int32_t alt);
void updateCoords(const float lat, const float lon, const int32_t alt);
void updateCoords(const int32_t lat, const int32_t lon, const int32_t alt);
void updateCoords(const double lat, const double lon, const int32_t alt);
void updateCoords(const float lat, const float lon, const int32_t alt);
// Conversions
static void latLongToDMS(const double lat, const double lon, DMS &dms);
static void latLongToUTM(const double lat, const double lon, UTM &utm);
static void latLongToMGRS(const double lat, const double lon, MGRS &mgrs);
static void latLongToOSGR(const double lat, const double lon, OSGR &osgr);
static void latLongToOLC(const double lat, const double lon, OLC &olc);
static void convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude);
static float latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b);
static float bearing(double lat1, double lon1, double lat2, double lon2);
static float rangeRadiansToMeters(double range_radians);
static float rangeMetersToRadians(double range_meters);
// Conversions
static void latLongToDMS(const double lat, const double lon, DMS &dms);
static void latLongToUTM(const double lat, const double lon, UTM &utm);
static void latLongToMGRS(const double lat, const double lon, MGRS &mgrs);
static void latLongToOSGR(const double lat, const double lon, OSGR &osgr);
static void latLongToOLC(const double lat, const double lon, OLC &olc);
static void convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude);
static float latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b);
static float bearing(double lat1, double lon1, double lat2, double lon2);
static float rangeRadiansToMeters(double range_radians);
static float rangeMetersToRadians(double range_meters);
// Point to point conversions
int32_t distanceTo(const GeoCoord& pointB);
int32_t bearingTo(const GeoCoord& pointB);
std::shared_ptr<GeoCoord> pointAtDistance(double bearing, double range);
// Point to point conversions
int32_t distanceTo(const GeoCoord &pointB);
int32_t bearingTo(const GeoCoord &pointB);
std::shared_ptr<GeoCoord> pointAtDistance(double bearing, double range);
// Lat lon alt getters
int32_t getLatitude() const { return _latitude; }
int32_t getLongitude() const { return _longitude; }
int32_t getAltitude() const { return _altitude; }
// Lat lon alt getters
int32_t getLatitude() const { return _latitude; }
int32_t getLongitude() const { return _longitude; }
int32_t getAltitude() const { return _altitude; }
// DMS getters
uint8_t getDMSLatDeg() const { return _dms.latDeg; }
uint8_t getDMSLatMin() const { return _dms.latMin; }
uint32_t getDMSLatSec() const { return _dms.latSec; }
char getDMSLatCP() const { return _dms.latCP; }
uint8_t getDMSLonDeg() const { return _dms.lonDeg; }
uint8_t getDMSLonMin() const { return _dms.lonMin; }
uint32_t getDMSLonSec() const { return _dms.lonSec; }
char getDMSLonCP() const { return _dms.lonCP; }
// DMS getters
uint8_t getDMSLatDeg() const { return _dms.latDeg; }
uint8_t getDMSLatMin() const { return _dms.latMin; }
uint32_t getDMSLatSec() const { return _dms.latSec; }
char getDMSLatCP() const { return _dms.latCP; }
uint8_t getDMSLonDeg() const { return _dms.lonDeg; }
uint8_t getDMSLonMin() const { return _dms.lonMin; }
uint32_t getDMSLonSec() const { return _dms.lonSec; }
char getDMSLonCP() const { return _dms.lonCP; }
// UTM getters
uint8_t getUTMZone() const { return _utm.zone; }
char getUTMBand() const { return _utm.band; }
uint32_t getUTMEasting() const { return _utm.easting; }
uint32_t getUTMNorthing() const { return _utm.northing; }
// UTM getters
uint8_t getUTMZone() const { return _utm.zone; }
char getUTMBand() const { return _utm.band; }
uint32_t getUTMEasting() const { return _utm.easting; }
uint32_t getUTMNorthing() const { return _utm.northing; }
// MGRS getters
uint8_t getMGRSZone() const { return _mgrs.zone; }
char getMGRSBand() const { return _mgrs.band; }
char getMGRSEast100k() const { return _mgrs.east100k; }
char getMGRSNorth100k() const { return _mgrs.north100k; }
uint32_t getMGRSEasting() const { return _mgrs.easting; }
uint32_t getMGRSNorthing() const { return _mgrs.northing; }
// MGRS getters
uint8_t getMGRSZone() const { return _mgrs.zone; }
char getMGRSBand() const { return _mgrs.band; }
char getMGRSEast100k() const { return _mgrs.east100k; }
char getMGRSNorth100k() const { return _mgrs.north100k; }
uint32_t getMGRSEasting() const { return _mgrs.easting; }
uint32_t getMGRSNorthing() const { return _mgrs.northing; }
// OSGR getters
char getOSGRE100k() const { return _osgr.e100k; }
char getOSGRN100k() const { return _osgr.n100k; }
uint32_t getOSGREasting() const { return _osgr.easting; }
uint32_t getOSGRNorthing() const { return _osgr.northing; }
// OSGR getters
char getOSGRE100k() const { return _osgr.e100k; }
char getOSGRN100k() const { return _osgr.n100k; }
uint32_t getOSGREasting() const { return _osgr.easting; }
uint32_t getOSGRNorthing() const { return _osgr.northing; }
// OLC getter
void getOLCCode(char* code) { strncpy(code, _olc.code, OLC_CODE_LEN + 1); } // +1 for null termination
// OLC getter
void getOLCCode(char *code) { strncpy(code, _olc.code, OLC_CODE_LEN + 1); } // +1 for null termination
};

Wyświetl plik

@ -1,12 +1,12 @@
#include "configuration.h"
#include "NMEAGPS.h"
#include "RTC.h"
#include "configuration.h"
#include <TinyGPS++.h>
// GPS solutions older than this will be rejected - see TinyGPSDatum::age()
#define GPS_SOL_EXPIRY_MS 5000 // in millis. give 1 second time to combine different sentences. NMEA Frequency isn't higher anyway
#define NMEA_MSG_GXGSA "GNGSA" // GSA message (GPGSA, GNGSA etc)
#define GPS_SOL_EXPIRY_MS 5000 // in millis. give 1 second time to combine different sentences. NMEA Frequency isn't higher anyway
#define NMEA_MSG_GXGSA "GNGSA" // GSA message (GPGSA, GNGSA etc)
static int32_t toDegInt(RawDegrees d)
{
@ -20,19 +20,18 @@ static int32_t toDegInt(RawDegrees d)
bool NMEAGPS::factoryReset()
{
#ifdef PIN_GPS_REINIT
//The L76K GNSS on the T-Echo requires the RESET pin to be pulled LOW
// The L76K GNSS on the T-Echo requires the RESET pin to be pulled LOW
digitalWrite(PIN_GPS_REINIT, 0);
pinMode(PIN_GPS_REINIT, OUTPUT);
delay(150); //The L76K datasheet calls for at least 100MS delay
delay(150); // The L76K datasheet calls for at least 100MS delay
digitalWrite(PIN_GPS_REINIT, 1);
#endif
#endif
// send the UBLOX Factory Reset Command regardless of detect state, something is very wrong, just assume it's UBLOX.
// Factory Reset
byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF,
0xFB, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xFF, 0xFF, 0x00, 0x00, 0x17, 0x2B, 0x7E};
_serial_gps->write(_message_reset,sizeof(_message_reset));
byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFB, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x17, 0x2B, 0x7E};
_serial_gps->write(_message_reset, sizeof(_message_reset));
delay(1000);
return true;
}
@ -40,7 +39,7 @@ bool NMEAGPS::factoryReset()
bool NMEAGPS::setupGPS()
{
GPS::setupGPS();
#ifdef PIN_GPS_PPS
// pulse per second
// FIXME - move into shared GPS code
@ -84,8 +83,9 @@ The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of s
t.tm_mon = d.month() - 1;
t.tm_year = d.year() - 1900;
t.tm_isdst = false;
if (t.tm_mon > -1){
LOG_DEBUG("NMEA GPS time %02d-%02d-%02d %02d:%02d:%02d\n", d.year(), d.month(), t.tm_mday, t.tm_hour, t.tm_min, t.tm_sec);
if (t.tm_mon > -1) {
LOG_DEBUG("NMEA GPS time %02d-%02d-%02d %02d:%02d:%02d\n", d.year(), d.month(), t.tm_mday, t.tm_hour, t.tm_min,
t.tm_sec);
perhapsSetRTC(RTCQualityGPS, t);
return true;
} else
@ -102,47 +102,44 @@ The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of s
*/
bool NMEAGPS::lookForLocation()
{
// By default, TinyGPS++ does not parse GPGSA lines, which give us
// By default, TinyGPS++ does not parse GPGSA lines, which give us
// the 2D/3D fixType (see NMEAGPS.h)
// At a minimum, use the fixQuality indicator in GPGGA (FIXME?)
fixQual = reader.fixQuality();
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
fixType = atoi(gsafixtype.value()); // will set to zero if no data
fixType = atoi(gsafixtype.value()); // will set to zero if no data
// LOG_DEBUG("FIX QUAL=%d, TYPE=%d\n", fixQual, fixType);
#endif
// check if GPS has an acceptable lock
if (! hasLock())
if (!hasLock())
return false;
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("AGE: LOC=%d FIX=%d DATE=%d TIME=%d\n",
reader.location.age(),
LOG_DEBUG("AGE: LOC=%d FIX=%d DATE=%d TIME=%d\n", reader.location.age(),
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
gsafixtype.age(),
gsafixtype.age(),
#else
0,
0,
#endif
reader.date.age(), reader.time.age());
#endif // GPS_EXTRAVERBOSE
reader.date.age(), reader.time.age());
#endif // GPS_EXTRAVERBOSE
// check if a complete GPS solution set is available for reading
// tinyGPSDatum::age() also includes isValid() test
// FIXME
if (! ((reader.location.age() < GPS_SOL_EXPIRY_MS) &&
if (!((reader.location.age() < GPS_SOL_EXPIRY_MS) &&
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
(gsafixtype.age() < GPS_SOL_EXPIRY_MS) &&
(gsafixtype.age() < GPS_SOL_EXPIRY_MS) &&
#endif
(reader.time.age() < GPS_SOL_EXPIRY_MS) &&
(reader.date.age() < GPS_SOL_EXPIRY_MS)))
{
(reader.time.age() < GPS_SOL_EXPIRY_MS) && (reader.date.age() < GPS_SOL_EXPIRY_MS))) {
LOG_WARN("SOME data is TOO OLD: LOC %u, TIME %u, DATE %u\n", reader.location.age(), reader.time.age(), reader.date.age());
return false;
}
// Is this a new point or are we re-reading the previous one?
if (! reader.location.isUpdated())
if (!reader.location.isUpdated())
return false;
// We know the solution is fresh and valid, so just read the data
@ -150,14 +147,14 @@ bool NMEAGPS::lookForLocation()
// Bail out EARLY to avoid overwriting previous good data (like #857)
if (toDegInt(loc.lat) > 900000000) {
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LAT %i\n",toDegInt(loc.lat));
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LAT %i\n", toDegInt(loc.lat));
#endif
return false;
}
if (toDegInt(loc.lng) > 1800000000) {
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LNG %i\n",toDegInt(loc.lng));
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LNG %i\n", toDegInt(loc.lng));
#endif
return false;
}
@ -209,11 +206,11 @@ bool NMEAGPS::lookForLocation()
}
if (reader.course.isUpdated() && reader.course.isValid()) {
if (reader.course.value() < 36000) { // sanity check
p.ground_track = reader.course.value() * 1e3; // Scale the heading (in degrees * 10^-2) to match the expected degrees * 10^-5
if (reader.course.value() < 36000) { // sanity check
p.ground_track =
reader.course.value() * 1e3; // Scale the heading (in degrees * 10^-2) to match the expected degrees * 10^-5
} else {
LOG_WARN("BOGUS course.value() REJECTED: %d\n",
reader.course.value());
LOG_WARN("BOGUS course.value() REJECTED: %d\n", reader.course.value());
}
}
@ -224,14 +221,13 @@ bool NMEAGPS::lookForLocation()
return true;
}
bool NMEAGPS::hasLock()
{
// Using GPGGA fix quality indicator
if (fixQual >= 1 && fixQual <= 5) {
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
// Use GPGSA fix type 2D/3D (better) if available
if (fixType == 3 || fixType == 0) // zero means "no data received"
if (fixType == 3 || fixType == 0) // zero means "no data received"
#endif
return true;
}

Wyświetl plik

@ -12,14 +12,14 @@
class NMEAGPS : public GPS
{
TinyGPSPlus reader;
uint8_t fixQual = 0; // fix quality from GPGGA
uint8_t fixQual = 0; // fix quality from GPGGA
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
// (20210908) TinyGps++ can only read the GPGSA "FIX TYPE" field
// via optional feature "custom fields", currently disabled (bug #525)
TinyGPSCustom gsafixtype; // custom extract fix type from GPGSA
TinyGPSCustom gsapdop; // custom extract PDOP from GPGSA
uint8_t fixType = 0; // fix type from GPGSA
TinyGPSCustom gsafixtype; // custom extract fix type from GPGSA
TinyGPSCustom gsapdop; // custom extract PDOP from GPGSA
uint8_t fixType = 0; // fix type from GPGSA
#endif
public:
@ -29,9 +29,9 @@ class NMEAGPS : public GPS
protected:
/** Subclasses should look for serial rx characters here and feed it to their GPS parser
*
*
* Return true if we received a valid message from the GPS
*/
*/
virtual bool whileIdle() override;
/**

Wyświetl plik

@ -18,15 +18,11 @@
uint32_t printWPL(char *buf, size_t bufsz, const Position &pos, const char *name)
{
GeoCoord geoCoord(pos.latitude_i,pos.longitude_i,pos.altitude);
uint32_t len = snprintf(buf, bufsz, "$GNWPL,%02d%07.4f,%c,%03d%07.4f,%c,%s",
geoCoord.getDMSLatDeg(),
(abs(geoCoord.getLatitude()) - geoCoord.getDMSLatDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLatCP(),
geoCoord.getDMSLonDeg(),
(abs(geoCoord.getLongitude()) - geoCoord.getDMSLonDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLonCP(),
name);
GeoCoord geoCoord(pos.latitude_i, pos.longitude_i, pos.altitude);
uint32_t len = snprintf(buf, bufsz, "$GNWPL,%02d%07.4f,%c,%03d%07.4f,%c,%s", geoCoord.getDMSLatDeg(),
(abs(geoCoord.getLatitude()) - geoCoord.getDMSLatDeg() * 1e+7) * 6e-6, geoCoord.getDMSLatCP(),
geoCoord.getDMSLonDeg(), (abs(geoCoord.getLongitude()) - geoCoord.getDMSLonDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLonCP(), name);
uint32_t chk = 0;
for (uint32_t i = 1; i < len; i++) {
chk ^= buf[i];
@ -51,35 +47,21 @@ uint32_t printWPL(char *buf, size_t bufsz, const Position &pos, const char *name
* 8 Horizontal Dilution of precision (meters)
* 9 Antenna Altitude above/below mean-sea-level (geoid) (in meters)
* 10 Units of antenna altitude, meters
* 11 Geoidal separation, the difference between the WGS-84 earth ellipsoid and mean-sea-level (geoid), "-" means mean-sea-level below ellipsoid
* 12 Units of geoidal separation, meters
* 13 Age of differential GPS data, time in seconds since last SC104 type 1 or 9 update, null field when DGPS is not used
* 14 Differential reference station ID, 0000-1023
* 15 Checksum
* 11 Geoidal separation, the difference between the WGS-84 earth ellipsoid and mean-sea-level (geoid), "-" means mean-sea-level
* below ellipsoid 12 Units of geoidal separation, meters 13 Age of differential GPS data, time in seconds since last SC104 type 1
* or 9 update, null field when DGPS is not used 14 Differential reference station ID, 0000-1023 15 Checksum
* -------------------------------------------
*/
uint32_t printGGA(char *buf, size_t bufsz, const Position &pos)
{
GeoCoord geoCoord(pos.latitude_i,pos.longitude_i,pos.altitude);
uint32_t len = snprintf(buf, bufsz, "$GNGGA,%06u.%03u,%02d%07.4f,%c,%03d%07.4f,%c,%u,%02u,%04u,%04d,%c,%04d,%c,%d,%04d",
pos.time / 1000,
pos.time % 1000,
geoCoord.getDMSLatDeg(),
(abs(geoCoord.getLatitude()) - geoCoord.getDMSLatDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLatCP(),
geoCoord.getDMSLonDeg(),
(abs(geoCoord.getLongitude()) - geoCoord.getDMSLonDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLonCP(),
pos.fix_type,
pos.sats_in_view,
pos.HDOP,
geoCoord.getAltitude(),
'M',
pos.altitude_geoidal_separation,
'M',
0,
0);
GeoCoord geoCoord(pos.latitude_i, pos.longitude_i, pos.altitude);
uint32_t len =
snprintf(buf, bufsz, "$GNGGA,%06u.%03u,%02d%07.4f,%c,%03d%07.4f,%c,%u,%02u,%04u,%04d,%c,%04d,%c,%d,%04d", pos.time / 1000,
pos.time % 1000, geoCoord.getDMSLatDeg(), (abs(geoCoord.getLatitude()) - geoCoord.getDMSLatDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLatCP(), geoCoord.getDMSLonDeg(),
(abs(geoCoord.getLongitude()) - geoCoord.getDMSLonDeg() * 1e+7) * 6e-6, geoCoord.getDMSLonCP(), pos.fix_type,
pos.sats_in_view, pos.HDOP, geoCoord.getAltitude(), 'M', pos.altitude_geoidal_separation, 'M', 0, 0);
uint32_t chk = 0;
for (uint32_t i = 1; i < len; i++) {

Wyświetl plik

@ -1,7 +1,7 @@
#pragma once
#include <Arduino.h>
#include "main.h"
#include <Arduino.h>
uint32_t printWPL(char *buf, size_t bufsz, const Position &pos, const char *name);
uint32_t printGGA(char *buf, size_t bufsz, const Position &pos);

Wyświetl plik

@ -20,7 +20,7 @@ void readFromRTC()
{
struct timeval tv; /* btw settimeofday() is helpfull here too*/
#ifdef RV3028_RTC
if(rtc_found == RV3028_RTC) {
if (rtc_found == RV3028_RTC) {
uint32_t now = millis();
Melopero_RV3028 rtc;
rtc.initI2C();
@ -41,7 +41,7 @@ void readFromRTC()
}
}
#elif defined(PCF8563_RTC)
if(rtc_found == PCF8563_RTC) {
if (rtc_found == PCF8563_RTC) {
uint32_t now = millis();
PCF8563_Class rtc;
#ifdef RTC_USE_WIRE1
@ -66,7 +66,7 @@ void readFromRTC()
currentQuality = RTCQualityDevice;
}
}
#else
#else
if (!gettimeofday(&tv, NULL)) {
uint32_t now = millis();
LOG_DEBUG("Read RTC time as %ld\n", tv.tv_sec);
@ -87,12 +87,11 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
currentQuality = q;
shouldSet = true;
LOG_DEBUG("Upgrading time to RTC %ld secs (quality %d)\n", tv->tv_sec, q);
} else if(q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000UL)) {
} else if (q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000UL)) {
// Every 12 hrs we will slam in a new GPS time, to correct for local RTC clock drift
shouldSet = true;
LOG_DEBUG("Reapplying external time to correct clock drift %ld secs\n", tv->tv_sec);
}
else
} else
shouldSet = false;
if (shouldSet) {
@ -104,24 +103,26 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
// If this platform has a setable RTC, set it
#ifdef RV3028_RTC
if(rtc_found == RV3028_RTC) {
if (rtc_found == RV3028_RTC) {
Melopero_RV3028 rtc;
rtc.initI2C();
tm *t = localtime(&tv->tv_sec);
rtc.setTime(t->tm_year + 1900, t->tm_mon + 1, t->tm_wday, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec);
LOG_DEBUG("RV3028_RTC setTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
LOG_DEBUG("RV3028_RTC setTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday,
t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
}
#elif defined(PCF8563_RTC)
if(rtc_found == PCF8563_RTC) {
if (rtc_found == PCF8563_RTC) {
PCF8563_Class rtc;
#ifdef RTC_USE_WIRE1
rtc.begin(Wire1);
rtc.begin(Wire1);
#else
rtc.begin();
rtc.begin();
#endif
tm *t = localtime(&tv->tv_sec);
rtc.setDateTime(t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec);
LOG_DEBUG("PCF8563_RTC setDateTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
LOG_DEBUG("PCF8563_RTC setDateTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday,
t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
}
#elif defined(ARCH_ESP32)
settimeofday(tv, NULL);
@ -160,7 +161,7 @@ bool perhapsSetRTC(RTCQuality q, struct tm &t)
uint32_t getTime()
{
return (((uint32_t) millis() - timeStartMsec) / 1000) + zeroOffsetSecs;
return (((uint32_t)millis() - timeStartMsec) / 1000) + zeroOffsetSecs;
}
uint32_t getValidTime(RTCQuality minQuality)

Wyświetl plik

@ -2,425 +2,425 @@
// Font generated or edited with the glyphEditor
const uint8_t ArialMT_Plain_10_RU[] PROGMEM = {
0x0A, // Width: 10
0x0D, // Height: 13
0x20, // First char: 32
0xE0, // Number of chars: 224
// Jump Table:
0xFF, 0xFF, 0x00, 0x0A, // 32
0x00, 0x00, 0x04, 0x03, // 33
0x00, 0x04, 0x05, 0x04, // 34
0x00, 0x09, 0x09, 0x06, // 35
0x00, 0x12, 0x0A, 0x06, // 36
0x00, 0x1C, 0x10, 0x09, // 37
0x00, 0x2C, 0x0E, 0x08, // 38
0x00, 0x3A, 0x01, 0x02, // 39
0x00, 0x3B, 0x06, 0x04, // 40
0x00, 0x41, 0x06, 0x04, // 41
0x00, 0x47, 0x05, 0x04, // 42
0x00, 0x4C, 0x09, 0x06, // 43
0x00, 0x55, 0x04, 0x03, // 44
0x00, 0x59, 0x03, 0x03, // 45
0x00, 0x5C, 0x04, 0x03, // 46
0x00, 0x60, 0x05, 0x04, // 47
0x00, 0x65, 0x0A, 0x06, // 48
0x00, 0x6F, 0x08, 0x05, // 49
0x00, 0x77, 0x0A, 0x06, // 50
0x00, 0x81, 0x0A, 0x06, // 51
0x00, 0x8B, 0x0B, 0x07, // 52
0x00, 0x96, 0x0A, 0x06, // 53
0x00, 0xA0, 0x0A, 0x06, // 54
0x00, 0xAA, 0x09, 0x06, // 55
0x00, 0xB3, 0x0A, 0x06, // 56
0x00, 0xBD, 0x0A, 0x06, // 57
0x00, 0xC7, 0x04, 0x03, // 58
0x00, 0xCB, 0x04, 0x03, // 59
0x00, 0xCF, 0x0A, 0x06, // 60
0x00, 0xD9, 0x09, 0x06, // 61
0x00, 0xE2, 0x09, 0x06, // 62
0x00, 0xEB, 0x0B, 0x07, // 63
0x00, 0xF6, 0x14, 0x0B, // 64
0x01, 0x0A, 0x0E, 0x08, // 65
0x01, 0x18, 0x0C, 0x07, // 66
0x01, 0x24, 0x0C, 0x07, // 67
0x01, 0x30, 0x0B, 0x07, // 68
0x01, 0x3B, 0x0C, 0x07, // 69
0x01, 0x47, 0x09, 0x06, // 70
0x01, 0x50, 0x0D, 0x08, // 71
0x01, 0x5D, 0x0C, 0x07, // 72
0x01, 0x69, 0x04, 0x03, // 73
0x01, 0x6D, 0x08, 0x05, // 74
0x01, 0x75, 0x0E, 0x08, // 75
0x01, 0x83, 0x0C, 0x07, // 76
0x01, 0x8F, 0x10, 0x09, // 77
0x01, 0x9F, 0x0C, 0x07, // 78
0x01, 0xAB, 0x0E, 0x08, // 79
0x01, 0xB9, 0x0B, 0x07, // 80
0x01, 0xC4, 0x0E, 0x08, // 81
0x01, 0xD2, 0x0C, 0x07, // 82
0x01, 0xDE, 0x0C, 0x07, // 83
0x01, 0xEA, 0x0B, 0x07, // 84
0x01, 0xF5, 0x0C, 0x07, // 85
0x02, 0x01, 0x0D, 0x08, // 86
0x02, 0x0E, 0x11, 0x0A, // 87
0x02, 0x1F, 0x0E, 0x08, // 88
0x02, 0x2D, 0x0D, 0x08, // 89
0x02, 0x3A, 0x0C, 0x07, // 90
0x02, 0x46, 0x06, 0x04, // 91
0x02, 0x4C, 0x06, 0x04, // 92
0x02, 0x52, 0x04, 0x03, // 93
0x02, 0x56, 0x09, 0x06, // 94
0x02, 0x5F, 0x0C, 0x07, // 95
0x02, 0x6B, 0x03, 0x03, // 96
0x02, 0x6E, 0x0A, 0x06, // 97
0x02, 0x78, 0x0A, 0x06, // 98
0x02, 0x82, 0x0A, 0x06, // 99
0x02, 0x8C, 0x0A, 0x06, // 100
0x02, 0x96, 0x0A, 0x06, // 101
0x02, 0xA0, 0x05, 0x04, // 102
0x02, 0xA5, 0x0A, 0x06, // 103
0x02, 0xAF, 0x0A, 0x06, // 104
0x02, 0xB9, 0x04, 0x03, // 105
0x02, 0xBD, 0x04, 0x03, // 106
0x02, 0xC1, 0x08, 0x05, // 107
0x02, 0xC9, 0x04, 0x03, // 108
0x02, 0xCD, 0x10, 0x09, // 109
0x02, 0xDD, 0x0A, 0x06, // 110
0x02, 0xE7, 0x0A, 0x06, // 111
0x02, 0xF1, 0x0A, 0x06, // 112
0x02, 0xFB, 0x0A, 0x06, // 113
0x03, 0x05, 0x05, 0x04, // 114
0x03, 0x0A, 0x08, 0x05, // 115
0x03, 0x12, 0x06, 0x04, // 116
0x03, 0x18, 0x0A, 0x06, // 117
0x03, 0x22, 0x09, 0x06, // 118
0x03, 0x2B, 0x0E, 0x08, // 119
0x03, 0x39, 0x0A, 0x06, // 120
0x03, 0x43, 0x09, 0x06, // 121
0x03, 0x4C, 0x0A, 0x06, // 122
0x03, 0x56, 0x06, 0x04, // 123
0x03, 0x5C, 0x04, 0x03, // 124
0x03, 0x60, 0x05, 0x04, // 125
0x03, 0x65, 0x09, 0x06, // 126
0xFF, 0xFF, 0x00, 0x0A, // 127
0xFF, 0xFF, 0x00, 0x0A, // 128
0xFF, 0xFF, 0x00, 0x0A, // 129
0xFF, 0xFF, 0x00, 0x0A, // 130
0xFF, 0xFF, 0x00, 0x0A, // 131
0xFF, 0xFF, 0x00, 0x0A, // 132
0xFF, 0xFF, 0x00, 0x0A, // 133
0xFF, 0xFF, 0x00, 0x0A, // 134
0xFF, 0xFF, 0x00, 0x0A, // 135
0xFF, 0xFF, 0x00, 0x0A, // 136
0xFF, 0xFF, 0x00, 0x0A, // 137
0xFF, 0xFF, 0x00, 0x0A, // 138
0xFF, 0xFF, 0x00, 0x0A, // 139
0xFF, 0xFF, 0x00, 0x0A, // 140
0xFF, 0xFF, 0x00, 0x0A, // 141
0xFF, 0xFF, 0x00, 0x0A, // 142
0xFF, 0xFF, 0x00, 0x0A, // 143
0xFF, 0xFF, 0x00, 0x0A, // 144
0xFF, 0xFF, 0x00, 0x0A, // 145
0xFF, 0xFF, 0x00, 0x0A, // 146
0xFF, 0xFF, 0x00, 0x0A, // 147
0xFF, 0xFF, 0x00, 0x0A, // 148
0xFF, 0xFF, 0x00, 0x0A, // 149
0xFF, 0xFF, 0x00, 0x0A, // 150
0xFF, 0xFF, 0x00, 0x0A, // 151
0xFF, 0xFF, 0x00, 0x0A, // 152
0xFF, 0xFF, 0x00, 0x0A, // 153
0xFF, 0xFF, 0x00, 0x0A, // 154
0xFF, 0xFF, 0x00, 0x0A, // 155
0xFF, 0xFF, 0x00, 0x0A, // 156
0xFF, 0xFF, 0x00, 0x0A, // 157
0xFF, 0xFF, 0x00, 0x0A, // 158
0xFF, 0xFF, 0x00, 0x0A, // 159
0xFF, 0xFF, 0x00, 0x0A, // 160
0x03, 0x6E, 0x04, 0x03, // 161
0x03, 0x72, 0x0A, 0x06, // 162
0x03, 0x7C, 0x0C, 0x07, // 163
0x03, 0x88, 0x0A, 0x06, // 164
0x03, 0x92, 0x0A, 0x06, // 165
0x03, 0x9C, 0x04, 0x03, // 166
0x03, 0xA0, 0x0A, 0x06, // 167
0x03, 0xAA, 0x0C, 0x07, // 168
0x03, 0xB6, 0x0D, 0x08, // 169
0x03, 0xC3, 0x07, 0x05, // 170
0x03, 0xCA, 0x0A, 0x06, // 171
0x03, 0xD4, 0x09, 0x06, // 172
0x03, 0xDD, 0x03, 0x03, // 173
0x03, 0xE0, 0x0D, 0x08, // 174
0x03, 0xED, 0x0B, 0x07, // 175
0x03, 0xF8, 0x07, 0x05, // 176
0x03, 0xFF, 0x0A, 0x06, // 177
0x04, 0x09, 0x05, 0x04, // 178
0x04, 0x0E, 0x05, 0x04, // 179
0x04, 0x13, 0x05, 0x04, // 180
0x04, 0x18, 0x0A, 0x06, // 181
0x04, 0x22, 0x09, 0x06, // 182
0x04, 0x2B, 0x03, 0x03, // 183
0x04, 0x2E, 0x0B, 0x07, // 184
0x04, 0x39, 0x0B, 0x07, // 185
0x04, 0x44, 0x07, 0x05, // 186
0x04, 0x4B, 0x0A, 0x06, // 187
0x04, 0x55, 0x10, 0x09, // 188
0x04, 0x65, 0x10, 0x09, // 189
0x04, 0x75, 0x10, 0x09, // 190
0x04, 0x85, 0x0A, 0x06, // 191
0x04, 0x8F, 0x0C, 0x07, // 192
0x04, 0x9B, 0x0C, 0x07, // 193
0x04, 0xA7, 0x0C, 0x07, // 194
0x04, 0xB3, 0x0B, 0x07, // 195
0x04, 0xBE, 0x0C, 0x07, // 196
0x04, 0xCA, 0x0C, 0x07, // 197
0x04, 0xD6, 0x0C, 0x07, // 198
0x04, 0xE2, 0x0C, 0x07, // 199
0x04, 0xEE, 0x0C, 0x07, // 200
0x04, 0xFA, 0x0C, 0x07, // 201
0x05, 0x06, 0x0C, 0x07, // 202
0x05, 0x12, 0x0C, 0x07, // 203
0x05, 0x1E, 0x0C, 0x07, // 204
0x05, 0x2A, 0x0C, 0x07, // 205
0x05, 0x36, 0x0C, 0x07, // 206
0x05, 0x42, 0x0C, 0x07, // 207
0x05, 0x4E, 0x0B, 0x07, // 208
0x05, 0x59, 0x0C, 0x07, // 209
0x05, 0x65, 0x0B, 0x07, // 210
0x05, 0x70, 0x0C, 0x07, // 211
0x05, 0x7C, 0x0B, 0x07, // 212
0x05, 0x87, 0x0C, 0x07, // 213
0x05, 0x93, 0x0C, 0x07, // 214
0x05, 0x9F, 0x0C, 0x07, // 215
0x05, 0xAB, 0x0C, 0x07, // 216
0x05, 0xB7, 0x0E, 0x08, // 217
0x05, 0xC5, 0x0C, 0x07, // 218
0x05, 0xD1, 0x0C, 0x07, // 219
0x05, 0xDD, 0x0C, 0x07, // 220
0x05, 0xE9, 0x0C, 0x07, // 221
0x05, 0xF5, 0x0C, 0x07, // 222
0x06, 0x01, 0x0C, 0x07, // 223
0x06, 0x0D, 0x0C, 0x07, // 224
0x06, 0x19, 0x0C, 0x07, // 225
0x06, 0x25, 0x0C, 0x07, // 226
0x06, 0x31, 0x0B, 0x07, // 227
0x06, 0x3C, 0x0C, 0x07, // 228
0x06, 0x48, 0x0B, 0x07, // 229
0x06, 0x53, 0x0C, 0x07, // 230
0x06, 0x5F, 0x0C, 0x07, // 231
0x06, 0x6B, 0x0C, 0x07, // 232
0x06, 0x77, 0x0C, 0x07, // 233
0x06, 0x83, 0x0C, 0x07, // 234
0x06, 0x8F, 0x0C, 0x07, // 235
0x06, 0x9B, 0x0C, 0x07, // 236
0x06, 0xA7, 0x0C, 0x07, // 237
0x06, 0xB3, 0x0C, 0x07, // 238
0x06, 0xBF, 0x0C, 0x07, // 239
0x06, 0xCB, 0x0B, 0x07, // 240
0x06, 0xD6, 0x0C, 0x07, // 241
0x06, 0xE2, 0x0B, 0x07, // 242
0x06, 0xED, 0x0C, 0x07, // 243
0x06, 0xF9, 0x0B, 0x07, // 244
0x07, 0x04, 0x0C, 0x07, // 245
0x07, 0x10, 0x0C, 0x07, // 246
0x07, 0x1C, 0x0C, 0x07, // 247
0x07, 0x28, 0x0C, 0x07, // 248
0x07, 0x34, 0x0E, 0x08, // 249
0x07, 0x42, 0x0C, 0x07, // 250
0x07, 0x4E, 0x0C, 0x07, // 251
0x07, 0x5A, 0x0C, 0x07, // 252
0x07, 0x66, 0x0C, 0x07, // 253
0x07, 0x72, 0x0C, 0x07, // 254
0x07, 0x7E, 0x0C, 0x07, // 255
// Font Data:
0x00, 0x00, 0xF8, 0x02, // 33
0x38, 0x00, 0x00, 0x00, 0x38, // 34
0xA0, 0x03, 0xE0, 0x00, 0xB8, 0x03, 0xE0, 0x00, 0xB8, // 35
0x30, 0x01, 0x28, 0x02, 0xF8, 0x07, 0x48, 0x02, 0x90, 0x01, // 36
0x00, 0x00, 0x30, 0x00, 0x48, 0x00, 0x30, 0x03, 0xC0, 0x00, 0xB0, 0x01, 0x48, 0x02, 0x80, 0x01, // 37
0x80, 0x01, 0x50, 0x02, 0x68, 0x02, 0xA8, 0x02, 0x18, 0x01, 0x80, 0x03, 0x80, 0x02, // 38
0x38, // 39
0xE0, 0x03, 0x10, 0x04, 0x08, 0x08, // 40
0x08, 0x08, 0x10, 0x04, 0xE0, 0x03, // 41
0x28, 0x00, 0x18, 0x00, 0x28, // 42
0x40, 0x00, 0x40, 0x00, 0xF0, 0x01, 0x40, 0x00, 0x40, // 43
0x00, 0x00, 0x00, 0x06, // 44
0x80, 0x00, 0x80, // 45
0x00, 0x00, 0x00, 0x02, // 46
0x00, 0x03, 0xE0, 0x00, 0x18, // 47
0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 48
0x00, 0x00, 0x20, 0x00, 0x10, 0x00, 0xF8, 0x03, // 49
0x10, 0x02, 0x08, 0x03, 0x88, 0x02, 0x48, 0x02, 0x30, 0x02, // 50
0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 51
0xC0, 0x00, 0xA0, 0x00, 0x90, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x80, // 52
0x60, 0x01, 0x38, 0x02, 0x28, 0x02, 0x28, 0x02, 0xC8, 0x01, // 53
0xF0, 0x01, 0x28, 0x02, 0x28, 0x02, 0x28, 0x02, 0xD0, 0x01, // 54
0x08, 0x00, 0x08, 0x03, 0xC8, 0x00, 0x38, 0x00, 0x08, // 55
0xB0, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 56
0x70, 0x01, 0x88, 0x02, 0x88, 0x02, 0x88, 0x02, 0xF0, 0x01, // 57
0x00, 0x00, 0x20, 0x02, // 58
0x00, 0x00, 0x20, 0x06, // 59
0x00, 0x00, 0x40, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x10, 0x01, // 60
0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, // 61
0x00, 0x00, 0x10, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 62
0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0xC8, 0x02, 0x48, 0x00, 0x30, // 63
0x00, 0x00, 0xC0, 0x03, 0x30, 0x04, 0xD0, 0x09, 0x28, 0x0A, 0x28, 0x0A, 0xC8, 0x0B, 0x68, 0x0A, 0x10, 0x05, 0xE0, 0x04, // 64
0x00, 0x02, 0xC0, 0x01, 0xB0, 0x00, 0x88, 0x00, 0xB0, 0x00, 0xC0, 0x01, 0x00, 0x02, // 65
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 66
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 67
0x00, 0x00, 0xF8, 0x03, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, 0xE0, // 68
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, // 69
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x08, // 70
0x00, 0x00, 0xE0, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x50, 0x01, 0xC0, // 71
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 72
0x00, 0x00, 0xF8, 0x03, // 73
0x00, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 74
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 75
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 76
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x30, 0x00, 0xF8, 0x03, // 77
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0x40, 0x00, 0x80, 0x01, 0xF8, 0x03, // 78
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 79
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 80
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x03, 0x08, 0x03, 0xF0, 0x02, // 81
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0xC8, 0x00, 0x30, 0x03, // 82
0x00, 0x00, 0x30, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x90, 0x01, // 83
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 84
0x00, 0x00, 0xF8, 0x01, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 85
0x08, 0x00, 0x70, 0x00, 0x80, 0x01, 0x00, 0x02, 0x80, 0x01, 0x70, 0x00, 0x08, // 86
0x18, 0x00, 0xE0, 0x01, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0xF0, 0x01, 0x00, 0x02, 0xE0, 0x01, 0x18, // 87
0x00, 0x02, 0x08, 0x01, 0x90, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 88
0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x20, 0x00, 0x10, 0x00, 0x08, // 89
0x08, 0x03, 0x88, 0x02, 0xC8, 0x02, 0x68, 0x02, 0x38, 0x02, 0x18, 0x02, // 90
0x00, 0x00, 0xF8, 0x0F, 0x08, 0x08, // 91
0x18, 0x00, 0xE0, 0x00, 0x00, 0x03, // 92
0x08, 0x08, 0xF8, 0x0F, // 93
0x40, 0x00, 0x30, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, // 94
0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, // 95
0x08, 0x00, 0x10, // 96
0x00, 0x00, 0x00, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xE0, 0x03, // 97
0x00, 0x00, 0xF8, 0x03, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 98
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x40, 0x01, // 99
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xF8, 0x03, // 100
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x02, // 101
0x20, 0x00, 0xF0, 0x03, 0x28, // 102
0x00, 0x00, 0xC0, 0x05, 0x20, 0x0A, 0x20, 0x0A, 0xE0, 0x07, // 103
0x00, 0x00, 0xF8, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 104
0x00, 0x00, 0xE8, 0x03, // 105
0x00, 0x08, 0xE8, 0x07, // 106
0xF8, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, // 107
0x00, 0x00, 0xF8, 0x03, // 108
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 109
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 110
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 111
0x00, 0x00, 0xE0, 0x0F, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 112
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xE0, 0x0F, // 113
0x00, 0x00, 0xE0, 0x03, 0x20, // 114
0x40, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x20, 0x01, // 115
0x20, 0x00, 0xF8, 0x03, 0x20, 0x02, // 116
0x00, 0x00, 0xE0, 0x01, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 117
0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, // 118
0xE0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xE0, 0x01, // 119
0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 120
0x20, 0x00, 0xC0, 0x09, 0x00, 0x06, 0xC0, 0x01, 0x20, // 121
0x20, 0x02, 0x20, 0x03, 0xA0, 0x02, 0x60, 0x02, 0x20, 0x02, // 122
0x80, 0x00, 0x78, 0x0F, 0x08, 0x08, // 123
0x00, 0x00, 0xF8, 0x0F, // 124
0x08, 0x08, 0x78, 0x0F, 0x80, // 125
0xC0, 0x00, 0x40, 0x00, 0xC0, 0x00, 0x80, 0x00, 0xC0, // 126
0x00, 0x00, 0xA0, 0x0F, // 161
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x0F, 0x78, 0x02, 0x40, 0x01, // 162
0x40, 0x02, 0x70, 0x03, 0xC8, 0x02, 0x48, 0x02, 0x08, 0x02, 0x10, 0x02, // 163
0x00, 0x00, 0xE0, 0x01, 0x20, 0x01, 0x20, 0x01, 0xE0, 0x01, // 164
0x48, 0x01, 0x70, 0x01, 0xC0, 0x03, 0x70, 0x01, 0x48, 0x01, // 165
0x00, 0x00, 0x38, 0x0F, // 166
0xD0, 0x04, 0x28, 0x09, 0x48, 0x09, 0x48, 0x0A, 0x90, 0x05, // 167
0x00, 0x00, 0xE0, 0x03, 0xA8, 0x02, 0xA0, 0x02, 0xA8, 0x02, 0x20, 0x02, // 168
0xE0, 0x00, 0x10, 0x01, 0x48, 0x02, 0xA8, 0x02, 0xA8, 0x02, 0x10, 0x01, 0xE0, // 169
0x68, 0x00, 0x68, 0x00, 0x68, 0x00, 0x78, // 170
0x00, 0x00, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, // 171
0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, // 172
0x80, 0x00, 0x80, // 173
0xE0, 0x00, 0x10, 0x01, 0xE8, 0x02, 0x68, 0x02, 0xC8, 0x02, 0x10, 0x01, 0xE0, // 174
0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 175
0x00, 0x00, 0x38, 0x00, 0x28, 0x00, 0x38, // 176
0x40, 0x02, 0x40, 0x02, 0xF0, 0x03, 0x40, 0x02, 0x40, 0x02, // 177
0x48, 0x00, 0x68, 0x00, 0x58, // 178
0x48, 0x00, 0x58, 0x00, 0x68, // 179
0x00, 0x00, 0x10, 0x00, 0x08, // 180
0x00, 0x00, 0xE0, 0x0F, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 181
0x70, 0x00, 0xF8, 0x0F, 0x08, 0x00, 0xF8, 0x0F, 0x08, // 182
0x00, 0x00, 0x40, // 183
0x00, 0x00, 0xC0, 0x01, 0xA8, 0x02, 0xA0, 0x02, 0xA8, 0x02, 0xC0, // 184
0x00, 0x00, 0xF0, 0x03, 0x40, 0x00, 0x80, 0x00, 0xF8, 0x03, 0x08, // 185
0x30, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 186
0x00, 0x00, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, // 187
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0xC0, 0x00, 0x20, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 188
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0x80, 0x00, 0x60, 0x00, 0x50, 0x02, 0x48, 0x03, 0xC0, 0x02, // 189
0x48, 0x00, 0x58, 0x00, 0x68, 0x03, 0x80, 0x00, 0x60, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 190
0x00, 0x00, 0x00, 0x06, 0x00, 0x09, 0xA0, 0x09, 0x00, 0x04, // 191
0x00, 0x00, 0xF0, 0x03, 0x88, 0x00, 0x88, 0x00, 0x88, 0x00, 0xF0, 0x03, // 192
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x88, 0x01, // 193
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 194
0x00, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x18, // 195
0x00, 0x00, 0x00, 0x02, 0xFC, 0x03, 0x04, 0x02, 0xFC, 0x03, 0x00, 0x02, // 196
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x08, 0x02, // 197
0x00, 0x00, 0xB8, 0x03, 0x40, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xB8, 0x03, // 198
0x00, 0x00, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 199
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0xF8, 0x03, // 200
0x00, 0x00, 0xE0, 0x03, 0x08, 0x01, 0x90, 0x00, 0x48, 0x00, 0xE0, 0x03, // 201
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xA0, 0x00, 0x10, 0x01, 0x08, 0x02, // 202
0x00, 0x00, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, // 203
0x00, 0x00, 0xF8, 0x03, 0x10, 0x00, 0x60, 0x00, 0x10, 0x00, 0xF8, 0x03, // 204
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 205
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 206
0x00, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, // 207
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 208
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 209
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 210
0x00, 0x00, 0x38, 0x00, 0x40, 0x02, 0x40, 0x02, 0x40, 0x02, 0xF8, 0x01, // 211
0x00, 0x00, 0x70, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x88, 0x00, 0x70, // 212
0x00, 0x00, 0x18, 0x03, 0xA0, 0x00, 0x40, 0x00, 0xA0, 0x00, 0x18, 0x03, // 213
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, // 214
0x00, 0x00, 0x38, 0x00, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 215
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, // 216
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x06, // 217
0x00, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, // 218
0x00, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, 0xF8, 0x03, // 219
0x00, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, // 220
0x00, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 221
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xF0, 0x01, 0x08, 0x02, 0xF0, 0x01, // 222
0x00, 0x00, 0x30, 0x02, 0x48, 0x01, 0xC8, 0x00, 0x48, 0x00, 0xF8, 0x03, // 223
0x00, 0x00, 0x00, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x03, // 224
0x00, 0x00, 0xE0, 0x01, 0x50, 0x02, 0x50, 0x02, 0x48, 0x02, 0x88, 0x01, // 225
0x00, 0x00, 0xE0, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x40, 0x01, // 226
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x60, // 227
0x00, 0x00, 0x00, 0x02, 0xC0, 0x03, 0x20, 0x02, 0xE0, 0x03, 0x00, 0x02, // 228
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, // 229
0x00, 0x00, 0x60, 0x03, 0x80, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x60, 0x03, // 230
0x00, 0x00, 0x20, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x40, 0x01, // 231
0x00, 0x00, 0xE0, 0x03, 0x00, 0x01, 0x80, 0x00, 0x40, 0x00, 0xE0, 0x03, // 232
0x00, 0x00, 0xE0, 0x03, 0x00, 0x01, 0x98, 0x00, 0x40, 0x00, 0xE0, 0x03, // 233
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 234
0x00, 0x00, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, // 235
0x00, 0x00, 0xE0, 0x03, 0x40, 0x00, 0x80, 0x00, 0x40, 0x00, 0xE0, 0x03, // 236
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0xE0, 0x03, // 237
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 238
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, // 239
0x00, 0x00, 0xE0, 0x03, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 240
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x20, 0x02, 0x40, 0x02, // 241
0x00, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, // 242
0x00, 0x00, 0x60, 0x00, 0x80, 0x02, 0x80, 0x02, 0x80, 0x02, 0xE0, 0x01, // 243
0x00, 0x00, 0xC0, 0x00, 0x20, 0x01, 0xE0, 0x03, 0x20, 0x01, 0xC0, // 244
0x00, 0x00, 0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 245
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, // 246
0x00, 0x00, 0x60, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0xE0, 0x03, // 247
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, // 248
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x06, // 249
0x00, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, // 250
0x00, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, 0xE0, 0x03, // 251
0x00, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, // 252
0x00, 0x00, 0x40, 0x01, 0x20, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x01, // 253
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, 0xC0, 0x01, // 254
0x00, 0x00, 0x40, 0x02, 0xA0, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0xE0, 0x03, // 255
0x0A, // Width: 10
0x0D, // Height: 13
0x20, // First char: 32
0xE0, // Number of chars: 224
// Jump Table:
0xFF, 0xFF, 0x00, 0x0A, // 32
0x00, 0x00, 0x04, 0x03, // 33
0x00, 0x04, 0x05, 0x04, // 34
0x00, 0x09, 0x09, 0x06, // 35
0x00, 0x12, 0x0A, 0x06, // 36
0x00, 0x1C, 0x10, 0x09, // 37
0x00, 0x2C, 0x0E, 0x08, // 38
0x00, 0x3A, 0x01, 0x02, // 39
0x00, 0x3B, 0x06, 0x04, // 40
0x00, 0x41, 0x06, 0x04, // 41
0x00, 0x47, 0x05, 0x04, // 42
0x00, 0x4C, 0x09, 0x06, // 43
0x00, 0x55, 0x04, 0x03, // 44
0x00, 0x59, 0x03, 0x03, // 45
0x00, 0x5C, 0x04, 0x03, // 46
0x00, 0x60, 0x05, 0x04, // 47
0x00, 0x65, 0x0A, 0x06, // 48
0x00, 0x6F, 0x08, 0x05, // 49
0x00, 0x77, 0x0A, 0x06, // 50
0x00, 0x81, 0x0A, 0x06, // 51
0x00, 0x8B, 0x0B, 0x07, // 52
0x00, 0x96, 0x0A, 0x06, // 53
0x00, 0xA0, 0x0A, 0x06, // 54
0x00, 0xAA, 0x09, 0x06, // 55
0x00, 0xB3, 0x0A, 0x06, // 56
0x00, 0xBD, 0x0A, 0x06, // 57
0x00, 0xC7, 0x04, 0x03, // 58
0x00, 0xCB, 0x04, 0x03, // 59
0x00, 0xCF, 0x0A, 0x06, // 60
0x00, 0xD9, 0x09, 0x06, // 61
0x00, 0xE2, 0x09, 0x06, // 62
0x00, 0xEB, 0x0B, 0x07, // 63
0x00, 0xF6, 0x14, 0x0B, // 64
0x01, 0x0A, 0x0E, 0x08, // 65
0x01, 0x18, 0x0C, 0x07, // 66
0x01, 0x24, 0x0C, 0x07, // 67
0x01, 0x30, 0x0B, 0x07, // 68
0x01, 0x3B, 0x0C, 0x07, // 69
0x01, 0x47, 0x09, 0x06, // 70
0x01, 0x50, 0x0D, 0x08, // 71
0x01, 0x5D, 0x0C, 0x07, // 72
0x01, 0x69, 0x04, 0x03, // 73
0x01, 0x6D, 0x08, 0x05, // 74
0x01, 0x75, 0x0E, 0x08, // 75
0x01, 0x83, 0x0C, 0x07, // 76
0x01, 0x8F, 0x10, 0x09, // 77
0x01, 0x9F, 0x0C, 0x07, // 78
0x01, 0xAB, 0x0E, 0x08, // 79
0x01, 0xB9, 0x0B, 0x07, // 80
0x01, 0xC4, 0x0E, 0x08, // 81
0x01, 0xD2, 0x0C, 0x07, // 82
0x01, 0xDE, 0x0C, 0x07, // 83
0x01, 0xEA, 0x0B, 0x07, // 84
0x01, 0xF5, 0x0C, 0x07, // 85
0x02, 0x01, 0x0D, 0x08, // 86
0x02, 0x0E, 0x11, 0x0A, // 87
0x02, 0x1F, 0x0E, 0x08, // 88
0x02, 0x2D, 0x0D, 0x08, // 89
0x02, 0x3A, 0x0C, 0x07, // 90
0x02, 0x46, 0x06, 0x04, // 91
0x02, 0x4C, 0x06, 0x04, // 92
0x02, 0x52, 0x04, 0x03, // 93
0x02, 0x56, 0x09, 0x06, // 94
0x02, 0x5F, 0x0C, 0x07, // 95
0x02, 0x6B, 0x03, 0x03, // 96
0x02, 0x6E, 0x0A, 0x06, // 97
0x02, 0x78, 0x0A, 0x06, // 98
0x02, 0x82, 0x0A, 0x06, // 99
0x02, 0x8C, 0x0A, 0x06, // 100
0x02, 0x96, 0x0A, 0x06, // 101
0x02, 0xA0, 0x05, 0x04, // 102
0x02, 0xA5, 0x0A, 0x06, // 103
0x02, 0xAF, 0x0A, 0x06, // 104
0x02, 0xB9, 0x04, 0x03, // 105
0x02, 0xBD, 0x04, 0x03, // 106
0x02, 0xC1, 0x08, 0x05, // 107
0x02, 0xC9, 0x04, 0x03, // 108
0x02, 0xCD, 0x10, 0x09, // 109
0x02, 0xDD, 0x0A, 0x06, // 110
0x02, 0xE7, 0x0A, 0x06, // 111
0x02, 0xF1, 0x0A, 0x06, // 112
0x02, 0xFB, 0x0A, 0x06, // 113
0x03, 0x05, 0x05, 0x04, // 114
0x03, 0x0A, 0x08, 0x05, // 115
0x03, 0x12, 0x06, 0x04, // 116
0x03, 0x18, 0x0A, 0x06, // 117
0x03, 0x22, 0x09, 0x06, // 118
0x03, 0x2B, 0x0E, 0x08, // 119
0x03, 0x39, 0x0A, 0x06, // 120
0x03, 0x43, 0x09, 0x06, // 121
0x03, 0x4C, 0x0A, 0x06, // 122
0x03, 0x56, 0x06, 0x04, // 123
0x03, 0x5C, 0x04, 0x03, // 124
0x03, 0x60, 0x05, 0x04, // 125
0x03, 0x65, 0x09, 0x06, // 126
0xFF, 0xFF, 0x00, 0x0A, // 127
0xFF, 0xFF, 0x00, 0x0A, // 128
0xFF, 0xFF, 0x00, 0x0A, // 129
0xFF, 0xFF, 0x00, 0x0A, // 130
0xFF, 0xFF, 0x00, 0x0A, // 131
0xFF, 0xFF, 0x00, 0x0A, // 132
0xFF, 0xFF, 0x00, 0x0A, // 133
0xFF, 0xFF, 0x00, 0x0A, // 134
0xFF, 0xFF, 0x00, 0x0A, // 135
0xFF, 0xFF, 0x00, 0x0A, // 136
0xFF, 0xFF, 0x00, 0x0A, // 137
0xFF, 0xFF, 0x00, 0x0A, // 138
0xFF, 0xFF, 0x00, 0x0A, // 139
0xFF, 0xFF, 0x00, 0x0A, // 140
0xFF, 0xFF, 0x00, 0x0A, // 141
0xFF, 0xFF, 0x00, 0x0A, // 142
0xFF, 0xFF, 0x00, 0x0A, // 143
0xFF, 0xFF, 0x00, 0x0A, // 144
0xFF, 0xFF, 0x00, 0x0A, // 145
0xFF, 0xFF, 0x00, 0x0A, // 146
0xFF, 0xFF, 0x00, 0x0A, // 147
0xFF, 0xFF, 0x00, 0x0A, // 148
0xFF, 0xFF, 0x00, 0x0A, // 149
0xFF, 0xFF, 0x00, 0x0A, // 150
0xFF, 0xFF, 0x00, 0x0A, // 151
0xFF, 0xFF, 0x00, 0x0A, // 152
0xFF, 0xFF, 0x00, 0x0A, // 153
0xFF, 0xFF, 0x00, 0x0A, // 154
0xFF, 0xFF, 0x00, 0x0A, // 155
0xFF, 0xFF, 0x00, 0x0A, // 156
0xFF, 0xFF, 0x00, 0x0A, // 157
0xFF, 0xFF, 0x00, 0x0A, // 158
0xFF, 0xFF, 0x00, 0x0A, // 159
0xFF, 0xFF, 0x00, 0x0A, // 160
0x03, 0x6E, 0x04, 0x03, // 161
0x03, 0x72, 0x0A, 0x06, // 162
0x03, 0x7C, 0x0C, 0x07, // 163
0x03, 0x88, 0x0A, 0x06, // 164
0x03, 0x92, 0x0A, 0x06, // 165
0x03, 0x9C, 0x04, 0x03, // 166
0x03, 0xA0, 0x0A, 0x06, // 167
0x03, 0xAA, 0x0C, 0x07, // 168
0x03, 0xB6, 0x0D, 0x08, // 169
0x03, 0xC3, 0x07, 0x05, // 170
0x03, 0xCA, 0x0A, 0x06, // 171
0x03, 0xD4, 0x09, 0x06, // 172
0x03, 0xDD, 0x03, 0x03, // 173
0x03, 0xE0, 0x0D, 0x08, // 174
0x03, 0xED, 0x0B, 0x07, // 175
0x03, 0xF8, 0x07, 0x05, // 176
0x03, 0xFF, 0x0A, 0x06, // 177
0x04, 0x09, 0x05, 0x04, // 178
0x04, 0x0E, 0x05, 0x04, // 179
0x04, 0x13, 0x05, 0x04, // 180
0x04, 0x18, 0x0A, 0x06, // 181
0x04, 0x22, 0x09, 0x06, // 182
0x04, 0x2B, 0x03, 0x03, // 183
0x04, 0x2E, 0x0B, 0x07, // 184
0x04, 0x39, 0x0B, 0x07, // 185
0x04, 0x44, 0x07, 0x05, // 186
0x04, 0x4B, 0x0A, 0x06, // 187
0x04, 0x55, 0x10, 0x09, // 188
0x04, 0x65, 0x10, 0x09, // 189
0x04, 0x75, 0x10, 0x09, // 190
0x04, 0x85, 0x0A, 0x06, // 191
0x04, 0x8F, 0x0C, 0x07, // 192
0x04, 0x9B, 0x0C, 0x07, // 193
0x04, 0xA7, 0x0C, 0x07, // 194
0x04, 0xB3, 0x0B, 0x07, // 195
0x04, 0xBE, 0x0C, 0x07, // 196
0x04, 0xCA, 0x0C, 0x07, // 197
0x04, 0xD6, 0x0C, 0x07, // 198
0x04, 0xE2, 0x0C, 0x07, // 199
0x04, 0xEE, 0x0C, 0x07, // 200
0x04, 0xFA, 0x0C, 0x07, // 201
0x05, 0x06, 0x0C, 0x07, // 202
0x05, 0x12, 0x0C, 0x07, // 203
0x05, 0x1E, 0x0C, 0x07, // 204
0x05, 0x2A, 0x0C, 0x07, // 205
0x05, 0x36, 0x0C, 0x07, // 206
0x05, 0x42, 0x0C, 0x07, // 207
0x05, 0x4E, 0x0B, 0x07, // 208
0x05, 0x59, 0x0C, 0x07, // 209
0x05, 0x65, 0x0B, 0x07, // 210
0x05, 0x70, 0x0C, 0x07, // 211
0x05, 0x7C, 0x0B, 0x07, // 212
0x05, 0x87, 0x0C, 0x07, // 213
0x05, 0x93, 0x0C, 0x07, // 214
0x05, 0x9F, 0x0C, 0x07, // 215
0x05, 0xAB, 0x0C, 0x07, // 216
0x05, 0xB7, 0x0E, 0x08, // 217
0x05, 0xC5, 0x0C, 0x07, // 218
0x05, 0xD1, 0x0C, 0x07, // 219
0x05, 0xDD, 0x0C, 0x07, // 220
0x05, 0xE9, 0x0C, 0x07, // 221
0x05, 0xF5, 0x0C, 0x07, // 222
0x06, 0x01, 0x0C, 0x07, // 223
0x06, 0x0D, 0x0C, 0x07, // 224
0x06, 0x19, 0x0C, 0x07, // 225
0x06, 0x25, 0x0C, 0x07, // 226
0x06, 0x31, 0x0B, 0x07, // 227
0x06, 0x3C, 0x0C, 0x07, // 228
0x06, 0x48, 0x0B, 0x07, // 229
0x06, 0x53, 0x0C, 0x07, // 230
0x06, 0x5F, 0x0C, 0x07, // 231
0x06, 0x6B, 0x0C, 0x07, // 232
0x06, 0x77, 0x0C, 0x07, // 233
0x06, 0x83, 0x0C, 0x07, // 234
0x06, 0x8F, 0x0C, 0x07, // 235
0x06, 0x9B, 0x0C, 0x07, // 236
0x06, 0xA7, 0x0C, 0x07, // 237
0x06, 0xB3, 0x0C, 0x07, // 238
0x06, 0xBF, 0x0C, 0x07, // 239
0x06, 0xCB, 0x0B, 0x07, // 240
0x06, 0xD6, 0x0C, 0x07, // 241
0x06, 0xE2, 0x0B, 0x07, // 242
0x06, 0xED, 0x0C, 0x07, // 243
0x06, 0xF9, 0x0B, 0x07, // 244
0x07, 0x04, 0x0C, 0x07, // 245
0x07, 0x10, 0x0C, 0x07, // 246
0x07, 0x1C, 0x0C, 0x07, // 247
0x07, 0x28, 0x0C, 0x07, // 248
0x07, 0x34, 0x0E, 0x08, // 249
0x07, 0x42, 0x0C, 0x07, // 250
0x07, 0x4E, 0x0C, 0x07, // 251
0x07, 0x5A, 0x0C, 0x07, // 252
0x07, 0x66, 0x0C, 0x07, // 253
0x07, 0x72, 0x0C, 0x07, // 254
0x07, 0x7E, 0x0C, 0x07, // 255
// Font Data:
0x00, 0x00, 0xF8, 0x02, // 33
0x38, 0x00, 0x00, 0x00, 0x38, // 34
0xA0, 0x03, 0xE0, 0x00, 0xB8, 0x03, 0xE0, 0x00, 0xB8, // 35
0x30, 0x01, 0x28, 0x02, 0xF8, 0x07, 0x48, 0x02, 0x90, 0x01, // 36
0x00, 0x00, 0x30, 0x00, 0x48, 0x00, 0x30, 0x03, 0xC0, 0x00, 0xB0, 0x01, 0x48, 0x02, 0x80, 0x01, // 37
0x80, 0x01, 0x50, 0x02, 0x68, 0x02, 0xA8, 0x02, 0x18, 0x01, 0x80, 0x03, 0x80, 0x02, // 38
0x38, // 39
0xE0, 0x03, 0x10, 0x04, 0x08, 0x08, // 40
0x08, 0x08, 0x10, 0x04, 0xE0, 0x03, // 41
0x28, 0x00, 0x18, 0x00, 0x28, // 42
0x40, 0x00, 0x40, 0x00, 0xF0, 0x01, 0x40, 0x00, 0x40, // 43
0x00, 0x00, 0x00, 0x06, // 44
0x80, 0x00, 0x80, // 45
0x00, 0x00, 0x00, 0x02, // 46
0x00, 0x03, 0xE0, 0x00, 0x18, // 47
0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 48
0x00, 0x00, 0x20, 0x00, 0x10, 0x00, 0xF8, 0x03, // 49
0x10, 0x02, 0x08, 0x03, 0x88, 0x02, 0x48, 0x02, 0x30, 0x02, // 50
0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 51
0xC0, 0x00, 0xA0, 0x00, 0x90, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x80, // 52
0x60, 0x01, 0x38, 0x02, 0x28, 0x02, 0x28, 0x02, 0xC8, 0x01, // 53
0xF0, 0x01, 0x28, 0x02, 0x28, 0x02, 0x28, 0x02, 0xD0, 0x01, // 54
0x08, 0x00, 0x08, 0x03, 0xC8, 0x00, 0x38, 0x00, 0x08, // 55
0xB0, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 56
0x70, 0x01, 0x88, 0x02, 0x88, 0x02, 0x88, 0x02, 0xF0, 0x01, // 57
0x00, 0x00, 0x20, 0x02, // 58
0x00, 0x00, 0x20, 0x06, // 59
0x00, 0x00, 0x40, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x10, 0x01, // 60
0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, // 61
0x00, 0x00, 0x10, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 62
0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0xC8, 0x02, 0x48, 0x00, 0x30, // 63
0x00, 0x00, 0xC0, 0x03, 0x30, 0x04, 0xD0, 0x09, 0x28, 0x0A, 0x28, 0x0A, 0xC8, 0x0B, 0x68, 0x0A, 0x10, 0x05, 0xE0, 0x04, // 64
0x00, 0x02, 0xC0, 0x01, 0xB0, 0x00, 0x88, 0x00, 0xB0, 0x00, 0xC0, 0x01, 0x00, 0x02, // 65
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 66
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 67
0x00, 0x00, 0xF8, 0x03, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, 0xE0, // 68
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, // 69
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x08, // 70
0x00, 0x00, 0xE0, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x50, 0x01, 0xC0, // 71
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 72
0x00, 0x00, 0xF8, 0x03, // 73
0x00, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 74
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 75
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 76
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x30, 0x00, 0xF8, 0x03, // 77
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0x40, 0x00, 0x80, 0x01, 0xF8, 0x03, // 78
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 79
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 80
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x03, 0x08, 0x03, 0xF0, 0x02, // 81
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0xC8, 0x00, 0x30, 0x03, // 82
0x00, 0x00, 0x30, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x90, 0x01, // 83
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 84
0x00, 0x00, 0xF8, 0x01, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 85
0x08, 0x00, 0x70, 0x00, 0x80, 0x01, 0x00, 0x02, 0x80, 0x01, 0x70, 0x00, 0x08, // 86
0x18, 0x00, 0xE0, 0x01, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0xF0, 0x01, 0x00, 0x02, 0xE0, 0x01, 0x18, // 87
0x00, 0x02, 0x08, 0x01, 0x90, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 88
0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x20, 0x00, 0x10, 0x00, 0x08, // 89
0x08, 0x03, 0x88, 0x02, 0xC8, 0x02, 0x68, 0x02, 0x38, 0x02, 0x18, 0x02, // 90
0x00, 0x00, 0xF8, 0x0F, 0x08, 0x08, // 91
0x18, 0x00, 0xE0, 0x00, 0x00, 0x03, // 92
0x08, 0x08, 0xF8, 0x0F, // 93
0x40, 0x00, 0x30, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, // 94
0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, // 95
0x08, 0x00, 0x10, // 96
0x00, 0x00, 0x00, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xE0, 0x03, // 97
0x00, 0x00, 0xF8, 0x03, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 98
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x40, 0x01, // 99
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xF8, 0x03, // 100
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x02, // 101
0x20, 0x00, 0xF0, 0x03, 0x28, // 102
0x00, 0x00, 0xC0, 0x05, 0x20, 0x0A, 0x20, 0x0A, 0xE0, 0x07, // 103
0x00, 0x00, 0xF8, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 104
0x00, 0x00, 0xE8, 0x03, // 105
0x00, 0x08, 0xE8, 0x07, // 106
0xF8, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, // 107
0x00, 0x00, 0xF8, 0x03, // 108
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 109
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 110
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 111
0x00, 0x00, 0xE0, 0x0F, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 112
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xE0, 0x0F, // 113
0x00, 0x00, 0xE0, 0x03, 0x20, // 114
0x40, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x20, 0x01, // 115
0x20, 0x00, 0xF8, 0x03, 0x20, 0x02, // 116
0x00, 0x00, 0xE0, 0x01, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 117
0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, // 118
0xE0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xE0, 0x01, // 119
0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 120
0x20, 0x00, 0xC0, 0x09, 0x00, 0x06, 0xC0, 0x01, 0x20, // 121
0x20, 0x02, 0x20, 0x03, 0xA0, 0x02, 0x60, 0x02, 0x20, 0x02, // 122
0x80, 0x00, 0x78, 0x0F, 0x08, 0x08, // 123
0x00, 0x00, 0xF8, 0x0F, // 124
0x08, 0x08, 0x78, 0x0F, 0x80, // 125
0xC0, 0x00, 0x40, 0x00, 0xC0, 0x00, 0x80, 0x00, 0xC0, // 126
0x00, 0x00, 0xA0, 0x0F, // 161
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x0F, 0x78, 0x02, 0x40, 0x01, // 162
0x40, 0x02, 0x70, 0x03, 0xC8, 0x02, 0x48, 0x02, 0x08, 0x02, 0x10, 0x02, // 163
0x00, 0x00, 0xE0, 0x01, 0x20, 0x01, 0x20, 0x01, 0xE0, 0x01, // 164
0x48, 0x01, 0x70, 0x01, 0xC0, 0x03, 0x70, 0x01, 0x48, 0x01, // 165
0x00, 0x00, 0x38, 0x0F, // 166
0xD0, 0x04, 0x28, 0x09, 0x48, 0x09, 0x48, 0x0A, 0x90, 0x05, // 167
0x00, 0x00, 0xE0, 0x03, 0xA8, 0x02, 0xA0, 0x02, 0xA8, 0x02, 0x20, 0x02, // 168
0xE0, 0x00, 0x10, 0x01, 0x48, 0x02, 0xA8, 0x02, 0xA8, 0x02, 0x10, 0x01, 0xE0, // 169
0x68, 0x00, 0x68, 0x00, 0x68, 0x00, 0x78, // 170
0x00, 0x00, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, // 171
0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, // 172
0x80, 0x00, 0x80, // 173
0xE0, 0x00, 0x10, 0x01, 0xE8, 0x02, 0x68, 0x02, 0xC8, 0x02, 0x10, 0x01, 0xE0, // 174
0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 175
0x00, 0x00, 0x38, 0x00, 0x28, 0x00, 0x38, // 176
0x40, 0x02, 0x40, 0x02, 0xF0, 0x03, 0x40, 0x02, 0x40, 0x02, // 177
0x48, 0x00, 0x68, 0x00, 0x58, // 178
0x48, 0x00, 0x58, 0x00, 0x68, // 179
0x00, 0x00, 0x10, 0x00, 0x08, // 180
0x00, 0x00, 0xE0, 0x0F, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 181
0x70, 0x00, 0xF8, 0x0F, 0x08, 0x00, 0xF8, 0x0F, 0x08, // 182
0x00, 0x00, 0x40, // 183
0x00, 0x00, 0xC0, 0x01, 0xA8, 0x02, 0xA0, 0x02, 0xA8, 0x02, 0xC0, // 184
0x00, 0x00, 0xF0, 0x03, 0x40, 0x00, 0x80, 0x00, 0xF8, 0x03, 0x08, // 185
0x30, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 186
0x00, 0x00, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, // 187
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0xC0, 0x00, 0x20, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 188
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0x80, 0x00, 0x60, 0x00, 0x50, 0x02, 0x48, 0x03, 0xC0, 0x02, // 189
0x48, 0x00, 0x58, 0x00, 0x68, 0x03, 0x80, 0x00, 0x60, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 190
0x00, 0x00, 0x00, 0x06, 0x00, 0x09, 0xA0, 0x09, 0x00, 0x04, // 191
0x00, 0x00, 0xF0, 0x03, 0x88, 0x00, 0x88, 0x00, 0x88, 0x00, 0xF0, 0x03, // 192
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x88, 0x01, // 193
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 194
0x00, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x18, // 195
0x00, 0x00, 0x00, 0x02, 0xFC, 0x03, 0x04, 0x02, 0xFC, 0x03, 0x00, 0x02, // 196
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x08, 0x02, // 197
0x00, 0x00, 0xB8, 0x03, 0x40, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xB8, 0x03, // 198
0x00, 0x00, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 199
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0xF8, 0x03, // 200
0x00, 0x00, 0xE0, 0x03, 0x08, 0x01, 0x90, 0x00, 0x48, 0x00, 0xE0, 0x03, // 201
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xA0, 0x00, 0x10, 0x01, 0x08, 0x02, // 202
0x00, 0x00, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, // 203
0x00, 0x00, 0xF8, 0x03, 0x10, 0x00, 0x60, 0x00, 0x10, 0x00, 0xF8, 0x03, // 204
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 205
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 206
0x00, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, // 207
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 208
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 209
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 210
0x00, 0x00, 0x38, 0x00, 0x40, 0x02, 0x40, 0x02, 0x40, 0x02, 0xF8, 0x01, // 211
0x00, 0x00, 0x70, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x88, 0x00, 0x70, // 212
0x00, 0x00, 0x18, 0x03, 0xA0, 0x00, 0x40, 0x00, 0xA0, 0x00, 0x18, 0x03, // 213
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, // 214
0x00, 0x00, 0x38, 0x00, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 215
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, // 216
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x06, // 217
0x00, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, // 218
0x00, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, 0xF8, 0x03, // 219
0x00, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, // 220
0x00, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 221
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xF0, 0x01, 0x08, 0x02, 0xF0, 0x01, // 222
0x00, 0x00, 0x30, 0x02, 0x48, 0x01, 0xC8, 0x00, 0x48, 0x00, 0xF8, 0x03, // 223
0x00, 0x00, 0x00, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x03, // 224
0x00, 0x00, 0xE0, 0x01, 0x50, 0x02, 0x50, 0x02, 0x48, 0x02, 0x88, 0x01, // 225
0x00, 0x00, 0xE0, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x40, 0x01, // 226
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x60, // 227
0x00, 0x00, 0x00, 0x02, 0xC0, 0x03, 0x20, 0x02, 0xE0, 0x03, 0x00, 0x02, // 228
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, // 229
0x00, 0x00, 0x60, 0x03, 0x80, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x60, 0x03, // 230
0x00, 0x00, 0x20, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x40, 0x01, // 231
0x00, 0x00, 0xE0, 0x03, 0x00, 0x01, 0x80, 0x00, 0x40, 0x00, 0xE0, 0x03, // 232
0x00, 0x00, 0xE0, 0x03, 0x00, 0x01, 0x98, 0x00, 0x40, 0x00, 0xE0, 0x03, // 233
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 234
0x00, 0x00, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, // 235
0x00, 0x00, 0xE0, 0x03, 0x40, 0x00, 0x80, 0x00, 0x40, 0x00, 0xE0, 0x03, // 236
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0xE0, 0x03, // 237
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 238
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, // 239
0x00, 0x00, 0xE0, 0x03, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 240
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x20, 0x02, 0x40, 0x02, // 241
0x00, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, // 242
0x00, 0x00, 0x60, 0x00, 0x80, 0x02, 0x80, 0x02, 0x80, 0x02, 0xE0, 0x01, // 243
0x00, 0x00, 0xC0, 0x00, 0x20, 0x01, 0xE0, 0x03, 0x20, 0x01, 0xC0, // 244
0x00, 0x00, 0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 245
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, // 246
0x00, 0x00, 0x60, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0xE0, 0x03, // 247
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, // 248
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x06, // 249
0x00, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, // 250
0x00, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, 0xE0, 0x03, // 251
0x00, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, // 252
0x00, 0x00, 0x40, 0x01, 0x20, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x01, // 253
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, 0xC0, 0x01, // 254
0x00, 0x00, 0x40, 0x02, 0xA0, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0xE0, 0x03, // 255
};

Wyświetl plik

@ -6,24 +6,27 @@ const uint8_t SATELLITE_IMAGE[] PROGMEM = {0x00, 0x08, 0x00, 0x1C, 0x00, 0x0E, 0
0xF8, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC8, 0x01, 0x9C, 0x54,
0x0E, 0x52, 0x07, 0x48, 0x02, 0x26, 0x00, 0x10, 0x00, 0x0E};
const uint8_t imgSatellite[] PROGMEM = { 0x70, 0x71, 0x22, 0xFA, 0xFA, 0x22, 0x71, 0x70 };
const uint8_t imgUSB[] PROGMEM = { 0x60, 0x60, 0x30, 0x18, 0x18, 0x18, 0x24, 0x42, 0x42, 0x42, 0x42, 0x7E, 0x24, 0x24, 0x24, 0x3C };
const uint8_t imgPower[] PROGMEM = { 0x40, 0x40, 0x40, 0x58, 0x48, 0x08, 0x08, 0x08, 0x1C, 0x22, 0x22, 0x41, 0x7F, 0x22, 0x22, 0x22 };
const uint8_t imgUser[] PROGMEM = { 0x3C, 0x42, 0x99, 0xA5, 0xA5, 0x99, 0x42, 0x3C };
const uint8_t imgPositionEmpty[] PROGMEM = { 0x20, 0x30, 0x28, 0x24, 0x42, 0xFF };
const uint8_t imgPositionSolid[] PROGMEM = { 0x20, 0x30, 0x38, 0x3C, 0x7E, 0xFF };
const uint8_t imgSatellite[] PROGMEM = {0x70, 0x71, 0x22, 0xFA, 0xFA, 0x22, 0x71, 0x70};
const uint8_t imgUSB[] PROGMEM = {0x60, 0x60, 0x30, 0x18, 0x18, 0x18, 0x24, 0x42, 0x42, 0x42, 0x42, 0x7E, 0x24, 0x24, 0x24, 0x3C};
const uint8_t imgPower[] PROGMEM = {0x40, 0x40, 0x40, 0x58, 0x48, 0x08, 0x08, 0x08,
0x1C, 0x22, 0x22, 0x41, 0x7F, 0x22, 0x22, 0x22};
const uint8_t imgUser[] PROGMEM = {0x3C, 0x42, 0x99, 0xA5, 0xA5, 0x99, 0x42, 0x3C};
const uint8_t imgPositionEmpty[] PROGMEM = {0x20, 0x30, 0x28, 0x24, 0x42, 0xFF};
const uint8_t imgPositionSolid[] PROGMEM = {0x20, 0x30, 0x38, 0x3C, 0x7E, 0xFF};
#if defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS)
const uint8_t imgQuestionL1[] PROGMEM = { 0xff, 0x01, 0x01, 0x32, 0x7b, 0x49, 0x49, 0x6f, 0x26, 0x01, 0x01, 0xff };
const uint8_t imgQuestionL2[] PROGMEM = { 0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f };
const uint8_t imgInfoL1[] PROGMEM = { 0xff, 0x01, 0x01, 0x01, 0x1e, 0x7f, 0x1e, 0x01, 0x01, 0x01, 0x01, 0xff };
const uint8_t imgInfoL2[] PROGMEM = { 0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f };
const uint8_t imgSFL1[] PROGMEM = { 0xb6, 0x8f, 0x19, 0x11, 0x31, 0xe3, 0xc2, 0x01, 0x01, 0xf9, 0xf9, 0x89, 0x89, 0x89, 0x09, 0xeb};
const uint8_t imgSFL2[] PROGMEM = { 0x0e, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x08, 0x00, 0x0f, 0x0f, 0x00, 0x08, 0x08, 0x08, 0x0f};
const uint8_t imgQuestionL1[] PROGMEM = {0xff, 0x01, 0x01, 0x32, 0x7b, 0x49, 0x49, 0x6f, 0x26, 0x01, 0x01, 0xff};
const uint8_t imgQuestionL2[] PROGMEM = {0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f};
const uint8_t imgInfoL1[] PROGMEM = {0xff, 0x01, 0x01, 0x01, 0x1e, 0x7f, 0x1e, 0x01, 0x01, 0x01, 0x01, 0xff};
const uint8_t imgInfoL2[] PROGMEM = {0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f};
const uint8_t imgSFL1[] PROGMEM = {0xb6, 0x8f, 0x19, 0x11, 0x31, 0xe3, 0xc2, 0x01,
0x01, 0xf9, 0xf9, 0x89, 0x89, 0x89, 0x09, 0xeb};
const uint8_t imgSFL2[] PROGMEM = {0x0e, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x08,
0x00, 0x0f, 0x0f, 0x00, 0x08, 0x08, 0x08, 0x0f};
#else
const uint8_t imgInfo[] PROGMEM = { 0xff, 0x81, 0x00, 0xfb, 0xfb, 0x00, 0x81, 0xff };
const uint8_t imgQuestion[] PROGMEM = { 0xbf, 0x41, 0xc0, 0x8b, 0xdb, 0x70, 0xa1, 0xdf };
const uint8_t imgSF[] PROGMEM = { 0xd2, 0xb7, 0xad, 0xbb, 0x92, 0x01, 0xfd, 0xfd, 0x15, 0x85, 0xf5};
const uint8_t imgInfo[] PROGMEM = {0xff, 0x81, 0x00, 0xfb, 0xfb, 0x00, 0x81, 0xff};
const uint8_t imgQuestion[] PROGMEM = {0xbf, 0x41, 0xc0, 0x8b, 0xdb, 0x70, 0xa1, 0xdf};
const uint8_t imgSF[] PROGMEM = {0xd2, 0xb7, 0xad, 0xbb, 0x92, 0x01, 0xfd, 0xfd, 0x15, 0x85, 0xf5};
#endif
#include "img/icon.xbm"

Wyświetl plik

@ -3,9 +3,7 @@
InputBroker *inputBroker;
InputBroker::InputBroker()
{
};
InputBroker::InputBroker(){};
void InputBroker::registerSource(Observable<const InputEvent *> *source)
{
@ -14,7 +12,7 @@ void InputBroker::registerSource(Observable<const InputEvent *> *source)
int InputBroker::handleInputEvent(const InputEvent *event)
{
powerFSM.trigger(EVENT_INPUT);
this->notifyObservers(event);
return 0;
powerFSM.trigger(EVENT_INPUT);
this->notifyObservers(event);
return 0;
}

Wyświetl plik

@ -5,12 +5,11 @@
#define MATRIXKEY 0xFE
typedef struct _InputEvent {
const char* source;
const char *source;
char inputEvent;
char kbchar;
} InputEvent;
class InputBroker :
public Observable<const InputEvent *>
class InputBroker : public Observable<const InputEvent *>
{
CallbackObserver<InputBroker, const InputEvent *> inputEventObserver =
CallbackObserver<InputBroker, const InputEvent *>(this, &InputBroker::handleInputEvent);

Wyświetl plik

@ -8,8 +8,7 @@
* to your device as you wish, but you always need to have separate event
* handlers, thus you need to have a RotaryEncoderInterrupt implementation.
*/
class RotaryEncoderInterruptImpl1 :
public RotaryEncoderInterruptBase
class RotaryEncoderInterruptImpl1 : public RotaryEncoderInterruptBase
{
public:
RotaryEncoderInterruptImpl1();

Wyświetl plik

@ -1,16 +1,13 @@
#include "configuration.h"
#include "UpDownInterruptBase.h"
#include "configuration.h"
UpDownInterruptBase::UpDownInterruptBase(
const char *name)
UpDownInterruptBase::UpDownInterruptBase(const char *name)
{
this->_originName = name;
}
void UpDownInterruptBase::init(
uint8_t pinDown, uint8_t pinUp, uint8_t pinPress,
char eventDown, char eventUp, char eventPressed,
void (*onIntDown)(), void (*onIntUp)(), void (*onIntPress)())
void UpDownInterruptBase::init(uint8_t pinDown, uint8_t pinUp, uint8_t pinPress, char eventDown, char eventUp, char eventPressed,
void (*onIntDown)(), void (*onIntUp)(), void (*onIntPress)())
{
this->_pinDown = pinDown;
this->_pinUp = pinUp;
@ -26,8 +23,7 @@ void UpDownInterruptBase::init(
attachInterrupt(this->_pinDown, onIntDown, RISING);
attachInterrupt(this->_pinUp, onIntUp, RISING);
LOG_DEBUG("GPIO initialized (%d, %d, %d)\n",
this->_pinDown, this->_pinUp, pinPress);
LOG_DEBUG("GPIO initialized (%d, %d, %d)\n", this->_pinDown, this->_pinUp, pinPress);
}
void UpDownInterruptBase::intPressHandler()

Wyświetl plik

@ -1,8 +1,7 @@
#pragma once
#include "UpDownInterruptBase.h"
class UpDownInterruptImpl1 :
public UpDownInterruptBase
class UpDownInterruptImpl1 : public UpDownInterruptBase
{
public:
UpDownInterruptImpl1();

Wyświetl plik

@ -3,15 +3,11 @@
CardKbI2cImpl *cardKbI2cImpl;
CardKbI2cImpl::CardKbI2cImpl() :
KbI2cBase("cardKB")
{
}
CardKbI2cImpl::CardKbI2cImpl() : KbI2cBase("cardKB") {}
void CardKbI2cImpl::init()
{
if (cardkb_found != CARDKB_ADDR)
{
if (cardkb_found != CARDKB_ADDR) {
disable();
return;
}

Wyświetl plik

@ -9,8 +9,7 @@
* to your device as you wish, but you always need to have separate event
* handlers, thus you need to have a RotaryEncoderInterrupt implementation.
*/
class CardKbI2cImpl :
public KbI2cBase
class CardKbI2cImpl : public KbI2cBase
{
public:
CardKbI2cImpl();

Wyświetl plik

@ -12,32 +12,32 @@ KbI2cBase::KbI2cBase(const char *name) : concurrency::OSThread(name)
uint8_t read_from_14004(uint8_t reg, uint8_t *data, uint8_t length)
{
uint8_t readflag = 0;
Wire.beginTransmission(CARDKB_ADDR);
Wire.write(reg);
Wire.endTransmission(); // stop transmitting
delay(20);
Wire.requestFrom(CARDKB_ADDR, (int)length);
int i = 0;
while ( Wire.available() ) // slave may send less than requested
{
data[i++] = Wire.read(); // receive a byte as a proper uint8_t
readflag = 1;
}
return readflag;
uint8_t readflag = 0;
Wire.beginTransmission(CARDKB_ADDR);
Wire.write(reg);
Wire.endTransmission(); // stop transmitting
delay(20);
Wire.requestFrom(CARDKB_ADDR, (int)length);
int i = 0;
while (Wire.available()) // slave may send less than requested
{
data[i++] = Wire.read(); // receive a byte as a proper uint8_t
readflag = 1;
}
return readflag;
}
void write_to_14004(uint8_t reg, uint8_t data)
{
Wire.beginTransmission(CARDKB_ADDR);
Wire.write(reg);
Wire.write(data);
Wire.endTransmission(); // stop transmitting
Wire.beginTransmission(CARDKB_ADDR);
Wire.write(reg);
Wire.write(data);
Wire.endTransmission(); // stop transmitting
}
int32_t KbI2cBase::runOnce()
{
if (cardkb_found != CARDKB_ADDR){
if (cardkb_found != CARDKB_ADDR) {
// Input device is not detected.
return INT32_MAX;
}
@ -48,7 +48,7 @@ int32_t KbI2cBase::runOnce()
uint8_t PrintDataBuf = 0;
if (read_from_14004(0x01, rDataBuf, 0x04) == 1) {
for (uint8_t aCount = 0; aCount < 0x04; aCount++) {
for (uint8_t bCount = 0; bCount < 0x04; bCount++ ) {
for (uint8_t bCount = 0; bCount < 0x04; bCount++) {
if (((rDataBuf[aCount] >> bCount) & 0x01) == 0x01) {
PrintDataBuf = aCount * 0x04 + bCount + 1;
}
@ -97,7 +97,7 @@ int32_t KbI2cBase::runOnce()
case 0x0d: // Enter
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_SELECT;
break;
case 0x00: //nopress
case 0x00: // nopress
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
break;
default: // all other keys

Wyświetl plik

@ -1,11 +1,9 @@
#pragma once
#include "SinglePortModule.h" // TODO: what header file to include?
#include "InputBroker.h"
#include "SinglePortModule.h" // TODO: what header file to include?
class KbI2cBase :
public Observable<const InputEvent *>,
public concurrency::OSThread
class KbI2cBase : public Observable<const InputEvent *>, public concurrency::OSThread
{
public:
explicit KbI2cBase(const char *name);

Wyświetl plik

@ -120,7 +120,7 @@ CryptoKey Channels::getKey(ChannelIndex chIndex)
else if (oemStore.oem_aes_key.size > 1) {
// Use the OEM key
LOG_DEBUG("Using OEM Key with %d bytes\n", oemStore.oem_aes_key.size);
memcpy(k.bytes, oemStore.oem_aes_key.bytes , oemStore.oem_aes_key.size);
memcpy(k.bytes, oemStore.oem_aes_key.bytes, oemStore.oem_aes_key.size);
k.length = oemStore.oem_aes_key.size;
// Bump up the last byte of PSK as needed
uint8_t *last = k.bytes + oemStore.oem_aes_key.size - 1;
@ -196,7 +196,7 @@ Channel &Channels::getByIndex(ChannelIndex chIndex)
Channel *ch = channelFile.channels + chIndex;
return *ch;
} else {
LOG_ERROR("Invalid channel index %d > %d, malformed packet received?\n", chIndex , channelFile.channels_count);
LOG_ERROR("Invalid channel index %d > %d, malformed packet received?\n", chIndex, channelFile.channels_count);
static Channel *ch = (Channel *)malloc(sizeof(Channel));
memset(ch, 0, sizeof(Channel));
@ -207,7 +207,7 @@ Channel &Channels::getByIndex(ChannelIndex chIndex)
}
}
Channel &Channels::getByName(const char* chName)
Channel &Channels::getByName(const char *chName)
{
for (ChannelIndex i = 0; i < getNumChannels(); i++) {
if (strcasecmp(getGlobalId(i), chName) == 0) {
@ -267,8 +267,7 @@ const char *Channels::getName(size_t chIndex)
channelName = "Invalid";
break;
}
}
else {
} else {
channelName = "Custom";
}
}

Wyświetl plik

@ -29,7 +29,6 @@ class Channels
int16_t hashes[MAX_NUM_CHANNELS] = {};
public:
Channels() {}
/// Well known channel names
@ -40,8 +39,8 @@ class Channels
/** Return the Channel for a specified index */
Channel &getByIndex(ChannelIndex chIndex);
/** Return the Channel for a specified name, return primary if not found. */
Channel &getByName(const char* chName);
/** Return the Channel for a specified name, return primary if not found. */
Channel &getByName(const char *chName);
/** Using the index inside the channel, update the specified channel's settings and role. If this channel is being promoted
* to be primary, force all other channels to be secondary.

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "CryptoEngine.h"
#include "configuration.h"
void CryptoEngine::setKey(const CryptoKey &k)
{

Wyświetl plik

@ -31,10 +31,10 @@ void FloodingRouter::sniffReceived(const MeshPacket *p, const Routing *c)
{
bool isAck = ((c && c->error_reason == Routing_Error_NONE)); // consider only ROUTING_APP message without error as ACK
if (isAck && p->to != getNodeNum()) {
// do not flood direct message that is ACKed
// do not flood direct message that is ACKed
LOG_DEBUG("Receiving an ACK not for me, but don't need to rebroadcast this direct message anymore.\n");
Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM
}
Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM
}
if ((p->to != getNodeNum()) && (p->hop_limit > 0) && (getFrom(p) != getNodeNum())) {
if (p->id != 0) {
if (config.device.role != Config_DeviceConfig_Role_CLIENT_MUTE) {

Wyświetl plik

@ -1,9 +1,9 @@
#include "SX126xInterface.h"
#include "SX126xInterface.cpp"
#include "SX128xInterface.h"
#include "SX126xInterface.h"
#include "SX128xInterface.cpp"
#include "api/ServerAPI.h"
#include "SX128xInterface.h"
#include "api/ServerAPI.cpp"
#include "api/ServerAPI.h"
// We need this declaration for proper linking in derived classes
template class SX126xInterface<SX1262>;

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "LLCC68Interface.h"
#include "configuration.h"
#include "error.h"
LLCC68Interface::LLCC68Interface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy,

Wyświetl plik

@ -1,8 +1,8 @@
#include "configuration.h"
#include "MeshModule.h"
#include "Channels.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "configuration.h"
#include "modules/RoutingModule.h"
#include <assert.h>
@ -106,8 +106,8 @@ void MeshModule::callPlugins(const MeshPacket &mp, RxSource src)
/// Is the channel this packet arrived on acceptable? (security check)
/// Note: we can't know channel names for encrypted packets, so those are NEVER sent to boundChannel modules
/// Also: if a packet comes in on the local PC interface, we don't check for bound channels, because it is TRUSTED and it needs to
/// to be able to fetch the initial admin packets without yet knowing any channels.
/// Also: if a packet comes in on the local PC interface, we don't check for bound channels, because it is TRUSTED and
/// it needs to to be able to fetch the initial admin packets without yet knowing any channels.
bool rxChannelOk = !pi.boundChannel || (mp.from == 0) || (strcasecmp(ch->settings.name, pi.boundChannel) == 0);
@ -161,7 +161,7 @@ void MeshModule::callPlugins(const MeshPacket &mp, RxSource src)
printPacket("Sending response", currentReply);
service.sendToMesh(currentReply);
currentReply = NULL;
} else if(mp.from != ourNodeNum) {
} else if (mp.from != ourNodeNum) {
// Note: if the message started with the local node we don't want to send a no response reply
// No one wanted to reply to this requst, tell the requster that happened
@ -175,9 +175,8 @@ void MeshModule::callPlugins(const MeshPacket &mp, RxSource src)
}
if (!moduleFound)
LOG_DEBUG("No modules interested in portnum=%d, src=%s\n",
mp.decoded.portnum,
(src == RX_SRC_LOCAL) ? "LOCAL":"REMOTE");
LOG_DEBUG("No modules interested in portnum=%d, src=%s\n", mp.decoded.portnum,
(src == RX_SRC_LOCAL) ? "LOCAL" : "REMOTE");
}
MeshPacket *MeshModule::allocReply()
@ -235,14 +234,12 @@ std::vector<MeshModule *> MeshModule::GetMeshModulesWithUIFrames()
return modulesWithUIFrames;
}
void MeshModule::observeUIEvents(
Observer<const UIFrameEvent *> *observer)
void MeshModule::observeUIEvents(Observer<const UIFrameEvent *> *observer)
{
if (modules) {
for (auto i = modules->begin(); i != modules->end(); ++i) {
auto &pi = **i;
Observable<const UIFrameEvent *> *observable =
pi.getUIFrameObservable();
Observable<const UIFrameEvent *> *observable = pi.getUIFrameObservable();
if (observable != NULL) {
LOG_DEBUG("Module wants a UI Frame\n");
observer->observe(observable);
@ -251,24 +248,19 @@ void MeshModule::observeUIEvents(
}
}
AdminMessageHandleResult MeshModule::handleAdminMessageForAllPlugins(const MeshPacket &mp, AdminMessage *request, AdminMessage *response)
AdminMessageHandleResult MeshModule::handleAdminMessageForAllPlugins(const MeshPacket &mp, AdminMessage *request,
AdminMessage *response)
{
AdminMessageHandleResult handled = AdminMessageHandleResult::NOT_HANDLED;
if (modules) {
for (auto i = modules->begin(); i != modules->end(); ++i) {
auto &pi = **i;
AdminMessageHandleResult h = pi.handleAdminMessageForModule(mp, request, response);
if (h == AdminMessageHandleResult::HANDLED_WITH_RESPONSE)
{
if (h == AdminMessageHandleResult::HANDLED_WITH_RESPONSE) {
// In case we have a response it always has priority.
LOG_DEBUG("Reply prepared by module '%s' of variant: %d\n",
pi.name,
response->which_payload_variant);
LOG_DEBUG("Reply prepared by module '%s' of variant: %d\n", pi.name, response->which_payload_variant);
handled = h;
}
else if ((handled != AdminMessageHandleResult::HANDLED_WITH_RESPONSE) &&
(h == AdminMessageHandleResult::HANDLED))
{
} else if ((handled != AdminMessageHandleResult::HANDLED_WITH_RESPONSE) && (h == AdminMessageHandleResult::HANDLED)) {
// In case the message is handled it should be populated, but will not overwrite
// a result with response.
handled = h;

Wyświetl plik

@ -10,15 +10,14 @@
#endif
/** handleReceived return enumeration
*
*
* Use ProcessMessage::CONTINUE to allows other modules to process a message.
*
*
* Use ProcessMessage::STOP to stop further message processing.
*/
enum class ProcessMessage
{
CONTINUE = 0,
STOP = 1,
enum class ProcessMessage {
CONTINUE = 0,
STOP = 1,
};
/**
@ -27,8 +26,7 @@ enum class ProcessMessage
* If response is also prepared for the request, then HANDLED_WITH_RESPONSE
* should be returned.
*/
enum class AdminMessageHandleResult
{
enum class AdminMessageHandleResult {
NOT_HANDLED = 0,
HANDLED = 1,
HANDLED_WITH_RESPONSE = 2,
@ -70,10 +68,13 @@ class MeshModule
static std::vector<MeshModule *> GetMeshModulesWithUIFrames();
static void observeUIEvents(Observer<const UIFrameEvent *> *observer);
static AdminMessageHandleResult handleAdminMessageForAllPlugins(
const MeshPacket &mp, AdminMessage *request, AdminMessage *response);
static AdminMessageHandleResult handleAdminMessageForAllPlugins(const MeshPacket &mp, AdminMessage *request,
AdminMessage *response);
#if HAS_SCREEN
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { return; }
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
return;
}
#endif
protected:
const char *name;
@ -127,9 +128,13 @@ class MeshModule
/** Called to handle a particular incoming message
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for it
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for
it
*/
virtual ProcessMessage handleReceived(const MeshPacket &mp) { return ProcessMessage::CONTINUE; }
virtual ProcessMessage handleReceived(const MeshPacket &mp)
{
return ProcessMessage::CONTINUE;
}
/** Messages can be received that have the want_response bit set. If set, this callback will be invoked
* so that subclasses can (optionally) send a response back to the original sender.
@ -142,26 +147,35 @@ class MeshModule
/***
* @return true if you want to be alloced a UI screen frame
*/
virtual bool wantUIFrame() { return false; }
virtual Observable<const UIFrameEvent *>* getUIFrameObservable() { return NULL; }
virtual bool wantUIFrame()
{
return false;
}
virtual Observable<const UIFrameEvent *> *getUIFrameObservable()
{
return NULL;
}
MeshPacket *allocAckNak(Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex);
/// Send an error response for the specified packet.
MeshPacket *allocErrorResponse(Routing_Error err, const MeshPacket *p);
/**
* @brief An admin message arrived to AdminModule. Module was asked whether it want to handle the request.
*
* @param mp The mesh packet arrived.
* @param request The AdminMessage request extracted from the packet.
* @param response The prepared response
* @return AdminMessageHandleResult
* HANDLED if message was handled
* HANDLED_WITH_RESPONSE if a response is also prepared and to be sent.
*/
virtual AdminMessageHandleResult handleAdminMessageForModule(
const MeshPacket &mp, AdminMessage *request, AdminMessage *response) { return AdminMessageHandleResult::NOT_HANDLED; };
/**
* @brief An admin message arrived to AdminModule. Module was asked whether it want to handle the request.
*
* @param mp The mesh packet arrived.
* @param request The AdminMessage request extracted from the packet.
* @param response The prepared response
* @return AdminMessageHandleResult
* HANDLED if message was handled
* HANDLED_WITH_RESPONSE if a response is also prepared and to be sent.
*/
virtual AdminMessageHandleResult handleAdminMessageForModule(const MeshPacket &mp, AdminMessage *request,
AdminMessage *response)
{
return AdminMessageHandleResult::NOT_HANDLED;
};
private:
/**

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "MeshPacketQueue.h"
#include "configuration.h"
#include <assert.h>
#include <algorithm>
@ -26,7 +26,8 @@ bool CompareMeshPacketFunc(const MeshPacket *p1, const MeshPacket *p2)
MeshPacketQueue::MeshPacketQueue(size_t _maxLen) : maxLen(_maxLen) {}
bool MeshPacketQueue::empty() {
bool MeshPacketQueue::empty()
{
return queue.empty();
}
@ -40,8 +41,9 @@ void fixPriority(MeshPacket *p)
if (p->priority == MeshPacket_Priority_UNSET) {
// if acks give high priority
// if a reliable message give a bit higher default priority
p->priority = (p->decoded.portnum == PortNum_ROUTING_APP) ? MeshPacket_Priority_ACK :
(p->want_ack ? MeshPacket_Priority_RELIABLE : MeshPacket_Priority_DEFAULT);
p->priority = (p->decoded.portnum == PortNum_ROUTING_APP)
? MeshPacket_Priority_ACK
: (p->want_ack ? MeshPacket_Priority_RELIABLE : MeshPacket_Priority_DEFAULT);
}
}
@ -99,7 +101,8 @@ MeshPacket *MeshPacketQueue::remove(NodeNum from, PacketId id)
}
/** Attempt to find and remove a packet from this queue. Returns the packet which was removed from the queue */
bool MeshPacketQueue::replaceLowerPriorityPacket(MeshPacket *p) {
bool MeshPacketQueue::replaceLowerPriorityPacket(MeshPacket *p)
{
std::sort_heap(queue.begin(), queue.end(), &CompareMeshPacketFunc); // sort ascending based on priority (0 -> 127)
// find first packet which does not compare less (in priority) than parameter packet
@ -119,7 +122,7 @@ bool MeshPacketQueue::replaceLowerPriorityPacket(MeshPacket *p) {
if (getPriority(p) > getPriority(*low)) {
packetPool.release(*low); // deallocate and drop the packet we're replacing
*low = p; // replace low-pri packet at this position with incoming packet with higher priority
*low = p; // replace low-pri packet at this position with incoming packet with higher priority
}
std::make_heap(queue.begin(), queue.end(), &CompareMeshPacketFunc);

Wyświetl plik

@ -4,7 +4,6 @@
#include <queue>
/**
* A priority queue of packets
*/
@ -13,7 +12,8 @@ class MeshPacketQueue
size_t maxLen;
std::vector<MeshPacket *> queue;
/** Replace a lower priority package in the queue with 'mp' (provided there are lower pri packages). Return true if replaced. */
/** Replace a lower priority package in the queue with 'mp' (provided there are lower pri packages). Return true if replaced.
*/
bool replaceLowerPriorityPacket(MeshPacket *mp);
public:

Wyświetl plik

@ -2,9 +2,9 @@
#include <assert.h>
#include <string>
#include "GPS.h"
#include "../concurrency/Periodic.h"
#include "BluetoothCommon.h" // needed for updateBatteryLevel, FIXME, eventually when we pull mesh out into a lib we shouldn't be whacking bluetooth from here
#include "GPS.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
@ -59,7 +59,7 @@ Allocator<QueueStatus> &queueStatusPool = staticQueueStatusPool;
MeshService::MeshService() : toPhoneQueue(MAX_RX_TOPHONE), toPhoneQueueStatusQueue(MAX_RX_TOPHONE)
{
lastQueueStatus = { 0, 0, 16, 0 };
lastQueueStatus = {0, 0, 16, 0};
}
void MeshService::init()
@ -132,7 +132,7 @@ void MeshService::reloadOwner(bool shouldSave)
*/
void MeshService::handleToRadio(MeshPacket &p)
{
#ifdef ARCH_PORTDUINO
#ifdef ARCH_PORTDUINO
// Simulates device is receiving a packet via the LoRa chip
if (p.decoded.portnum == PortNum_SIMULATOR_APP) {
// Simulator packet (=Compressed packet) is encapsulated in a MeshPacket, so need to unwrap first
@ -140,21 +140,22 @@ void MeshService::handleToRadio(MeshPacket &p)
Compressed *decoded = NULL;
if (p.which_payload_variant == MeshPacket_decoded_tag) {
memset(&scratch, 0, sizeof(scratch));
p.decoded.payload.size = pb_decode_from_bytes(p.decoded.payload.bytes, p.decoded.payload.size, &Compressed_msg, &scratch);
p.decoded.payload.size =
pb_decode_from_bytes(p.decoded.payload.bytes, p.decoded.payload.size, &Compressed_msg, &scratch);
if (p.decoded.payload.size) {
decoded = &scratch;
// Extract the original payload and replace
memcpy(&p.decoded.payload, &decoded->data, sizeof(decoded->data));
// Switch the port from PortNum_SIMULATOR_APP back to the original PortNum
// Switch the port from PortNum_SIMULATOR_APP back to the original PortNum
p.decoded.portnum = decoded->portnum;
} else
LOG_ERROR("Error decoding protobuf for simulator message!\n");
}
// Let SimRadio receive as if it did via its LoRa chip
SimRadio::instance->startReceive(&p);
return;
SimRadio::instance->startReceive(&p);
return;
}
#endif
#endif
if (p.from != 0) { // We don't let phones assign nodenums to their sent messages
LOG_WARN("phone tried to pick a nodenum, we don't allow that.\n");
p.from = 0;
@ -323,7 +324,7 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
return 0;
}
bool MeshService::isToPhoneQueueEmpty()
bool MeshService::isToPhoneQueueEmpty()
{
return toPhoneQueue.isEmpty();
}

Wyświetl plik

@ -80,7 +80,7 @@ class MeshService
/** The radioConfig object just changed, call this to force the hw to change to the new settings
* @return true if client devices should be sent a new set of radio configs
*/
bool reloadConfig(int saveWhat=SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS);
bool reloadConfig(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS);
/// The owner User record just got updated, update our node DB and broadcast the info into the mesh
void reloadOwner(bool shouldSave = true);
@ -100,7 +100,7 @@ class MeshService
/// Pull the latest power and time info into my nodeinfo
NodeInfo *refreshMyNodeInfo();
/// Send a packet to the phone
/// Send a packet to the phone
void sendToPhone(MeshPacket *p);
bool isToPhoneQueueEmpty();

Wyświetl plik

@ -19,9 +19,9 @@ typedef uint32_t PacketId; // A packet sequence number
* Source of a received message
*/
enum RxSource {
RX_SRC_LOCAL, // message was generated locally
RX_SRC_RADIO, // message was received from radio mesh
RX_SRC_USER // message was received from end-user device
RX_SRC_LOCAL, // message was generated locally
RX_SRC_RADIO, // message was received from radio mesh
RX_SRC_USER // message was received from end-user device
};
/**

Wyświetl plik

@ -13,9 +13,9 @@
#include "error.h"
#include "main.h"
#include "mesh-pb-constants.h"
#include <ErriezCRC32.h>
#include <pb_decode.h>
#include <pb_encode.h>
#include <ErriezCRC32.h>
#ifdef ARCH_ESP32
#include "mesh/http/WiFiAPClient.h"
@ -81,7 +81,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
radioGeneration++;
if (factory_reset) {
didFactoryReset = factoryReset();
didFactoryReset = factoryReset();
}
if (channelFile.channels_count != MAX_NUM_CHANNELS) {
@ -121,7 +121,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
return didFactoryReset;
}
bool NodeDB::factoryReset()
bool NodeDB::factoryReset()
{
LOG_INFO("Performing factory reset!\n");
// first, remove the "/prefs" (this removes most prefs)
@ -160,8 +160,9 @@ void NodeDB::installDefaultConfig()
config.has_power = true;
config.has_network = true;
config.has_bluetooth = true;
config.lora.tx_enabled = true; // FIXME: maybe false in the future, and setting region to enable it. (unset region forces it off)
config.lora.override_duty_cycle = false;
config.lora.tx_enabled =
true; // FIXME: maybe false in the future, and setting region to enable it. (unset region forces it off)
config.lora.override_duty_cycle = false;
config.lora.region = Config_LoRaConfig_RegionCode_UNSET;
config.lora.modem_preset = Config_LoRaConfig_ModemPreset_LONG_FAST;
config.lora.hop_limit = HOP_RELIABLE;
@ -178,14 +179,16 @@ void NodeDB::installDefaultConfig()
#else
bool hasScreen = screen_found;
#endif
config.bluetooth.mode = hasScreen ? Config_BluetoothConfig_PairingMode_RANDOM_PIN : Config_BluetoothConfig_PairingMode_FIXED_PIN;
config.bluetooth.mode =
hasScreen ? Config_BluetoothConfig_PairingMode_RANDOM_PIN : Config_BluetoothConfig_PairingMode_FIXED_PIN;
// for backward compat, default position flags are ALT+MSL
config.position.position_flags = (Config_PositionConfig_PositionFlags_ALTITUDE | Config_PositionConfig_PositionFlags_ALTITUDE_MSL);
config.position.position_flags =
(Config_PositionConfig_PositionFlags_ALTITUDE | Config_PositionConfig_PositionFlags_ALTITUDE_MSL);
initConfigIntervals();
}
void NodeDB::initConfigIntervals()
void NodeDB::initConfigIntervals()
{
config.position.gps_update_interval = default_gps_update_interval;
config.position.gps_attempt_time = default_gps_attempt_time;
@ -196,7 +199,7 @@ void NodeDB::initConfigIntervals()
config.power.min_wake_secs = default_min_wake_secs;
config.power.sds_secs = default_sds_secs;
config.power.wait_bluetooth_secs = default_wait_bluetooth_secs;
config.display.screen_on_secs = default_screen_on_secs;
}
@ -204,7 +207,7 @@ void NodeDB::installDefaultModuleConfig()
{
LOG_INFO("Installing default ModuleConfig\n");
memset(&moduleConfig, 0, sizeof(ModuleConfig));
moduleConfig.version = DEVICESTATE_CUR_VER;
moduleConfig.has_mqtt = true;
moduleConfig.has_range_test = true;
@ -221,7 +224,7 @@ void NodeDB::installDefaultModuleConfig()
initModuleConfigIntervals();
}
void NodeDB::initModuleConfigIntervals()
void NodeDB::initModuleConfigIntervals()
{
moduleConfig.telemetry.device_update_interval = default_broadcast_interval_secs;
moduleConfig.telemetry.environment_update_interval = default_broadcast_interval_secs;
@ -247,7 +250,7 @@ void NodeDB::installDefaultDeviceState()
memset(&devicestate, 0, sizeof(DeviceState));
*numNodes = 0;
// init our devicestate with valid flags so protobuf writing/reading will work
devicestate.has_my_node = true;
devicestate.has_owner = true;
@ -285,7 +288,8 @@ void NodeDB::init()
myNodeInfo.max_channels = MAX_NUM_CHANNELS; // tell others the max # of channels we can understand
myNodeInfo.error_code = CriticalErrorCode_NONE; // For the error code, only show values from this boot (discard value from flash)
myNodeInfo.error_code =
CriticalErrorCode_NONE; // For the error code, only show values from this boot (discard value from flash)
myNodeInfo.error_address = 0;
// likewise - we always want the app requirements to come from the running appload
@ -364,7 +368,6 @@ static const char *moduleConfigFileName = "/prefs/module.proto";
static const char *channelFileName = "/prefs/channels.proto";
static const char *oemConfigFile = "/oem/oem.proto";
/** Load a protobuf from a file, return true for success */
bool NodeDB::loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, void *dest_struct)
{
@ -422,7 +425,8 @@ void NodeDB::loadFromDisk()
}
}
if (!loadProto(moduleConfigFileName, LocalModuleConfig_size, sizeof(LocalModuleConfig), &LocalModuleConfig_msg, &moduleConfig)) {
if (!loadProto(moduleConfigFileName, LocalModuleConfig_size, sizeof(LocalModuleConfig), &LocalModuleConfig_msg,
&moduleConfig)) {
installDefaultModuleConfig(); // Our in RAM copy might now be corrupt
} else {
if (moduleConfig.version < DEVICESTATE_MIN_VER) {
@ -478,9 +482,9 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_
#ifdef ARCH_NRF52
static uint8_t failedCounter = 0;
failedCounter++;
if(failedCounter >= 2){
if (failedCounter >= 2) {
FSCom.format();
//After formatting, the device needs to be restarted
// After formatting, the device needs to be restarted
nodeDB.resetRadioConfig(true);
}
#endif
@ -501,7 +505,7 @@ void NodeDB::saveChannelsToDisk()
}
}
void NodeDB::saveDeviceStateToDisk()
void NodeDB::saveDeviceStateToDisk()
{
if (!devicestate.no_save) {
#ifdef FSCom
@ -599,7 +603,7 @@ void NodeDB::updatePosition(uint32_t nodeId, const Position &p, RxSource src)
if (src == RX_SRC_LOCAL) {
// Local packet, fully authoritative
LOG_INFO("updatePosition LOCAL pos@%x, time=%u, latI=%d, lonI=%d, alt=%d\n", p.timestamp, p.time, p.latitude_i,
p.longitude_i, p.altitude);
p.longitude_i, p.altitude);
info->position = p;
} else if ((p.time > 0) && !p.latitude_i && !p.longitude_i && !p.timestamp && !p.location_source) {

Wyświetl plik

@ -58,7 +58,8 @@ class NodeDB
void init();
/// write to flash
void saveToDisk(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS), saveChannelsToDisk(), saveDeviceStateToDisk();
void saveToDisk(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS),
saveChannelsToDisk(), saveDeviceStateToDisk();
/** Reinit radio config if needed, because either:
* a) sometimes a buggy android app might send us bogus settings or
@ -122,7 +123,7 @@ class NodeDB
size_t getNumOnlineNodes();
void initConfigIntervals(), initModuleConfigIntervals(), resetNodes();
bool factoryReset();
bool loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, void *dest_struct);
@ -140,13 +141,11 @@ class NodeDB
newStatus.notifyObservers(&status);
}
/// read our db from flash
void loadFromDisk();
/// Reinit device state from scratch (not loading from disk)
void installDefaultDeviceState(), installDefaultChannels(), installDefaultConfig(),
installDefaultModuleConfig();
void installDefaultDeviceState(), installDefaultChannels(), installDefaultConfig(), installDefaultModuleConfig();
};
/**
@ -203,13 +202,15 @@ extern NodeDB nodeDB;
inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval)
{
if (configuredInterval > 0) return configuredInterval * 1000;
if (configuredInterval > 0)
return configuredInterval * 1000;
return default_broadcast_interval_secs * 1000;
}
inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval)
{
if (configuredInterval > 0) return configuredInterval * 1000;
if (configuredInterval > 0)
return configuredInterval * 1000;
return defaultInterval * 1000;
}
@ -218,4 +219,7 @@ inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t d
*/
extern uint32_t radioGeneration;
#define Module_Config_size (ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + ModuleConfig_TelemetryConfig_size + ModuleConfig_size)
#define Module_Config_size \
(ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + \
ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \
ModuleConfig_TelemetryConfig_size + ModuleConfig_size)

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "PacketHistory.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
PacketHistory::PacketHistory()
@ -26,10 +26,10 @@ bool PacketHistory::wasSeenRecently(const MeshPacket *p, bool withUpdate)
r.rxTimeMsec = now;
auto found = recentPackets.find(r);
bool seenRecently = (found != recentPackets.end()); // found not equal to .end() means packet was seen recently
bool seenRecently = (found != recentPackets.end()); // found not equal to .end() means packet was seen recently
if (seenRecently && (now - found->rxTimeMsec) >= FLOOD_EXPIRE_TIME) { // Check whether found packet has already expired
recentPackets.erase(found); // Erase and pretend packet has not been seen recently
recentPackets.erase(found); // Erase and pretend packet has not been seen recently
found = recentPackets.end();
seenRecently = false;
}
@ -58,12 +58,13 @@ bool PacketHistory::wasSeenRecently(const MeshPacket *p, bool withUpdate)
/**
* Iterate through all recent packets, and remove all older than FLOOD_EXPIRE_TIME
*/
void PacketHistory::clearExpiredRecentPackets() {
void PacketHistory::clearExpiredRecentPackets()
{
uint32_t now = millis();
LOG_DEBUG("recentPackets size=%ld\n", recentPackets.size());
for (auto it = recentPackets.begin(); it != recentPackets.end(); ) {
for (auto it = recentPackets.begin(); it != recentPackets.end();) {
if ((now - it->rxTimeMsec) >= FLOOD_EXPIRE_TIME) {
it = recentPackets.erase(it); // erase returns iterator pointing to element immediately following the one erased
} else {

Wyświetl plik

@ -1,4 +1,2 @@
#include "configuration.h"
#include "ProtobufModule.h"
#include "configuration.h"

Wyświetl plik

@ -22,8 +22,6 @@ template <class T> class ProtobufModule : protected SinglePortModule
}
protected:
/**
* Handle a received message, the data field in the message is already decoded and is provided
*
@ -62,7 +60,8 @@ template <class T> class ProtobufModule : protected SinglePortModule
private:
/** Called to handle a particular incoming message
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for it
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for
it
*/
virtual ProcessMessage handleReceived(const MeshPacket &mp) override
{
@ -70,8 +69,7 @@ template <class T> class ProtobufModule : protected SinglePortModule
// it would be better to update even if the message was destined to others.
auto &p = mp.decoded;
LOG_INFO("Received %s from=0x%0x, id=0x%x, portnum=%d, payloadlen=%d\n", name, mp.from, mp.id, p.portnum,
p.payload.size);
LOG_INFO("Received %s from=0x%0x, id=0x%x, portnum=%d, payloadlen=%d\n", name, mp.from, mp.id, p.portnum, p.payload.size);
T scratch;
T *decoded = NULL;

Wyświetl plik

@ -1,7 +1,7 @@
#include "configuration.h"
#include "RF95Interface.h"
#include "MeshRadio.h" // kinda yucky, but we need to know which region we are in
#include "RadioLibRF95.h"
#include "configuration.h"
#include "error.h"
#define MAX_POWER 20
@ -70,9 +70,9 @@ bool RF95Interface::init()
int res = lora->begin(getFreq(), bw, sf, cr, syncWord, power, currentLimit, preambleLength);
LOG_INFO("RF95 init result %d\n", res);
LOG_INFO("Frequency set to %f\n", getFreq());
LOG_INFO("Bandwidth set to %f\n", bw);
LOG_INFO("Power output set to %d\n", power);
LOG_INFO("Frequency set to %f\n", getFreq());
LOG_INFO("Bandwidth set to %f\n", bw);
LOG_INFO("Power output set to %d\n", power);
// current limit was removed from module' ctor
// override default value (60 mA)
@ -129,7 +129,7 @@ bool RF95Interface::reconfigure()
if (power > MAX_POWER) // This chip has lower power limits than some
power = MAX_POWER;
err = lora->setOutputPower(power);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_INVALID_RADIO_SETTING);
@ -146,7 +146,6 @@ void RF95Interface::addReceiveMetadata(MeshPacket *mp)
{
mp->rx_snr = lora->getSNR();
mp->rx_rssi = lround(lora->getRSSI());
}
void RF95Interface::setStandby()
@ -186,15 +185,15 @@ bool RF95Interface::isChannelActive()
// check if we can detect a LoRa preamble on the current channel
int16_t result;
setTransmitEnable(false);
setStandby(); // needed for smooth transition
setStandby(); // needed for smooth transition
result = lora->scanChannel();
if (result == RADIOLIB_PREAMBLE_DETECTED) {
// LOG_DEBUG("Channel is busy!\n");
return true;
}
assert(result != RADIOLIB_ERR_WRONG_MODEM);
// LOG_DEBUG("Channel is free!\n");
return false;
}

Wyświetl plik

@ -13,8 +13,8 @@ class RF95Interface : public RadioLibInterface
public:
RF95Interface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, SPIClass &spi);
//TODO: Verify that this irq flag works with RFM95 / SX1276 radios the way it used to
// TODO: Verify that this irq flag works with RFM95 / SX1276 radios the way it used to
bool isIRQPending() override { return lora->getIRQFlags() & RADIOLIB_SX127X_MASK_IRQ_FLAG_VALID_HEADER; }
/// Initialise the Driver transport hardware and software.

Wyświetl plik

@ -11,10 +11,10 @@
#include <pb_decode.h>
#include <pb_encode.h>
#define RDEF(name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, frequency_switching, wide_lora) \
#define RDEF(name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, frequency_switching, wide_lora) \
{ \
Config_LoRaConfig_RegionCode_##name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, \
frequency_switching, wide_lora, #name \
frequency_switching, wide_lora, #name \
}
const RegionInfo regions[] = {
@ -38,9 +38,9 @@ const RegionInfo regions[] = {
Special Note:
The link above describes LoRaWAN's band plan, stating a power limit of 16 dBm. This is their own suggested specification,
we do not need to follow it. The European Union regulations clearly state that the power limit for this frequency range is 500 mW, or 27 dBm.
It also states that we can use interference avoidance and spectrum access techniques to avoid a duty cycle.
(Please refer to section 4.21 in the following document)
we do not need to follow it. The European Union regulations clearly state that the power limit for this frequency range is
500 mW, or 27 dBm. It also states that we can use interference avoidance and spectrum access techniques to avoid a duty
cycle. (Please refer to section 4.21 in the following document)
https://ec.europa.eu/growth/tools-databases/tris/index.cfm/ro/search/?trisaction=search.detail&year=2021&num=528&dLang=EN
*/
RDEF(EU_868, 869.4f, 869.65f, 10, 0, 27, false, false, false),
@ -94,7 +94,7 @@ const RegionInfo regions[] = {
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
*/
RDEF(TH, 920.0f, 925.0f, 100, 0, 16, true, false, false),
/*
433,05-434,7 Mhz 10 mW
https://nkrzi.gov.ua/images/upload/256/5810/PDF_UUZ_19_01_2016.pdf
@ -178,7 +178,7 @@ uint32_t RadioInterface::getPacketTime(uint32_t pl)
uint32_t RadioInterface::getPacketTime(MeshPacket *p)
{
uint32_t pl = 0;
if(p->which_payload_variant == MeshPacket_encrypted_tag) {
if (p->which_payload_variant == MeshPacket_encrypted_tag) {
pl = p->encrypted.size + sizeof(PacketHeader);
} else {
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &Data_msg, &p->decoded);
@ -197,7 +197,7 @@ uint32_t RadioInterface::getRetransmissionMsec(const MeshPacket *p)
float channelUtil = airTime->channelUtilizationPercent();
uint8_t CWsize = map(channelUtil, 0, 100, CWmin, CWmax);
// Assuming we pick max. of CWsize and there will be a receiver with SNR at half the range
return 2*packetAirtime + (pow(2, CWsize) + pow(2, int((CWmax+CWmin)/2))) * slotTimeMsec + PROCESSING_TIME_MSEC;
return 2 * packetAirtime + (pow(2, CWsize) + pow(2, int((CWmax + CWmin) / 2))) * slotTimeMsec + PROCESSING_TIME_MSEC;
}
/** The delay to use when we want to send something */
@ -226,9 +226,8 @@ uint32_t RadioInterface::getTxDelayMsecWeighted(float snr)
uint32_t delay = 0;
uint8_t CWsize = map(snr, SNR_MIN, SNR_MAX, CWmin, CWmax);
// LOG_DEBUG("rx_snr of %f so setting CWsize to:%d\n", snr, CWsize);
if (config.device.role == Config_DeviceConfig_Role_ROUTER ||
config.device.role == Config_DeviceConfig_Role_ROUTER_CLIENT) {
delay = random(0, 2*CWsize) * slotTimeMsec;
if (config.device.role == Config_DeviceConfig_Role_ROUTER || config.device.role == Config_DeviceConfig_Role_ROUTER_CLIENT) {
delay = random(0, 2 * CWsize) * slotTimeMsec;
LOG_DEBUG("rx_snr found in packet. As a router, setting tx delay:%d\n", delay);
} else {
delay = random(0, pow(2, CWsize)) * slotTimeMsec;
@ -453,14 +452,16 @@ void RadioInterface::applyModemConfig()
// float freq = myRegion->freqStart + ((((myRegion->freqEnd - myRegion->freqStart) / numChannels) / 2) * channel_num);
// New frequency selection formula
float freq = myRegion->freqStart + (bw / 2000) + ( channel_num * (bw / 1000));
float freq = myRegion->freqStart + (bw / 2000) + (channel_num * (bw / 1000));
saveChannelNum(channel_num);
saveFreq(freq + config.lora.frequency_offset);
LOG_INFO("Radio freq=%.3f, config.lora.frequency_offset=%.3f\n", freq, config.lora.frequency_offset);
LOG_INFO("Set radio: region=%s, name=%s, config=%u, ch=%d, power=%d\n", myRegion->name, channelName, loraConfig.modem_preset, channel_num, power);
LOG_INFO("Radio myRegion->freqStart -> myRegion->freqEnd: %f -> %f (%f mhz)\n", myRegion->freqStart, myRegion->freqEnd, myRegion->freqEnd - myRegion->freqStart);
LOG_INFO("Set radio: region=%s, name=%s, config=%u, ch=%d, power=%d\n", myRegion->name, channelName, loraConfig.modem_preset,
channel_num, power);
LOG_INFO("Radio myRegion->freqStart -> myRegion->freqEnd: %f -> %f (%f mhz)\n", myRegion->freqStart, myRegion->freqEnd,
myRegion->freqEnd - myRegion->freqStart);
LOG_INFO("Radio myRegion->numChannels: %d x %.3fkHz\n", numChannels, bw);
LOG_INFO("Radio channel_num: %d\n", channel_num);
LOG_INFO("Radio frequency: %f\n", getFreq());
@ -486,7 +487,6 @@ void RadioInterface::limitPower()
LOG_INFO("Set radio: final power level=%d\n", power);
}
void RadioInterface::deliverToReceiver(MeshPacket *p)
{
if (router)

Some files were not shown because too many files have changed in this diff Show More