T-Watch S3 Support (#2632)

* T-Watch WIP

* Updates

* Temp

* Update screen spi bus and and backlight en

* Peripherals progress

* Fixes

* Fixes

* Updates

* DRV scaffolding

* Fixed touch-screen driver selection. WIP on DRV haptic feedback

* DRV2605 pmu channel

* Trunk

* Fixes and defaults

* Dropped an s

* Move PMU and turn off screen that way

* Add t-deck and t-watch-s3 to CI and cleanup

* More cleanup
This commit is contained in:
Ben Meadors
2023-07-22 09:26:54 -05:00
committed by GitHub
parent 1c74479555
commit 0739bc0cea
25 changed files with 423 additions and 33 deletions

View File

@@ -6,10 +6,37 @@
#include <Adafruit_LIS3DH.h>
#include <Adafruit_MPU6050.h>
#include <Arduino.h>
#include <Wire.h>
#include <bma.h>
BMA423 bmaSensor;
bool BMA_IRQ = false;
#define ACCELEROMETER_CHECK_INTERVAL_MS 100
#define ACCELEROMETER_CLICK_THRESHOLD 40
uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len)
{
Wire.beginTransmission(address);
Wire.write(reg);
Wire.endTransmission();
Wire.requestFrom((uint8_t)address, (uint8_t)len);
uint8_t i = 0;
while (Wire.available()) {
data[i++] = Wire.read();
}
return 0; // Pass
}
uint16_t writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len)
{
Wire.beginTransmission(address);
Wire.write(reg);
Wire.write(data, len);
return (0 != Wire.endTransmission());
}
namespace concurrency
{
class AccelerometerThread : public concurrency::OSThread
@@ -29,10 +56,10 @@ class AccelerometerThread : public concurrency::OSThread
return;
}
accleremoter_type = type;
acceleremoter_type = type;
LOG_DEBUG("AccelerometerThread initializing\n");
if (accleremoter_type == ScanI2C::DeviceType::MPU6050 && mpu.begin(accelerometer_found.address)) {
if (acceleremoter_type == ScanI2C::DeviceType::MPU6050 && mpu.begin(accelerometer_found.address)) {
LOG_DEBUG("MPU6050 initializing\n");
// setup motion detection
mpu.setHighPassFilter(MPU6050_HIGHPASS_0_63_HZ);
@@ -40,11 +67,60 @@ class AccelerometerThread : public concurrency::OSThread
mpu.setMotionDetectionDuration(20);
mpu.setInterruptPinLatch(true); // Keep it latched. Will turn off when reinitialized.
mpu.setInterruptPinPolarity(true);
} else if (accleremoter_type == ScanI2C::DeviceType::LIS3DH && lis.begin(accelerometer_found.address)) {
} else if (acceleremoter_type == ScanI2C::DeviceType::LIS3DH && lis.begin(accelerometer_found.address)) {
LOG_DEBUG("LIS3DH initializing\n");
lis.setRange(LIS3DH_RANGE_2_G);
// Adjust threshold, higher numbers are less sensitive
lis.setClick(config.device.double_tap_as_button_press ? 2 : 1, ACCELEROMETER_CLICK_THRESHOLD);
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.begin(readRegister, writeRegister, delay)) {
LOG_DEBUG("BMA423 initializing\n");
Acfg cfg;
cfg.odr = BMA4_OUTPUT_DATA_RATE_100HZ;
cfg.range = BMA4_ACCEL_RANGE_2G;
cfg.bandwidth = BMA4_ACCEL_NORMAL_AVG4;
cfg.perf_mode = BMA4_CONTINUOUS_MODE;
bmaSensor.setAccelConfig(cfg);
bmaSensor.enableAccel();
struct bma4_int_pin_config pin_config;
pin_config.edge_ctrl = BMA4_LEVEL_TRIGGER;
pin_config.lvl = BMA4_ACTIVE_HIGH;
pin_config.od = BMA4_PUSH_PULL;
pin_config.output_en = BMA4_OUTPUT_ENABLE;
pin_config.input_en = BMA4_INPUT_DISABLE;
// The correct trigger interrupt needs to be configured as needed
bmaSensor.setINTPinConfig(pin_config, BMA4_INTR1_MAP);
#ifdef BMA423_INT
pinMode(BMA4XX_INT, INPUT);
attachInterrupt(
BMA4XX_INT,
[] {
// Set interrupt to set irq value to true
BMA_IRQ = true;
},
RISING); // Select the interrupt mode according to the actual circuit
#endif
struct bma423_axes_remap remap_data;
remap_data.x_axis = 0;
remap_data.x_axis_sign = 1;
remap_data.y_axis = 1;
remap_data.y_axis_sign = 0;
remap_data.z_axis = 2;
remap_data.z_axis_sign = 1;
// Need to raise the wrist function, need to set the correct axis
bmaSensor.setRemapAxes(&remap_data);
// sensor.enableFeature(BMA423_STEP_CNTR, true);
bmaSensor.enableFeature(BMA423_TILT, true);
bmaSensor.enableFeature(BMA423_WAKEUP, true);
// sensor.resetStepCounter();
// Turn on feature interrupt
bmaSensor.enableStepCountInterrupt();
bmaSensor.enableTiltInterrupt();
// It corresponds to isDoubleClick interrupt
bmaSensor.enableWakeupInterrupt();
}
}
@@ -53,9 +129,9 @@ class AccelerometerThread : public concurrency::OSThread
{
canSleep = true; // Assume we should not keep the board awake
if (accleremoter_type == ScanI2C::DeviceType::MPU6050 && mpu.getMotionInterruptStatus()) {
if (acceleremoter_type == ScanI2C::DeviceType::MPU6050 && mpu.getMotionInterruptStatus()) {
wakeScreen();
} else if (accleremoter_type == ScanI2C::DeviceType::LIS3DH && lis.getClick() > 0) {
} else if (acceleremoter_type == ScanI2C::DeviceType::LIS3DH && lis.getClick() > 0) {
uint8_t click = lis.getClick();
if (!config.device.double_tap_as_button_press) {
wakeScreen();
@@ -65,7 +141,13 @@ class AccelerometerThread : public concurrency::OSThread
buttonPress();
return 500;
}
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.getINT()) {
if (bmaSensor.isTilt() || bmaSensor.isDoubleClick()) {
wakeScreen();
return 500;
}
}
return ACCELEROMETER_CHECK_INTERVAL_MS;
}
@@ -84,9 +166,9 @@ class AccelerometerThread : public concurrency::OSThread
powerFSM.trigger(EVENT_PRESS);
}
ScanI2C::DeviceType accleremoter_type;
ScanI2C::DeviceType acceleremoter_type;
Adafruit_MPU6050 mpu;
Adafruit_LIS3DH lis;
};
} // namespace concurrency
} // namespace concurrency

View File

@@ -4,6 +4,7 @@
#include "concurrency/OSThread.h"
#include "configuration.h"
#include "graphics/Screen.h"
#include "main.h"
#include "power.h"
#include <OneButton.h>
@@ -100,6 +101,21 @@ class ButtonThread : public concurrency::OSThread
#endif
// if (!canSleep) LOG_DEBUG("Suppressing sleep!\n");
// else LOG_DEBUG("sleep ok\n");
#if defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS)
int x, y = 0;
screen->getTouch(&x, &y);
if (x > 0 && y > 0) {
#ifdef T_WATCH_S3
drv.setWaveform(0, 75);
drv.setWaveform(1, 0); // end waveform
drv.go();
#endif
LOG_DEBUG("touch %d %d\n", x, y);
powerFSM.trigger(EVENT_PRESS);
return 150; // Check for next touch every in 150ms
}
#endif
return 5;
}

View File

@@ -540,10 +540,12 @@ int32_t Power::runOnce()
LOG_DEBUG("Battery removed\n");
}
*/
#ifndef T_WATCH_S3 // FIXME - why is this triggering on the T-Watch S3?
if (PMU->isPekeyLongPressIrq()) {
LOG_DEBUG("PEK long button press\n");
screen->setOn(false);
}
#endif
PMU->clearIrqStatus();
}
@@ -681,7 +683,8 @@ bool Power::axpChipInit()
// GNSS VDD 3300mV
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
PMU->enablePowerOutput(XPOWERS_ALDO3);
} else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE) {
} else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE ||
HW_VENDOR == meshtastic_HardwareModel_T_WATCH_S3) {
// t-beam s3 core
/**
* gnss module power channel
@@ -716,6 +719,12 @@ bool Power::axpChipInit()
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
PMU->enablePowerOutput(XPOWERS_BLDO1);
#ifdef T_WATCH_S3
// DRV2605 power channel
PMU->setPowerChannelVoltage(XPOWERS_BLDO2, 3300);
PMU->enablePowerOutput(XPOWERS_BLDO2);
#endif
// PMU->setPowerChannelVoltage(XPOWERS_DCDC4, 3300);
// PMU->enablePowerOutput(XPOWERS_DCDC4);

View File

@@ -123,6 +123,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// -----------------------------------------------------------------------------
#define MPU6050_ADDR 0x68
#define LIS3DH_ADR 0x18
#define BMA423_ADDR 0x19
// -----------------------------------------------------------------------------
// LED
@@ -193,4 +194,4 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#ifndef HW_VENDOR
#error HW_VENDOR must be defined
#endif
#endif

View File

@@ -36,8 +36,8 @@ ScanI2C::FoundDevice ScanI2C::firstKeyboard() const
ScanI2C::FoundDevice ScanI2C::firstAccelerometer() const
{
ScanI2C::DeviceType types[] = {MPU6050, LIS3DH};
return firstOfOrNONE(2, types);
ScanI2C::DeviceType types[] = {MPU6050, LIS3DH, BMA423};
return firstOfOrNONE(3, types);
}
ScanI2C::FoundDevice ScanI2C::find(ScanI2C::DeviceType) const
@@ -73,4 +73,4 @@ bool ScanI2C::DeviceAddress::operator<(const ScanI2C::DeviceAddress &other) cons
|| (port != NO_I2C && other.port != NO_I2C && (address < other.address));
}
ScanI2C::FoundDevice::FoundDevice(ScanI2C::DeviceType type, ScanI2C::DeviceAddress address) : type(type), address(address) {}
ScanI2C::FoundDevice::FoundDevice(ScanI2C::DeviceType type, ScanI2C::DeviceAddress address) : type(type), address(address) {}

View File

@@ -33,6 +33,7 @@ class ScanI2C
PMSA0031,
MPU6050,
LIS3DH,
BMA423,
#ifdef HAS_NCP5623
NCP5623,
#endif

View File

@@ -274,6 +274,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port)
SCAN_SIMPLE_CASE(PMSA0031_ADDR, PMSA0031, "PMSA0031 air quality sensor found\n")
SCAN_SIMPLE_CASE(MPU6050_ADDR, MPU6050, "MPU6050 accelerometer found\n");
SCAN_SIMPLE_CASE(BMA423_ADDR, BMA423, "BMA423 accelerometer found\n");
default:
LOG_INFO("Device found at address 0x%x was not able to be enumerated\n", addr.address);

View File

@@ -944,6 +944,9 @@ void Screen::handleSetOn(bool on)
if (on != screenOn) {
if (on) {
LOG_INFO("Turning on screen\n");
#ifdef T_WATCH_S3
PMU->enablePowerOutput(XPOWERS_ALDO2);
#endif
dispdev.displayOn();
dispdev.displayOn();
enabled = true;
@@ -952,6 +955,9 @@ void Screen::handleSetOn(bool on)
} else {
LOG_INFO("Turning off screen\n");
dispdev.displayOff();
#ifdef T_WATCH_S3
PMU->disablePowerOutput(XPOWERS_ALDO2);
#endif
enabled = false;
}
screenOn = on;

View File

@@ -313,6 +313,13 @@ class Screen : public concurrency::OSThread
void setWelcomeFrames();
void getTouch(int *x, int *y)
{
#if defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7789_CS)
dispdev.getTouch(x, y);
#endif
};
protected:
/// Updates the UI.
//
@@ -394,4 +401,4 @@ class Screen : public concurrency::OSThread
};
} // namespace graphics
#endif
#endif

View File

@@ -108,7 +108,11 @@ class LGFX : public lgfx::LGFX_Device
lgfx::Panel_ST7789 _panel_instance;
lgfx::Bus_SPI _bus_instance;
lgfx::Light_PWM _light_instance;
#ifdef T_WATCH_S3
lgfx::Touch_FT5x06 _touch_instance;
#else
lgfx::Touch_GT911 _touch_instance;
#endif
public:
LGFX(void)
@@ -194,8 +198,13 @@ class LGFX : public lgfx::LGFX_Device
// I2C
cfg.i2c_port = 1;
cfg.i2c_addr = TOUCH_SLAVE_ADDRESS;
#ifdef SCREEN_TOUCH_USE_I2C1
cfg.pin_sda = I2C_SDA1;
cfg.pin_scl = I2C_SCL1;
#else
cfg.pin_sda = I2C_SDA;
cfg.pin_scl = I2C_SCL;
#endif
cfg.freq = 400000;
_touch_instance.config(cfg);
@@ -261,7 +270,7 @@ void TFTDisplay::sendCommand(uint8_t com)
// handle display on/off directly
switch (com) {
case DISPLAYON: {
#ifdef TFT_BL
#if defined(TFT_BL) && defined(TFT_BACKLIGHT_ON)
digitalWrite(TFT_BL, TFT_BACKLIGHT_ON);
#endif
#ifdef VTFT_CTRL
@@ -270,7 +279,7 @@ void TFTDisplay::sendCommand(uint8_t com)
break;
}
case DISPLAYOFF: {
#ifdef TFT_BL
#if defined(TFT_BL) && defined(TFT_BACKLIGHT_ON)
digitalWrite(TFT_BL, !TFT_BACKLIGHT_ON);
#endif
#ifdef VTFT_CTRL
@@ -304,6 +313,8 @@ bool TFTDisplay::connect()
tft.init();
#if defined(M5STACK) || defined(T_DECK)
tft.setRotation(1); // M5Stack/T-Deck have the TFT in landscape
#elif defined(T_WATCH_S3)
tft.setRotation(0); // T-Watch S3 has the TFT in portrait
#else
tft.setRotation(3); // Orient horizontal and wide underneath the silkscreen name label
#endif
@@ -311,4 +322,12 @@ bool TFTDisplay::connect()
return true;
}
// Get touch coords from the display
void TFTDisplay::getTouch(int *x, int *y)
{
#ifndef M5STACK
tft.getTouch(x, y);
#endif
}
#endif

View File

@@ -28,6 +28,8 @@ class TFTDisplay : public OLEDDisplay
*/
void setDetected(uint8_t detected);
void getTouch(int *x, int *y);
protected:
// the header size of the buffer used, e.g. for the SPI command header
virtual int getBufferOffset(void) override { return 0; }
@@ -37,4 +39,4 @@ class TFTDisplay : public OLEDDisplay
// Connect to the display
virtual bool connect() override;
};
};

View File

@@ -110,6 +110,11 @@ ScanI2C::FoundDevice rgb_found = ScanI2C::FoundDevice(ScanI2C::DeviceType::NONE,
ATECCX08A atecc;
#endif
#ifdef T_WATCH_S3
Adafruit_DRV2605 drv;
#endif
bool isVibrating = false;
bool eink_found = true;
uint32_t serialSinceMsec;
@@ -485,10 +490,19 @@ void setup()
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
if (acc_info.type != ScanI2C::DeviceType::NONE) {
config.display.wake_on_tap_or_motion = true;
moduleConfig.external_notification.enabled = true;
accelerometerThread = new AccelerometerThread(acc_info.type);
}
#endif
#ifdef T_WATCH_S3
drv.begin();
drv.selectLibrary(1);
// I2C trigger by sending 'go' command
drv.setMode(DRV2605_MODE_INTTRIG);
#endif
// Init our SPI controller (must be before screen and lora)
initSPI();
#ifdef ARCH_RP2040

View File

@@ -38,6 +38,12 @@ extern bool isUSBPowered;
extern ATECCX08A atecc;
#endif
#ifdef T_WATCH_S3
#include <Adafruit_DRV2605.h>
extern Adafruit_DRV2605 drv;
#endif
extern bool isVibrating;
extern int TCPPort; // set by Portduino
// Global Screen singleton.

View File

@@ -165,6 +165,7 @@ void NodeDB::installDefaultConfig()
config.has_network = true;
config.has_bluetooth = true;
config.device.rebroadcast_mode = meshtastic_Config_DeviceConfig_RebroadcastMode_ALL;
config.lora.sx126x_rx_boosted_gain = false;
config.lora.tx_enabled =
true; // FIXME: maybe false in the future, and setting region to enable it. (unset region forces it off)
@@ -195,6 +196,11 @@ void NodeDB::installDefaultConfig()
config.position.position_flags =
(meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE | meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE_MSL);
#ifdef T_WATCH_S3
config.display.screen_on_secs = 30;
config.display.wake_on_tap_or_motion = true;
#endif
initConfigIntervals();
}
@@ -233,6 +239,10 @@ void NodeDB::installDefaultModuleConfig()
moduleConfig.external_notification.alert_message = true;
moduleConfig.external_notification.output_ms = 1000;
moduleConfig.external_notification.nag_timeout = 60;
#endif
#ifdef T_WATCH_S3
// Don't worry about the other settings, we'll use the DRV2056 behavior for notifications
moduleConfig.external_notification.enabled = true;
#endif
moduleConfig.has_canned_message = true;
@@ -916,4 +926,4 @@ void recordCriticalError(meshtastic_CriticalErrorCode code, uint32_t address, co
LOG_ERROR("A critical failure occurred, portduino is exiting...");
exit(2);
#endif
}
}

View File

@@ -93,6 +93,10 @@ int32_t ExternalNotificationModule::runOnce()
rgb.setColor(red, green, blue);
}
#endif
#ifdef T_WATCH_S3
drv.go();
#endif
}
// now let the PWM buzzer play
@@ -124,7 +128,8 @@ void ExternalNotificationModule::setExternalOn(uint8_t index)
digitalWrite(moduleConfig.external_notification.output_buzzer, true);
break;
default:
digitalWrite(output, (moduleConfig.external_notification.active ? true : false));
if (output > 0)
digitalWrite(output, (moduleConfig.external_notification.active ? true : false));
break;
}
#ifdef HAS_NCP5623
@@ -132,6 +137,9 @@ void ExternalNotificationModule::setExternalOn(uint8_t index)
rgb.setColor(red, green, blue);
}
#endif
#ifdef T_WATCH_S3
drv.go();
#endif
}
void ExternalNotificationModule::setExternalOff(uint8_t index)
@@ -149,7 +157,8 @@ void ExternalNotificationModule::setExternalOff(uint8_t index)
digitalWrite(moduleConfig.external_notification.output_buzzer, false);
break;
default:
digitalWrite(output, (moduleConfig.external_notification.active ? false : true));
if (output > 0)
digitalWrite(output, (moduleConfig.external_notification.active ? false : true));
break;
}
@@ -161,6 +170,9 @@ void ExternalNotificationModule::setExternalOff(uint8_t index)
rgb.setColor(red, green, blue);
}
#endif
#ifdef T_WATCH_S3
drv.stop();
#endif
}
bool ExternalNotificationModule::getExternal(uint8_t index)
@@ -174,6 +186,9 @@ void ExternalNotificationModule::stopNow()
nagCycleCutoff = 1; // small value
isNagging = false;
setIntervalFromNow(0);
#ifdef T_WATCH_S3
drv.stop();
#endif
}
ExternalNotificationModule::ExternalNotificationModule()
@@ -185,7 +200,6 @@ ExternalNotificationModule::ExternalNotificationModule()
without having to configure it from the PythonAPI or WebUI.
*/
// moduleConfig.external_notification.enabled = true;
// moduleConfig.external_notification.alert_message = true;
// moduleConfig.external_notification.alert_message_buzzer = true;
// moduleConfig.external_notification.alert_message_vibra = true;
@@ -213,8 +227,10 @@ ExternalNotificationModule::ExternalNotificationModule()
: EXT_NOTIFICATION_MODULE_OUTPUT;
// Set the direction of a pin
LOG_INFO("Using Pin %i in digital mode\n", output);
pinMode(output, OUTPUT);
if (output > 0) {
LOG_INFO("Using Pin %i in digital mode\n", output);
pinMode(output, OUTPUT);
}
setExternalOff(0);
externalTurnedOn[0] = 0;
if (moduleConfig.external_notification.output_vibra) {
@@ -250,7 +266,12 @@ ExternalNotificationModule::ExternalNotificationModule()
ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshPacket &mp)
{
if (moduleConfig.external_notification.enabled) {
#if T_WATCH_S3
drv.setWaveform(0, 75);
drv.setWaveform(1, 56);
drv.setWaveform(2, 0);
drv.go();
#endif
if (getFrom(&mp) != nodeDB.getNodeNum()) {
// Check if the message contains a bell character. Don't do this loop for every pin, just once.
@@ -343,7 +364,6 @@ ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshP
}
setIntervalFromNow(0); // run once so we know if we should do something
}
} else {
LOG_INFO("External Notification Module Disabled\n");
}

View File

@@ -46,6 +46,10 @@
#if defined(HAS_AXP192) || defined(HAS_AXP2101)
#define HAS_PMU
#endif
#ifdef PIN_BUTTON_TOUCH
#define BUTTON_PIN_TOUCH PIN_BUTTON_TOUCH
#endif
//
// set HW_VENDOR
//
@@ -83,6 +87,8 @@
#define HW_VENDOR meshtastic_HardwareModel_TLORA_V2_1_1P8
#elif defined(T_DECK)
#define HW_VENDOR meshtastic_HardwareModel_T_DECK
#elif defined(T_WATCH_S3)
#define HW_VENDOR meshtastic_HardwareModel_T_WATCH_S3
#elif defined(GENIEBLOCKS)
#define HW_VENDOR meshtastic_HardwareModel_GENIEBLOCKS
#elif defined(PRIVATE_HW)

View File

@@ -23,11 +23,6 @@ esp_sleep_source_t wakeCause; // the reason we booted this time
#define INCLUDE_vTaskSuspend 0
#endif
#ifdef HAS_PMU
#include "XPowersLibInterface.hpp"
extern XPowersLibInterface *PMU;
#endif
/// Called to ask any observers if they want to veto sleep. Return 1 to veto or 0 to allow sleep to happen
Observable<void *> preflightSleep;
@@ -259,7 +254,8 @@ void doDeepSleep(uint32_t msecToWake)
if (HW_VENDOR == meshtastic_HardwareModel_TBEAM) {
// t-beam v1.2 radio power channel
PMU->disablePowerOutput(XPOWERS_ALDO2); // lora radio power channel
} else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE) {
} else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE ||
HW_VENDOR == meshtastic_HardwareModel_T_WATCH_S3) {
PMU->disablePowerOutput(XPOWERS_ALDO3); // lora radio power channel
}
} else if (model == XPOWERS_AXP192) {
@@ -388,4 +384,4 @@ void enableModemSleep()
int rv = esp_pm_configure(&esp32_config);
LOG_DEBUG("Sleep request result %x\n", rv);
}
#endif
#endif

View File

@@ -12,6 +12,12 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t msecToWake);
extern esp_sleep_source_t wakeCause;
#endif
#ifdef HAS_PMU
#include "XPowersLibInterface.hpp"
extern XPowersLibInterface *PMU;
#endif
void setGPSPower(bool on);
void doGPSpowersave(bool on);
// Perform power on init that we do on each wake from deep sleep