Added very basic support for Heltec V3 battery voltage

This commit is contained in:
macvenez 2024-09-02 18:14:44 +02:00
parent 06b4683993
commit a73bdad9fd
2 changed files with 1180 additions and 1096 deletions

791
Boards.h

File diff suppressed because it is too large Load Diff

367
Power.h
View File

@ -1,16 +1,18 @@
#if BOARD_MODEL == BOARD_TBEAM #if BOARD_MODEL == BOARD_TBEAM
#include <XPowersLib.h> #include <XPowersLib.h>
XPowersLibInterface* PMU = NULL; XPowersLibInterface *PMU = NULL;
#ifndef PMU_WIRE_PORT #ifndef PMU_WIRE_PORT
#define PMU_WIRE_PORT Wire #define PMU_WIRE_PORT Wire
#endif #endif
#define BAT_V_MIN 3.15 #define BAT_V_MIN 3.15
#define BAT_V_MAX 4.14 #define BAT_V_MAX 4.14
void disablePeripherals() { void disablePeripherals()
if (PMU) { {
if (PMU)
{
// GNSS RTC PowerVDD // GNSS RTC PowerVDD
PMU->enablePowerOutput(XPOWERS_VBACKUP); PMU->enablePowerOutput(XPOWERS_VBACKUP);
@ -20,30 +22,30 @@
// GNSS VDD // GNSS VDD
PMU->disablePowerOutput(XPOWERS_ALDO3); PMU->disablePowerOutput(XPOWERS_ALDO3);
} }
} }
bool pmuInterrupt; bool pmuInterrupt;
void setPmuFlag() void setPmuFlag()
{ {
pmuInterrupt = true; pmuInterrupt = true;
} }
#elif BOARD_MODEL == BOARD_RNODE_NG_21 || BOARD_MODEL == BOARD_LORA32_V2_1 #elif BOARD_MODEL == BOARD_RNODE_NG_21 || BOARD_MODEL == BOARD_LORA32_V2_1
#define BAT_C_SAMPLES 7 #define BAT_C_SAMPLES 7
#define BAT_D_SAMPLES 2 #define BAT_D_SAMPLES 2
#define BAT_V_MIN 3.15 #define BAT_V_MIN 3.15
#define BAT_V_MAX 4.3 #define BAT_V_MAX 4.3
#define BAT_V_CHG 4.48 #define BAT_V_CHG 4.48
#define BAT_V_FLOAT 4.33 #define BAT_V_FLOAT 4.33
#define BAT_SAMPLES 5 #define BAT_SAMPLES 5
const uint8_t pin_vbat = 35; const uint8_t pin_vbat = 35;
float bat_p_samples[BAT_SAMPLES]; float bat_p_samples[BAT_SAMPLES];
float bat_v_samples[BAT_SAMPLES]; float bat_v_samples[BAT_SAMPLES];
uint8_t bat_samples_count = 0; uint8_t bat_samples_count = 0;
int bat_discharging_samples = 0; int bat_discharging_samples = 0;
int bat_charging_samples = 0; int bat_charging_samples = 0;
int bat_charged_samples = 0; int bat_charged_samples = 0;
bool bat_voltage_dropping = false; bool bat_voltage_dropping = false;
float bat_delay_v = 0; float bat_delay_v = 0;
#elif BOARD_MODEL == BOARD_RAK4631 #elif BOARD_MODEL == BOARD_RAK4631
#include "nrfx_power.h" #include "nrfx_power.h"
#define BAT_C_SAMPLES 7 #define BAT_C_SAMPLES 7
@ -64,65 +66,81 @@ int bat_charging_samples = 0;
int bat_charged_samples = 0; int bat_charged_samples = 0;
bool bat_voltage_dropping = false; bool bat_voltage_dropping = false;
float bat_delay_v = 0; float bat_delay_v = 0;
#elif BOARD_MODEL == BOARD_HELTEC32_V3
#define PIN_VBAT 1
#define VBAT_READ_CNTRL_PIN 37
#endif #endif
uint32_t last_pmu_update = 0; uint32_t last_pmu_update = 0;
uint8_t pmu_target_pps = 1; uint8_t pmu_target_pps = 1;
int pmu_update_interval = 1000/pmu_target_pps; int pmu_update_interval = 1000 / pmu_target_pps;
uint8_t pmu_rc = 0; uint8_t pmu_rc = 0;
#define PMU_R_INTERVAL 5 #define PMU_R_INTERVAL 5
void kiss_indicate_battery(); void kiss_indicate_battery();
void measure_battery() { void measure_battery()
#if BOARD_MODEL == BOARD_RNODE_NG_21 || BOARD_MODEL == BOARD_LORA32_V2_1 {
#if BOARD_MODEL == BOARD_RNODE_NG_21 || BOARD_MODEL == BOARD_LORA32_V2_1
battery_installed = true; battery_installed = true;
battery_indeterminate = true; battery_indeterminate = true;
bat_v_samples[bat_samples_count%BAT_SAMPLES] = (float)(analogRead(pin_vbat)) / 4095*2*3.3*1.1; bat_v_samples[bat_samples_count % BAT_SAMPLES] = (float)(analogRead(pin_vbat)) / 4095 * 2 * 3.3 * 1.1;
bat_p_samples[bat_samples_count%BAT_SAMPLES] = ((battery_voltage-BAT_V_MIN) / (BAT_V_MAX-BAT_V_MIN))*100.0; bat_p_samples[bat_samples_count % BAT_SAMPLES] = ((battery_voltage - BAT_V_MIN) / (BAT_V_MAX - BAT_V_MIN)) * 100.0;
bat_samples_count++; bat_samples_count++;
if (!battery_ready && bat_samples_count >= BAT_SAMPLES) { if (!battery_ready && bat_samples_count >= BAT_SAMPLES)
{
battery_ready = true; battery_ready = true;
} }
if (battery_ready) { if (battery_ready)
{
battery_percent = 0; battery_percent = 0;
for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++) { for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++)
{
battery_percent += bat_p_samples[bi]; battery_percent += bat_p_samples[bi];
} }
battery_percent = battery_percent/BAT_SAMPLES; battery_percent = battery_percent / BAT_SAMPLES;
battery_voltage = 0; battery_voltage = 0;
for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++) { for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++)
{
battery_voltage += bat_v_samples[bi]; battery_voltage += bat_v_samples[bi];
} }
battery_voltage = battery_voltage/BAT_SAMPLES; battery_voltage = battery_voltage / BAT_SAMPLES;
if (bat_delay_v == 0) bat_delay_v = battery_voltage; if (bat_delay_v == 0)
if (battery_percent > 100.0) battery_percent = 100.0; bat_delay_v = battery_voltage;
if (battery_percent < 0.0) battery_percent = 0.0; if (battery_percent > 100.0)
battery_percent = 100.0;
if (battery_percent < 0.0)
battery_percent = 0.0;
if (bat_samples_count%BAT_SAMPLES == 0) { if (bat_samples_count % BAT_SAMPLES == 0)
if (battery_voltage < bat_delay_v && battery_voltage < BAT_V_FLOAT) { {
if (battery_voltage < bat_delay_v && battery_voltage < BAT_V_FLOAT)
{
bat_voltage_dropping = true; bat_voltage_dropping = true;
} else { }
else
{
bat_voltage_dropping = false; bat_voltage_dropping = false;
} }
bat_samples_count = 0; bat_samples_count = 0;
} }
if (bat_voltage_dropping && battery_voltage < BAT_V_FLOAT) { if (bat_voltage_dropping && battery_voltage < BAT_V_FLOAT)
{
battery_state = BATTERY_STATE_DISCHARGING; battery_state = BATTERY_STATE_DISCHARGING;
} else {
#if BOARD_MODEL == BOARD_RNODE_NG_21
battery_state = BATTERY_STATE_CHARGING;
#else
battery_state = BATTERY_STATE_DISCHARGING;
#endif
} }
else
{
#if BOARD_MODEL == BOARD_RNODE_NG_21
battery_state = BATTERY_STATE_CHARGING;
#else
battery_state = BATTERY_STATE_DISCHARGING;
#endif
}
// if (bt_state == BT_STATE_CONNECTED) { // if (bt_state == BT_STATE_CONNECTED) {
// SerialBT.printf("Bus voltage %.3fv. Unfiltered %.3fv.", battery_voltage, bat_v_samples[BAT_SAMPLES-1]); // SerialBT.printf("Bus voltage %.3fv. Unfiltered %.3fv.", battery_voltage, bat_v_samples[BAT_SAMPLES-1]);
@ -134,55 +152,98 @@ void measure_battery() {
// } // }
} }
#elif BOARD_MODEL == BOARD_TBEAM #elif BOARD_MODEL == BOARD_HELTEC32_V3
if (PMU) { battery_installed = true;
battery_indeterminate = false;
battery_state = BATTERY_STATE_DISCHARGING;
battery_ready = true;
digitalWrite(VBAT_READ_CNTRL_PIN, LOW);
analogSetPinAttenuation(PIN_VBAT, ADC_2_5db);
delay(50);
analogRead(PIN_VBAT); // to clear out potential wrong reads on first read
int analogValue = 0;
for (int i = 0; i < 5; i++)
{
analogValue += analogRead(PIN_VBAT); // reading value to make an average over 5 values
delay(10);
}
analogValue /= 5; // calculate average value
digitalWrite(VBAT_READ_CNTRL_PIN, HIGH);
battery_voltage = (float(analogValue) / 4095.0) * 1.25 * (4.9); // at 2.5db attenuation range is 0-1250mV, 4.9 is voltage divider ratio
battery_percent = (battery_voltage - 3.4) * 125.0;
if (battery_percent > 100.0)
{
battery_percent = 100.0;
}
if (battery_percent < 0.0)
{
battery_percent = 0.0;
}
#elif BOARD_MODEL == BOARD_TBEAM
if (PMU)
{
float discharge_current = 0; float discharge_current = 0;
float charge_current = 0; float charge_current = 0;
float ext_voltage = 0; float ext_voltage = 0;
float ext_current = 0; float ext_current = 0;
if (PMU->getChipModel() == XPOWERS_AXP192) { if (PMU->getChipModel() == XPOWERS_AXP192)
discharge_current = ((XPowersAXP192*)PMU)->getBattDischargeCurrent(); {
charge_current = ((XPowersAXP192*)PMU)->getBatteryChargeCurrent(); discharge_current = ((XPowersAXP192 *)PMU)->getBattDischargeCurrent();
battery_voltage = PMU->getBattVoltage()/1000.0; charge_current = ((XPowersAXP192 *)PMU)->getBatteryChargeCurrent();
battery_voltage = PMU->getBattVoltage() / 1000.0;
// battery_percent = PMU->getBattPercentage()*1.0; // battery_percent = PMU->getBattPercentage()*1.0;
battery_installed = PMU->isBatteryConnect(); battery_installed = PMU->isBatteryConnect();
external_power = PMU->isVbusIn(); external_power = PMU->isVbusIn();
ext_voltage = PMU->getVbusVoltage()/1000.0; ext_voltage = PMU->getVbusVoltage() / 1000.0;
ext_current = ((XPowersAXP192*)PMU)->getVbusCurrent(); ext_current = ((XPowersAXP192 *)PMU)->getVbusCurrent();
} }
else if (PMU->getChipModel() == XPOWERS_AXP2101) { else if (PMU->getChipModel() == XPOWERS_AXP2101)
battery_voltage = PMU->getBattVoltage()/1000.0; {
battery_voltage = PMU->getBattVoltage() / 1000.0;
// battery_percent = PMU->getBattPercentage()*1.0; // battery_percent = PMU->getBattPercentage()*1.0;
battery_installed = PMU->isBatteryConnect(); battery_installed = PMU->isBatteryConnect();
external_power = PMU->isVbusIn(); external_power = PMU->isVbusIn();
ext_voltage = PMU->getVbusVoltage()/1000.0; ext_voltage = PMU->getVbusVoltage() / 1000.0;
} }
if (battery_installed) { if (battery_installed)
if (PMU->isCharging()) { {
if (PMU->isCharging())
{
battery_state = BATTERY_STATE_CHARGING; battery_state = BATTERY_STATE_CHARGING;
battery_percent = ((battery_voltage-BAT_V_MIN) / (BAT_V_MAX-BAT_V_MIN))*100.0; battery_percent = ((battery_voltage - BAT_V_MIN) / (BAT_V_MAX - BAT_V_MIN)) * 100.0;
} else { }
if (PMU->isDischarge()) { else
{
if (PMU->isDischarge())
{
battery_state = BATTERY_STATE_DISCHARGING; battery_state = BATTERY_STATE_DISCHARGING;
battery_percent = ((battery_voltage-BAT_V_MIN) / (BAT_V_MAX-BAT_V_MIN))*100.0; battery_percent = ((battery_voltage - BAT_V_MIN) / (BAT_V_MAX - BAT_V_MIN)) * 100.0;
} else { }
else
{
battery_state = BATTERY_STATE_CHARGED; battery_state = BATTERY_STATE_CHARGED;
battery_percent = 100.0; battery_percent = 100.0;
} }
} }
} else { }
else
{
battery_state = BATTERY_STATE_DISCHARGING; battery_state = BATTERY_STATE_DISCHARGING;
battery_percent = 0.0; battery_percent = 0.0;
battery_voltage = 0.0; battery_voltage = 0.0;
} }
if (battery_percent > 100.0) battery_percent = 100.0; if (battery_percent > 100.0)
if (battery_percent < 0.0) battery_percent = 0.0; battery_percent = 100.0;
if (battery_percent < 0.0)
battery_percent = 0.0;
float charge_watts = battery_voltage*(charge_current/1000.0); float charge_watts = battery_voltage * (charge_current / 1000.0);
float discharge_watts = battery_voltage*(discharge_current/1000.0); float discharge_watts = battery_voltage * (discharge_current / 1000.0);
float ext_watts = ext_voltage*(ext_current/1000.0); float ext_watts = ext_voltage * (ext_current / 1000.0);
battery_ready = true; battery_ready = true;
@ -210,116 +271,158 @@ void measure_battery() {
// SerialBT.println(""); // SerialBT.println("");
// } // }
} }
else { else
{
battery_ready = false; battery_ready = false;
} }
#elif BOARD_MODEL == BOARD_RAK4631 #elif BOARD_MODEL == BOARD_RAK4631
battery_installed = true; battery_installed = true;
battery_indeterminate = false; battery_indeterminate = false;
bat_v_samples[bat_samples_count%BAT_SAMPLES] = (float)(analogRead(PIN_VBAT)) * VBAT_MV_PER_LSB_FIN; bat_v_samples[bat_samples_count % BAT_SAMPLES] = (float)(analogRead(PIN_VBAT)) * VBAT_MV_PER_LSB_FIN;
if (bat_v_samples[bat_samples_count%BAT_SAMPLES] < 3300) { if (bat_v_samples[bat_samples_count % BAT_SAMPLES] < 3300)
bat_p_samples[bat_samples_count%BAT_SAMPLES] = 0;
}
else if (bat_v_samples[bat_samples_count%BAT_SAMPLES] < 3600)
{ {
bat_v_samples[bat_samples_count%BAT_SAMPLES] -= 3300; bat_p_samples[bat_samples_count % BAT_SAMPLES] = 0;
bat_p_samples[bat_samples_count%BAT_SAMPLES] = bat_v_samples[bat_samples_count%BAT_SAMPLES] / 30;
} else {
bat_v_samples[bat_samples_count%BAT_SAMPLES] -= 3600;
} }
bat_p_samples[bat_samples_count%BAT_SAMPLES] = 10 + (bat_v_samples[bat_samples_count%BAT_SAMPLES] * 0.15F); else if (bat_v_samples[bat_samples_count % BAT_SAMPLES] < 3600)
{
bat_v_samples[bat_samples_count % BAT_SAMPLES] -= 3300;
bat_p_samples[bat_samples_count % BAT_SAMPLES] = bat_v_samples[bat_samples_count % BAT_SAMPLES] / 30;
}
else
{
bat_v_samples[bat_samples_count % BAT_SAMPLES] -= 3600;
}
bat_p_samples[bat_samples_count % BAT_SAMPLES] = 10 + (bat_v_samples[bat_samples_count % BAT_SAMPLES] * 0.15F);
bat_samples_count++; bat_samples_count++;
if (!battery_ready && bat_samples_count >= BAT_SAMPLES) { if (!battery_ready && bat_samples_count >= BAT_SAMPLES)
{
battery_ready = true; battery_ready = true;
} }
battery_percent = 0; battery_percent = 0;
for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++) { for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++)
{
battery_percent += bat_p_samples[bi]; battery_percent += bat_p_samples[bi];
} }
battery_percent = battery_percent/BAT_SAMPLES; battery_percent = battery_percent / BAT_SAMPLES;
battery_voltage = 0; battery_voltage = 0;
for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++) { for (uint8_t bi = 0; bi < BAT_SAMPLES; bi++)
{
battery_voltage += bat_v_samples[bi]; battery_voltage += bat_v_samples[bi];
} }
battery_voltage = battery_voltage/BAT_SAMPLES; battery_voltage = battery_voltage / BAT_SAMPLES;
if (bat_delay_v == 0) bat_delay_v = battery_voltage; if (bat_delay_v == 0)
if (battery_percent > 100.0) battery_percent = 100.0; bat_delay_v = battery_voltage;
if (battery_percent < 0.0) battery_percent = 0.0; if (battery_percent > 100.0)
battery_percent = 100.0;
if (battery_percent < 0.0)
battery_percent = 0.0;
if (bat_samples_count%BAT_SAMPLES == 0) { if (bat_samples_count % BAT_SAMPLES == 0)
if (battery_voltage < bat_delay_v && battery_voltage < BAT_V_FLOAT) { {
if (battery_voltage < bat_delay_v && battery_voltage < BAT_V_FLOAT)
{
bat_voltage_dropping = true; bat_voltage_dropping = true;
} else { }
else
{
bat_voltage_dropping = false; bat_voltage_dropping = false;
} }
bat_samples_count = 0; bat_samples_count = 0;
} }
nrfx_power_usb_state_t usbstate = nrfx_power_usbstatus_get(); nrfx_power_usb_state_t usbstate = nrfx_power_usbstatus_get();
if (usbstate == NRFX_POWER_USB_STATE_CONNECTED || usbstate == NRFX_POWER_USB_STATE_READY) { if (usbstate == NRFX_POWER_USB_STATE_CONNECTED || usbstate == NRFX_POWER_USB_STATE_READY)
{
// charging // charging
battery_state = BATTERY_STATE_CHARGING; battery_state = BATTERY_STATE_CHARGING;
} else { }
else
{
battery_state = BATTERY_STATE_DISCHARGING; battery_state = BATTERY_STATE_DISCHARGING;
} }
if (battery_percent >= 98) { if (battery_percent >= 98)
{
battery_state = BATTERY_STATE_CHARGED; battery_state = BATTERY_STATE_CHARGED;
} }
#endif #endif
if (battery_ready) { if (battery_ready)
{
pmu_rc++; pmu_rc++;
if (pmu_rc%PMU_R_INTERVAL == 0) { if (pmu_rc % PMU_R_INTERVAL == 0)
{
kiss_indicate_battery(); kiss_indicate_battery();
} }
} }
} }
void update_pmu() { void update_pmu()
if (millis()-last_pmu_update >= pmu_update_interval) { {
if (millis() - last_pmu_update >= pmu_update_interval)
{
measure_battery(); measure_battery();
last_pmu_update = millis(); last_pmu_update = millis();
} }
} }
bool init_pmu() { bool init_pmu()
#if BOARD_MODEL == BOARD_RNODE_NG_21 || BOARD_MODEL == BOARD_LORA32_V2_1 {
#if BOARD_MODEL == BOARD_RNODE_NG_21 || BOARD_MODEL == BOARD_LORA32_V2_1
pinMode(pin_vbat, INPUT); pinMode(pin_vbat, INPUT);
return true; return true;
#elif BOARD_MODEL == BOARD_TBEAM
#elif BOARD_MODEL == BOARD_HELTEC32_V3
pinMode(PIN_VBAT, INPUT);
pinMode(VBAT_READ_CNTRL_PIN, OUTPUT);
adcAttachPin(PIN_VBAT);
analogReadResolution(12);
return true;
#elif BOARD_MODEL == BOARD_TBEAM
Wire.begin(I2C_SDA, I2C_SCL); Wire.begin(I2C_SDA, I2C_SCL);
if (!PMU) { if (!PMU)
{
PMU = new XPowersAXP2101(PMU_WIRE_PORT); PMU = new XPowersAXP2101(PMU_WIRE_PORT);
if (!PMU->init()) { if (!PMU->init())
{
Serial.println("Warning: Failed to find AXP2101 power management"); Serial.println("Warning: Failed to find AXP2101 power management");
delete PMU; delete PMU;
PMU = NULL; PMU = NULL;
} else { }
else
{
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU"); Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
} }
} }
if (!PMU) { if (!PMU)
{
PMU = new XPowersAXP192(PMU_WIRE_PORT); PMU = new XPowersAXP192(PMU_WIRE_PORT);
if (!PMU->init()) { if (!PMU->init())
{
Serial.println("Warning: Failed to find AXP192 power management"); Serial.println("Warning: Failed to find AXP192 power management");
delete PMU; delete PMU;
PMU = NULL; PMU = NULL;
} else { }
else
{
Serial.println("AXP192 PMU init succeeded, using AXP192 PMU"); Serial.println("AXP192 PMU init succeeded, using AXP192 PMU");
} }
} }
if (!PMU) { if (!PMU)
{
return false; return false;
} }
@ -329,7 +432,8 @@ bool init_pmu() {
pinMode(PMU_IRQ, INPUT_PULLUP); pinMode(PMU_IRQ, INPUT_PULLUP);
attachInterrupt(PMU_IRQ, setPmuFlag, FALLING); attachInterrupt(PMU_IRQ, setPmuFlag, FALLING);
if (PMU->getChipModel() == XPOWERS_AXP192) { if (PMU->getChipModel() == XPOWERS_AXP192)
{
// Turn off unused power sources to save power // Turn off unused power sources to save power
PMU->disablePowerOutput(XPOWERS_DCDC1); PMU->disablePowerOutput(XPOWERS_DCDC1);
@ -349,7 +453,7 @@ bool init_pmu() {
PMU->enablePowerOutput(XPOWERS_LDO2); PMU->enablePowerOutput(XPOWERS_LDO2);
// Turn on GPS // Turn on GPS
//PMU->enablePowerOutput(XPOWERS_LDO3); // PMU->enablePowerOutput(XPOWERS_LDO3);
// protected oled power source // protected oled power source
PMU->setProtectedChannel(XPOWERS_DCDC1); PMU->setProtectedChannel(XPOWERS_DCDC1);
@ -366,11 +470,10 @@ bool init_pmu() {
XPOWERS_AXP192_BAT_CHG_START_IRQ | XPOWERS_AXP192_BAT_CHG_START_IRQ |
XPOWERS_AXP192_BAT_REMOVE_IRQ | XPOWERS_AXP192_BAT_REMOVE_IRQ |
XPOWERS_AXP192_BAT_INSERT_IRQ | XPOWERS_AXP192_BAT_INSERT_IRQ |
XPOWERS_AXP192_PKEY_SHORT_IRQ XPOWERS_AXP192_PKEY_SHORT_IRQ);
);
} }
else if (PMU->getChipModel() == XPOWERS_AXP2101) { else if (PMU->getChipModel() == XPOWERS_AXP2101)
{
// Turn off unused power sources to save power // Turn off unused power sources to save power
PMU->disablePowerOutput(XPOWERS_DCDC2); PMU->disablePowerOutput(XPOWERS_DCDC2);
@ -404,10 +507,10 @@ bool init_pmu() {
PMU->enablePowerOutput(XPOWERS_ALDO2); PMU->enablePowerOutput(XPOWERS_ALDO2);
// GNSS VDD // GNSS VDD
//PMU->enablePowerOutput(XPOWERS_ALDO3); // PMU->enablePowerOutput(XPOWERS_ALDO3);
// GNSS RTC PowerVDD // GNSS RTC PowerVDD
//PMU->enablePowerOutput(XPOWERS_VBACKUP); // PMU->enablePowerOutput(XPOWERS_VBACKUP);
} }
PMU->enableSystemVoltageMeasure(); PMU->enableSystemVoltageMeasure();
@ -421,7 +524,7 @@ bool init_pmu() {
PMU->setPowerKeyPressOffTime(XPOWERS_POWEROFF_4S); PMU->setPowerKeyPressOffTime(XPOWERS_POWEROFF_4S);
return true; return true;
#elif BOARD_MODEL == BOARD_RAK4631 #elif BOARD_MODEL == BOARD_RAK4631
// board doesn't have PMU but we can measure batt voltage // board doesn't have PMU but we can measure batt voltage
// prep ADC for reading battery level // prep ADC for reading battery level
@ -436,7 +539,7 @@ bool init_pmu() {
// Get a single ADC sample and throw it away // Get a single ADC sample and throw it away
float raw = analogRead(PIN_VBAT); float raw = analogRead(PIN_VBAT);
return true; return true;
#else #else
return false; return false;
#endif #endif
} }