pmu reorg, preparing for axp2101
This commit is contained in:
parent
082b6ccdf5
commit
60e97d917b
|
|
@ -1,7 +1,6 @@
|
||||||
#include "features.h"
|
#include "features.h"
|
||||||
#include "version.h"
|
#include "version.h"
|
||||||
|
|
||||||
#include "axp20x.h"
|
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
#include <WiFiUdp.h>
|
#include <WiFiUdp.h>
|
||||||
#include <ESPAsyncWebServer.h>
|
#include <ESPAsyncWebServer.h>
|
||||||
|
|
@ -28,6 +27,8 @@
|
||||||
#include "src/json.h"
|
#include "src/json.h"
|
||||||
#include "src/posinfo.h"
|
#include "src/posinfo.h"
|
||||||
|
|
||||||
|
#include "src/pmu.h"
|
||||||
|
|
||||||
/* Data exchange connectors */
|
/* Data exchange connectors */
|
||||||
#if FEATURE_CHASEMAPPER
|
#if FEATURE_CHASEMAPPER
|
||||||
#include "src/conn-chasemapper.h"
|
#include "src/conn-chasemapper.h"
|
||||||
|
|
@ -51,11 +52,9 @@ const char *mainStateStr[5] = {"DECODER", "SPECTRUM", "WIFISCAN", "UPDATE", "TOU
|
||||||
|
|
||||||
AsyncWebServer server(80);
|
AsyncWebServer server(80);
|
||||||
|
|
||||||
AXP20X_Class axp;
|
PMU *pmu = NULL;
|
||||||
#define PMU_IRQ 35
|
|
||||||
SemaphoreHandle_t axpSemaphore;
|
SemaphoreHandle_t axpSemaphore;
|
||||||
// 0: cleared; 1: set; 2: do not check, also query state of axp via i2c on each loop
|
extern uint8_t pmu_irq;
|
||||||
uint8_t pmu_irq = 0;
|
|
||||||
|
|
||||||
const char *updateHost = "rdzsonde.mooo.com";
|
const char *updateHost = "rdzsonde.mooo.com";
|
||||||
int updatePort = 80;
|
int updatePort = 80;
|
||||||
|
|
@ -161,7 +160,7 @@ String processor(const String& var) {
|
||||||
lat = sonde.config.rxlat;
|
lat = sonde.config.rxlat;
|
||||||
lon = sonde.config.rxlon;
|
lon = sonde.config.rxlon;
|
||||||
}
|
}
|
||||||
if ( !isnan(lat) && !isnan(lon) ) {
|
//if ( !isnan(lat) && !isnan(lon) ) {
|
||||||
#endif
|
#endif
|
||||||
if ( posInfo.valid ) {
|
if ( posInfo.valid ) {
|
||||||
char p[40];
|
char p[40];
|
||||||
|
|
@ -318,7 +317,7 @@ const char *createQRGForm() {
|
||||||
return message;
|
return message;
|
||||||
}
|
}
|
||||||
|
|
||||||
const char *handleQRGPost(AsyncWebServerRequest *request) {
|
const char *handleQRGPost(AsyncWebServerRequest * request) {
|
||||||
char label[10];
|
char label[10];
|
||||||
// parameters: a_i, f_1, t_i (active/frequency/type)
|
// parameters: a_i, f_1, t_i (active/frequency/type)
|
||||||
File file = SPIFFS.open("/qrg.txt", "w");
|
File file = SPIFFS.open("/qrg.txt", "w");
|
||||||
|
|
@ -451,7 +450,7 @@ const char *createSondeHubMap() {
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const char *handleWIFIPost(AsyncWebServerRequest *request) {
|
const char *handleWIFIPost(AsyncWebServerRequest * request) {
|
||||||
char label[10];
|
char label[10];
|
||||||
// parameters: a_i, f_1, t_i (active/frequency/type)
|
// parameters: a_i, f_1, t_i (active/frequency/type)
|
||||||
#if 1
|
#if 1
|
||||||
|
|
@ -809,7 +808,7 @@ const char *handleConfigPost(AsyncWebServerRequest * request) {
|
||||||
f.close();
|
f.close();
|
||||||
Serial.printf("Re-reading file file\n");
|
Serial.printf("Re-reading file file\n");
|
||||||
setupConfigData();
|
setupConfigData();
|
||||||
if(!gpsPos.valid) fixedToPosInfo();
|
if (!gpsPos.valid) fixedToPosInfo();
|
||||||
// TODO: Check if this is better done elsewhere?
|
// TODO: Check if this is better done elsewhere?
|
||||||
// Use new config (whereever this is feasible without a reboot)
|
// Use new config (whereever this is feasible without a reboot)
|
||||||
disp.setContrast();
|
disp.setContrast();
|
||||||
|
|
@ -1595,23 +1594,10 @@ int getKeyPress() {
|
||||||
void handlePMUirq() {
|
void handlePMUirq() {
|
||||||
if (sonde.config.button2_axp) {
|
if (sonde.config.button2_axp) {
|
||||||
// Use AXP power button as second button
|
// Use AXP power button as second button
|
||||||
if (pmu_irq) {
|
int key = pmu->handleIRQ();
|
||||||
Serial.println("PMU_IRQ is set\n");
|
if (key > 0) {
|
||||||
xSemaphoreTake( axpSemaphore, portMAX_DELAY );
|
button2.pressed = (KeyPress)key;
|
||||||
axp.readIRQ();
|
button2.keydownTime = my_millis();
|
||||||
if (axp.isPEKShortPressIRQ()) {
|
|
||||||
button2.pressed = KP_SHORT;
|
|
||||||
button2.keydownTime = my_millis();
|
|
||||||
}
|
|
||||||
if (axp.isPEKLongtPressIRQ()) {
|
|
||||||
button2.pressed = KP_MID;
|
|
||||||
button2.keydownTime = my_millis();
|
|
||||||
}
|
|
||||||
if (pmu_irq != 2) {
|
|
||||||
pmu_irq = 0;
|
|
||||||
}
|
|
||||||
axp.clearIRQ();
|
|
||||||
xSemaphoreGive( axpSemaphore );
|
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
Serial.println("handlePMIirq() called. THIS SHOULD NOT HAPPEN w/o button2_axp set");
|
Serial.println("handlePMIirq() called. THIS SHOULD NOT HAPPEN w/o button2_axp set");
|
||||||
|
|
@ -1642,7 +1628,7 @@ int getKeyPressEvent() {
|
||||||
|
|
||||||
#define SSD1306_ADDRESS 0x3c
|
#define SSD1306_ADDRESS 0x3c
|
||||||
bool ssd1306_found = false;
|
bool ssd1306_found = false;
|
||||||
bool axp192_found = false;
|
bool axp_found = false;
|
||||||
|
|
||||||
int scanI2Cdevice(void)
|
int scanI2Cdevice(void)
|
||||||
{
|
{
|
||||||
|
|
@ -1663,9 +1649,9 @@ int scanI2Cdevice(void)
|
||||||
ssd1306_found = true;
|
ssd1306_found = true;
|
||||||
Serial.println("ssd1306 display found");
|
Serial.println("ssd1306 display found");
|
||||||
}
|
}
|
||||||
if (addr == AXP192_SLAVE_ADDRESS) {
|
if (addr == AXP192_SLAVE_ADDRESS) { // Same for AXP2101
|
||||||
axp192_found = true;
|
axp_found = true;
|
||||||
Serial.println("axp192 PMU found");
|
Serial.println("axp2101 PMU found");
|
||||||
}
|
}
|
||||||
} else if (err == 4) {
|
} else if (err == 4) {
|
||||||
Serial.print("Unknow error at address 0x");
|
Serial.print("Unknow error at address 0x");
|
||||||
|
|
@ -1746,71 +1732,25 @@ void setup()
|
||||||
delay(500);
|
delay(500);
|
||||||
|
|
||||||
scanI2Cdevice();
|
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)
|
if (!pmu) {
|
||||||
// so do this manually (default value 2.8V did not have the expected effect :))
|
pmu = PMU::getInstance(Wire);
|
||||||
// data = Read8bit(0x91);
|
if (pmu) {
|
||||||
// write1Byte(0x91, (data & 0X0F) | 0XF0);
|
Serial.println("PMU found");
|
||||||
uint8_t reg;
|
pmu->init();
|
||||||
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);
|
|
||||||
|
|
||||||
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);
|
|
||||||
}
|
|
||||||
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);
|
|
||||||
attachInterrupt(PMU_IRQ, [] {
|
|
||||||
pmu_irq = 1;
|
|
||||||
}, 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 );
|
if (sonde.config.button2_axp ) {
|
||||||
axp.clearIRQ();
|
//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();
|
||||||
|
pmu->disableAllIRQ();
|
||||||
|
pmu->enableIRQ();
|
||||||
|
}
|
||||||
|
int ndevices = scanI2Cdevice();
|
||||||
|
if (sonde.fingerprint != 17 || ndevices > 0) break; // only retry for fingerprint 17 (startup problems of new t-beam with oled)
|
||||||
|
delay(500);
|
||||||
}
|
}
|
||||||
int ndevices = scanI2Cdevice();
|
|
||||||
if (sonde.fingerprint != 17 || ndevices > 0) break; // only retry for fingerprint 17 (startup problems of new t-beam with oled)
|
|
||||||
delay(500);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (sonde.config.batt_adc >= 0) {
|
if (sonde.config.batt_adc >= 0) {
|
||||||
|
|
@ -2088,7 +2028,7 @@ void loopDecoder() {
|
||||||
if (c == '\n' || c == '}' || rdzDataPos >= RDZ_DATA_LEN) {
|
if (c == '\n' || c == '}' || rdzDataPos >= RDZ_DATA_LEN) {
|
||||||
// parse GPS position from phone
|
// parse GPS position from phone
|
||||||
rdzData[rdzDataPos] = c;
|
rdzData[rdzDataPos] = c;
|
||||||
if (rdzDataPos > 2) parseGpsJson(rdzData, rdzDataPos+1);
|
if (rdzDataPos > 2) parseGpsJson(rdzData, rdzDataPos + 1);
|
||||||
rdzDataPos = 0;
|
rdzDataPos = 0;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
|
@ -2113,7 +2053,7 @@ void loopDecoder() {
|
||||||
connAPRS.updateSonde(s);
|
connAPRS.updateSonde(s);
|
||||||
#endif
|
#endif
|
||||||
#if 0
|
#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 *str = aprs_senddata(s, sonde.config.call, sonde.config.objcall, sonde.config.udpfeed.symbol);
|
||||||
char raw[201];
|
char raw[201];
|
||||||
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
|
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
|
||||||
|
|
@ -2329,7 +2269,7 @@ void enableNetwork(bool enable) {
|
||||||
MDNS.addService("jsonrdz", "tcp", 14570);
|
MDNS.addService("jsonrdz", "tcp", 14570);
|
||||||
//if (sonde.config.kisstnc.active) {
|
//if (sonde.config.kisstnc.active) {
|
||||||
// tncserver.begin();
|
// tncserver.begin();
|
||||||
rdzserver.begin();
|
rdzserver.begin();
|
||||||
//}
|
//}
|
||||||
#if FEATURE_MQTT
|
#if FEATURE_MQTT
|
||||||
connMQTT.netsetup();
|
connMQTT.netsetup();
|
||||||
|
|
|
||||||
|
|
@ -2,10 +2,10 @@
|
||||||
#include <U8x8lib.h>
|
#include <U8x8lib.h>
|
||||||
#include <U8g2lib.h>
|
#include <U8g2lib.h>
|
||||||
#include <SPIFFS.h>
|
#include <SPIFFS.h>
|
||||||
#include <axp20x.h>
|
|
||||||
#include <MicroNMEA.h>
|
#include <MicroNMEA.h>
|
||||||
#include "Display.h"
|
#include "Display.h"
|
||||||
#include "Sonde.h"
|
#include "Sonde.h"
|
||||||
|
#include "pmu.h"
|
||||||
|
|
||||||
int readLine(Stream &stream, char *buffer, int maxlen);
|
int readLine(Stream &stream, char *buffer, int maxlen);
|
||||||
|
|
||||||
|
|
@ -22,8 +22,7 @@ extern const char *version_id;
|
||||||
|
|
||||||
extern Sonde sonde;
|
extern Sonde sonde;
|
||||||
|
|
||||||
extern AXP20X_Class axp;
|
extern PMU *pmu;
|
||||||
extern bool axp192_found;
|
|
||||||
extern SemaphoreHandle_t axpSemaphore;
|
extern SemaphoreHandle_t axpSemaphore;
|
||||||
|
|
||||||
extern xSemaphoreHandle globalLock;
|
extern xSemaphoreHandle globalLock;
|
||||||
|
|
@ -1668,13 +1667,14 @@ void Display::drawGPS(DispEntry *de) {
|
||||||
void Display::drawBatt(DispEntry *de) {
|
void Display::drawBatt(DispEntry *de) {
|
||||||
float val;
|
float val;
|
||||||
char buf[30];
|
char buf[30];
|
||||||
if (!axp192_found) {
|
if (!pmu) {
|
||||||
if (sonde.config.batt_adc<0) return;
|
if (sonde.config.batt_adc<0) return;
|
||||||
switch (de->extra[0])
|
switch (de->extra[0])
|
||||||
{
|
{
|
||||||
case 'V':
|
case 'V':
|
||||||
val = (float)(analogRead(sonde.config.batt_adc)) / 4095 * 2 * 3.3 * 1.1;
|
val = (float)(analogRead(sonde.config.batt_adc)) / 4095 * 2 * 3.3 * 1.1;
|
||||||
snprintf(buf, 30, "%.2f%s", val, de->extra + 1);
|
snprintf(buf, 30, "%.2f%s", val, de->extra + 1);
|
||||||
|
Serial.printf("Batt: %s", buf);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
*buf = 0;
|
*buf = 0;
|
||||||
|
|
@ -1685,48 +1685,65 @@ void Display::drawBatt(DispEntry *de) {
|
||||||
xSemaphoreTake( axpSemaphore, portMAX_DELAY );
|
xSemaphoreTake( axpSemaphore, portMAX_DELAY );
|
||||||
switch(de->extra[0]) {
|
switch(de->extra[0]) {
|
||||||
case 'S':
|
case 'S':
|
||||||
if(!axp.isBatteryConnect()) {
|
if(!pmu->isBatteryConnected()) {
|
||||||
if(axp.isVBUSPlug()) { strcpy(buf, "U"); }
|
if(pmu->isVbusIn()) { strcpy(buf, "U"); }
|
||||||
else { strcpy(buf, "N"); } // no battary
|
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
|
else { strcpy(buf, "B"); } // battery, but not charging
|
||||||
|
Serial.printf("Battery: %s\n", buf);
|
||||||
break;
|
break;
|
||||||
case 'V':
|
case 'V':
|
||||||
val = axp.getBattVoltage();
|
val = pmu->getBattVoltage();
|
||||||
snprintf(buf, 30, "%.2f%s", val/1000, de->extra+1);
|
snprintf(buf, 30, "%.2f%s", val/1000, de->extra+1);
|
||||||
|
Serial.printf("Vbatt: %s\n", buf);
|
||||||
break;
|
break;
|
||||||
case 'C':
|
}
|
||||||
val = axp.getBattChargeCurrent();
|
if(pmu->type==TYPE_AXP192) {
|
||||||
|
switch(de->extra[0]) {
|
||||||
|
case 'C':
|
||||||
|
val = pmu->getBattChargeCurrent();
|
||||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||||
|
Serial.printf("Icharge: %s\n", buf);
|
||||||
break;
|
break;
|
||||||
case 'D':
|
case 'D':
|
||||||
val = axp.getBattDischargeCurrent();
|
val = pmu->getBattDischargeCurrent();
|
||||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||||
|
Serial.printf("Idischarge: %s\n", buf);
|
||||||
break;
|
break;
|
||||||
case 'U':
|
case 'U':
|
||||||
if(sonde.config.type == TYPE_M5_CORE2) {
|
if(sonde.config.type == TYPE_M5_CORE2) {
|
||||||
val = axp.getAcinVoltage();
|
val = pmu->getAcinVoltage();
|
||||||
} else {
|
} else {
|
||||||
val = axp.getVbusVoltage();
|
val = pmu->getVbusVoltage();
|
||||||
}
|
}
|
||||||
snprintf(buf, 30, "%.2f%s", val/1000, de->extra+1);
|
snprintf(buf, 30, "%.2f%s", val/1000, de->extra+1);
|
||||||
|
Serial.printf("Vbus: %s\n", buf);
|
||||||
break;
|
break;
|
||||||
case 'I':
|
case 'I':
|
||||||
if(sonde.config.type == TYPE_M5_CORE2) {
|
if(sonde.config.type == TYPE_M5_CORE2) {
|
||||||
val = axp.getAcinCurrent();
|
val = pmu->getAcinCurrent();
|
||||||
} else {
|
} else {
|
||||||
val = axp.getVbusCurrent();
|
val = pmu->getVbusCurrent();
|
||||||
}
|
}
|
||||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||||
|
Serial.printf("Ibus: %s\n", buf);
|
||||||
break;
|
break;
|
||||||
case 'T':
|
case 'T':
|
||||||
val = axp.getTemp(); // fixed in newer versions of libraray: -144.7 no longer needed here!
|
val = pmu->getTemperature();
|
||||||
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||||
|
Serial.printf("temp: %s\n", buf);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
*buf=0;
|
*buf=0;
|
||||||
}
|
}
|
||||||
|
} else if (pmu->type == TYPE_AXP2101) {
|
||||||
|
*buf = 0;
|
||||||
|
if(de->extra[0]=='T') {
|
||||||
|
val = pmu->getTemperature();
|
||||||
|
snprintf(buf, 30, "%.2f%s", val, de->extra+1);
|
||||||
|
}
|
||||||
|
}
|
||||||
xSemaphoreGive( axpSemaphore );
|
xSemaphoreGive( axpSemaphore );
|
||||||
rdis->setFont(de->fmt);
|
rdis->setFont(de->fmt);
|
||||||
drawString(de, buf);
|
drawString(de, buf);
|
||||||
|
|
|
||||||
|
|
@ -0,0 +1,370 @@
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
#include "pmu.h"
|
||||||
|
#include "src/sonde.h"
|
||||||
|
|
||||||
|
// 0: cleared; 1: set; 2: do not check, also query state of axp via i2c on each loop
|
||||||
|
uint8_t pmu_irq = 0;
|
||||||
|
#define PMU_IRQ 35
|
||||||
|
|
||||||
|
#define AXP192_VMIN 1800
|
||||||
|
#define AXP192_VSTEP 100
|
||||||
|
|
||||||
|
|
||||||
|
#define AXP192_IC_TYPE (0x03)
|
||||||
|
|
||||||
|
#define AXP192_DC_MIN 700
|
||||||
|
#define AXP192_DC_STEPS 25
|
||||||
|
|
||||||
|
#define AXP192_LDO_MIN (1800)
|
||||||
|
#define AXP192_LDO_STEPS (100)
|
||||||
|
|
||||||
|
#define AXP192_VOLTREG_DC1
|
||||||
|
|
||||||
|
// some registers:
|
||||||
|
#define AXP192_STATUS (0x00)
|
||||||
|
#define AXP192_MODE_CHGSTATUS (0x01)
|
||||||
|
|
||||||
|
// Power voltage control register
|
||||||
|
#define AXP192_DC2OUT_VOL (0x23)
|
||||||
|
#define AXP192_DC1OUT_VOL (0x26)
|
||||||
|
#define AXP192_DC3OUT_VOL (0x27)
|
||||||
|
#define AXP192_LDO23OUT_VOL (0x28)
|
||||||
|
#define AXP192_GPIO0_VOL (0x91)
|
||||||
|
|
||||||
|
// Power enable registers
|
||||||
|
#define AXP192_LDO23_DC123_EXT_CTL (0x12)
|
||||||
|
|
||||||
|
// ADC control
|
||||||
|
#define AXP192_ADC_EN1 (0x82)
|
||||||
|
|
||||||
|
// ADC results
|
||||||
|
#define AXP192_BAT_AVERVOL_H8 (0x78)
|
||||||
|
#define AXP192_BAT_AVERVOL_L4 (0x79)
|
||||||
|
#define AXP192_BAT_AVERCHGCUR_H8 (0x7A)
|
||||||
|
#define AXP192_BAT_AVERCHGCUR_L4 (0x7B)
|
||||||
|
#define AXP192_BAT_AVERCHGCUR_L5 (0x7B)
|
||||||
|
#define AXP192_ACIN_VOL_H8 (0x56)
|
||||||
|
#define AXP192_ACIN_VOL_L4 (0x57)
|
||||||
|
#define AXP192_ACIN_CUR_H8 (0x58)
|
||||||
|
#define AXP192_ACIN_CUR_L4 (0x59)
|
||||||
|
#define AXP192_VBUS_VOL_H8 (0x5A)
|
||||||
|
#define AXP192_VBUS_VOL_L4 (0x5B)
|
||||||
|
#define AXP192_VBUS_CUR_H8 (0x5C)
|
||||||
|
#define AXP192_VBUS_CUR_L4 (0x5D)
|
||||||
|
#define AXP192_INTERNAL_TEMP_H8 (0x5E)
|
||||||
|
#define AXP192_INTERNAL_TEMP_L4 (0x5F)
|
||||||
|
#define AXP192_TS_IN_H8 (0x62)
|
||||||
|
#define AXP192_TS_IN_L4 (0x63)
|
||||||
|
#define AXP192_GPIO0_VOL_ADC_H8 (0x64)
|
||||||
|
#define AXP192_GPIO0_VOL_ADC_L4 (0x65)
|
||||||
|
#define AXP192_GPIO1_VOL_ADC_H8 (0x66)
|
||||||
|
#define AXP192_GPIO1_VOL_ADC_L4 (0x67)
|
||||||
|
#define AXP192_BAT_AVERDISCHGCUR_H8 (0x7C)
|
||||||
|
#define AXP192_BAT_AVERDISCHGCUR_L5 (0x7D)
|
||||||
|
|
||||||
|
|
||||||
|
// Interrupt enable
|
||||||
|
#define AXP192_INTEN1 (0x40)
|
||||||
|
#define AXP192_INTEN2 (0x41)
|
||||||
|
#define AXP192_INTEN3 (0x42)
|
||||||
|
#define AXP192_INTEN4 (0x43)
|
||||||
|
#define AXP192_INTEN5 (0x4A)
|
||||||
|
|
||||||
|
// Int clear.
|
||||||
|
#define AXP192_INTSTS1 (0x44)
|
||||||
|
#define AXP192_INTSTS2 (0x45)
|
||||||
|
#define AXP192_INTSTS3 (0x46)
|
||||||
|
#define AXP192_INTSTS4 (0x47)
|
||||||
|
#define AXP192_INTSTS5 (0x4D)
|
||||||
|
|
||||||
|
extern SemaphoreHandle_t axpSemaphore;
|
||||||
|
|
||||||
|
/////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
/// High-level functions
|
||||||
|
PMU *PMU::getInstance(TwoWire &wire) {
|
||||||
|
PMU *pmu = NULL;
|
||||||
|
// Check if there is some AXP192 or AXP2101 present
|
||||||
|
uint8_t chipid = readRegisterWire(wire, AXP192_IC_TYPE);
|
||||||
|
// AXP192: 0x03 AXP2101: 0x4A
|
||||||
|
if(chipid==0x03) {
|
||||||
|
pmu = new AXP192PMU(wire);
|
||||||
|
}
|
||||||
|
#if 0
|
||||||
|
else if (chipid==0x4A) {
|
||||||
|
pmu = new AXP2101PMU(wire);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
return pmu;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int PMU::readRegisterWire(TwoWire &wire, uint8_t reg) {
|
||||||
|
wire.beginTransmission(AXP192_SLAVE_ADDRESS);
|
||||||
|
wire.write(reg);
|
||||||
|
if (wire.endTransmission() != 0) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
wire.requestFrom(AXP192_SLAVE_ADDRESS, 1U);
|
||||||
|
return wire.read();
|
||||||
|
}
|
||||||
|
int PMU::readRegister(uint8_t reg) {
|
||||||
|
return readRegisterWire(_wire, reg);
|
||||||
|
}
|
||||||
|
uint16_t PMU::readRegisters_8_4(uint8_t regh, uint8_t regl)
|
||||||
|
{
|
||||||
|
uint8_t hi = readRegister(regh);
|
||||||
|
uint8_t lo = readRegister(regl);
|
||||||
|
return (hi << 4) | (lo & 0x0F);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t PMU::readRegisters_8_5(uint8_t regh, uint8_t regl)
|
||||||
|
{
|
||||||
|
uint8_t hi = readRegister(regh);
|
||||||
|
uint8_t lo = readRegister(regl);
|
||||||
|
return (hi << 5) | (lo & 0x1F);
|
||||||
|
}
|
||||||
|
|
||||||
|
int PMU::writeRegister(uint8_t reg, uint8_t val) {
|
||||||
|
_wire.beginTransmission(AXP192_SLAVE_ADDRESS);
|
||||||
|
_wire.write(reg);
|
||||||
|
_wire.write(val);
|
||||||
|
return (_wire.endTransmission() == 0) ? 0 : -1;
|
||||||
|
}
|
||||||
|
int PMU::getRegisterBit(uint8_t reg, uint8_t bit) {
|
||||||
|
int val = readRegister(reg);
|
||||||
|
if (val == -1) { return -1; }
|
||||||
|
return (val >> bit) & 0x01;
|
||||||
|
}
|
||||||
|
int PMU::setRegisterBit(uint8_t reg, uint8_t bit) {
|
||||||
|
int val = readRegister(reg);
|
||||||
|
if (val == -1) { return -1; }
|
||||||
|
return writeRegister(reg, (val | (1<<bit)));
|
||||||
|
}
|
||||||
|
int PMU::clearRegisterBit(uint8_t reg, uint8_t bit) {
|
||||||
|
int val = readRegister(reg);
|
||||||
|
if (val == -1) { return -1; }
|
||||||
|
return writeRegister(reg, (val & ( ~(1<<bit))));
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns if there was a keypress, using the following enum defined in RX_FSK.ini:
|
||||||
|
enum KeyPress { KP_NONE = 0, KP_SHORT, KP_DOUBLE, KP_MID, KP_LONG };
|
||||||
|
|
||||||
|
int PMU::handleIRQ() {
|
||||||
|
if (pmu_irq) {
|
||||||
|
Serial.println("PMU_IRQ is set\n");
|
||||||
|
} else {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
int keypress = -1;
|
||||||
|
xSemaphoreTake( axpSemaphore, portMAX_DELAY );
|
||||||
|
keypress = getIrqKeyStatus();
|
||||||
|
if(keypress) { Serial.printf("Keypress: %d (%s)", keypress, keypress==KP_SHORT?"short":"mid"); }
|
||||||
|
if (pmu_irq != 2) {
|
||||||
|
pmu_irq = 0;
|
||||||
|
}
|
||||||
|
xSemaphoreGive( axpSemaphore );
|
||||||
|
return keypress;
|
||||||
|
}
|
||||||
|
|
||||||
|
int AXP192PMU::init() {
|
||||||
|
// Initialize AXP192, for T-BEAM v1.1 or M5Stack
|
||||||
|
|
||||||
|
// LDO2: LoRa VCC on T-BEAM, PERI_VDD on M5Core2 (LCD)
|
||||||
|
setLDO2(3300);
|
||||||
|
enableLDO2();
|
||||||
|
if(sonde.config.type == TYPE_M5_CORE2) {
|
||||||
|
// Display backlight (LCD_BL) on M5 Core2
|
||||||
|
setDC3(3300);
|
||||||
|
enableDC3();
|
||||||
|
///// pmu_irq = 2; // IRQ pin not connected on Core2
|
||||||
|
// Set GPIO0 VDO to 3.3V (as is done by original M5Stack software)
|
||||||
|
// (default value 2.8V did not have the expected effect :))
|
||||||
|
setLDOio(3300);
|
||||||
|
// ADC configuration: Enable monitoring of AC [bits 4,5 in enable register]
|
||||||
|
uint8_t val = readRegister(AXP192_ADC_EN1);
|
||||||
|
writeRegister(AXP192_ADC_EN1, val | (1 << 4) | (1 << 5) );
|
||||||
|
} else {
|
||||||
|
// T-Beam specific
|
||||||
|
// GPS power on T-Beam (its the buzzer on M5 Core2, so only enable for T-Beam)
|
||||||
|
enableLDO3();
|
||||||
|
// ADC configuration: Enable monitoring of USB [bits 2,3 in enable register]
|
||||||
|
uint8_t val = readRegister(AXP192_ADC_EN1);
|
||||||
|
writeRegister(AXP192_ADC_EN1, val | (1 << 4) | (1 << 5) );
|
||||||
|
}
|
||||||
|
// Common configuration for T-Beam and M5 Core2
|
||||||
|
// DCDC2: M5Core: Unused, T-Beam: Unused, so set to disabled!! (was enabled in previous versions)
|
||||||
|
enableDC2(false);
|
||||||
|
|
||||||
|
// EXTEN: M5Core2: 5V Boost enable; T-Beam EXTEN
|
||||||
|
enableEXTEN();
|
||||||
|
|
||||||
|
// DCDC1: M5Core: MCU_VDD, T-Beam 1.1: "VCC_2.5V" == 3V3-Pin on pin header on board
|
||||||
|
setDC1(3300);
|
||||||
|
enableDC1();
|
||||||
|
|
||||||
|
// ADC configuration: Enable monitor batt current [bit 6 in eable register]
|
||||||
|
uint8_t val = readRegister(AXP192_ADC_EN1);
|
||||||
|
writeRegister(AXP192_ADC_EN1, val | (1 << 6) );
|
||||||
|
|
||||||
|
if (pmu_irq != 2) {
|
||||||
|
pinMode(PMU_IRQ, INPUT_PULLUP);
|
||||||
|
attachInterrupt(PMU_IRQ, [] {
|
||||||
|
pmu_irq = 1;
|
||||||
|
}, FALLING);
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int AXP2101PMU::init() {
|
||||||
|
// Initialize AXP2101, for T-BEAM v1.2
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
////////////////////////////////////////////////////////////
|
||||||
|
/// Helper functions
|
||||||
|
|
||||||
|
int AXP192PMU::getIrqKeyStatus() {
|
||||||
|
int status = readRegister(AXP192_INTSTS3);
|
||||||
|
|
||||||
|
// Also clear IRQ status
|
||||||
|
writeRegister(AXP192_INTSTS1, 0xFF);
|
||||||
|
writeRegister(AXP192_INTSTS2, 0xFF);
|
||||||
|
writeRegister(AXP192_INTSTS3, 0xFF);
|
||||||
|
writeRegister(AXP192_INTSTS4, 0xFF);
|
||||||
|
writeRegister(AXP192_INTSTS5, 0xFF);
|
||||||
|
|
||||||
|
//
|
||||||
|
if ( status & 0x01 ) return KP_MID;
|
||||||
|
if ( status & 0x02 ) return KP_SHORT;
|
||||||
|
return KP_NONE;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void AXP192PMU::disableAllIRQ() {
|
||||||
|
writeRegister(AXP192_INTEN1, 0);
|
||||||
|
writeRegister(AXP192_INTEN2, 0);
|
||||||
|
writeRegister(AXP192_INTEN3, 0);
|
||||||
|
writeRegister(AXP192_INTEN4, 0);
|
||||||
|
writeRegister(AXP192_INTEN5, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void AXP192PMU::_enableIRQ(uint8_t addr, uint8_t mask) {
|
||||||
|
int data = readRegister(addr);
|
||||||
|
writeRegister(addr, data | mask);
|
||||||
|
}
|
||||||
|
|
||||||
|
// we want KP_SHORT and KP_LONG interrupts...
|
||||||
|
// IRQ4, in reg 0x42h, Bit 16+17
|
||||||
|
void AXP192PMU::enableIRQ() {
|
||||||
|
//_enableIRQ( AXP192_INTEN1, mask&0xFF );
|
||||||
|
//_enableIRQ( AXP192_INTEN2, mask>>8 );
|
||||||
|
_enableIRQ( AXP192_INTEN3, 0x03 );
|
||||||
|
//_enableIRQ( AXP192_INTEN4, mask>>24 );
|
||||||
|
//_enableIRQ( AXP192_INTEN5, mask>>32 );
|
||||||
|
}
|
||||||
|
|
||||||
|
// Functions for setting voltage output levels
|
||||||
|
int AXP192PMU::setVoltageReg(uint8_t reg, uint8_t regval) {
|
||||||
|
int val = readRegister(reg);
|
||||||
|
if (val==-1) return -1;
|
||||||
|
val &= 0x80;
|
||||||
|
val |= regval;
|
||||||
|
return writeRegister(reg, val);
|
||||||
|
}
|
||||||
|
|
||||||
|
int AXP192PMU::setDC1(uint16_t millivolt) {
|
||||||
|
return setVoltageReg(AXP192_DC1OUT_VOL, (millivolt-AXP192_DC_MIN)/AXP192_DC_STEPS );
|
||||||
|
}
|
||||||
|
int AXP192PMU::setDC2(uint16_t millivolt) {
|
||||||
|
return setVoltageReg(AXP192_DC2OUT_VOL, (millivolt-AXP192_DC_MIN)/AXP192_DC_STEPS );
|
||||||
|
}
|
||||||
|
int AXP192PMU::setDC3(uint16_t millivolt) {
|
||||||
|
return setVoltageReg(AXP192_DC3OUT_VOL , (millivolt-AXP192_DC_MIN)/AXP192_DC_STEPS );
|
||||||
|
}
|
||||||
|
int AXP192PMU::setLDO2(uint16_t millivolt) {
|
||||||
|
return setVoltageReg(AXP192_LDO23OUT_VOL, (millivolt-AXP192_LDO_MIN)/AXP192_LDO_STEPS);
|
||||||
|
}
|
||||||
|
int AXP192PMU::setLDOio(uint16_t millivolt) {
|
||||||
|
return setVoltageReg(AXP192_GPIO0_VOL, (millivolt-AXP192_LDO_MIN)/AXP192_LDO_STEPS);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// LDO23_DC123_EXT_CTL
|
||||||
|
// 0:DC-DC1, 1:DC-DC3, 2:LDO2, 3:LDO3, 4:DC-DC2, 6:EXTEN
|
||||||
|
int AXP192PMU::enableDC1(bool onoff) {
|
||||||
|
return onoff ? setRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 0) : clearRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 0);
|
||||||
|
}
|
||||||
|
int AXP192PMU::enableDC3(bool onoff) {
|
||||||
|
return onoff ? setRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 1) : clearRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 1);
|
||||||
|
}
|
||||||
|
int AXP192PMU::enableLDO2(bool onoff) {
|
||||||
|
return onoff ? setRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 2) : clearRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 2);
|
||||||
|
}
|
||||||
|
int AXP192PMU::enableLDO3(bool onoff) {
|
||||||
|
return onoff ? setRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 3) : clearRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 3);
|
||||||
|
}
|
||||||
|
int AXP192PMU::enableDC2(bool onoff) {
|
||||||
|
return onoff ? setRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 4) : clearRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 4);
|
||||||
|
}
|
||||||
|
int AXP192PMU::enableEXTEN(bool onoff) {
|
||||||
|
return onoff ? setRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 6) : clearRegisterBit(AXP192_LDO23_DC123_EXT_CTL, 6);
|
||||||
|
}
|
||||||
|
|
||||||
|
int AXP192PMU::enableADC(uint8_t channels) {
|
||||||
|
uint8_t val = readRegister(AXP192_ADC_EN1);
|
||||||
|
return writeRegister(AXP192_ADC_EN1, val | channels );
|
||||||
|
}
|
||||||
|
|
||||||
|
int AXP192PMU::isBatteryConnected() {
|
||||||
|
return getRegisterBit(AXP192_MODE_CHGSTATUS, 5);
|
||||||
|
}
|
||||||
|
int AXP192PMU::isVbusIn() {
|
||||||
|
return getRegisterBit(AXP192_STATUS, 5);
|
||||||
|
}
|
||||||
|
int AXP192PMU::isCharging() {
|
||||||
|
return getRegisterBit(AXP192_MODE_CHGSTATUS, 6);
|
||||||
|
}
|
||||||
|
|
||||||
|
#define AXP192_BATT_VOLTAGE_STEP (1.1F)
|
||||||
|
float AXP192PMU::getBattVoltage() {
|
||||||
|
return readRegisters_8_4(AXP192_BAT_AVERVOL_H8, AXP192_BAT_AVERVOL_L4) * AXP192_BATT_VOLTAGE_STEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define AXP192_BATT_DISCHARGE_CUR_STEP (0.5F)
|
||||||
|
float AXP192PMU::getBattDischargeCurrent() {
|
||||||
|
return readRegisters_8_5(AXP192_BAT_AVERDISCHGCUR_H8, AXP192_BAT_AVERDISCHGCUR_L5) * AXP192_BATT_DISCHARGE_CUR_STEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define AXP192_BATT_CHARGE_CUR_STEP (0.5F)
|
||||||
|
float AXP192PMU::getBattChargeCurrent() {
|
||||||
|
return readRegisters_8_5(AXP192_BAT_AVERCHGCUR_H8, AXP192_BAT_AVERCHGCUR_L5) * AXP192_BATT_CHARGE_CUR_STEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define AXP192_ACIN_VOLTAGE_STEP (1.7F)
|
||||||
|
float AXP192PMU::getAcinVoltage() {
|
||||||
|
return readRegisters_8_4(AXP192_ACIN_VOL_H8, AXP192_ACIN_VOL_L4) * AXP192_ACIN_VOLTAGE_STEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define AXP192_ACIN_CUR_STEP (0.625F)
|
||||||
|
float AXP192PMU::getAcinCurrent() {
|
||||||
|
return readRegisters_8_4(AXP192_ACIN_CUR_H8, AXP192_ACIN_CUR_L4) * AXP192_ACIN_CUR_STEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define AXP192_VBUS_VOLTAGE_STEP (1.7F)
|
||||||
|
float AXP192PMU::getVbusVoltage() {
|
||||||
|
return readRegisters_8_4(AXP192_VBUS_VOL_H8, AXP192_VBUS_VOL_L4) * AXP192_VBUS_VOLTAGE_STEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define AXP192_VBUS_CUR_STEP (0.375F)
|
||||||
|
float AXP192PMU::getVbusCurrent() {
|
||||||
|
return readRegisters_8_4(AXP192_VBUS_CUR_H8, AXP192_VBUS_CUR_L4) * AXP192_VBUS_CUR_STEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define AXP192_INTERNAL_TEMP_STEP (0.1F)
|
||||||
|
float AXP192PMU::getTemperature() {
|
||||||
|
return readRegisters_8_4(AXP192_INTERNAL_TEMP_H8, AXP192_INTERNAL_TEMP_L4) * AXP192_INTERNAL_TEMP_STEP - 144.7;
|
||||||
|
}
|
||||||
|
|
||||||
|
/////// Functions for AXP2101
|
||||||
|
|
@ -0,0 +1,103 @@
|
||||||
|
#include <inttypes.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
#define AXP192_SLAVE_ADDRESS 0x34
|
||||||
|
|
||||||
|
enum { TYPE_NONE=-1, TYPE_UNKNOWN=0, TYPE_AXP192, TYPE_AXP2101 };
|
||||||
|
|
||||||
|
class PMU {
|
||||||
|
protected:
|
||||||
|
PMU(TwoWire &wire) : _wire(wire) { };
|
||||||
|
|
||||||
|
public:
|
||||||
|
TwoWire &_wire;
|
||||||
|
static PMU *getInstance(TwoWire &wire);
|
||||||
|
int type;
|
||||||
|
|
||||||
|
static int readRegisterWire(TwoWire &wire, uint8_t reg);
|
||||||
|
int readRegister(uint8_t reg);
|
||||||
|
uint16_t readRegisters_8_4(uint8_t reghi, uint8_t reglo);
|
||||||
|
uint16_t readRegisters_8_5(uint8_t reghi, uint8_t reglo);
|
||||||
|
int writeRegister(uint8_t reg, uint8_t val);
|
||||||
|
int getRegisterBit(uint8_t register, uint8_t bit);
|
||||||
|
int setRegisterBit(uint8_t register, uint8_t bit);
|
||||||
|
int clearRegisterBit(uint8_t register, uint8_t bit);
|
||||||
|
|
||||||
|
int handleIRQ();
|
||||||
|
|
||||||
|
virtual int init();
|
||||||
|
virtual void disableAllIRQ();
|
||||||
|
virtual void enableIRQ();
|
||||||
|
virtual int getIrqKeyStatus();
|
||||||
|
|
||||||
|
virtual int isBatteryConnected();
|
||||||
|
virtual int isVbusIn();
|
||||||
|
virtual int isCharging();
|
||||||
|
virtual float getBattVoltage();
|
||||||
|
virtual float getBattDischargeCurrent();
|
||||||
|
virtual float getBattChargeCurrent();
|
||||||
|
virtual float getAcinVoltage();
|
||||||
|
virtual float getAcinCurrent();
|
||||||
|
virtual float getVbusVoltage();
|
||||||
|
virtual float getVbusCurrent();
|
||||||
|
virtual float getTemperature();
|
||||||
|
};
|
||||||
|
|
||||||
|
/* Interface */
|
||||||
|
class AXP192PMU : public PMU {
|
||||||
|
public:
|
||||||
|
AXP192PMU(TwoWire &wire) : PMU(wire) { type = TYPE_AXP192; };
|
||||||
|
int init();
|
||||||
|
void disableAllIRQ();
|
||||||
|
void enableIRQ();
|
||||||
|
int getIrqKeyStatus();
|
||||||
|
|
||||||
|
int isBatteryConnected();
|
||||||
|
int isVbusIn();
|
||||||
|
int isCharging();
|
||||||
|
float getBattVoltage();
|
||||||
|
float getBattDischargeCurrent();
|
||||||
|
float getBattChargeCurrent();
|
||||||
|
float getAcinVoltage();
|
||||||
|
float getAcinCurrent();
|
||||||
|
float getVbusVoltage();
|
||||||
|
float getVbusCurrent();
|
||||||
|
float getTemperature();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void _enableIRQ(uint8_t addr, uint8_t mask);
|
||||||
|
|
||||||
|
int setVoltageReg(uint8_t reg, uint8_t regval);
|
||||||
|
int setDC1(uint16_t millivolt);
|
||||||
|
int setDC2(uint16_t millivolt);
|
||||||
|
int setDC3(uint16_t millivolt);
|
||||||
|
int setLDO2(uint16_t millivolt);
|
||||||
|
int setLDOio(uint16_t millivolt);
|
||||||
|
|
||||||
|
int enableDC1(bool onff = true);
|
||||||
|
int enableDC3(bool onoff = true);
|
||||||
|
int enableLDO2(bool onoff = true);
|
||||||
|
int enableLDO3(bool onoff = true);
|
||||||
|
int enableDC2(bool onoff = true);
|
||||||
|
int enableEXTEN(bool onoff = true);
|
||||||
|
|
||||||
|
int enableADC(uint8_t channels);
|
||||||
|
};
|
||||||
|
|
||||||
|
class AXP2101PMU : public PMU {
|
||||||
|
public:
|
||||||
|
AXP2101PMU(TwoWire &wire) : PMU(wire) { };
|
||||||
|
int init();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
int setVBACKUP(uint16_t millivolt);
|
||||||
|
int setDCDC1(uint16_t millivolt);
|
||||||
|
int setALDO2(uint16_t millivolt);
|
||||||
|
int setALDO3(uint16_t millivolt);
|
||||||
|
|
||||||
|
int disableAll();
|
||||||
|
int enableVBACKUP(bool onoff = true);
|
||||||
|
int enableDC1(bool onoff = true);
|
||||||
|
int enableALDO2(bool onoff = true);
|
||||||
|
int enableALDO3(bool onoff = true);
|
||||||
|
};
|
||||||
|
|
@ -18,7 +18,6 @@ lib_deps_builtin =
|
||||||
; src
|
; src
|
||||||
lib_deps_external =
|
lib_deps_external =
|
||||||
olikraus/U8g2 @ ^2.28.8
|
olikraus/U8g2 @ ^2.28.8
|
||||||
AXP202X_Library
|
|
||||||
stevemarple/MicroNMEA @ ^2.0.5
|
stevemarple/MicroNMEA @ ^2.0.5
|
||||||
me-no-dev/ESP Async WebServer @ ^1.2.3
|
me-no-dev/ESP Async WebServer @ ^1.2.3
|
||||||
https://github.com/moononournation/Arduino_GFX#v1.1.5
|
https://github.com/moononournation/Arduino_GFX#v1.1.5
|
||||||
|
|
@ -47,3 +46,4 @@ lib_ignore = Time
|
||||||
;
|
;
|
||||||
extra_scripts = post:scripts/makefontpartition.py
|
extra_scripts = post:scripts/makefontpartition.py
|
||||||
;board_build.partitions = partition-fonts.csv
|
;board_build.partitions = partition-fonts.csv
|
||||||
|
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue