diff --git a/.github/actions/setup-base/action.yml b/.github/actions/setup-base/action.yml index b5b4cb6f3..7f8659523 100644 --- a/.github/actions/setup-base/action.yml +++ b/.github/actions/setup-base/action.yml @@ -14,7 +14,7 @@ runs: - name: Install dependencies shell: bash run: | - sudo apt-get -y update + sudo apt-get -y update --fix-missing sudo apt-get install -y cppcheck libbluetooth-dev libgpiod-dev libyaml-cpp-dev - name: Setup Python diff --git a/.github/workflows/build_native.yml b/.github/workflows/build_native.yml index 8fe8e6c31..3e8b4c001 100644 --- a/.github/workflows/build_native.yml +++ b/.github/workflows/build_native.yml @@ -13,7 +13,7 @@ jobs: - name: Install libbluetooth shell: bash run: | - sudo apt-get update + sudo apt-get update --fix-missing sudo apt-get install -y libbluetooth-dev libgpiod-dev libyaml-cpp-dev openssl libssl-dev libulfius-dev liborcania-dev - name: Checkout code diff --git a/.github/workflows/build_nrf52.yml b/.github/workflows/build_nrf52.yml index eb1779963..ac509a096 100644 --- a/.github/workflows/build_nrf52.yml +++ b/.github/workflows/build_nrf52.yml @@ -29,6 +29,7 @@ jobs: name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip overwrite: true path: | + release/*.hex release/*.uf2 release/*.elf release/*.zip diff --git a/.github/workflows/build_raspbian.yml b/.github/workflows/build_raspbian.yml index d262d8739..1fd8fad30 100644 --- a/.github/workflows/build_raspbian.yml +++ b/.github/workflows/build_raspbian.yml @@ -13,7 +13,7 @@ jobs: - name: Install libbluetooth shell: bash run: | - apt-get update -y + apt-get update -y --fix-missing apt-get install -y libbluetooth-dev libgpiod-dev libyaml-cpp-dev openssl libssl-dev libulfius-dev liborcania-dev - name: Checkout code diff --git a/.github/workflows/build_raspbian_armv7l.yml b/.github/workflows/build_raspbian_armv7l.yml index ee5eb66eb..39b297d1b 100644 --- a/.github/workflows/build_raspbian_armv7l.yml +++ b/.github/workflows/build_raspbian_armv7l.yml @@ -13,6 +13,7 @@ jobs: - name: Install libbluetooth shell: bash run: | + apt-get update -y --fix-missing apt-get install -y libbluetooth-dev libgpiod-dev libyaml-cpp-dev openssl libssl-dev libulfius-dev liborcania-dev - name: Checkout code diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 25a0fbad2..14c8a9d10 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -136,7 +136,7 @@ jobs: build-rpi2040, package-raspbian, package-raspbian-armv7l, - package-native + package-native, ] steps: - name: Checkout code @@ -168,6 +168,7 @@ jobs: path: | ./firmware-*.bin ./firmware-*.uf2 + ./firmware-*.hex ./firmware-*-ota.zip ./device-*.sh ./device-*.bat diff --git a/.trunk/trunk.yaml b/.trunk/trunk.yaml index 8a2f18ad5..2d9f60899 100644 --- a/.trunk/trunk.yaml +++ b/.trunk/trunk.yaml @@ -1,6 +1,6 @@ version: 0.1 cli: - version: 1.22.1 + version: 1.22.2 plugins: sources: - id: trunk @@ -31,6 +31,10 @@ lint: - gitleaks@8.18.2 - clang-format@16.0.3 - prettier@3.2.5 + ignore: + - linters: [ALL] + paths: + - bin/** runtimes: enabled: - python@3.10.8 diff --git a/bin/build-nrf52.sh b/bin/build-nrf52.sh index fa6eacd23..cf4ca60cb 100755 --- a/bin/build-nrf52.sh +++ b/bin/build-nrf52.sh @@ -23,8 +23,10 @@ basename=firmware-$1-$VERSION pio run --environment $1 # -v SRCELF=.pio/build/$1/firmware.elf -DFUPKG=.pio/build/$1/firmware.zip cp $SRCELF $OUTDIR/$basename.elf + +echo "Generating NRF52 dfu file" +DFUPKG=.pio/build/$1/firmware.zip cp $DFUPKG $OUTDIR/$basename-ota.zip echo "Generating NRF52 uf2 file" @@ -33,13 +35,15 @@ SRCHEX=.pio/build/$1/firmware.hex # if WM1110 target, merge hex with softdevice 7.3.0 if (echo $1 | grep -q "wio-sdk-wm1110"); then echo "Merging with softdevice" - sudo chmod +x ./bin/mergehex - bin/mergehex -m bin/s140_nrf52_7.3.0_softdevice.hex $SRCHEX -o .pio/build/$1/merged_fimware.hex - SRCHEX=.pio/build/$1/merged_fimware.hex + sudo chmod +x ./bin/mergehex + bin/mergehex -m bin/s140_nrf52_7.3.0_softdevice.hex $SRCHEX -o .pio/build/$1/$basename.hex + SRCHEX=.pio/build/$1/$basename.hex + bin/uf2conv.py $SRCHEX -c -o $OUTDIR/$basename.uf2 -f 0xADA52840 + cp $SRCHEX $OUTDIR + cp bin/*.uf2 $OUTDIR +else + bin/uf2conv.py $SRCHEX -c -o $OUTDIR/$basename.uf2 -f 0xADA52840 + cp bin/device-install.* $OUTDIR + cp bin/device-update.* $OUTDIR + cp bin/*.uf2 $OUTDIR fi - -bin/uf2conv.py $SRCHEX -c -o $OUTDIR/$basename.uf2 -f 0xADA52840 - -cp bin/device-install.* $OUTDIR -cp bin/device-update.* $OUTDIR -cp bin/*.uf2 $OUTDIR diff --git a/bin/uf2conv.py b/bin/uf2conv.py index b619d14db..a1e241b7a 100755 --- a/bin/uf2conv.py +++ b/bin/uf2conv.py @@ -1,39 +1,38 @@ #!/usr/bin/env python3 -import sys -import struct -import subprocess -import re +import argparse import os import os.path -import argparse +import re +import struct +import subprocess +import sys - -UF2_MAGIC_START0 = 0x0A324655 # "UF2\n" -UF2_MAGIC_START1 = 0x9E5D5157 # Randomly selected -UF2_MAGIC_END = 0x0AB16F30 # Ditto +UF2_MAGIC_START0 = 0x0A324655 # "UF2\n" +UF2_MAGIC_START1 = 0x9E5D5157 # Randomly selected +UF2_MAGIC_END = 0x0AB16F30 # Ditto families = { - 'SAMD21': 0x68ed2b88, - 'SAML21': 0x1851780a, - 'SAMD51': 0x55114460, - 'NRF52': 0x1b57745f, - 'STM32F0': 0x647824b6, - 'STM32F1': 0x5ee21072, - 'STM32F2': 0x5d1a0a2e, - 'STM32F3': 0x6b846188, - 'STM32F4': 0x57755a57, - 'STM32F7': 0x53b80f00, - 'STM32G0': 0x300f5633, - 'STM32G4': 0x4c71240a, - 'STM32H7': 0x6db66082, - 'STM32L0': 0x202e3a91, - 'STM32L1': 0x1e1f432d, - 'STM32L4': 0x00ff6919, - 'STM32L5': 0x04240bdf, - 'STM32WB': 0x70d16653, - 'STM32WL': 0x21460ff0, - 'ATMEGA32': 0x16573617, - 'MIMXRT10XX': 0x4FB2D5BD + "SAMD21": 0x68ED2B88, + "SAML21": 0x1851780A, + "SAMD51": 0x55114460, + "NRF52": 0x1B57745F, + "STM32F0": 0x647824B6, + "STM32F1": 0x5EE21072, + "STM32F2": 0x5D1A0A2E, + "STM32F3": 0x6B846188, + "STM32F4": 0x57755A57, + "STM32F7": 0x53B80F00, + "STM32G0": 0x300F5633, + "STM32G4": 0x4C71240A, + "STM32H7": 0x6DB66082, + "STM32L0": 0x202E3A91, + "STM32L1": 0x1E1F432D, + "STM32L4": 0x00FF6919, + "STM32L5": 0x04240BDF, + "STM32WB": 0x70D16653, + "STM32WL": 0x21460FF0, + "ATMEGA32": 0x16573617, + "MIMXRT10XX": 0x4FB2D5BD, } INFO_FILE = "/INFO_UF2.TXT" @@ -46,15 +45,17 @@ def is_uf2(buf): w = struct.unpack(" 10*1024*1024: + if padding > 10 * 1024 * 1024: assert False, "More than 10M of padding needed at " + ptr if padding % 4 != 0: assert False, "Non-word padding size at " + ptr @@ -91,6 +92,7 @@ def convert_from_uf2(buf): curraddr = newaddr + datalen return outp + def convert_to_carray(file_content): outp = "const unsigned char bindata[] __attribute__((aligned(16))) = {" for i in range(len(file_content)): @@ -100,6 +102,7 @@ def convert_to_carray(file_content): outp += "\n};\n" return outp + def convert_to_uf2(file_content): global familyid datapadding = b"" @@ -109,13 +112,21 @@ def convert_to_uf2(file_content): outp = b"" for blockno in range(numblocks): ptr = 256 * blockno - chunk = file_content[ptr:ptr + 256] + chunk = file_content[ptr : ptr + 256] flags = 0x0 if familyid: flags |= 0x2000 - hd = struct.pack(b"= 3 and words[1] == "2" and words[2] == "FAT": drives.append(words[0]) else: @@ -206,7 +238,6 @@ def get_drives(): for d in os.listdir(rootpath): drives.append(os.path.join(rootpath, d)) - def has_info(d): try: return os.path.isfile(d + INFO_FILE) @@ -217,7 +248,7 @@ def get_drives(): def board_id(path): - with open(path + INFO_FILE, mode='r') as file: + with open(path + INFO_FILE, mode="r") as file: file_content = file.read() return re.search("Board-ID: ([^\r\n]*)", file_content).group(1) @@ -235,30 +266,61 @@ def write_file(name, buf): def main(): global appstartaddr, familyid + def error(msg): print(msg) sys.exit(1) - parser = argparse.ArgumentParser(description='Convert to UF2 or flash directly.') - parser.add_argument('input', metavar='INPUT', type=str, nargs='?', - help='input file (HEX, BIN or UF2)') - parser.add_argument('-b' , '--base', dest='base', type=str, - default="0x2000", - help='set base address of application for BIN format (default: 0x2000)') - parser.add_argument('-o' , '--output', metavar="FILE", dest='output', type=str, - help='write output to named file; defaults to "flash.uf2" or "flash.bin" where sensible') - parser.add_argument('-d' , '--device', dest="device_path", - help='select a device path to flash') - parser.add_argument('-l' , '--list', action='store_true', - help='list connected devices') - parser.add_argument('-c' , '--convert', action='store_true', - help='do not flash, just convert') - parser.add_argument('-D' , '--deploy', action='store_true', - help='just flash, do not convert') - parser.add_argument('-f' , '--family', dest='family', type=str, - default="0x0", - help='specify familyID - number or name (default: 0x0)') - parser.add_argument('-C' , '--carray', action='store_true', - help='convert binary file to a C array, not UF2') + + parser = argparse.ArgumentParser(description="Convert to UF2 or flash directly.") + parser.add_argument( + "input", + metavar="INPUT", + type=str, + nargs="?", + help="input file (HEX, BIN or UF2)", + ) + parser.add_argument( + "-b", + "--base", + dest="base", + type=str, + default="0x2000", + help="set base address of application for BIN format (default: 0x2000)", + ) + parser.add_argument( + "-o", + "--output", + metavar="FILE", + dest="output", + type=str, + help='write output to named file; defaults to "flash.uf2" or "flash.bin" where sensible', + ) + parser.add_argument( + "-d", "--device", dest="device_path", help="select a device path to flash" + ) + parser.add_argument( + "-l", "--list", action="store_true", help="list connected devices" + ) + parser.add_argument( + "-c", "--convert", action="store_true", help="do not flash, just convert" + ) + parser.add_argument( + "-D", "--deploy", action="store_true", help="just flash, do not convert" + ) + parser.add_argument( + "-f", + "--family", + dest="family", + type=str, + default="0x0", + help="specify familyID - number or name (default: 0x0)", + ) + parser.add_argument( + "-C", + "--carray", + action="store_true", + help="convert binary file to a C array, not UF2", + ) args = parser.parse_args() appstartaddr = int(args.base, 0) @@ -268,14 +330,17 @@ def main(): try: familyid = int(args.family, 0) except ValueError: - error("Family ID needs to be a number or one of: " + ", ".join(families.keys())) + error( + "Family ID needs to be a number or one of: " + + ", ".join(families.keys()) + ) if args.list: list_drives() else: if not args.input: error("Need input file") - with open(args.input, mode='rb') as f: + with open(args.input, mode="rb") as f: inpbuf = f.read() from_uf2 = is_uf2(inpbuf) ext = "uf2" @@ -291,8 +356,10 @@ def main(): ext = "h" else: outbuf = convert_to_uf2(inpbuf) - print("Converting to %s, output size: %d, start address: 0x%x" % - (ext, len(outbuf), appstartaddr)) + print( + "Converting to %s, output size: %d, start address: 0x%x" + % (ext, len(outbuf), appstartaddr) + ) if args.convert or ext != "uf2": drives = [] if args.output == None: diff --git a/boards/heltec_mesh_node_t114.json b/boards/heltec_mesh_node_t114.json new file mode 100644 index 000000000..5c97d8c75 --- /dev/null +++ b/boards/heltec_mesh_node_t114.json @@ -0,0 +1,53 @@ +{ + "build": { + "arduino": { + "ldscript": "nrf52840_s140_v6.ld" + }, + "core": "nRF5", + "cpu": "cortex-m4", + "extra_flags": "-DARDUINO_NRF52840_PCA10056 -DNRF52840_XXAA", + "f_cpu": "64000000L", + "hwids": [ + ["0x239A", "0x4405"], + ["0x239A", "0x0029"], + ["0x239A", "0x002A"] + ], + "usb_product": "HT-n5262", + "mcu": "nrf52840", + "variant": "heltec_mesh_node_t114", + "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" + } + }, + "connectivity": ["bluetooth"], + "debug": { + "jlink_device": "nRF52840_xxAA", + "onboard_tools": ["jlink"], + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" + }, + "frameworks": ["arduino"], + "name": "Heltec nrf (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 + }, + "url": "FIXME", + "vendor": "Heltec" +} diff --git a/platformio.ini b/platformio.ini index bcdcc0034..b3f677247 100644 --- a/platformio.ini +++ b/platformio.ini @@ -35,6 +35,10 @@ default_envs = tbeam ;default_envs = radiomaster_900_bandit_nano ;default_envs = radiomaster_900_bandit_micro ;default_envs = heltec_capsule_sensor_v3 +;default_envs = heltec_vision_master_t190 +;default_envs = heltec_vision_master_e213 +;default_envs = heltec_vision_master_e290 +;default_envs = heltec_mesh_node_t114 extra_configs = arch/*/*.ini diff --git a/protobufs b/protobufs index 8f4faf76e..d191975eb 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 8f4faf76e52c2ef63c582c26642d312d9781b7c0 +Subproject commit d191975ebc572527c6d9eec48d5b0a1e3331999f diff --git a/src/Power.cpp b/src/Power.cpp index cea373806..19c5c9937 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -232,12 +232,20 @@ class AnalogBatteryLevel : public HasBatteryLevel raw = espAdcRead(); scaled = esp_adc_cal_raw_to_voltage(raw, adc_characs); scaled *= operativeAdcMultiplier; -#else // block for all other platforms +#else // block for all other platforms +#ifdef ADC_CTRL // enable adc voltage divider when we need to read + pinMode(ADC_CTRL, OUTPUT); + digitalWrite(ADC_CTRL, ADC_CTRL_ENABLED); + delay(10); +#endif for (uint32_t i = 0; i < BATTERY_SENSE_SAMPLES; i++) { raw += analogRead(BATTERY_PIN); } raw = raw / BATTERY_SENSE_SAMPLES; scaled = operativeAdcMultiplier * ((1000 * AREF_VOLTAGE) / pow(2, BATTERY_SENSE_RESOLUTION_BITS)) * raw; +#ifdef ADC_CTRL // disable adc voltage divider when we need to read + digitalWrite(ADC_CTRL, !ADC_CTRL_ENABLED); +#endif #endif if (!initial_read_done) { @@ -441,6 +449,11 @@ class AnalogBatteryLevel : public HasBatteryLevel if (!ina260Sensor.isInitialized()) return ina260Sensor.runOnce() > 0; return ina260Sensor.isRunning(); + } else if (nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_INA3221].first == + config.power.device_battery_ina_address) { + if (!ina3221Sensor.isInitialized()) + return ina3221Sensor.runOnce() > 0; + return ina3221Sensor.isRunning(); } return false; } diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index ec7d725b8..8eb7fef27 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -9,6 +9,7 @@ #include "main.h" // pmu_found #include "sleep.h" +#include "GPSUpdateScheduling.h" #include "cas.h" #include "ubx.h" @@ -22,19 +23,6 @@ #define GPS_RESET_MODE HIGH #endif -// How many minutes of sleep make it worthwhile to power-off the GPS -// Shorter than this, and GPS will only enter standby -// Affected by lock-time, and config.position.gps_update_interval -#ifndef GPS_STANDBY_THRESHOLD_MINUTES -#define GPS_STANDBY_THRESHOLD_MINUTES 15 -#endif - -// How many seconds of sleep make it worthwhile for the GPS to use powered-on standby -// Shorter than this, and we'll just wait instead -#ifndef GPS_IDLE_THRESHOLD_SECONDS -#define GPS_IDLE_THRESHOLD_SECONDS 10 -#endif - #if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) || defined(ARCH_PORTDUINO) HardwareSerial *GPS::_serial_gps = &Serial1; #else @@ -43,6 +31,8 @@ HardwareSerial *GPS::_serial_gps = NULL; GPS *gps = nullptr; +GPSUpdateScheduling scheduling; + /// Multiple GPS instances might use the same serial port (in sequence), but we can /// only init that port once. static bool didSerialInit; @@ -52,6 +42,25 @@ uint8_t uBloxProtocolVersion; #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) +// For logging +const char *getGPSPowerStateString(GPSPowerState state) +{ + switch (state) { + case GPS_ACTIVE: + return "ACTIVE"; + case GPS_IDLE: + return "IDLE"; + case GPS_SOFTSLEEP: + return "SOFTSLEEP"; + case GPS_HARDSLEEP: + return "HARDSLEEP"; + case GPS_OFF: + return "OFF"; + default: + assert(false); // Unhandled enum value.. + } +} + void GPS::UBXChecksum(uint8_t *message, size_t length) { uint8_t CK_A = 0, CK_B = 0; @@ -767,7 +776,6 @@ bool GPS::setup() } notifyDeepSleepObserver.observe(¬ifyDeepSleep); - notifyGPSSleepObserver.observe(¬ifyGPSSleep); return true; } @@ -776,124 +784,185 @@ GPS::~GPS() { // we really should unregister our sleep observer notifyDeepSleepObserver.unobserve(¬ifyDeepSleep); - notifyGPSSleepObserver.observe(¬ifyGPSSleep); } -const char *GPS::powerStateToString() +// Put the GPS hardware into a specified state +void GPS::setPowerState(GPSPowerState newState, uint32_t sleepTime) { - switch (powerState) { - case GPS_OFF: - return "OFF"; - case GPS_IDLE: - return "IDLE"; - case GPS_STANDBY: - return "STANDBY"; + // Update the stored GPSPowerstate, and create local copies + GPSPowerState oldState = powerState; + powerState = newState; + LOG_INFO("GPS power state moving from %s to %s\n", getGPSPowerStateString(oldState), getGPSPowerStateString(newState)); + + switch (newState) { case GPS_ACTIVE: - return "ACTIVE"; - default: - return "UNKNOWN"; + case GPS_IDLE: + if (oldState == GPS_ACTIVE || oldState == GPS_IDLE) // If hardware already awake, no changes needed + break; + if (oldState != GPS_ACTIVE && oldState != GPS_IDLE) // If hardware just waking now, clear buffer + clearBuffer(); + powerMon->setState(meshtastic_PowerMon_State_GPS_Active); // Report change for power monitoring (during testing) + writePinEN(true); // Power (EN pin): on + setPowerPMU(true); // Power (PMU): on + writePinStandby(false); // Standby (pin): awake (not standby) + setPowerUBLOX(true); // Standby (UBLOX): awake + break; + + case GPS_SOFTSLEEP: + powerMon->clearState(meshtastic_PowerMon_State_GPS_Active); // Report change for power monitoring (during testing) + writePinEN(true); // Power (EN pin): on + setPowerPMU(true); // Power (PMU): on + writePinStandby(true); // Standby (pin): asleep (not awake) + setPowerUBLOX(false, sleepTime); // Standby (UBLOX): asleep, timed + break; + + case GPS_HARDSLEEP: + powerMon->clearState(meshtastic_PowerMon_State_GPS_Active); // Report change for power monitoring (during testing) + writePinEN(false); // Power (EN pin): off + setPowerPMU(false); // Power (PMU): off + writePinStandby(true); // Standby (pin): asleep (not awake) + setPowerUBLOX(false, sleepTime); // Standby (UBLOX): asleep, timed + break; + + case GPS_OFF: + assert(sleepTime == 0); // This is an indefinite sleep + powerMon->clearState(meshtastic_PowerMon_State_GPS_Active); // Report change for power monitoring (during testing) + writePinEN(false); // Power (EN pin): off + setPowerPMU(false); // Power (PMU): off + writePinStandby(true); // Standby (pin): asleep + setPowerUBLOX(false, 0); // Standby (UBLOX): asleep, indefinitely + break; } } -void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime) +// Set power with EN pin, if relevant +void GPS::writePinEN(bool on) { - // Record the current powerState - if (on) - powerState = GPS_ACTIVE; - else if (!enabled) // User has disabled with triple press - powerState = GPS_OFF; - else if (sleepTime <= GPS_IDLE_THRESHOLD_SECONDS * 1000UL) - powerState = GPS_IDLE; - else if (standbyOnly) - powerState = GPS_STANDBY; - else - powerState = GPS_OFF; - - LOG_DEBUG("GPS::powerState=%s\n", powerStateToString()); - - // If the next update is due *really soon*, don't actually power off or enter standby. Just wait it out. - if (!on && powerState == GPS_IDLE) + // Abort: if conflict with Canned Messages when using Wisblock(?) + if (HW_VENDOR == meshtastic_HardwareModel_RAK4631 && (rotaryEncoderInterruptImpl1 || upDownInterruptImpl1)) return; - if (on) { - powerMon->setState(meshtastic_PowerMon_State_GPS_Active); - clearBuffer(); // drop any old data waiting in the buffer before re-enabling - if (en_gpio) - digitalWrite(en_gpio, on ? GPS_EN_ACTIVE : !GPS_EN_ACTIVE); // turn this on if defined, every time - } else { - powerMon->clearState(meshtastic_PowerMon_State_GPS_Active); - } - isInPowersave = !on; - if (!standbyOnly && en_gpio != 0 && - !(HW_VENDOR == meshtastic_HardwareModel_RAK4631 && (rotaryEncoderInterruptImpl1 || upDownInterruptImpl1))) { - LOG_DEBUG("GPS powerdown using GPS_EN_ACTIVE\n"); - digitalWrite(en_gpio, on ? GPS_EN_ACTIVE : !GPS_EN_ACTIVE); + // Abort: if pin unset + if (!en_gpio) return; - } -#ifdef HAS_PMU // We only have PMUs on the T-Beam, and that board has a tiny battery to save GPS ephemera, so treat as a standby. - if (pmu_found && PMU) { - uint8_t model = PMU->getChipModel(); - if (model == XPOWERS_AXP2101) { - if (HW_VENDOR == meshtastic_HardwareModel_TBEAM) { - // t-beam v1.2 GNSS power channel - on ? PMU->enablePowerOutput(XPOWERS_ALDO3) : PMU->disablePowerOutput(XPOWERS_ALDO3); - } else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE) { - // t-beam-s3-core GNSS power channel - on ? PMU->enablePowerOutput(XPOWERS_ALDO4) : PMU->disablePowerOutput(XPOWERS_ALDO4); - } - } else if (model == XPOWERS_AXP192) { - // t-beam v1.1 GNSS power channel - on ? PMU->enablePowerOutput(XPOWERS_LDO3) : PMU->disablePowerOutput(XPOWERS_LDO3); - } - return; - } + + // Determine new value for the pin + bool val = GPS_EN_ACTIVE ? on : !on; + + // Write and log + pinMode(en_gpio, OUTPUT); + digitalWrite(en_gpio, val); +#ifdef GPS_EXTRAVERBOSE + LOG_DEBUG("Pin EN %s\n", val == HIGH ? "HIGH" : "LOW"); #endif +} + +// Set the value of the STANDBY pin, if relevant +// true for standby state, false for awake +void GPS::writePinStandby(bool standby) +{ #ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76B, L76K and clones - if (on) { - LOG_INFO("Waking GPS\n"); - pinMode(PIN_GPS_STANDBY, OUTPUT); - // Some PCB's use an inverse logic due to a transistor driver - // Example for this is the Pico-Waveshare Lora+GPS HAT -#ifdef PIN_GPS_STANDBY_INVERTED - digitalWrite(PIN_GPS_STANDBY, 0); + +// Determine the new value for the pin +// Normally: active HIGH for awake +#if PIN_GPS_STANDBY_INVERTED + bool val = standby; #else - digitalWrite(PIN_GPS_STANDBY, 1); + bool val = !standby; #endif - return; - } else { - LOG_INFO("GPS entering sleep\n"); - // notifyGPSSleep.notifyObservers(NULL); - pinMode(PIN_GPS_STANDBY, OUTPUT); -#ifdef PIN_GPS_STANDBY_INVERTED - digitalWrite(PIN_GPS_STANDBY, 1); -#else - digitalWrite(PIN_GPS_STANDBY, 0); + + // Write and log + pinMode(PIN_GPS_STANDBY, OUTPUT); + digitalWrite(PIN_GPS_STANDBY, val); +#ifdef GPS_EXTRAVERBOSE + LOG_DEBUG("Pin STANDBY %s\n", val == HIGH ? "HIGH" : "LOW"); #endif +#endif +} + +// Enable / Disable GPS with PMU, if present +void GPS::setPowerPMU(bool on) +{ + // We only have PMUs on the T-Beam, and that board has a tiny battery to save GPS ephemera, + // so treat as a standby. +#ifdef HAS_PMU + // Abort: if no PMU + if (!pmu_found) return; + + // Abort: if PMU not initialized + if (!PMU) + return; + + uint8_t model = PMU->getChipModel(); + if (model == XPOWERS_AXP2101) { + if (HW_VENDOR == meshtastic_HardwareModel_TBEAM) { + // t-beam v1.2 GNSS power channel + on ? PMU->enablePowerOutput(XPOWERS_ALDO3) : PMU->disablePowerOutput(XPOWERS_ALDO3); + } else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE) { + // t-beam-s3-core GNSS power channel + on ? PMU->enablePowerOutput(XPOWERS_ALDO4) : PMU->disablePowerOutput(XPOWERS_ALDO4); + } + } else if (model == XPOWERS_AXP192) { + // t-beam v1.1 GNSS power channel + on ? PMU->enablePowerOutput(XPOWERS_LDO3) : PMU->disablePowerOutput(XPOWERS_LDO3); } + +#ifdef GPS_EXTRAVERBOSE + LOG_DEBUG("PMU %s\n", on ? "on" : "off"); #endif - if (!on) { - if (gnssModel == GNSS_MODEL_UBLOX) { - uint8_t msglen; - LOG_DEBUG("Sleep Time: %i\n", sleepTime); - if (strncmp(info.hwVersion, "000A0000", 8) != 0) { - for (int i = 0; i < 4; i++) { - gps->_message_PMREQ[0 + i] = sleepTime >> (i * 8); // Encode the sleep time in millis into the packet - } - msglen = gps->makeUBXPacket(0x02, 0x41, sizeof(_message_PMREQ), gps->_message_PMREQ); - } else { - for (int i = 0; i < 4; i++) { - gps->_message_PMREQ_10[4 + i] = sleepTime >> (i * 8); // Encode the sleep time in millis into the packet - } - msglen = gps->makeUBXPacket(0x02, 0x41, sizeof(_message_PMREQ_10), gps->_message_PMREQ_10); - } - gps->_serial_gps->write(gps->UBXscratch, msglen); +#endif +} + +// Set UBLOX power, if relevant +void GPS::setPowerUBLOX(bool on, uint32_t sleepMs) +{ + // Abort: if not UBLOX hardware + if (gnssModel != GNSS_MODEL_UBLOX) + return; + + // If waking + if (on) { + gps->_serial_gps->write(0xFF); + clearBuffer(); // This often returns old data, so drop it +#ifdef GPS_EXTRAVERBOSE + LOG_DEBUG("UBLOX: wake\n"); +#endif + } + + // If putting to sleep + else { + uint8_t msglen; + + // If we're being asked to sleep indefinitely, make *sure* we're awake first, to process the new sleep command + if (sleepMs == 0) { + setPowerUBLOX(true); + delay(500); } - } else { - if (gnssModel == GNSS_MODEL_UBLOX) { - gps->_serial_gps->write(0xFF); - clearBuffer(); // This often returns old data, so drop it + + // Determine hardware version + if (strncmp(info.hwVersion, "000A0000", 8) != 0) { + // Encode the sleep time in millis into the packet + for (int i = 0; i < 4; i++) + gps->_message_PMREQ[0 + i] = sleepMs >> (i * 8); + + // Record the message length + msglen = gps->makeUBXPacket(0x02, 0x41, sizeof(_message_PMREQ), gps->_message_PMREQ); + } else { + // Encode the sleep time in millis into the packet + for (int i = 0; i < 4; i++) + gps->_message_PMREQ_10[4 + i] = sleepMs >> (i * 8); + + // Record the message length + msglen = gps->makeUBXPacket(0x02, 0x41, sizeof(_message_PMREQ_10), gps->_message_PMREQ_10); } + + // Send the UBX packet + gps->_serial_gps->write(gps->UBXscratch, msglen); + +#ifdef GPS_EXTRAVERBOSE + LOG_DEBUG("UBLOX: sleep for %dmS\n", sleepMs); +#endif } } @@ -906,108 +975,54 @@ void GPS::setConnected() } } -/** - * Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode - * - * calls sleep/wake - */ -void GPS::setAwake(bool wantAwake) +// We want a GPS lock. Wake the hardware +void GPS::up() { + scheduling.informSearching(); + setPowerState(GPS_ACTIVE); +} - // If user has disabled GPS, make sure it is off, not just in standby or idle - if (!wantAwake && !enabled && powerState != GPS_OFF) { - setGPSPower(false, false, 0); - return; - } +// We've got a GPS lock. Enter a low power state, potentially. +void GPS::down() +{ + scheduling.informGotLock(); + uint32_t predictedSearchDuration = scheduling.predictedSearchDurationMs(); + uint32_t sleepTime = scheduling.msUntilNextSearch(); + uint32_t updateInterval = Default::getConfiguredOrDefaultMs(config.position.gps_update_interval); - // If GPS power state needs to change - if ((wantAwake && powerState != GPS_ACTIVE) || (!wantAwake && powerState == GPS_ACTIVE)) { - LOG_DEBUG("WANT GPS=%d\n", wantAwake); + LOG_DEBUG("%us until next search\n", sleepTime / 1000); - // Calculate how long it takes to get a GPS lock - if (wantAwake) { - // Record the time we start looking for a lock - lastWakeStartMsec = millis(); - } else { - // Record by how much we missed our ideal target postion.gps_update_interval (for logging only) - // Need to calculate this before we update lastSleepStartMsec, to make the new prediction - int32_t lateByMsec = (int32_t)(millis() - lastSleepStartMsec) - (int32_t)getSleepTime(); + // If update interval less than 10 seconds, no attempt to sleep + if (updateInterval <= 10 * 1000UL) + setPowerState(GPS_IDLE); - // Record the time we finish looking for a lock - lastSleepStartMsec = millis(); - - // How long did it take to get GPS lock this time? - uint32_t lockTime = lastSleepStartMsec - lastWakeStartMsec; - - // Update the lock-time prediction - // Used pre-emptively, attempting to hit target of gps.position_update_interval - switch (GPSCycles) { - case 0: - LOG_DEBUG("Initial GPS lock took %ds\n", lockTime / 1000); - break; - case 1: - predictedLockTime = lockTime; // Avoid slow ramp-up - start with a real value - LOG_DEBUG("GPS Lock took %ds\n", lockTime / 1000); - break; - default: - // Predict lock-time using exponential smoothing: respond slowly to changes - predictedLockTime = (lockTime * 0.2) + (predictedLockTime * 0.8); // Latest lock time has 20% weight on prediction - LOG_INFO("GPS Lock took %ds. %s by %ds. Next lock predicted to take %ds.\n", lockTime / 1000, - (lateByMsec > 0) ? "Late" : "Early", abs(lateByMsec) / 1000, predictedLockTime / 1000); - } - GPSCycles++; - } - - // How long to wait before attempting next GPS update - // Aims to hit position.gps_update_interval by using the lock-time prediction - uint32_t compensatedSleepTime = (getSleepTime() > predictedLockTime) ? (getSleepTime() - predictedLockTime) : 0; - - // If long interval between updates: power off between updates - if (compensatedSleepTime > GPS_STANDBY_THRESHOLD_MINUTES * MS_IN_MINUTE) { - setGPSPower(wantAwake, false, getSleepTime() - predictedLockTime); - } - - // If waking relatively frequently: don't power off. Would use more energy trying to reacquire lock each time - // We'll either use a "powered-on" standby, or just wait it out, depending on how soon the next update is due - // Will decide which inside setGPSPower method - else { -#ifdef GPS_UC6580 - setGPSPower(wantAwake, false, compensatedSleepTime); -#else - setGPSPower(wantAwake, true, compensatedSleepTime); + else { + // Check whether the GPS hardware is capable of GPS_SOFTSLEEP + // If not, fallback to GPS_HARDSLEEP instead + bool softsleepSupported = false; + if (gnssModel == GNSS_MODEL_UBLOX) // U-blox is supported via PMREQ + softsleepSupported = true; +#ifdef PIN_GPS_STANDBY // L76B, L76K and clones have a standby pin + softsleepSupported = true; #endif - } + + // How long does gps_update_interval need to be, for GPS_HARDSLEEP to become more efficient than GPS_SOFTSLEEP? + // Heuristic equation. A compromise manually fitted to power observations from U-blox NEO-6M and M10050 + // https://www.desmos.com/calculator/6gvjghoumr + // This is not particularly accurate, but probably an impromevement over a single, fixed threshold + uint32_t hardsleepThreshold = (2750 * pow(predictedSearchDuration / 1000, 1.22)); + LOG_DEBUG("gps_update_interval >= %us needed to justify hardsleep\n", hardsleepThreshold / 1000); + + // If update interval too short: softsleep (if supported by hardware) + if (softsleepSupported && updateInterval < hardsleepThreshold) + setPowerState(GPS_SOFTSLEEP, sleepTime); + + // If update interval long enough (or softsleep unsupported): hardsleep instead + else + setPowerState(GPS_HARDSLEEP, sleepTime); } } -/** Get how long we should stay looking for each acquisition in msecs - */ -uint32_t GPS::getWakeTime() const -{ - uint32_t t = config.position.position_broadcast_secs; - - if (t == UINT32_MAX) - return t; // already maxint - - return Default::getConfiguredOrDefaultMs(t, default_broadcast_interval_secs); -} - -/** Get how long we should sleep between aqusition attempts in msecs - */ -uint32_t GPS::getSleepTime() const -{ - uint32_t t = config.position.gps_update_interval; - - // We'll not need the GPS thread to wake up again after first acq. with fixed position. - if (config.position.gps_mode != meshtastic_Config_PositionConfig_GpsMode_ENABLED || config.position.fixed_position) - t = UINT32_MAX; // Sleep forever now - - if (t == UINT32_MAX) - return t; // already maxint - - return Default::getConfiguredOrDefaultMs(t, default_gps_update_interval); -} - void GPS::publishUpdate() { if (shouldPublish) { @@ -1056,13 +1071,13 @@ int32_t GPS::runOnce() return disable(); } - if (whileIdle()) { + if (whileActive()) { // if we have received valid NMEA claim we are connected setConnected(); } else { if ((config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) && (gnssModel == GNSS_MODEL_UBLOX)) { // reset the GPS on next bootup - if (devicestate.did_gps_reset && (millis() - lastWakeStartMsec > 60000) && !hasFlow()) { + if (devicestate.did_gps_reset && scheduling.elapsedSearchMs() > 60 * 1000UL && !hasFlow()) { LOG_DEBUG("GPS is not communicating, trying factory reset on next bootup.\n"); devicestate.did_gps_reset = false; nodeDB->saveDeviceStateToDisk(); @@ -1077,54 +1092,43 @@ int32_t GPS::runOnce() // gps->factoryReset(); } - // If we are overdue for an update, turn on the GPS and at least publish the current status - uint32_t now = millis(); - uint32_t timeAsleep = now - lastSleepStartMsec; + // If we're due for an update, wake the GPS + if (!config.position.fixed_position && powerState != GPS_ACTIVE && scheduling.isUpdateDue()) + up(); - auto sleepTime = getSleepTime(); - if (powerState != GPS_ACTIVE && (sleepTime != UINT32_MAX) && - ((timeAsleep > sleepTime) || (isInPowersave && timeAsleep > (sleepTime - predictedLockTime)))) { - // We now want to be awake - so wake up the GPS - setAwake(true); + // If we've already set time from the GPS, no need to ask the GPS + bool gotTime = (getRTCQuality() >= RTCQualityGPS); + if (!gotTime && lookForTime()) { // Note: we count on this && short-circuiting and not resetting the RTC time + gotTime = true; + shouldPublish = true; } - // While we are awake - if (powerState == GPS_ACTIVE) { - // LOG_DEBUG("looking for location\n"); - // If we've already set time from the GPS, no need to ask the GPS - bool gotTime = (getRTCQuality() >= RTCQualityGPS); - if (!gotTime && lookForTime()) { // Note: we count on this && short-circuiting and not resetting the RTC time - gotTime = true; - shouldPublish = true; - } + bool gotLoc = lookForLocation(); + if (gotLoc && !hasValidLocation) { // declare that we have location ASAP + LOG_DEBUG("hasValidLocation RISING EDGE\n"); + hasValidLocation = true; + shouldPublish = true; + } - bool gotLoc = lookForLocation(); - if (gotLoc && !hasValidLocation) { // declare that we have location ASAP - LOG_DEBUG("hasValidLocation RISING EDGE\n"); - hasValidLocation = true; - shouldPublish = true; - } + bool tooLong = scheduling.searchedTooLong(); + if (tooLong) + LOG_WARN("Couldn't publish a valid location: didn't get a GPS lock in time.\n"); - now = millis(); - auto wakeTime = getWakeTime(); - bool tooLong = wakeTime != UINT32_MAX && (now - lastWakeStartMsec) > wakeTime; + // Once we get a location we no longer desperately want an update + // LOG_DEBUG("gotLoc %d, tooLong %d, gotTime %d\n", gotLoc, tooLong, gotTime); + if ((gotLoc && gotTime) || tooLong) { - // Once we get a location we no longer desperately want an update - // LOG_DEBUG("gotLoc %d, tooLong %d, gotTime %d\n", gotLoc, tooLong, gotTime); - if ((gotLoc && gotTime) || tooLong) { - - if (tooLong) { - // we didn't get a location during this ack window, therefore declare loss of lock - if (hasValidLocation) { - LOG_DEBUG("hasValidLocation FALLING EDGE (last read: %d)\n", gotLoc); - } - p = meshtastic_Position_init_default; - hasValidLocation = false; + if (tooLong) { + // we didn't get a location during this ack window, therefore declare loss of lock + if (hasValidLocation) { + LOG_DEBUG("hasValidLocation FALLING EDGE\n"); } - - setAwake(false); - shouldPublish = true; // publish our update for this just finished acquisition window + p = meshtastic_Position_init_default; + hasValidLocation = false; } + + down(); + shouldPublish = true; // publish our update for this just finished acquisition window } // If state has changed do a publish @@ -1150,9 +1154,7 @@ void GPS::clearBuffer() int GPS::prepareDeepSleep(void *unused) { LOG_INFO("GPS deep sleep!\n"); - - setAwake(false); - + disable(); return 0; } @@ -1348,12 +1350,6 @@ GPS *GPS::createGps() new_gps->tx_gpio = _tx_gpio; new_gps->en_gpio = _en_gpio; - if (_en_gpio != 0) { - LOG_DEBUG("Setting %d to output.\n", _en_gpio); - pinMode(_en_gpio, OUTPUT); - digitalWrite(_en_gpio, !GPS_EN_ACTIVE); - } - #ifdef PIN_GPS_PPS // pulse per second pinMode(PIN_GPS_PPS, INPUT); @@ -1368,7 +1364,8 @@ GPS *GPS::createGps() LOG_DEBUG("Using " NMEA_MSG_GXGSA " for 3DFIX and PDOP\n"); #endif - new_gps->setGPSPower(true, false, 0); + // Make sure the GPS is awake before performing any init. + new_gps->up(); #ifdef PIN_GPS_RESET pinMode(PIN_GPS_RESET, OUTPUT); @@ -1376,7 +1373,6 @@ GPS *GPS::createGps() delay(10); digitalWrite(PIN_GPS_RESET, !GPS_RESET_MODE); #endif - new_gps->setAwake(true); // Wake GPS power before doing any init if (_serial_gps) { #ifdef ARCH_ESP32 @@ -1662,13 +1658,13 @@ bool GPS::hasFlow() return reader.passedChecksum() > 0; } -bool GPS::whileIdle() +bool GPS::whileActive() { unsigned int charsInBuf = 0; bool isValid = false; if (powerState != GPS_ACTIVE) { clearBuffer(); - return (powerState == GPS_ACTIVE); + return false; } #ifdef SERIAL_BUFFER_SIZE if (_serial_gps->available() >= SERIAL_BUFFER_SIZE - 1) { @@ -1699,20 +1695,21 @@ bool GPS::whileIdle() } void GPS::enable() { - // Clear the old lock-time prediction - GPSCycles = 0; - predictedLockTime = 0; + // Clear the old scheduling info (reset the lock-time prediction) + scheduling.reset(); enabled = true; setInterval(GPS_THREAD_INTERVAL); - setAwake(true); + + scheduling.informSearching(); + setPowerState(GPS_ACTIVE); } int32_t GPS::disable() { enabled = false; setInterval(INT32_MAX); - setAwake(false); + setPowerState(GPS_OFF); return INT32_MAX; } @@ -1721,11 +1718,11 @@ void GPS::toggleGpsMode() { if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) { config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_DISABLED; - LOG_DEBUG("Flag set to false for gps power. GpsMode: DISABLED\n"); + LOG_INFO("User toggled GpsMode. Now DISABLED.\n"); disable(); } else if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_DISABLED) { config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED; - LOG_DEBUG("Flag set to true to restore power. GpsMode: ENABLED\n"); + LOG_INFO("User toggled GpsMode. Now ENABLED\n"); enable(); } } diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 6afbd4fab..7cbf771bc 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -39,10 +39,11 @@ typedef enum { } GPS_RESPONSE; enum GPSPowerState : uint8_t { - GPS_OFF = 0, // Physically powered off - GPS_ACTIVE = 1, // Awake and want a position - GPS_STANDBY = 2, // Physically powered on, but soft-sleeping - GPS_IDLE = 3, // Awake, but not wanting another position yet + GPS_ACTIVE, // Awake and want a position + GPS_IDLE, // Awake, but not wanting another position yet + GPS_SOFTSLEEP, // Physically powered on, but soft-sleeping + GPS_HARDSLEEP, // Physically powered off, but scheduled to wake + GPS_OFF // Powered off indefinitely }; // Generate a string representation of DOP @@ -67,14 +68,11 @@ class GPS : private concurrency::OSThread uint8_t fixType = 0; // fix type from GPGSA #endif private: - uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0; const int serialSpeeds[6] = {9600, 4800, 38400, 57600, 115200, 9600}; uint32_t rx_gpio = 0; uint32_t tx_gpio = 0; uint32_t en_gpio = 0; - uint32_t predictedLockTime = 0; - uint32_t GPSCycles = 0; int speedSelect = 0; int probeTries = 2; @@ -99,7 +97,6 @@ class GPS : private concurrency::OSThread uint8_t numSatellites = 0; CallbackObserver notifyDeepSleepObserver = CallbackObserver(this, &GPS::prepareDeepSleep); - CallbackObserver notifyGPSSleepObserver = CallbackObserver(this, &GPS::prepareDeepSleep); public: /** If !NULL we will use this serial port to construct our GPS */ @@ -175,7 +172,8 @@ class GPS : private concurrency::OSThread // toggle between enabled/disabled void toggleGpsMode(); - void setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime); + // Change the power state of the GPS - for power saving / shutdown + void setPowerState(GPSPowerState newState, uint32_t sleepMs = 0); /// Returns true if we have acquired GPS lock. virtual bool hasLock(); @@ -206,18 +204,18 @@ class GPS : private concurrency::OSThread GPS_RESPONSE getACKCas(uint8_t class_id, uint8_t msg_id, uint32_t waitMillis); - /** - * Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode - * - * calls sleep/wake - */ - void setAwake(bool on); virtual bool factoryReset(); // Creates an instance of the GPS class. // Returns the new instance or null if the GPS is not present. static GPS *createGps(); + // Wake the GPS hardware - ready for an update + void up(); + + // Let the GPS hardware save power between updates + void down(); + protected: /** * Perform any processing that should be done only while the GPS is awake and looking for a fix. @@ -240,7 +238,7 @@ class GPS : private concurrency::OSThread * * Return true if we received a valid message from the GPS */ - virtual bool whileIdle(); + virtual bool whileActive(); /** * Perform any processing that should be done only while the GPS is awake and looking for a fix. @@ -267,13 +265,21 @@ class GPS : private concurrency::OSThread void UBXChecksum(uint8_t *message, size_t length); void CASChecksum(uint8_t *message, size_t length); - /** Get how long we should stay looking for each aquisition + /** Set power with EN pin, if relevant */ - uint32_t getWakeTime() const; + void writePinEN(bool on); - /** Get how long we should sleep between aqusition attempts + /** Set the value of the STANDBY pin, if relevant */ - uint32_t getSleepTime() const; + void writePinStandby(bool standby); + + /** Set GPS power with PMU, if relevant + */ + void setPowerPMU(bool on); + + /** Set UBLOX power, if relevant + */ + void setPowerUBLOX(bool on, uint32_t sleepMs = 0); /** * Tell users we have new GPS readings diff --git a/src/gps/GPSUpdateScheduling.cpp b/src/gps/GPSUpdateScheduling.cpp new file mode 100644 index 000000000..949ef6039 --- /dev/null +++ b/src/gps/GPSUpdateScheduling.cpp @@ -0,0 +1,118 @@ +#include "GPSUpdateScheduling.h" + +#include "Default.h" + +// Mark the time when searching for GPS position begins +void GPSUpdateScheduling::informSearching() +{ + searchStartedMs = millis(); +} + +// Mark the time when searching for GPS is complete, +// then update the predicted lock-time +void GPSUpdateScheduling::informGotLock() +{ + searchEndedMs = millis(); + LOG_DEBUG("Took %us to get lock\n", (searchEndedMs - searchStartedMs) / 1000); + updateLockTimePrediction(); +} + +// Clear old lock-time prediction data. +// When re-enabling GPS with user button. +void GPSUpdateScheduling::reset() +{ + searchStartedMs = 0; + searchEndedMs = 0; + searchCount = 0; + predictedMsToGetLock = 0; +} + +// How many milliseconds before we should next search for GPS position +// Used by GPS hardware directly, to enter timed hardware sleep +uint32_t GPSUpdateScheduling::msUntilNextSearch() +{ + uint32_t now = millis(); + + // Target interval (seconds), between GPS updates + uint32_t updateInterval = Default::getConfiguredOrDefaultMs(config.position.gps_update_interval, default_gps_update_interval); + + // Check how long until we should start searching, to hopefully hit our target interval + uint32_t dueAtMs = searchEndedMs + updateInterval; + uint32_t compensatedStart = dueAtMs - predictedMsToGetLock; + int32_t remainingMs = compensatedStart - now; + + // If we should have already started (negative value), start ASAP + if (remainingMs < 0) + remainingMs = 0; + + return (uint32_t)remainingMs; +} + +// How long have we already been searching? +// Used to abort a search in progress, if it runs unnaceptably long +uint32_t GPSUpdateScheduling::elapsedSearchMs() +{ + // If searching + if (searchStartedMs > searchEndedMs) + return millis() - searchStartedMs; + + // If not searching - 0ms. We shouldn't really consume this value + else + return 0; +} + +// Is it now time to begin searching for a GPS position? +bool GPSUpdateScheduling::isUpdateDue() +{ + return (msUntilNextSearch() == 0); +} + +// Have we been searching for a GPS position for too long? +bool GPSUpdateScheduling::searchedTooLong() +{ + uint32_t maxSearchMs = + Default::getConfiguredOrDefaultMs(config.position.position_broadcast_secs, default_broadcast_interval_secs); + + // If broadcast interval set to max, no such thing as "too long" + if (maxSearchMs == UINT32_MAX) + return false; + + // If we've been searching longer than our position broadcast interval: that's too long + else if (elapsedSearchMs() > maxSearchMs) + return true; + + // Otherwise, not too long yet! + else + return false; +} + +// Updates the predicted time-to-get-lock, by exponentially smoothing the latest observation +void GPSUpdateScheduling::updateLockTimePrediction() +{ + + // How long did it take to get GPS lock this time? + // Duration between down() calls + int32_t lockTime = searchEndedMs - searchStartedMs; + if (lockTime < 0) + lockTime = 0; + + // Ignore the first lock-time: likely to be long, will skew data + + // Second locktime: likely stable. Use to intialize the smoothing filter + if (searchCount == 1) + predictedMsToGetLock = lockTime; + + // Third locktime and after: predict using exponential smoothing. Respond slowly to changes + else if (searchCount > 1) + predictedMsToGetLock = (lockTime * weighting) + (predictedMsToGetLock * (1 - weighting)); + + searchCount++; // Only tracked so we can diregard initial lock-times + + LOG_DEBUG("Predicting %us to get next lock\n", predictedMsToGetLock / 1000); +} + +// How long do we expect to spend searching for a lock? +uint32_t GPSUpdateScheduling::predictedSearchDurationMs() +{ + return GPSUpdateScheduling::predictedMsToGetLock; +} \ No newline at end of file diff --git a/src/gps/GPSUpdateScheduling.h b/src/gps/GPSUpdateScheduling.h new file mode 100644 index 000000000..7e121c9b6 --- /dev/null +++ b/src/gps/GPSUpdateScheduling.h @@ -0,0 +1,29 @@ +#pragma once + +#include "configuration.h" + +// Encapsulates code responsible for the timing of GPS updates +class GPSUpdateScheduling +{ + public: + // Marks the time of these events, for calculation use + void informSearching(); + void informGotLock(); // Predicted lock-time is recalculated here + + void reset(); // Reset the prediction - after GPS::disable() / GPS::enable() + bool isUpdateDue(); // Is it time to begin searching for a GPS position? + bool searchedTooLong(); // Have we been searching for too long? + + uint32_t msUntilNextSearch(); // How long until we need to begin searching for a GPS? Info provided to GPS hardware for sleep + uint32_t elapsedSearchMs(); // How long have we been searching so far? + uint32_t predictedSearchDurationMs(); // How long do we expect to spend searching for a lock? + + private: + void updateLockTimePrediction(); // Called from informGotLock + uint32_t searchStartedMs = 0; + uint32_t searchEndedMs = 0; + uint32_t searchCount = 0; + uint32_t predictedMsToGetLock = 0; + + const float weighting = 0.2; // Controls exponential smoothing of lock-times prediction. 20% weighting of "latest lock-time". +}; \ No newline at end of file diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp index bbc12521a..d81ab6ff4 100644 --- a/src/graphics/EInkDisplay2.cpp +++ b/src/graphics/EInkDisplay2.cpp @@ -156,7 +156,8 @@ bool EInkDisplay::connect() } } -#elif defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_WIRELESS_PAPER) +#elif defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_VISION_MASTER_E213) || \ + defined(HELTEC_VISION_MASTER_E290) { // Start HSPI hspi = new SPIClass(HSPI); diff --git a/src/graphics/EInkDisplay2.h b/src/graphics/EInkDisplay2.h index f74416494..26091b2cd 100644 --- a/src/graphics/EInkDisplay2.h +++ b/src/graphics/EInkDisplay2.h @@ -5,11 +5,6 @@ #include "GxEPD2_BW.h" #include -#if defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_WIRELESS_PAPER) -// Re-enable SPI after deep sleep: rtc_gpio_hold_dis() -#include "driver/rtc_io.h" -#endif - /** * An adapter class that allows using the GxEPD2 library as if it was an OLEDDisplay implementation. * @@ -72,7 +67,8 @@ class EInkDisplay : public OLEDDisplay GxEPD2_BW *adafruitDisplay = NULL; // If display uses HSPI -#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) +#if defined(HELTEC_WIRELESS_PAPER) || defined(HELTEC_WIRELESS_PAPER_V1_0) || defined(HELTEC_VISION_MASTER_E213) || \ + defined(HELTEC_VISION_MASTER_E290) SPIClass *hspi = NULL; #endif diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index f724ddd3d..7f9c905a8 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1485,6 +1485,10 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_ screen->drawColumns(display, x, y, fields); } +#if defined(ESP_PLATFORM) && defined(USE_ST7789) +SPIClass SPI1(HSPI); +#endif + Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_OledType screenType, OLEDDISPLAY_GEOMETRY geometry) : concurrency::OSThread("Screen"), address_found(address), model(screenType), geometry(geometry), cmdQueue(32) { @@ -1492,6 +1496,13 @@ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_O #if defined(USE_SH1106) || defined(USE_SH1107) || defined(USE_SH1107_128_64) dispdev = new SH1106Wire(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); +#elif defined(USE_ST7789) +#ifdef ESP_PLATFORM + dispdev = new ST7789Spi(&SPI1, ST7789_RESET, ST7789_RS, ST7789_NSS, GEOMETRY_RAWMODE, TFT_WIDTH, TFT_HEIGHT, ST7789_SDA, + ST7789_MISO, ST7789_SCK); +#else + dispdev = new ST7789Spi(&SPI1, ST7789_RESET, ST7789_RS, ST7789_NSS, GEOMETRY_RAWMODE, TFT_WIDTH, TFT_HEIGHT); +#endif #elif defined(USE_SSD1306) dispdev = new SSD1306Wire(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); @@ -1570,7 +1581,14 @@ void Screen::handleSetOn(bool on, FrameCallback einkScreensaver) #endif dispdev->displayOn(); - +#ifdef USE_ST7789 +#ifdef ESP_PLATFORM + analogWrite(VTFT_LEDA, BRIGHTNESS_DEFAULT); +#else + pinMode(VTFT_LEDA, OUTPUT); + digitalWrite(VTFT_LEDA, TFT_BACKLIGHT_ON); +#endif +#endif enabled = true; setInterval(0); // Draw ASAP runASAP = true; @@ -1581,6 +1599,12 @@ void Screen::handleSetOn(bool on, FrameCallback einkScreensaver) #endif LOG_INFO("Turning off screen\n"); dispdev->displayOff(); + +#ifdef USE_ST7789 + pinMode(VTFT_LEDA, OUTPUT); + digitalWrite(VTFT_LEDA, !TFT_BACKLIGHT_ON); +#endif + #ifdef T_WATCH_S3 PMU->disablePowerOutput(XPOWERS_ALDO2); #endif diff --git a/src/graphics/Screen.h b/src/graphics/Screen.h index 83c9a7a94..b89a2917e 100644 --- a/src/graphics/Screen.h +++ b/src/graphics/Screen.h @@ -45,6 +45,8 @@ class Screen #include #elif defined(USE_SSD1306) #include +#elif defined(USE_ST7789) +#include #else // the SH1106/SSD1306 variant is auto-detected #include diff --git a/src/main.cpp b/src/main.cpp index 1e0d998e1..95eeb998d 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -275,6 +275,9 @@ void setup() digitalWrite(VEXT_ENABLE_V05, 1); // turn on the lora antenna boost digitalWrite(ST7735_BL_V05, 1); // turn on display backligth LOG_DEBUG("HELTEC Detect Tracker V1.1\n"); +#elif defined(VEXT_ENABLE) && defined(VEXT_ON_VALUE) + pinMode(VEXT_ENABLE, OUTPUT); + digitalWrite(VEXT_ENABLE, VEXT_ON_VALUE); // turn on the display power #elif defined(VEXT_ENABLE) pinMode(VEXT_ENABLE, OUTPUT); digitalWrite(VEXT_ENABLE, 0); // turn on the display power @@ -713,7 +716,8 @@ void setup() // Don't call screen setup until after nodedb is setup (because we need // the current region name) -#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(HX8357_CS) +#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(HX8357_CS) || \ + defined(USE_ST7789) screen->setup(); #elif defined(ARCH_PORTDUINO) if (screen_found.port != ScanI2C::I2CPort::NO_I2C || settingsMap[displayPanel]) { diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 84872e471..fa5c437c4 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -268,7 +268,8 @@ void NodeDB::installDefaultConfig() // FIXME: Default to bluetooth capability of platform as default config.bluetooth.enabled = true; config.bluetooth.fixed_pin = defaultBLEPin; -#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(HX8357_CS) +#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(HX8357_CS) || \ + defined(USE_ST7789) bool hasScreen = true; #elif ARCH_PORTDUINO bool hasScreen = false; diff --git a/src/mesh/generated/meshtastic/apponly.pb.h b/src/mesh/generated/meshtastic/apponly.pb.h index ba9f90873..f5bacea52 100644 --- a/src/mesh/generated/meshtastic/apponly.pb.h +++ b/src/mesh/generated/meshtastic/apponly.pb.h @@ -55,7 +55,7 @@ extern const pb_msgdesc_t meshtastic_ChannelSet_msg; /* Maximum encoded size of messages (where known) */ #define MESHTASTIC_MESHTASTIC_APPONLY_PB_H_MAX_SIZE meshtastic_ChannelSet_size -#define meshtastic_ChannelSet_size 674 +#define meshtastic_ChannelSet_size 676 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index e3037c910..44a86f4d6 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -497,6 +497,8 @@ typedef struct _meshtastic_Config_LoRaConfig { Please respect your local laws and regulations. If you are a HAM, make sure you enable HAM mode and turn off encryption. */ float override_frequency; + /* If true, disable the build-in PA FAN using pin define in RF95_FAN_EN. */ + bool pa_fan_disabled; /* For testing it is useful sometimes to force a node to never listen to particular other nodes (simulating radio out of range). All nodenums listed in ignore_incoming will have packets they send dropped on receive (by router.cpp) */ @@ -618,7 +620,7 @@ extern "C" { #define meshtastic_Config_NetworkConfig_init_default {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_default, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_default {0, 0, 0, 0} #define meshtastic_Config_DisplayConfig_init_default {0, _meshtastic_Config_DisplayConfig_GpsCoordinateFormat_MIN, 0, 0, 0, _meshtastic_Config_DisplayConfig_DisplayUnits_MIN, _meshtastic_Config_DisplayConfig_OledType_MIN, _meshtastic_Config_DisplayConfig_DisplayMode_MIN, 0, 0, _meshtastic_Config_DisplayConfig_CompassOrientation_MIN} -#define meshtastic_Config_LoRaConfig_init_default {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0} +#define meshtastic_Config_LoRaConfig_init_default {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0} #define meshtastic_Config_BluetoothConfig_init_default {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0, 0} #define meshtastic_Config_init_zero {0, {meshtastic_Config_DeviceConfig_init_zero}} #define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0, "", 0} @@ -627,7 +629,7 @@ extern "C" { #define meshtastic_Config_NetworkConfig_init_zero {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_zero, ""} #define meshtastic_Config_NetworkConfig_IpV4Config_init_zero {0, 0, 0, 0} #define meshtastic_Config_DisplayConfig_init_zero {0, _meshtastic_Config_DisplayConfig_GpsCoordinateFormat_MIN, 0, 0, 0, _meshtastic_Config_DisplayConfig_DisplayUnits_MIN, _meshtastic_Config_DisplayConfig_OledType_MIN, _meshtastic_Config_DisplayConfig_DisplayMode_MIN, 0, 0, _meshtastic_Config_DisplayConfig_CompassOrientation_MIN} -#define meshtastic_Config_LoRaConfig_init_zero {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0} +#define meshtastic_Config_LoRaConfig_init_zero {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0} #define meshtastic_Config_BluetoothConfig_init_zero {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0, 0} /* Field tags (for use in manual encoding/decoding) */ @@ -702,6 +704,7 @@ extern "C" { #define meshtastic_Config_LoRaConfig_override_duty_cycle_tag 12 #define meshtastic_Config_LoRaConfig_sx126x_rx_boosted_gain_tag 13 #define meshtastic_Config_LoRaConfig_override_frequency_tag 14 +#define meshtastic_Config_LoRaConfig_pa_fan_disabled_tag 15 #define meshtastic_Config_LoRaConfig_ignore_incoming_tag 103 #define meshtastic_Config_LoRaConfig_ignore_mqtt_tag 104 #define meshtastic_Config_BluetoothConfig_enabled_tag 1 @@ -832,6 +835,7 @@ X(a, STATIC, SINGULAR, UINT32, channel_num, 11) \ X(a, STATIC, SINGULAR, BOOL, override_duty_cycle, 12) \ X(a, STATIC, SINGULAR, BOOL, sx126x_rx_boosted_gain, 13) \ X(a, STATIC, SINGULAR, FLOAT, override_frequency, 14) \ +X(a, STATIC, SINGULAR, BOOL, pa_fan_disabled, 15) \ X(a, STATIC, REPEATED, UINT32, ignore_incoming, 103) \ X(a, STATIC, SINGULAR, BOOL, ignore_mqtt, 104) #define meshtastic_Config_LoRaConfig_CALLBACK NULL @@ -871,7 +875,7 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg; #define meshtastic_Config_BluetoothConfig_size 12 #define meshtastic_Config_DeviceConfig_size 100 #define meshtastic_Config_DisplayConfig_size 30 -#define meshtastic_Config_LoRaConfig_size 80 +#define meshtastic_Config_LoRaConfig_size 82 #define meshtastic_Config_NetworkConfig_IpV4Config_size 20 #define meshtastic_Config_NetworkConfig_size 196 #define meshtastic_Config_PositionConfig_size 62 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index fc7bea53a..eb37f4f95 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -307,7 +307,7 @@ extern const pb_msgdesc_t meshtastic_OEMStore_msg; #define MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_MAX_SIZE meshtastic_OEMStore_size #define meshtastic_ChannelFile_size 718 #define meshtastic_NodeInfoLite_size 166 -#define meshtastic_OEMStore_size 3384 +#define meshtastic_OEMStore_size 3388 #define meshtastic_PositionLite_size 28 #ifdef __cplusplus diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index c1d2a4ae3..983f48ad3 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -181,8 +181,8 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; /* Maximum encoded size of messages (where known) */ #define MESHTASTIC_MESHTASTIC_LOCALONLY_PB_H_MAX_SIZE meshtastic_LocalModuleConfig_size -#define meshtastic_LocalConfig_size 553 -#define meshtastic_LocalModuleConfig_size 685 +#define meshtastic_LocalConfig_size 555 +#define meshtastic_LocalModuleConfig_size 687 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/module_config.pb.h b/src/mesh/generated/meshtastic/module_config.pb.h index f3c48ee6d..7fd57fe00 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.h +++ b/src/mesh/generated/meshtastic/module_config.pb.h @@ -60,7 +60,9 @@ typedef enum _meshtastic_ModuleConfig_SerialConfig_Serial_Mode { meshtastic_ModuleConfig_SerialConfig_Serial_Mode_TEXTMSG = 3, meshtastic_ModuleConfig_SerialConfig_Serial_Mode_NMEA = 4, /* NMEA messages specifically tailored for CalTopo */ - meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO = 5 + meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO = 5, + /* Ecowitt WS85 weather station */ + meshtastic_ModuleConfig_SerialConfig_Serial_Mode_WS85 = 6 } meshtastic_ModuleConfig_SerialConfig_Serial_Mode; /* TODO: REPLACE */ @@ -273,6 +275,8 @@ typedef struct _meshtastic_ModuleConfig_StoreForwardConfig { uint32_t history_return_max; /* TODO: REPLACE */ uint32_t history_return_window; + /* Set to true to let this node act as a server that stores received messages and resends them upon request. */ + bool is_server; } meshtastic_ModuleConfig_StoreForwardConfig; /* Preferences for the RangeTestModule */ @@ -432,8 +436,8 @@ extern "C" { #define _meshtastic_ModuleConfig_SerialConfig_Serial_Baud_ARRAYSIZE ((meshtastic_ModuleConfig_SerialConfig_Serial_Baud)(meshtastic_ModuleConfig_SerialConfig_Serial_Baud_BAUD_921600+1)) #define _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_MIN meshtastic_ModuleConfig_SerialConfig_Serial_Mode_DEFAULT -#define _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_MAX meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO -#define _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_ARRAYSIZE ((meshtastic_ModuleConfig_SerialConfig_Serial_Mode)(meshtastic_ModuleConfig_SerialConfig_Serial_Mode_CALTOPO+1)) +#define _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_MAX meshtastic_ModuleConfig_SerialConfig_Serial_Mode_WS85 +#define _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_ARRAYSIZE ((meshtastic_ModuleConfig_SerialConfig_Serial_Mode)(meshtastic_ModuleConfig_SerialConfig_Serial_Mode_WS85+1)) #define _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE #define _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MAX meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_BACK @@ -474,7 +478,7 @@ extern "C" { #define meshtastic_ModuleConfig_PaxcounterConfig_init_default {0, 0, 0, 0} #define meshtastic_ModuleConfig_SerialConfig_init_default {0, 0, 0, 0, _meshtastic_ModuleConfig_SerialConfig_Serial_Baud_MIN, 0, _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_MIN, 0} #define meshtastic_ModuleConfig_ExternalNotificationConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} -#define meshtastic_ModuleConfig_StoreForwardConfig_init_default {0, 0, 0, 0, 0} +#define meshtastic_ModuleConfig_StoreForwardConfig_init_default {0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_RangeTestConfig_init_default {0, 0, 0} #define meshtastic_ModuleConfig_TelemetryConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_CannedMessageConfig_init_default {0, 0, 0, 0, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, 0, 0, "", 0} @@ -490,7 +494,7 @@ extern "C" { #define meshtastic_ModuleConfig_PaxcounterConfig_init_zero {0, 0, 0, 0} #define meshtastic_ModuleConfig_SerialConfig_init_zero {0, 0, 0, 0, _meshtastic_ModuleConfig_SerialConfig_Serial_Baud_MIN, 0, _meshtastic_ModuleConfig_SerialConfig_Serial_Mode_MIN, 0} #define meshtastic_ModuleConfig_ExternalNotificationConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} -#define meshtastic_ModuleConfig_StoreForwardConfig_init_zero {0, 0, 0, 0, 0} +#define meshtastic_ModuleConfig_StoreForwardConfig_init_zero {0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_RangeTestConfig_init_zero {0, 0, 0} #define meshtastic_ModuleConfig_TelemetryConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_CannedMessageConfig_init_zero {0, 0, 0, 0, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, 0, 0, "", 0} @@ -560,6 +564,7 @@ extern "C" { #define meshtastic_ModuleConfig_StoreForwardConfig_records_tag 3 #define meshtastic_ModuleConfig_StoreForwardConfig_history_return_max_tag 4 #define meshtastic_ModuleConfig_StoreForwardConfig_history_return_window_tag 5 +#define meshtastic_ModuleConfig_StoreForwardConfig_is_server_tag 6 #define meshtastic_ModuleConfig_RangeTestConfig_enabled_tag 1 #define meshtastic_ModuleConfig_RangeTestConfig_sender_tag 2 #define meshtastic_ModuleConfig_RangeTestConfig_save_tag 3 @@ -743,7 +748,8 @@ X(a, STATIC, SINGULAR, BOOL, enabled, 1) \ X(a, STATIC, SINGULAR, BOOL, heartbeat, 2) \ X(a, STATIC, SINGULAR, UINT32, records, 3) \ X(a, STATIC, SINGULAR, UINT32, history_return_max, 4) \ -X(a, STATIC, SINGULAR, UINT32, history_return_window, 5) +X(a, STATIC, SINGULAR, UINT32, history_return_window, 5) \ +X(a, STATIC, SINGULAR, BOOL, is_server, 6) #define meshtastic_ModuleConfig_StoreForwardConfig_CALLBACK NULL #define meshtastic_ModuleConfig_StoreForwardConfig_DEFAULT NULL @@ -848,7 +854,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_RangeTestConfig_size 10 #define meshtastic_ModuleConfig_RemoteHardwareConfig_size 96 #define meshtastic_ModuleConfig_SerialConfig_size 28 -#define meshtastic_ModuleConfig_StoreForwardConfig_size 22 +#define meshtastic_ModuleConfig_StoreForwardConfig_size 24 #define meshtastic_ModuleConfig_TelemetryConfig_size 36 #define meshtastic_ModuleConfig_size 257 #define meshtastic_RemoteHardwarePin_size 21 diff --git a/src/mesh/generated/meshtastic/telemetry.pb.h b/src/mesh/generated/meshtastic/telemetry.pb.h index 28d368754..82cd0a55d 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.h +++ b/src/mesh/generated/meshtastic/telemetry.pb.h @@ -115,6 +115,10 @@ typedef struct _meshtastic_EnvironmentMetrics { float wind_speed; /* Weight in KG */ float weight; + /* Wind gust in m/s */ + float wind_gust; + /* Wind lull in m/s */ + float wind_lull; } meshtastic_EnvironmentMetrics; /* Power Metrics (voltage / current / etc) */ @@ -205,13 +209,13 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_DeviceMetrics_init_default {0, 0, 0, 0, 0} -#define meshtastic_EnvironmentMetrics_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_EnvironmentMetrics_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_PowerMetrics_init_default {0, 0, 0, 0, 0, 0} #define meshtastic_AirQualityMetrics_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Telemetry_init_default {0, 0, {meshtastic_DeviceMetrics_init_default}} #define meshtastic_Nau7802Config_init_default {0, 0} #define meshtastic_DeviceMetrics_init_zero {0, 0, 0, 0, 0} -#define meshtastic_EnvironmentMetrics_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_EnvironmentMetrics_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_PowerMetrics_init_zero {0, 0, 0, 0, 0, 0} #define meshtastic_AirQualityMetrics_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_Telemetry_init_zero {0, 0, {meshtastic_DeviceMetrics_init_zero}} @@ -238,6 +242,8 @@ extern "C" { #define meshtastic_EnvironmentMetrics_wind_direction_tag 13 #define meshtastic_EnvironmentMetrics_wind_speed_tag 14 #define meshtastic_EnvironmentMetrics_weight_tag 15 +#define meshtastic_EnvironmentMetrics_wind_gust_tag 16 +#define meshtastic_EnvironmentMetrics_wind_lull_tag 17 #define meshtastic_PowerMetrics_ch1_voltage_tag 1 #define meshtastic_PowerMetrics_ch1_current_tag 2 #define meshtastic_PowerMetrics_ch2_voltage_tag 3 @@ -289,7 +295,9 @@ X(a, STATIC, SINGULAR, FLOAT, ir_lux, 11) \ X(a, STATIC, SINGULAR, FLOAT, uv_lux, 12) \ X(a, STATIC, SINGULAR, UINT32, wind_direction, 13) \ X(a, STATIC, SINGULAR, FLOAT, wind_speed, 14) \ -X(a, STATIC, SINGULAR, FLOAT, weight, 15) +X(a, STATIC, SINGULAR, FLOAT, weight, 15) \ +X(a, STATIC, SINGULAR, FLOAT, wind_gust, 16) \ +X(a, STATIC, SINGULAR, FLOAT, wind_lull, 17) #define meshtastic_EnvironmentMetrics_CALLBACK NULL #define meshtastic_EnvironmentMetrics_DEFAULT NULL @@ -357,10 +365,10 @@ extern const pb_msgdesc_t meshtastic_Nau7802Config_msg; #define MESHTASTIC_MESHTASTIC_TELEMETRY_PB_H_MAX_SIZE meshtastic_Telemetry_size #define meshtastic_AirQualityMetrics_size 72 #define meshtastic_DeviceMetrics_size 27 -#define meshtastic_EnvironmentMetrics_size 73 +#define meshtastic_EnvironmentMetrics_size 85 #define meshtastic_Nau7802Config_size 16 #define meshtastic_PowerMetrics_size 30 -#define meshtastic_Telemetry_size 80 +#define meshtastic_Telemetry_size 92 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index d37bb754d..23200fd00 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -115,6 +115,8 @@ int32_t EnvironmentTelemetryModule::runOnce() result = ina219Sensor.runOnce(); if (ina260Sensor.hasSensor()) result = ina260Sensor.runOnce(); + if (ina3221Sensor.hasSensor()) + result = ina3221Sensor.runOnce(); if (veml7700Sensor.hasSensor()) result = veml7700Sensor.runOnce(); if (tsl2591Sensor.hasSensor()) @@ -325,6 +327,10 @@ bool EnvironmentTelemetryModule::getEnvironmentTelemetry(meshtastic_Telemetry *m valid = valid && ina260Sensor.getMetrics(m); hasSensor = true; } + if (ina3221Sensor.hasSensor()) { + valid = valid && ina3221Sensor.getMetrics(m); + hasSensor = true; + } if (veml7700Sensor.hasSensor()) { valid = valid && veml7700Sensor.getMetrics(m); hasSensor = true; @@ -499,6 +505,11 @@ AdminMessageHandleResult EnvironmentTelemetryModule::handleAdminMessageForModule if (result != AdminMessageHandleResult::NOT_HANDLED) return result; } + if (ina3221Sensor.hasSensor()) { + result = ina3221Sensor.handleAdminMessage(mp, request, response); + if (result != AdminMessageHandleResult::NOT_HANDLED) + return result; + } if (veml7700Sensor.hasSensor()) { result = veml7700Sensor.handleAdminMessage(mp, request, response); if (result != AdminMessageHandleResult::NOT_HANDLED) diff --git a/src/modules/Telemetry/Sensor/INA3221Sensor.cpp b/src/modules/Telemetry/Sensor/INA3221Sensor.cpp index edd29682e..dec99c551 100644 --- a/src/modules/Telemetry/Sensor/INA3221Sensor.cpp +++ b/src/modules/Telemetry/Sensor/INA3221Sensor.cpp @@ -27,22 +27,69 @@ int32_t INA3221Sensor::runOnce() void INA3221Sensor::setup() {} +struct _INA3221Measurement INA3221Sensor::getMeasurement(ina3221_ch_t ch) +{ + struct _INA3221Measurement measurement; + + measurement.voltage = ina3221.getVoltage(ch); + measurement.current = ina3221.getCurrent(ch); + + return measurement; +} + +struct _INA3221Measurements INA3221Sensor::getMeasurements() +{ + struct _INA3221Measurements measurements; + + // INA3221 has 3 channels starting from 0 + for (int i = 0; i < 3; i++) { + measurements.measurements[i] = getMeasurement((ina3221_ch_t)i); + } + + return measurements; +} + bool INA3221Sensor::getMetrics(meshtastic_Telemetry *measurement) { - measurement->variant.environment_metrics.voltage = ina3221.getVoltage(INA3221_CH1); - measurement->variant.environment_metrics.current = ina3221.getCurrent(INA3221_CH1); - measurement->variant.power_metrics.ch1_voltage = ina3221.getVoltage(INA3221_CH1); - measurement->variant.power_metrics.ch1_current = ina3221.getCurrent(INA3221_CH1); - measurement->variant.power_metrics.ch2_voltage = ina3221.getVoltage(INA3221_CH2); - measurement->variant.power_metrics.ch2_current = ina3221.getCurrent(INA3221_CH2); - measurement->variant.power_metrics.ch3_voltage = ina3221.getVoltage(INA3221_CH3); - measurement->variant.power_metrics.ch3_current = ina3221.getCurrent(INA3221_CH3); + switch (measurement->which_variant) { + case meshtastic_Telemetry_environment_metrics_tag: + return getEnvironmentMetrics(measurement); + + case meshtastic_Telemetry_power_metrics_tag: + return getPowerMetrics(measurement); + } + + // unsupported metric + return false; +} + +bool INA3221Sensor::getEnvironmentMetrics(meshtastic_Telemetry *measurement) +{ + struct _INA3221Measurement m = getMeasurement(ENV_CH); + + measurement->variant.environment_metrics.voltage = m.voltage; + measurement->variant.environment_metrics.current = m.current; + + return true; +} + +bool INA3221Sensor::getPowerMetrics(meshtastic_Telemetry *measurement) +{ + struct _INA3221Measurements m = getMeasurements(); + + measurement->variant.power_metrics.ch1_voltage = m.measurements[INA3221_CH1].voltage; + measurement->variant.power_metrics.ch1_current = m.measurements[INA3221_CH1].current; + measurement->variant.power_metrics.ch2_voltage = m.measurements[INA3221_CH2].voltage; + measurement->variant.power_metrics.ch2_current = m.measurements[INA3221_CH2].current; + measurement->variant.power_metrics.ch3_voltage = m.measurements[INA3221_CH3].voltage; + measurement->variant.power_metrics.ch3_current = m.measurements[INA3221_CH3].current; + return true; } uint16_t INA3221Sensor::getBusVoltageMv() { - return lround(ina3221.getVoltage(INA3221_CH1) * 1000); + return lround(ina3221.getVoltage(BAT_CH) * 1000); } #endif \ No newline at end of file diff --git a/src/modules/Telemetry/Sensor/INA3221Sensor.h b/src/modules/Telemetry/Sensor/INA3221Sensor.h index 3b8e382ee..d5121aab6 100644 --- a/src/modules/Telemetry/Sensor/INA3221Sensor.h +++ b/src/modules/Telemetry/Sensor/INA3221Sensor.h @@ -12,6 +12,21 @@ class INA3221Sensor : public TelemetrySensor, VoltageSensor private: INA3221 ina3221 = INA3221(INA3221_ADDR42_SDA); + // channel to report voltage/current for environment metrics + ina3221_ch_t ENV_CH = INA3221_CH1; + + // channel to report battery voltage for device_battery_ina_address + ina3221_ch_t BAT_CH = INA3221_CH1; + + // get a single measurement for a channel + struct _INA3221Measurement getMeasurement(ina3221_ch_t ch); + + // get all measurements for all channels + struct _INA3221Measurements getMeasurements(); + + bool getEnvironmentMetrics(meshtastic_Telemetry *measurement); + bool getPowerMetrics(meshtastic_Telemetry *measurement); + protected: void setup() override; @@ -22,4 +37,14 @@ class INA3221Sensor : public TelemetrySensor, VoltageSensor virtual uint16_t getBusVoltageMv() override; }; +struct _INA3221Measurement { + float voltage; + float current; +}; + +struct _INA3221Measurements { + // INA3221 has 3 channels + struct _INA3221Measurement measurements[3]; +}; + #endif \ No newline at end of file diff --git a/src/platform/esp32/architecture.h b/src/platform/esp32/architecture.h index 5565b6468..fd3f92a9c 100644 --- a/src/platform/esp32/architecture.h +++ b/src/platform/esp32/architecture.h @@ -151,6 +151,14 @@ #define HW_VENDOR meshtastic_HardwareModel_RADIOMASTER_900_BANDIT_NANO #elif defined(HELTEC_CAPSULE_SENSOR_V3) #define HW_VENDOR meshtastic_HardwareModel_HELTEC_CAPSULE_SENSOR_V3 +#elif defined(HELTEC_VISION_MASTER_T190) +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_VISION_MASTER_T190 +#elif defined(HELTEC_VISION_MASTER_E213) +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_VISION_MASTER_E213 +#elif defined(HELTEC_VISION_MASTER_E290) +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_VISION_MASTER_E290 +#elif defined(HELTEC_MESH_NODE_T114) +#define HW_VENDOR meshtastic_HardwareModel_HELTEC_MESH_NODE_T114 #endif // ----------------------------------------------------------------------------- diff --git a/src/platform/nrf52/main-nrf52.cpp b/src/platform/nrf52/main-nrf52.cpp index b79f28f13..7334f3a04 100644 --- a/src/platform/nrf52/main-nrf52.cpp +++ b/src/platform/nrf52/main-nrf52.cpp @@ -234,6 +234,18 @@ void cpuDeepSleep(uint32_t msecToWake) // RAK-12039 set pin for Air quality sensor digitalWrite(AQ_SET_PIN, LOW); #endif +#ifdef RAK14014 + // GPIO restores input status, otherwise there will be leakage current + nrf_gpio_cfg_default(TFT_BL); + nrf_gpio_cfg_default(TFT_DC); + nrf_gpio_cfg_default(TFT_CS); + nrf_gpio_cfg_default(TFT_SCLK); + nrf_gpio_cfg_default(TFT_MOSI); + nrf_gpio_cfg_default(TFT_MISO); + nrf_gpio_cfg_default(SCREEN_TOUCH_INT); + nrf_gpio_cfg_default(WB_I2C1_SCL); + nrf_gpio_cfg_default(WB_I2C1_SDA); +#endif #endif // Sleepy trackers or sensors can low power "sleep" // Don't enter this if we're sleeping portMAX_DELAY, since that's a shutdown event @@ -274,5 +286,10 @@ void clearBonds() void enterDfuMode() { +// SDK kit does not have native USB like almost all other NRF52 boards +#ifdef NRF_USE_SERIAL_DFU + enterSerialDfu(); +#else enterUf2Dfu(); +#endif } \ No newline at end of file diff --git a/src/sleep.cpp b/src/sleep.cpp index e2c9549f3..3793ee0cf 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -37,10 +37,7 @@ Observable preflightSleep; /// Called to tell observers we are now entering sleep and you should prepare. Must return 0 /// notifySleep will be called for light or deep sleep, notifyDeepSleep is only called for deep sleep -/// notifyGPSSleep will be called when config.position.gps_enabled is set to 0 or from buttonthread when GPS_POWER_TOGGLE is -/// enabled. Observable notifySleep, notifyDeepSleep; -Observable notifyGPSSleep; // deep sleep support RTC_DATA_ATTR int bootCount = 0; @@ -240,11 +237,6 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) #ifdef PIN_POWER_EN pinMode(PIN_POWER_EN, INPUT); // power off peripherals // pinMode(PIN_POWER_EN1, INPUT_PULLDOWN); -#endif -#if HAS_GPS - // Kill GPS power completely (even if previously we just had it in sleep mode) - if (gps) - gps->setGPSPower(false, false, 0); #endif setLed(false); @@ -257,6 +249,8 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) #elif defined(VEXT_ENABLE_V05) digitalWrite(VEXT_ENABLE_V05, 0); // turn off the lora amplifier power digitalWrite(ST7735_BL_V05, 0); // turn off the display power +#elif defined(VEXT_ENABLE) && defined(VEXT_ON_VALUE) + digitalWrite(VEXT_ENABLE, !VEXT_ON_VALUE); // turn on the display power #elif defined(VEXT_ENABLE) digitalWrite(VEXT_ENABLE, 1); // turn off the display power #endif diff --git a/src/sleep.h b/src/sleep.h index 8d5b9a94f..f154b8d44 100644 --- a/src/sleep.h +++ b/src/sleep.h @@ -41,8 +41,6 @@ extern Observable notifySleep; /// Called to tell observers we are now entering (deep) sleep and you should prepare. Must return 0 extern Observable notifyDeepSleep; -/// Called to tell GPS thread to enter deep sleep independently of LoRa/MCU sleep, prior to full poweroff. Must return 0 -extern Observable notifyGPSSleep; void enableModemSleep(); #ifdef ARCH_ESP32 void enableLoraInterrupt(); diff --git a/variants/heltec_capsule_sensor_v3/variant.h b/variants/heltec_capsule_sensor_v3/variant.h index 0d5ab73cf..51c3cb6ad 100644 --- a/variants/heltec_capsule_sensor_v3/variant.h +++ b/variants/heltec_capsule_sensor_v3/variant.h @@ -1,5 +1,5 @@ #define LED_PIN 33 -#define LED_PIN2 34 +#define LED_PIN2 34 #define EXT_PWR_DETECT 35 #define BUTTON_PIN 18 diff --git a/variants/heltec_mesh_node_t114/platformio.ini b/variants/heltec_mesh_node_t114/platformio.ini new file mode 100644 index 000000000..99bdf77a7 --- /dev/null +++ b/variants/heltec_mesh_node_t114/platformio.ini @@ -0,0 +1,15 @@ +; First prototype nrf52840/sx1262 device +[env:heltec-mesh-node-t114] +extends = nrf52840_base +board = heltec_mesh_node_t114 +debug_tool = jlink + +# add -DCFG_SYSVIEW if you want to use the Segger systemview tool for OS profiling. +build_flags = ${nrf52840_base.build_flags} -Ivariants/heltec_mesh_node_t114 + -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard" + +build_src_filter = ${nrf52_base.build_src_filter} +<../variants/heltec_mesh_node_t114> +lib_deps = + ${nrf52840_base.lib_deps} + lewisxhe/PCF8563_Library@^1.0.1 + https://github.com/Bei-Ji-Quan/st7789#b8e7e076714b670764139289d3829b0beff67edb \ No newline at end of file diff --git a/variants/heltec_mesh_node_t114/variant.cpp b/variants/heltec_mesh_node_t114/variant.cpp new file mode 100644 index 000000000..cae079b74 --- /dev/null +++ b/variants/heltec_mesh_node_t114/variant.cpp @@ -0,0 +1,44 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "variant.h" +#include "nrf.h" +#include "wiring_constants.h" +#include "wiring_digital.h" + +const uint32_t g_ADigitalPinMap[] = { + // P0 - pins 0 and 1 are hardwired for xtal and should never be enabled + 0xff, 0xff, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, + + // P1 + 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47}; + +void initVariant() +{ + // LED1 & LED2 + pinMode(PIN_LED1, OUTPUT); + ledOff(PIN_LED1); + + pinMode(PIN_LED2, OUTPUT); + ledOff(PIN_LED2); + + pinMode(PIN_LED3, OUTPUT); + ledOff(PIN_LED3); +} diff --git a/variants/heltec_mesh_node_t114/variant.h b/variants/heltec_mesh_node_t114/variant.h new file mode 100644 index 000000000..b233069c6 --- /dev/null +++ b/variants/heltec_mesh_node_t114/variant.h @@ -0,0 +1,210 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_HELTEC_NRF_ +#define _VARIANT_HELTEC_NRF_ +/** Master clock frequency */ +#define VARIANT_MCK (64000000ul) + +#define USE_LFXO // Board uses 32khz crystal for LF + +/*---------------------------------------------------------------------------- + * Headers + *----------------------------------------------------------------------------*/ + +#include "WVariant.h" + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +#define HELTEC_MESH_NODE_T114 + +#define USE_ST7789 + +#define ST7789_NSS 11 +#define ST7789_RS 12 // DC +#define ST7789_SDA 41 // MOSI +#define ST7789_SCK 40 +#define ST7789_RESET 2 +#define ST7789_MISO -1 +#define ST7789_BUSY -1 +#define VTFT_CTRL 3 +#define VTFT_LEDA 15 +// #define ST7789_BL (32+6) +#define TFT_BACKLIGHT_ON LOW +#define ST7789_SPI_HOST SPI1_HOST +// #define ST7789_BACKLIGHT_EN (32+6) +#define SPI_FREQUENCY 40000000 +#define SPI_READ_FREQUENCY 16000000 +#define TFT_HEIGHT 135 +#define TFT_WIDTH 240 +#define TFT_OFFSET_X 0 +#define TFT_OFFSET_Y 0 +// #define TFT_OFFSET_ROTATION 0 +// #define SCREEN_ROTATE +// #define SCREEN_TRANSITION_FRAMERATE 5 + +// Number of pins defined in PinDescription array +#define PINS_COUNT (48) +#define NUM_DIGITAL_PINS (48) +#define NUM_ANALOG_INPUTS (1) +#define NUM_ANALOG_OUTPUTS (0) + +// LEDs +#define PIN_LED1 (32 + 3) // 13 red (confirmed on 1.0 board) +// Unused(by firmware) LEDs: +#define PIN_LED2 (1 + 1) // 14 blue +#define PIN_LED3 (1 + 11) // 15 green + +#define LED_RED PIN_LED3 +#define LED_BLUE PIN_LED1 +#define LED_GREEN PIN_LED2 + +#define LED_BUILTIN LED_BLUE +#define LED_CONN PIN_GREEN + +#define LED_STATE_ON 0 // State when LED is lit +#define LED_INVERTED 1 + +/* + * Buttons + */ +#define PIN_BUTTON1 (32 + 10) +// #define PIN_BUTTON2 (0 + 18) // 0.18 is labeled on the board as RESET but we configure it in the bootloader as a regular +// GPIO + +/* +No longer populated on PCB +*/ +#define PIN_SERIAL2_RX (0 + 9) +#define PIN_SERIAL2_TX (0 + 10) +// #define PIN_SERIAL2_EN (0 + 17) + +/** + Wire Interfaces + */ +#define WIRE_INTERFACES_COUNT 1 + +#define PIN_WIRE_SDA (26) +#define PIN_WIRE_SCL (27) + +// QSPI Pins +#define PIN_QSPI_SCK (32 + 14) +#define PIN_QSPI_CS (32 + 15) +#define PIN_QSPI_IO0 (32 + 12) // MOSI if using two bit interface +#define PIN_QSPI_IO1 (32 + 13) // MISO if using two bit interface +#define PIN_QSPI_IO2 (0 + 7) // WP if using two bit interface (i.e. not used) +#define PIN_QSPI_IO3 (0 + 5) // HOLD if using two bit interface (i.e. not used) + +// On-board QSPI Flash +#define EXTERNAL_FLASH_DEVICES MX25R1635F +#define EXTERNAL_FLASH_USE_QSPI + +/* + * Lora radio + */ + +#define USE_SX1262 +// #define USE_SX1268 +#define SX126X_CS (0 + 24) // FIXME - we really should define LORA_CS instead +#define LORA_CS (0 + 24) +#define SX126X_DIO1 (0 + 20) +// Note DIO2 is attached internally to the module to an analog switch for TX/RX switching +// #define SX1262_DIO3 \ +// (0 + 21) // This is used as an *output* from the sx1262 and connected internally to power the tcxo, do not drive from the +// main +// CPU? +#define SX126X_BUSY (0 + 17) +#define SX126X_RESET (0 + 25) +// Not really an E22 but TTGO seems to be trying to clone that +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 + +#define PIN_SPI1_MISO \ + ST7789_MISO // FIXME not really needed, but for now the SPI code requires something to be defined, pick an used GPIO +#define PIN_SPI1_MOSI ST7789_SDA +#define PIN_SPI1_SCK ST7789_SCK + +/* + * GPS pins + */ + +#define GPS_L76K + +#define PIN_GPS_RESET (32 + 6) // An output to reset L76K GPS. As per datasheet, low for > 100ms will reset the L76K +#define GPS_RESET_MODE LOW +#define PIN_GPS_EN (21) +#define GPS_EN_ACTIVE HIGH +#define PIN_GPS_STANDBY (32 + 2) // An output to wake GPS, low means allow sleep, high means force wake +#define PIN_GPS_PPS (32 + 4) +// Seems to be missing on this new board +// #define PIN_GPS_PPS (32 + 4) // Pulse per second input from the GPS +#define GPS_TX_PIN (32 + 5) // This is for bits going TOWARDS the CPU +#define GPS_RX_PIN (32 + 7) // This is for bits going TOWARDS the GPS + +#define GPS_THREAD_INTERVAL 50 + +#define PIN_SERIAL1_RX GPS_TX_PIN +#define PIN_SERIAL1_TX GPS_RX_PIN + +// PCF8563 RTC Module +#define PCF8563_RTC 0x51 + +/* + * SPI Interfaces + */ +#define SPI_INTERFACES_COUNT 2 + +// For LORA, spi 0 +#define PIN_SPI_MISO (0 + 23) +#define PIN_SPI_MOSI (0 + 22) +#define PIN_SPI_SCK (0 + 19) + +// #define PIN_PWR_EN (0 + 6) + +// To debug via the segger JLINK console rather than the CDC-ACM serial device +// #define USE_SEGGER + +// Battery +// The battery sense is hooked to pin A0 (4) +// it is defined in the anlaolgue pin section of this file +// and has 12 bit resolution + +#define ADC_CTRL 6 +#define ADC_CTRL_ENABLED HIGH +#define BATTERY_PIN 4 +#define ADC_RESOLUTION 14 + +#define BATTERY_SENSE_RESOLUTION_BITS 12 +#define BATTERY_SENSE_RESOLUTION 4096.0 +#undef AREF_VOLTAGE +#define AREF_VOLTAGE 3.0 +#define VBAT_AR_INTERNAL AR_INTERNAL_3_0 +#define ADC_MULTIPLIER (4.90F) + +#define HAS_RTC 0 +#ifdef __cplusplus +} +#endif + +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#endif \ No newline at end of file diff --git a/variants/heltec_vision_master_e213/pins_arduino.h b/variants/heltec_vision_master_e213/pins_arduino.h new file mode 100644 index 000000000..01c16c496 --- /dev/null +++ b/variants/heltec_vision_master_e213/pins_arduino.h @@ -0,0 +1,63 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include + +#define HELTEC_VISION_MASTER_E213 true + +static const uint8_t LED_BUILTIN = 35; +#define BUILTIN_LED LED_BUILTIN // backward compatibility +#define LED_BUILTIN LED_BUILTIN + +static const uint8_t TX = 43; +static const uint8_t RX = 44; + +static const uint8_t SDA = 41; +static const uint8_t SCL = 42; + +static const uint8_t SS = 8; +static const uint8_t MOSI = 10; +static const uint8_t MISO = 11; +static const uint8_t SCK = 9; + +static const uint8_t A0 = 1; +static const uint8_t A1 = 2; +static const uint8_t A2 = 3; +static const uint8_t A3 = 4; +static const uint8_t A4 = 5; +static const uint8_t A5 = 6; +static const uint8_t A6 = 7; +static const uint8_t A7 = 8; +static const uint8_t A8 = 9; +static const uint8_t A9 = 10; +static const uint8_t A10 = 11; +static const uint8_t A11 = 12; +static const uint8_t A12 = 13; +static const uint8_t A13 = 14; +static const uint8_t A14 = 15; +static const uint8_t A15 = 16; +static const uint8_t A16 = 17; +static const uint8_t A17 = 18; +static const uint8_t A18 = 19; +static const uint8_t A19 = 20; + +static const uint8_t T1 = 1; +static const uint8_t T2 = 2; +static const uint8_t T3 = 3; +static const uint8_t T4 = 4; +static const uint8_t T5 = 5; +static const uint8_t T6 = 6; +static const uint8_t T7 = 7; +static const uint8_t T8 = 8; +static const uint8_t T9 = 9; +static const uint8_t T10 = 10; +static const uint8_t T11 = 11; +static const uint8_t T12 = 12; +static const uint8_t T13 = 13; +static const uint8_t T14 = 14; + +static const uint8_t RST_LoRa = 12; +static const uint8_t BUSY_LoRa = 13; +static const uint8_t DIO0 = 14; + +#endif /* Pins_Arduino_h */ diff --git a/variants/heltec_vision_master_e213/platformio.ini b/variants/heltec_vision_master_e213/platformio.ini new file mode 100644 index 000000000..77cc65983 --- /dev/null +++ b/variants/heltec_vision_master_e213/platformio.ini @@ -0,0 +1,23 @@ +[env:heltec-vision-master-e213] +extends = esp32s3_base +board = heltec_wifi_lora_32_V3 +build_flags = + ${esp32s3_base.build_flags} + -Ivariants/heltec_vision_master_e213 + -DHELTEC_VISION_MASTER_E213 + -DEINK_DISPLAY_MODEL=GxEPD2_213_FC1 + -DEINK_WIDTH=250 + -DEINK_HEIGHT=122 + -DUSE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk + -DEINK_LIMIT_FASTREFRESH=10 ; How many consecutive fast-refreshes are permitted + -DEINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates + -DEINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates +; -D EINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated + -DEINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. + -DEINK_HASQUIRK_GHOSTING ; Display model is identified as "prone to ghosting" + -DEINK_HASQUIRK_WEAKFASTREFRESH ; Pixels set with fast-refresh are easy to clear, disrupted by sunlight +lib_deps = + ${esp32s3_base.lib_deps} + https://github.com/meshtastic/GxEPD2#b202ebfec6a4821e098cf7a625ba0f6f2400292d + lewisxhe/PCF8563_Library@^1.0.1 +upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_vision_master_e213/variant.h b/variants/heltec_vision_master_e213/variant.h new file mode 100644 index 000000000..169602a0d --- /dev/null +++ b/variants/heltec_vision_master_e213/variant.h @@ -0,0 +1,58 @@ +// #define LED_PIN 18 + +// Enable bus for external periherals +#define I2C_SDA SDA +#define I2C_SCL SCL + +#define USE_EINK + +/* + * eink display pins + */ +#define PIN_EINK_CS 5 +#define PIN_EINK_BUSY 1 +#define PIN_EINK_DC 2 +#define PIN_EINK_RES 3 +#define PIN_EINK_SCLK 4 +#define PIN_EINK_MOSI 6 + +/* + * SPI interfaces + */ +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO 10 // MISO P0.17 +#define PIN_SPI_MOSI 11 // MOSI P0.15 +#define PIN_SPI_SCK 9 // SCK P0.13 + +#define VEXT_ENABLE 18 // powers the oled display and the lora antenna boost +#define VEXT_ON_VALUE 1 +#define BUTTON_PIN 21 + +#define ADC_CTRL 46 +#define ADC_CTRL_ENABLED HIGH +#define BATTERY_PIN 7 +#define ADC_CHANNEL ADC1_GPIO7_CHANNEL +#define ADC_MULTIPLIER 4.9 * 1.03 // Voltage divider is roughly 1:1 +#define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // Voltage divider output is quite high + +#define USE_SX1262 + +#define LORA_DIO0 -1 // a No connect on the SX1262 module +#define LORA_RESET 12 +#define LORA_DIO1 14 // SX1262 IRQ +#define LORA_DIO2 13 // SX1262 BUSY +#define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled + +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 + +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET + +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 \ No newline at end of file diff --git a/variants/heltec_vision_master_e290/pins_arduino.h b/variants/heltec_vision_master_e290/pins_arduino.h new file mode 100644 index 000000000..e5d507846 --- /dev/null +++ b/variants/heltec_vision_master_e290/pins_arduino.h @@ -0,0 +1,61 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include + +static const uint8_t LED_BUILTIN = 35; +#define BUILTIN_LED LED_BUILTIN // backward compatibility +#define LED_BUILTIN LED_BUILTIN + +static const uint8_t TX = 43; +static const uint8_t RX = 44; + +static const uint8_t SDA = 41; +static const uint8_t SCL = 42; + +static const uint8_t SS = 8; +static const uint8_t MOSI = 10; +static const uint8_t MISO = 11; +static const uint8_t SCK = 9; + +static const uint8_t A0 = 1; +static const uint8_t A1 = 2; +static const uint8_t A2 = 3; +static const uint8_t A3 = 4; +static const uint8_t A4 = 5; +static const uint8_t A5 = 6; +static const uint8_t A6 = 7; +static const uint8_t A7 = 8; +static const uint8_t A8 = 9; +static const uint8_t A9 = 10; +static const uint8_t A10 = 11; +static const uint8_t A11 = 12; +static const uint8_t A12 = 13; +static const uint8_t A13 = 14; +static const uint8_t A14 = 15; +static const uint8_t A15 = 16; +static const uint8_t A16 = 17; +static const uint8_t A17 = 18; +static const uint8_t A18 = 19; +static const uint8_t A19 = 20; + +static const uint8_t T1 = 1; +static const uint8_t T2 = 2; +static const uint8_t T3 = 3; +static const uint8_t T4 = 4; +static const uint8_t T5 = 5; +static const uint8_t T6 = 6; +static const uint8_t T7 = 7; +static const uint8_t T8 = 8; +static const uint8_t T9 = 9; +static const uint8_t T10 = 10; +static const uint8_t T11 = 11; +static const uint8_t T12 = 12; +static const uint8_t T13 = 13; +static const uint8_t T14 = 14; + +static const uint8_t RST_LoRa = 12; +static const uint8_t BUSY_LoRa = 13; +static const uint8_t DIO0 = 14; + +#endif /* Pins_Arduino_h */ diff --git a/variants/heltec_vision_master_e290/platformio.ini b/variants/heltec_vision_master_e290/platformio.ini new file mode 100644 index 000000000..60ff60036 --- /dev/null +++ b/variants/heltec_vision_master_e290/platformio.ini @@ -0,0 +1,25 @@ +[env:heltec-vision-master-e290] +board_level = extra +extends = esp32s3_base +board = heltec_wifi_lora_32_V3 +build_flags = + ${esp32s3_base.build_flags} + -Ivariants/heltec_vision_master_e290 + -DHELTEC_VISION_MASTER_E290 + -DEINK_DISPLAY_MODEL=GxEPD2_290_BS + -DEINK_WIDTH=296 + -DEINK_HEIGHT=128 +; -D USE_EINK_DYNAMICDISPLAY ; Enable Dynamic EInk +; -D EINK_LIMIT_FASTREFRESH=10 ; How many consecutive fast-refreshes are permitted +; -D EINK_LIMIT_RATE_BACKGROUND_SEC=1 ; Minimum interval between BACKGROUND updates +; -D EINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates +; -D EINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated +; -D EINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached. +; -D EINK_HASQUIRK_GHOSTING ; Display model is identified as "prone to ghosting" +; -D EINK_HASQUIRK_WEAKFASTREFRESH ; Pixels set with fast-refresh are easy to clear, disrupted by sunlight + +lib_deps = + ${esp32s3_base.lib_deps} + https://github.com/meshtastic/GxEPD2#b202ebfec6a4821e098cf7a625ba0f6f2400292d + lewisxhe/PCF8563_Library@^1.0.1 +upload_speed = 115200 \ No newline at end of file diff --git a/variants/heltec_vision_master_e290/variant.h b/variants/heltec_vision_master_e290/variant.h new file mode 100644 index 000000000..a122a7e0f --- /dev/null +++ b/variants/heltec_vision_master_e290/variant.h @@ -0,0 +1,58 @@ +// #define LED_PIN 18 + +// Enable bus for external periherals +#define I2C_SDA SDA +#define I2C_SCL SCL + +#define USE_EINK + +/* + * eink display pins + */ +#define PIN_EINK_CS 3 +#define PIN_EINK_BUSY 5 +#define PIN_EINK_DC 4 +#define PIN_EINK_RES 5 +#define PIN_EINK_SCLK 2 +#define PIN_EINK_MOSI 1 + +/* + * SPI interfaces + */ +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO 10 // MISO +#define PIN_SPI_MOSI 11 // MOSI +#define PIN_SPI_SCK 9 // SCK + +#define VEXT_ENABLE 18 // powers the e-ink display +#define VEXT_ON_VALUE 1 +#define BUTTON_PIN 21 + +#define ADC_CTRL 46 +#define ADC_CTRL_ENABLED HIGH +#define BATTERY_PIN 7 +#define ADC_CHANNEL ADC1_GPIO7_CHANNEL +#define ADC_MULTIPLIER 4.9 * 1.03 +#define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // Voltage divider output is quite high + +#define USE_SX1262 + +#define LORA_DIO0 -1 // a No connect on the SX1262 module +#define LORA_RESET 12 +#define LORA_DIO1 14 // SX1262 IRQ +#define LORA_DIO2 13 // SX1262 BUSY +#define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled + +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 + +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET + +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 \ No newline at end of file diff --git a/variants/heltec_vision_master_t190/pins_arduino.h b/variants/heltec_vision_master_t190/pins_arduino.h new file mode 100644 index 000000000..e5d507846 --- /dev/null +++ b/variants/heltec_vision_master_t190/pins_arduino.h @@ -0,0 +1,61 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include + +static const uint8_t LED_BUILTIN = 35; +#define BUILTIN_LED LED_BUILTIN // backward compatibility +#define LED_BUILTIN LED_BUILTIN + +static const uint8_t TX = 43; +static const uint8_t RX = 44; + +static const uint8_t SDA = 41; +static const uint8_t SCL = 42; + +static const uint8_t SS = 8; +static const uint8_t MOSI = 10; +static const uint8_t MISO = 11; +static const uint8_t SCK = 9; + +static const uint8_t A0 = 1; +static const uint8_t A1 = 2; +static const uint8_t A2 = 3; +static const uint8_t A3 = 4; +static const uint8_t A4 = 5; +static const uint8_t A5 = 6; +static const uint8_t A6 = 7; +static const uint8_t A7 = 8; +static const uint8_t A8 = 9; +static const uint8_t A9 = 10; +static const uint8_t A10 = 11; +static const uint8_t A11 = 12; +static const uint8_t A12 = 13; +static const uint8_t A13 = 14; +static const uint8_t A14 = 15; +static const uint8_t A15 = 16; +static const uint8_t A16 = 17; +static const uint8_t A17 = 18; +static const uint8_t A18 = 19; +static const uint8_t A19 = 20; + +static const uint8_t T1 = 1; +static const uint8_t T2 = 2; +static const uint8_t T3 = 3; +static const uint8_t T4 = 4; +static const uint8_t T5 = 5; +static const uint8_t T6 = 6; +static const uint8_t T7 = 7; +static const uint8_t T8 = 8; +static const uint8_t T9 = 9; +static const uint8_t T10 = 10; +static const uint8_t T11 = 11; +static const uint8_t T12 = 12; +static const uint8_t T13 = 13; +static const uint8_t T14 = 14; + +static const uint8_t RST_LoRa = 12; +static const uint8_t BUSY_LoRa = 13; +static const uint8_t DIO0 = 14; + +#endif /* Pins_Arduino_h */ diff --git a/variants/heltec_vision_master_t190/platformio.ini b/variants/heltec_vision_master_t190/platformio.ini new file mode 100644 index 000000000..bbaa0075c --- /dev/null +++ b/variants/heltec_vision_master_t190/platformio.ini @@ -0,0 +1,13 @@ +[env:heltec-vision-master-t190] +extends = esp32s3_base +board = heltec_wifi_lora_32_V3 +build_flags = + ${esp32s3_base.build_flags} + -Ivariants/heltec_vision_master_t190 + -DHELTEC_VISION_MASTER_T190 + ; -D PRIVATE_HW +lib_deps = + ${esp32s3_base.lib_deps} + lewisxhe/PCF8563_Library@^1.0.1 + https://github.com/Bei-Ji-Quan/st7789#b8e7e076714b670764139289d3829b0beff67edb +upload_speed = 921600 \ No newline at end of file diff --git a/variants/heltec_vision_master_t190/variant.h b/variants/heltec_vision_master_t190/variant.h new file mode 100644 index 000000000..97500d357 --- /dev/null +++ b/variants/heltec_vision_master_t190/variant.h @@ -0,0 +1,76 @@ +// #define LED_PIN 18 + +// Enable bus for external periherals +#define I2C_SDA 1 +#define I2C_SCL 2 +#define USE_ST7789 + +#define ST7789_NSS 39 +// #define ST7789_CS 39 +#define ST7789_RS 47 // DC +#define ST7789_SDA 48 // MOSI +#define ST7789_SCK 38 +#define ST7789_RESET 40 +#define ST7789_MISO 4 +#define ST7789_BUSY -1 +#define VTFT_CTRL 7 +// #define TFT_BL 3 +#define VTFT_LEDA 17 +#define TFT_BACKLIGHT_ON HIGH +// #define TFT_BL 17 +// #define TFT_BACKLIGHT_ON HIGH +// #define ST7789_BL 3 +#define ST7789_SPI_HOST SPI2_HOST +// #define ST7789_BACKLIGHT_EN 17 +#define SPI_FREQUENCY 10000000 +#define SPI_READ_FREQUENCY 10000000 +#define TFT_HEIGHT 170 +#define TFT_WIDTH 320 +#define TFT_OFFSET_X 0 +#define TFT_OFFSET_Y 0 +// #define TFT_OFFSET_ROTATION 0 +// #define SCREEN_ROTATE +// #define SCREEN_TRANSITION_FRAMERATE 5 +#define BRIGHTNESS_DEFAULT 100 // Medium Low Brightnes + +// #define SLEEP_TIME 120 + +/* + * SPI interfaces + */ +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO 10 // MISO P0.17 +#define PIN_SPI_MOSI 11 // MOSI P0.15 +#define PIN_SPI_SCK 9 // SCK P0.13 + +// #define VEXT_ENABLE 7 // active low, powers the oled display and the lora antenna boost +#define BUTTON_PIN 0 + +#define ADC_CTRL 46 +#define ADC_CTRL_ENABLED HIGH +#define BATTERY_PIN 6 +#define ADC_CHANNEL ADC1_GPIO6_CHANNEL +#define ADC_MULTIPLIER 4.9 * 1.03 // Voltage divider is roughly 1:1 +#define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // Voltage divider output is quite high + +#define USE_SX1262 + +#define LORA_DIO0 -1 // a No connect on the SX1262 module +#define LORA_RESET 12 +#define LORA_DIO1 14 // SX1262 IRQ +#define LORA_DIO2 13 // SX1262 BUSY +#define LORA_DIO3 // Not connected on PCB, but internally on the TTGO SX1262, if DIO3 is high the TXCO is enabled + +#define LORA_SCK 9 +#define LORA_MISO 11 +#define LORA_MOSI 10 +#define LORA_CS 8 + +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET + +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 \ No newline at end of file diff --git a/variants/heltec_wireless_paper/pins_arduino.h b/variants/heltec_wireless_paper/pins_arduino.h index 2bb44161a..3e36d98f5 100644 --- a/variants/heltec_wireless_paper/pins_arduino.h +++ b/variants/heltec_wireless_paper/pins_arduino.h @@ -7,8 +7,6 @@ static const uint8_t LED_BUILTIN = 18; #define BUILTIN_LED LED_BUILTIN // backward compatibility #define LED_BUILTIN LED_BUILTIN -static const uint8_t KEY_BUILTIN = 0; - static const uint8_t TX = 43; static const uint8_t RX = 44; @@ -56,9 +54,6 @@ static const uint8_t T12 = 12; static const uint8_t T13 = 13; static const uint8_t T14 = 14; -static const uint8_t Vext = 45; -static const uint8_t LED = 18; - static const uint8_t RST_LoRa = 12; static const uint8_t BUSY_LoRa = 13; static const uint8_t DIO1 = 14; diff --git a/variants/wio-sdk-wm1110/platformio.ini b/variants/wio-sdk-wm1110/platformio.ini index dc7d47310..766717428 100644 --- a/variants/wio-sdk-wm1110/platformio.ini +++ b/variants/wio-sdk-wm1110/platformio.ini @@ -20,7 +20,7 @@ debug_tool = jlink ; No need to reflash if the binary hasn't changed debug_load_mode = modified ; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm) -upload_protocol = jlink +upload_protocol = nrfutil ;upload_protocol = stlink ; we prefer to stop in setup() because we are an 'ardiuno' app debug_init_break = tbreak setup diff --git a/variants/wio-sdk-wm1110/variant.h b/variants/wio-sdk-wm1110/variant.h index 8ad8c769a..8f66b1f8c 100644 --- a/variants/wio-sdk-wm1110/variant.h +++ b/variants/wio-sdk-wm1110/variant.h @@ -107,6 +107,8 @@ extern "C" { #define LR1110_GNSS_ANT_PIN (32 + 5) // P1.05 37 +#define NRF_USE_SERIAL_DFU + #ifdef __cplusplus } #endif