kopia lustrzana https://github.com/dl9rdz/rdz_ttgo_sonde
pmu code for axp2101 (not tested at all)
rodzic
082b6ccdf5
commit
4b5b8b9b25
|
@ -1,7 +1,7 @@
|
|||
#include "features.h"
|
||||
#include "version.h"
|
||||
|
||||
#include "axp20x.h"
|
||||
#include "XPowersLib.h"
|
||||
#include <WiFi.h>
|
||||
#include <WiFiUdp.h>
|
||||
#include <ESPAsyncWebServer.h>
|
||||
|
@ -51,7 +51,7 @@ const char *mainStateStr[5] = {"DECODER", "SPECTRUM", "WIFISCAN", "UPDATE", "TOU
|
|||
|
||||
AsyncWebServer server(80);
|
||||
|
||||
AXP20X_Class axp;
|
||||
XPowersLibInterface *pmu = NULL;
|
||||
#define PMU_IRQ 35
|
||||
SemaphoreHandle_t axpSemaphore;
|
||||
// 0: cleared; 1: set; 2: do not check, also query state of axp via i2c on each loop
|
||||
|
@ -161,7 +161,7 @@ String processor(const String& var) {
|
|||
lat = sonde.config.rxlat;
|
||||
lon = sonde.config.rxlon;
|
||||
}
|
||||
if ( !isnan(lat) && !isnan(lon) ) {
|
||||
//if ( !isnan(lat) && !isnan(lon) ) {
|
||||
#endif
|
||||
if ( posInfo.valid ) {
|
||||
char p[40];
|
||||
|
@ -318,7 +318,7 @@ const char *createQRGForm() {
|
|||
return message;
|
||||
}
|
||||
|
||||
const char *handleQRGPost(AsyncWebServerRequest *request) {
|
||||
const char *handleQRGPost(AsyncWebServerRequest * request) {
|
||||
char label[10];
|
||||
// parameters: a_i, f_1, t_i (active/frequency/type)
|
||||
File file = SPIFFS.open("/qrg.txt", "w");
|
||||
|
@ -451,7 +451,7 @@ const char *createSondeHubMap() {
|
|||
}
|
||||
#endif
|
||||
|
||||
const char *handleWIFIPost(AsyncWebServerRequest *request) {
|
||||
const char *handleWIFIPost(AsyncWebServerRequest * request) {
|
||||
char label[10];
|
||||
// parameters: a_i, f_1, t_i (active/frequency/type)
|
||||
#if 1
|
||||
|
@ -809,7 +809,7 @@ const char *handleConfigPost(AsyncWebServerRequest * request) {
|
|||
f.close();
|
||||
Serial.printf("Re-reading file file\n");
|
||||
setupConfigData();
|
||||
if(!gpsPos.valid) fixedToPosInfo();
|
||||
if (!gpsPos.valid) fixedToPosInfo();
|
||||
// TODO: Check if this is better done elsewhere?
|
||||
// Use new config (whereever this is feasible without a reboot)
|
||||
disp.setContrast();
|
||||
|
@ -1598,19 +1598,21 @@ void handlePMUirq() {
|
|||
if (pmu_irq) {
|
||||
Serial.println("PMU_IRQ is set\n");
|
||||
xSemaphoreTake( axpSemaphore, portMAX_DELAY );
|
||||
axp.readIRQ();
|
||||
if (axp.isPEKShortPressIRQ()) {
|
||||
pmu->getIrqStatus();
|
||||
if (pmu->isPekeyShortPressIrq()) {
|
||||
Serial.println("isPekeyShortPress");
|
||||
button2.pressed = KP_SHORT;
|
||||
button2.keydownTime = my_millis();
|
||||
}
|
||||
if (axp.isPEKLongtPressIRQ()) {
|
||||
if (pmu->isPekeyLongPressIrq()) {
|
||||
Serial.println("isPekeyLongPress");
|
||||
button2.pressed = KP_MID;
|
||||
button2.keydownTime = my_millis();
|
||||
}
|
||||
if (pmu_irq != 2) {
|
||||
pmu_irq = 0;
|
||||
}
|
||||
axp.clearIRQ();
|
||||
pmu->clearIrqStatus();
|
||||
xSemaphoreGive( axpSemaphore );
|
||||
}
|
||||
} else {
|
||||
|
@ -1642,7 +1644,7 @@ int getKeyPressEvent() {
|
|||
|
||||
#define SSD1306_ADDRESS 0x3c
|
||||
bool ssd1306_found = false;
|
||||
bool axp192_found = false;
|
||||
bool axp_found = false;
|
||||
|
||||
int scanI2Cdevice(void)
|
||||
{
|
||||
|
@ -1663,9 +1665,9 @@ int scanI2Cdevice(void)
|
|||
ssd1306_found = true;
|
||||
Serial.println("ssd1306 display found");
|
||||
}
|
||||
if (addr == AXP192_SLAVE_ADDRESS) {
|
||||
axp192_found = true;
|
||||
Serial.println("axp192 PMU found");
|
||||
if (addr == AXP192_SLAVE_ADDRESS) { // Same for AXP2101
|
||||
axp_found = true;
|
||||
Serial.println("axp192/axp2101 PMU found");
|
||||
}
|
||||
} else if (err == 4) {
|
||||
Serial.print("Unknow error at address 0x");
|
||||
|
@ -1746,57 +1748,171 @@ void setup()
|
|||
delay(500);
|
||||
|
||||
scanI2Cdevice();
|
||||
if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS)) {
|
||||
Serial.println("AXP192 Begin PASS");
|
||||
} else {
|
||||
Serial.println("AXP192 Begin FAIL");
|
||||
}
|
||||
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON);
|
||||
if (sonde.config.type == TYPE_M5_CORE2) {
|
||||
// Display backlight on M5 Core2
|
||||
axp.setPowerOutPut(AXP192_DCDC3, AXP202_ON);
|
||||
axp.setDCDC3Voltage(3300);
|
||||
// SetBusPowerMode(0):
|
||||
// #define AXP192_GPIO0_CTL (0x90)
|
||||
// #define AXP192_GPIO0_VOL (0x91)
|
||||
// #define AXP202_LDO234_DC23_CTL (0x12)
|
||||
|
||||
// The axp class lacks a functino to set GPIO0 VDO to 3.3V (as is done by original M5Stack software)
|
||||
// so do this manually (default value 2.8V did not have the expected effect :))
|
||||
// data = Read8bit(0x91);
|
||||
// write1Byte(0x91, (data & 0X0F) | 0XF0);
|
||||
uint8_t reg;
|
||||
Wire.beginTransmission((uint8_t)AXP192_SLAVE_ADDRESS);
|
||||
Wire.write(AXP192_GPIO0_VOL);
|
||||
Wire.endTransmission();
|
||||
Wire.requestFrom(AXP192_SLAVE_ADDRESS, 1);
|
||||
reg = Wire.read();
|
||||
reg = (reg & 0x0F) | 0xF0;
|
||||
Wire.beginTransmission((uint8_t)AXP192_SLAVE_ADDRESS);
|
||||
Wire.write(AXP192_GPIO0_VOL);
|
||||
Wire.write(reg);
|
||||
Wire.endTransmission();
|
||||
// data = Read8bit(0x90);
|
||||
// Write1Byte(0x90, (data & 0XF8) | 0X02)
|
||||
axp.setGPIOMode(AXP_GPIO_0, AXP_IO_LDO_MODE); // disable AXP supply from VBUS
|
||||
pmu_irq = 2; // IRQ pin is not connected on Core2
|
||||
// data = Read8bit(0x12); //read reg 0x12
|
||||
// Write1Byte(0x12, data | 0x40); // enable 3,3V => 5V booster
|
||||
// this is done below anyway: axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
|
||||
if (!pmu) {
|
||||
pmu = new XPowersAXP192(Wire);
|
||||
if (!pmu->init()) {
|
||||
Serial.println("Warning: AXP192 not found");
|
||||
delete pmu;
|
||||
pmu = NULL;
|
||||
} else {
|
||||
Serial.println("AXP192 PMU found");
|
||||
}
|
||||
if (!pmu) {
|
||||
pmu = new XPowersAXP2101(Wire);
|
||||
if (!pmu->init()) {
|
||||
Serial.println("Warning: AXP2101 not found");
|
||||
delete pmu;
|
||||
pmu = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU found");
|
||||
}
|
||||
}
|
||||
if (pmu && pmu->getChipModel() == XPOWERS_AXP2101) {
|
||||
// So this is currently for T-BEAM V1.2
|
||||
// Unused power channels
|
||||
pmu->disablePowerOutput(XPOWERS_DCDC2);
|
||||
pmu->disablePowerOutput(XPOWERS_DCDC3);
|
||||
pmu->disablePowerOutput(XPOWERS_DCDC4);
|
||||
pmu->disablePowerOutput(XPOWERS_DCDC5);
|
||||
pmu->disablePowerOutput(XPOWERS_ALDO1);
|
||||
pmu->disablePowerOutput(XPOWERS_ALDO4);
|
||||
pmu->disablePowerOutput(XPOWERS_BLDO1);
|
||||
pmu->disablePowerOutput(XPOWERS_BLDO2);
|
||||
pmu->disablePowerOutput(XPOWERS_DLDO1);
|
||||
pmu->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
axp.adc1Enable(AXP202_ACIN_VOL_ADC1, 1);
|
||||
axp.adc1Enable(AXP202_ACIN_CUR_ADC1, 1);
|
||||
} else {
|
||||
// GPS on T-Beam, buzzer on M5 Core2
|
||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON);
|
||||
axp.adc1Enable(AXP202_VBUS_VOL_ADC1, 1);
|
||||
axp.adc1Enable(AXP202_VBUS_CUR_ADC1, 1);
|
||||
// GNSS RTC PowerVDD 3300mV
|
||||
pmu->setPowerChannelVoltage(XPOWERS_VBACKUP, 3300);
|
||||
pmu->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
// ESP32 VDD 3300mV (already set, no need to change)
|
||||
pmu->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
// LoRa VDD 3300mV
|
||||
pmu->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
pmu->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
// GNSS VDD 3300mV
|
||||
pmu->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
pmu->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
} else if (pmu && pmu->getChipModel() == XPOWERS_AXP192) {
|
||||
// So this is either a T-BEAM V1.1 or a M5 Core2
|
||||
// axp.setPowerOutPut(AXP192_LDO2, AXP202_ON);
|
||||
// LDO2: LoRa VCC on T-BEAM, PERI_VDD on M5Core2 (LCD)
|
||||
pmu->setPowerChannelVoltage(XPOWERS_LDO2, 3300);
|
||||
pmu->enablePowerOutput(XPOWERS_LDO2);
|
||||
|
||||
|
||||
/*
|
||||
#####
|
||||
if (pmu->getChipModel() == XPOWERS_AXP192) {
|
||||
pmu->setProtectedChannel(XPOWERS_DCDC3);
|
||||
// lora
|
||||
// gps
|
||||
pmu->setPowerChannelVoltage(XPOWERS_LDO3, 3300);
|
||||
// oled
|
||||
pmu->setPowerChannelVoltage(XPOWERS_DCDC1, 3300);
|
||||
|
||||
pmu->enablePowerOutput(XPOWERS_LDO3);
|
||||
|
||||
// protected oled power source
|
||||
pmu->setProtectedChannel(XPOWERS_DCDC1);
|
||||
// protected esp32 power source
|
||||
pmu->setProtectedChannel(XPOWERS_DCDC3);
|
||||
// enable oled power
|
||||
pmu->enablePowerOutput(XPOWERS_DCDC1);
|
||||
|
||||
// disable not use channel
|
||||
pmu->disablePowerOutput(XPOWERS_DCDC2);
|
||||
|
||||
pmu->disableIRQ(XPOWERS_AXP192_ALL_IRQ);
|
||||
|
||||
pmu->enableIRQ(
|
||||
XPOWERS_AXP192_VBUS_REMOVE_IRQ | XPOWERS_AXP192_VBUS_INSERT_IRQ |
|
||||
XPOWERS_AXP192_BAT_CHG_DONE_IRQ | XPOWERS_AXP192_BAT_CHG_START_IRQ |
|
||||
XPOWERS_AXP192_BAT_REMOVE_IRQ | XPOWERS_AXP192_BAT_INSERT_IRQ |
|
||||
XPOWERS_AXP192_PKEY_SHORT_IRQ);
|
||||
|
||||
}
|
||||
#####
|
||||
*/
|
||||
if (sonde.config.type == TYPE_M5_CORE2) {
|
||||
// Display backlight (LCD_BL) on M5 Core2
|
||||
//axp.setDCDC3Voltage(3300);
|
||||
//axp.setPowerOutPut(AXP192_DCDC3, AXP202_ON);
|
||||
pmu->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
pmu->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
// SetBusPowerMode(0):
|
||||
// #define AXP192_GPIO0_CTL (0x90)
|
||||
// #define AXP192_GPIO0_VOL (0x91)
|
||||
// #define AXP202_LDO234_DC23_CTL (0x12)
|
||||
|
||||
// The axp class lacks a functino to set GPIO0 VDO to 3.3V (as is done by original M5Stack software)
|
||||
// so do this manually (default value 2.8V did not have the expected effect :))
|
||||
// data = Read8bit(0x91);
|
||||
// write1Byte(0x91, (data & 0X0F) | 0XF0);
|
||||
//uint8_t reg;
|
||||
//Wire.beginTransmission((uint8_t)AXP192_SLAVE_ADDRESS);
|
||||
//Wire.write(AXP192_GPIO0_VOL);
|
||||
//Wire.endTransmission();
|
||||
//Wire.requestFrom(AXP192_SLAVE_ADDRESS, 1);
|
||||
//reg = Wire.read();
|
||||
//reg = (reg & 0x0F) | 0xF0;
|
||||
//Wire.beginTransmission((uint8_t)AXP192_SLAVE_ADDRESS);
|
||||
//Wire.write(AXP192_GPIO0_VOL);
|
||||
//Wire.write(reg);
|
||||
//Wire.endTransmission();
|
||||
//// data = Read8bit(0x90);
|
||||
//// Write1Byte(0x90, (data & 0XF8) | 0X02)
|
||||
//axp.setGPIOMode(AXP_GPIO_0, AXP_IO_LDO_MODE); // disable AXP supply from VBUS
|
||||
((XPowersAXP192 *)pmu)->setLDOioVoltage(3300);
|
||||
|
||||
pmu_irq = 2; // IRQ pin is not connected on Core2
|
||||
// data = Read8bit(0x12); //read reg 0x12
|
||||
// Write1Byte(0x12, data | 0x40); // enable 3,3V => 5V booster
|
||||
// this is done below anyway: axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
|
||||
|
||||
|
||||
//((XPowersAXP192 *)pmu)->setSignalCaptureImpl((1<<4)|(1<<5), true); //MONITOR_AC_CURRENT | MONITOR_AC_VOLTAGE);
|
||||
//axp.adc1Enable(AXP202_ACIN_VOL_ADC1, 1); // 4,5 AC/CURRENT/VOLTAGE
|
||||
//axp.adc1Enable(AXP202_ACIN_CUR_ADC1, 1);
|
||||
uint8_t val = ((XPowersAXP192 *)pmu)->readRegister(XPOWERS_AXP192_ADC_EN1);
|
||||
((XPowersAXP192 *)pmu)->writeRegister(XPOWERS_AXP192_ADC_EN1, val | (1 << 4) | (1 << 5) );
|
||||
} else { // T-Beam
|
||||
// GPS on T-Beam (its the buzzer on M5 Core2, so only enable for T-Beam)
|
||||
//axp.setPowerOutPut(AXP192_LDO3, AXP202_ON);
|
||||
//axp.adc1Enable(AXP202_VBUS_VOL_ADC1, 1); // 3,2 USB_CURRENT/VOLTAGE
|
||||
//axp.adc1Enable(AXP202_VBUS_CUR_ADC1, 1);
|
||||
pmu->enablePowerOutput(XPOWERS_LDO3);
|
||||
// it's a protected function. ARGH
|
||||
//((XPowersAXP192 *)pmu)->setSignalCaptureImpl((1<<3)|(1<<3), true); //MONITOR_USB_CURRENT | MONITOR_USB_VOLTAGE);
|
||||
uint8_t val = ((XPowersAXP192 *)pmu)->readRegister(XPOWERS_AXP192_ADC_EN1);
|
||||
((XPowersAXP192 *)pmu)->writeRegister(XPOWERS_AXP192_ADC_EN1, val | (1 << 2) | (1 << 3) );
|
||||
}
|
||||
// Common configuration for T-Beam and M5 Core2
|
||||
// DCDC2: M5Core: Unused, T-Beam: Unused, so set to disabled!! (was enabled in previous versions)
|
||||
pmu->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// EXTEB: M5Core2: 5V Boost enable; T-Beam EXTEN
|
||||
//pmu->enablePowerOutput(XPOWERS_EXTEN);
|
||||
((XPowersAXP192 *)pmu)->enableExternalPin();
|
||||
// DCDC1: M5Core: MCU_VDD, T-Beam 1.1: "VCC_2.5V" == 3V3-Pin on pin header on board
|
||||
pmu->setPowerChannelVoltage(XPOWERS_DCDC1, 3300);
|
||||
pmu->enablePowerOutput(XPOWERS_DCDC1);
|
||||
//axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
|
||||
//axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
|
||||
//axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
|
||||
//axp.setDCDC1Voltage(3300);
|
||||
|
||||
//((XPowersAXP192 *)pmu)->setSignalCaptureImpl(MONITOR_BATT_CURRENT);
|
||||
// axp.adc1Enable(AXP202_BATT_CUR_ADC1, 1); // 6
|
||||
uint8_t val = ((XPowersAXP192 *)pmu)->readRegister(XPOWERS_AXP192_ADC_EN1);
|
||||
((XPowersAXP192 *)pmu)->writeRegister(XPOWERS_AXP192_ADC_EN1, val | (1 << 6) );
|
||||
}
|
||||
}
|
||||
axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
|
||||
axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
|
||||
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
|
||||
axp.setDCDC1Voltage(3300);
|
||||
axp.adc1Enable(AXP202_BATT_CUR_ADC1, 1);
|
||||
|
||||
if (sonde.config.button2_axp ) {
|
||||
if (pmu_irq != 2) {
|
||||
pinMode(PMU_IRQ, INPUT_PULLUP);
|
||||
|
@ -1805,8 +1921,10 @@ void setup()
|
|||
}, FALLING);
|
||||
}
|
||||
//axp.enableIRQ(AXP202_VBUS_REMOVED_IRQ | AXP202_VBUS_CONNECT_IRQ | AXP202_BATT_REMOVED_IRQ | AXP202_BATT_CONNECT_IRQ, 1);
|
||||
axp.enableIRQ( AXP202_PEK_LONGPRESS_IRQ | AXP202_PEK_SHORTPRESS_IRQ, 1 );
|
||||
axp.clearIRQ();
|
||||
//axp.enableIRQ( AXP202_PEK_LONGPRESS_IRQ | AXP202_PEK_SHORTPRESS_IRQ, 1 );
|
||||
//axp.clearIRQ();
|
||||
pmu->disableIRQ(XPOWERS_AXP192_ALL_IRQ);
|
||||
pmu->enableIRQ( XPOWERS_AXP192_PKEY_SHORT_IRQ | XPOWERS_AXP192_PKEY_LONG_IRQ );
|
||||
}
|
||||
int ndevices = scanI2Cdevice();
|
||||
if (sonde.fingerprint != 17 || ndevices > 0) break; // only retry for fingerprint 17 (startup problems of new t-beam with oled)
|
||||
|
@ -2006,7 +2124,7 @@ void enterMode(int mode) {
|
|||
} else if (mainState == ST_WIFISCAN) {
|
||||
sonde.clearDisplay();
|
||||
}
|
||||
|
||||
|
||||
if (mode == ST_DECODER) {
|
||||
// trigger activation of background task
|
||||
// currentSonde should be set before enterMode()
|
||||
|
@ -2074,7 +2192,7 @@ void loopDecoder() {
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
if (rdzserver.hasClient()) {
|
||||
Serial.println("TCP JSON socket: new connection");
|
||||
rdzclient.stop();
|
||||
|
@ -2088,7 +2206,7 @@ void loopDecoder() {
|
|||
if (c == '\n' || c == '}' || rdzDataPos >= RDZ_DATA_LEN) {
|
||||
// parse GPS position from phone
|
||||
rdzData[rdzDataPos] = c;
|
||||
if (rdzDataPos > 2) parseGpsJson(rdzData, rdzDataPos+1);
|
||||
if (rdzDataPos > 2) parseGpsJson(rdzData, rdzDataPos + 1);
|
||||
rdzDataPos = 0;
|
||||
}
|
||||
else {
|
||||
|
@ -2113,7 +2231,7 @@ void loopDecoder() {
|
|||
connAPRS.updateSonde(s);
|
||||
#endif
|
||||
#if 0
|
||||
// moved to conn-aprs.cpp
|
||||
// moved to conn-aprs.cpp
|
||||
char *str = aprs_senddata(s, sonde.config.call, sonde.config.objcall, sonde.config.udpfeed.symbol);
|
||||
char raw[201];
|
||||
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
|
||||
|
@ -2329,7 +2447,7 @@ void enableNetwork(bool enable) {
|
|||
MDNS.addService("jsonrdz", "tcp", 14570);
|
||||
//if (sonde.config.kisstnc.active) {
|
||||
// tncserver.begin();
|
||||
rdzserver.begin();
|
||||
rdzserver.begin();
|
||||
//}
|
||||
#if FEATURE_MQTT
|
||||
connMQTT.netsetup();
|
||||
|
|
|
@ -2,10 +2,10 @@
|
|||
#include <U8x8lib.h>
|
||||
#include <U8g2lib.h>
|
||||
#include <SPIFFS.h>
|
||||
#include <axp20x.h>
|
||||
#include <MicroNMEA.h>
|
||||
#include "Display.h"
|
||||
#include "Sonde.h"
|
||||
#include <XPowersLib.h>
|
||||
|
||||
int readLine(Stream &stream, char *buffer, int maxlen);
|
||||
|
||||
|
@ -22,8 +22,7 @@ extern const char *version_id;
|
|||
|
||||
extern Sonde sonde;
|
||||
|
||||
extern AXP20X_Class axp;
|
||||
extern bool axp192_found;
|
||||
extern XPowersLibInterface *pmu;
|
||||
extern SemaphoreHandle_t axpSemaphore;
|
||||
|
||||
extern xSemaphoreHandle globalLock;
|
||||
|
@ -1668,7 +1667,7 @@ void Display::drawGPS(DispEntry *de) {
|
|||
void Display::drawBatt(DispEntry *de) {
|
||||
float val;
|
||||
char buf[30];
|
||||
if (!axp192_found) {
|
||||
if (!pmu) {
|
||||
if (sonde.config.batt_adc<0) return;
|
||||
switch (de->extra[0])
|
||||
{
|
||||
|
@ -1685,48 +1684,59 @@ void Display::drawBatt(DispEntry *de) {
|
|||
xSemaphoreTake( axpSemaphore, portMAX_DELAY );
|
||||
switch(de->extra[0]) {
|
||||
case 'S':
|
||||
if(!axp.isBatteryConnect()) {
|
||||
if(axp.isVBUSPlug()) { strcpy(buf, "U"); }
|
||||
if(!pmu->isBatteryConnect()) {
|
||||
if(pmu->isVbusIn()) { strcpy(buf, "U"); }
|
||||
else { strcpy(buf, "N"); } // no battary
|
||||
}
|
||||
else if (axp.isChargeing()) { strcpy(buf, "C"); } // charging
|
||||
else if (pmu->isCharging()) { strcpy(buf, "C"); } // charging
|
||||
else { strcpy(buf, "B"); } // battery, but not charging
|
||||
break;
|
||||
case 'V':
|
||||
val = axp.getBattVoltage();
|
||||
val = pmu->getBattVoltage();
|
||||
snprintf(buf, 30, "%.2f%s", val/1000, de->extra+1);
|
||||
break;
|
||||
case 'C':
|
||||
val = axp.getBattChargeCurrent();
|
||||
}
|
||||
if(pmu->getChipModel() == XPOWERS_AXP192) {
|
||||
XPowersAXP192 *rpmu = (XPowersAXP192 *)pmu;
|
||||
switch(de->extra[0]) {
|
||||
case 'C':
|
||||
val = rpmu->getBatteryChargeCurrent(); //getBattChargeCurrent();
|
||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||
break;
|
||||
case 'D':
|
||||
val = axp.getBattDischargeCurrent();
|
||||
case 'D':
|
||||
val = rpmu->getBattDischargeCurrent();
|
||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||
break;
|
||||
case 'U':
|
||||
case 'U':
|
||||
if(sonde.config.type == TYPE_M5_CORE2) {
|
||||
val = axp.getAcinVoltage();
|
||||
val = rpmu->getAcinVoltage();
|
||||
} else {
|
||||
val = axp.getVbusVoltage();
|
||||
val = rpmu->getVbusVoltage();
|
||||
}
|
||||
snprintf(buf, 30, "%.2f%s", val/1000, de->extra+1);
|
||||
break;
|
||||
case 'I':
|
||||
case 'I':
|
||||
if(sonde.config.type == TYPE_M5_CORE2) {
|
||||
val = axp.getAcinCurrent();
|
||||
val = rpmu->getAcinCurrent();
|
||||
} else {
|
||||
val = axp.getVbusCurrent();
|
||||
val = rpmu->getVbusCurrent();
|
||||
}
|
||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||
break;
|
||||
case 'T':
|
||||
val = axp.getTemp(); // fixed in newer versions of libraray: -144.7 no longer needed here!
|
||||
case 'T':
|
||||
val = rpmu->getTemperature();
|
||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||
break;
|
||||
default:
|
||||
default:
|
||||
*buf=0;
|
||||
}
|
||||
}
|
||||
} else if (pmu->getChipModel() == XPOWERS_AXP2101) {
|
||||
*buf = 0;
|
||||
if(de->extra[0]=='T') {
|
||||
val = ((XPowersAXP2101 *)pmu)->getTemperature();
|
||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||
}
|
||||
}
|
||||
xSemaphoreGive( axpSemaphore );
|
||||
rdis->setFont(de->fmt);
|
||||
drawString(de, buf);
|
||||
|
|
|
@ -18,11 +18,11 @@ lib_deps_builtin =
|
|||
; src
|
||||
lib_deps_external =
|
||||
olikraus/U8g2 @ ^2.28.8
|
||||
AXP202X_Library
|
||||
stevemarple/MicroNMEA @ ^2.0.5
|
||||
me-no-dev/ESP Async WebServer @ ^1.2.3
|
||||
https://github.com/moononournation/Arduino_GFX#v1.1.5
|
||||
https://github.com/dx168b/async-mqtt-client
|
||||
https://github.com/lewisxhe/XPowersLib
|
||||
|
||||
[env:ttgo-lora32]
|
||||
platform = https://github.com/platformio/platform-espressif32.git#v3.3.2
|
||||
|
@ -47,3 +47,4 @@ lib_ignore = Time
|
|||
;
|
||||
extra_scripts = post:scripts/makefontpartition.py
|
||||
;board_build.partitions = partition-fonts.csv
|
||||
|
||||
|
|
Ładowanie…
Reference in New Issue