kopia lustrzana https://github.com/lora-aprs/LoRa_APRS_iGate
update tbeam axp2101
rodzic
08dc8380bc
commit
36511531ae
|
@ -43,6 +43,8 @@
|
||||||
"streambuf": "cpp",
|
"streambuf": "cpp",
|
||||||
"cinttypes": "cpp",
|
"cinttypes": "cpp",
|
||||||
"utility": "cpp",
|
"utility": "cpp",
|
||||||
"typeinfo": "cpp"
|
"typeinfo": "cpp",
|
||||||
|
"string": "cpp",
|
||||||
|
"string_view": "cpp"
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -52,7 +52,7 @@ monitor_speed = 115200
|
||||||
|
|
||||||
lib_deps =
|
lib_deps =
|
||||||
bblanchon/ArduinoJson @ 6.21.3
|
bblanchon/ArduinoJson @ 6.21.3
|
||||||
lewisxhe/AXP202X_Library @ 1.1.3
|
lewisxhe/XPowersLib @ 0.1.8
|
||||||
peterus/APRS-Decoder-Lib @ 0.0.6
|
peterus/APRS-Decoder-Lib @ 0.0.6
|
||||||
peterus/esp-logger @ 1.0.0
|
peterus/esp-logger @ 1.0.0
|
||||||
peterus/ESP-FTP-Server-Lib @ 0.14.0
|
peterus/ESP-FTP-Server-Lib @ 0.14.0
|
||||||
|
|
|
@ -35,6 +35,15 @@ TaskQueue<std::shared_ptr<APRSMessage>> toMQTT;
|
||||||
System LoRaSystem;
|
System LoRaSystem;
|
||||||
Configuration userConfig;
|
Configuration userConfig;
|
||||||
|
|
||||||
|
#ifdef HAS_AXP192
|
||||||
|
AXP192 axp;
|
||||||
|
PowerManagement *powerManagement = &axp;
|
||||||
|
#endif
|
||||||
|
#ifdef HAS_AXP2101
|
||||||
|
AXP2101 axp;
|
||||||
|
PowerManagement *powerManagement = &axp;
|
||||||
|
#endif
|
||||||
|
|
||||||
DisplayTask displayTask;
|
DisplayTask displayTask;
|
||||||
// ModemTask modemTask(fromModem, toModem);
|
// ModemTask modemTask(fromModem, toModem);
|
||||||
RadiolibTask modemTask(fromModem, toModem);
|
RadiolibTask modemTask(fromModem, toModem);
|
||||||
|
@ -68,21 +77,21 @@ void setup() {
|
||||||
}
|
}
|
||||||
}*/
|
}*/
|
||||||
|
|
||||||
#ifdef TBEAM_V10
|
#if defined(HAS_AXP192) || defined(HAS_AXP2101)
|
||||||
Wire.begin(SDA, SCL);
|
Wire.begin(SDA, SCL);
|
||||||
PowerManagement powerManagement;
|
if (powerManagement->begin(Wire)) {
|
||||||
if (!powerManagement.begin(Wire)) {
|
LoRaSystem.getLogger().log(logging::LoggerLevel::LOGGER_LEVEL_INFO, "PMU", "init done!");
|
||||||
LoRaSystem.getLogger().log(logging::LoggerLevel::LOGGER_LEVEL_INFO, MODULE_NAME, "AXP192 init done!");
|
|
||||||
} else {
|
} else {
|
||||||
LoRaSystem.getLogger().log(logging::LoggerLevel::LOGGER_LEVEL_ERROR, MODULE_NAME, "AXP192 init failed!");
|
LoRaSystem.getLogger().log(logging::LoggerLevel::LOGGER_LEVEL_ERROR, "PMU", "init failed!");
|
||||||
}
|
}
|
||||||
powerManagement.activateLoRa();
|
powerManagement->activateLoRa();
|
||||||
powerManagement.activateOLED();
|
powerManagement->activateOLED();
|
||||||
if (userConfig.beacon.use_gps) {
|
if (userConfig.beacon.use_gps) {
|
||||||
powerManagement.activateGPS();
|
powerManagement->activateGPS();
|
||||||
} else {
|
} else {
|
||||||
powerManagement.deactivateGPS();
|
powerManagement->deactivateGPS();
|
||||||
}
|
}
|
||||||
|
// powerManagement->activateMeasurement();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
LoRaSystem.setUserConfig(&userConfig);
|
LoRaSystem.setUserConfig(&userConfig);
|
||||||
|
@ -98,7 +107,7 @@ void setup() {
|
||||||
tcpip = true;
|
tcpip = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef TINTERNET_POE
|
#ifdef T_INTERNET_POE
|
||||||
LoRaSystem.getTaskManager().addAlwaysRunTask(ðTask);
|
LoRaSystem.getTaskManager().addAlwaysRunTask(ðTask);
|
||||||
tcpip = true;
|
tcpip = true;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,37 +1,218 @@
|
||||||
|
#include <XPowersAXP192.tpp>
|
||||||
|
#include <XPowersAXP2101.tpp>
|
||||||
|
|
||||||
#include "power_management.h"
|
#include "power_management.h"
|
||||||
|
|
||||||
PowerManagement::PowerManagement() : axp() {
|
AXP192::AXP192() {
|
||||||
}
|
}
|
||||||
|
|
||||||
bool PowerManagement::begin(TwoWire &port) {
|
// cppcheck-suppress unusedFunction
|
||||||
bool result = axp.begin(port, AXP192_SLAVE_ADDRESS);
|
bool AXP192::begin(TwoWire &port) {
|
||||||
if (!result) {
|
_pmu = new XPowersAXP192(port);
|
||||||
axp.setDCDC1Voltage(3300);
|
if (!_pmu->init()) {
|
||||||
|
delete _pmu;
|
||||||
|
_pmu = 0;
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
return result;
|
|
||||||
|
// lora radio power channel
|
||||||
|
_pmu->setPowerChannelVoltage(XPOWERS_LDO2, 3300);
|
||||||
|
|
||||||
|
// oled module power channel,
|
||||||
|
// disable it will cause abnormal communication between boot and AXP power supply,
|
||||||
|
// do not turn it off
|
||||||
|
_pmu->setPowerChannelVoltage(XPOWERS_DCDC1, 3300);
|
||||||
|
|
||||||
|
// gnss module power channel - now turned on in setGpsPower
|
||||||
|
_pmu->setPowerChannelVoltage(XPOWERS_LDO3, 3300);
|
||||||
|
|
||||||
|
// protected oled power source
|
||||||
|
//_pmu->setProtectedChannel(XPOWERS_DCDC1);
|
||||||
|
// protected esp32 power source
|
||||||
|
_pmu->setProtectedChannel(XPOWERS_DCDC3);
|
||||||
|
|
||||||
|
// disable not use channel
|
||||||
|
_pmu->disablePowerOutput(XPOWERS_DCDC2);
|
||||||
|
|
||||||
|
// disable all axp chip interrupt
|
||||||
|
_pmu->disableIRQ(XPOWERS_AXP192_ALL_IRQ);
|
||||||
|
|
||||||
|
// Set constant current charging current
|
||||||
|
_pmu->setChargerConstantCurr(XPOWERS_AXP192_CHG_CUR_780MA);
|
||||||
|
|
||||||
|
// Set up the charging voltage
|
||||||
|
_pmu->setChargeTargetVoltage(XPOWERS_AXP192_CHG_VOL_4V2);
|
||||||
|
|
||||||
|
_pmu->setChargingLedMode(XPOWERS_CHG_LED_CTRL_CHG);
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PowerManagement::activateLoRa() {
|
// cppcheck-suppress unusedFunction
|
||||||
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON);
|
void AXP192::activateLoRa() {
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_LDO2);
|
||||||
}
|
}
|
||||||
|
|
||||||
void PowerManagement::deactivateLoRa() {
|
// cppcheck-suppress unusedFunction
|
||||||
axp.setPowerOutPut(AXP192_LDO2, AXP202_OFF);
|
void AXP192::deactivateLoRa() {
|
||||||
|
_pmu->disablePowerOutput(XPOWERS_LDO2);
|
||||||
}
|
}
|
||||||
|
|
||||||
void PowerManagement::activateGPS() {
|
// cppcheck-suppress unusedFunction
|
||||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON);
|
void AXP192::activateGPS() {
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_LDO3);
|
||||||
}
|
}
|
||||||
|
|
||||||
void PowerManagement::deactivateGPS() {
|
// cppcheck-suppress unusedFunction
|
||||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_OFF);
|
void AXP192::deactivateGPS() {
|
||||||
|
_pmu->disablePowerOutput(XPOWERS_LDO3);
|
||||||
}
|
}
|
||||||
|
|
||||||
void PowerManagement::activateOLED() {
|
// cppcheck-suppress unusedFunction
|
||||||
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
|
void AXP192::activateOLED() {
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_DCDC1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void PowerManagement::deactivateOLED() {
|
// cppcheck-suppress unusedFunction
|
||||||
axp.setPowerOutPut(AXP192_DCDC1, AXP202_OFF);
|
void AXP192::deactivateOLED() {
|
||||||
|
_pmu->disablePowerOutput(XPOWERS_DCDC1);
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP192::activateMeasurement() {
|
||||||
|
_pmu->enableBattVoltageMeasure();
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP192::deactivateMeasurement() {
|
||||||
|
_pmu->disableBattVoltageMeasure();
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
double AXP192::getBatteryVoltage() {
|
||||||
|
return _pmu->getBattVoltage() / 1000.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
double AXP192::getBatteryChargeDischargeCurrent() {
|
||||||
|
if (isCharging()) {
|
||||||
|
return ((XPowersAXP192 *)_pmu)->getBatteryChargeCurrent();
|
||||||
|
}
|
||||||
|
return -1.0 * ((XPowersAXP192 *)_pmu)->getBattDischargeCurrent();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool AXP192::isBatteryConnect() {
|
||||||
|
return _pmu->isBatteryConnect();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool AXP192::isCharging() {
|
||||||
|
return _pmu->isCharging();
|
||||||
|
}
|
||||||
|
|
||||||
|
AXP2101::AXP2101() {
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
bool AXP2101::begin(TwoWire &port) {
|
||||||
|
_pmu = new XPowersAXP2101(port);
|
||||||
|
if (!_pmu->init()) {
|
||||||
|
delete _pmu;
|
||||||
|
_pmu = 0;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Unuse power channel
|
||||||
|
_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);
|
||||||
|
|
||||||
|
// GNSS RTC PowerVDD 3300mV
|
||||||
|
_pmu->setPowerChannelVoltage(XPOWERS_VBACKUP, 3300);
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_VBACKUP);
|
||||||
|
|
||||||
|
// LoRa VDD 3300mV
|
||||||
|
_pmu->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_ALDO2);
|
||||||
|
|
||||||
|
// GNSS VDD 3300mV
|
||||||
|
_pmu->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_ALDO3);
|
||||||
|
|
||||||
|
// disable all axp chip interrupt
|
||||||
|
_pmu->disableIRQ(XPOWERS_AXP2101_ALL_IRQ);
|
||||||
|
|
||||||
|
// Set constant current charging current
|
||||||
|
_pmu->setChargerConstantCurr(XPOWERS_AXP2101_CHG_CUR_800MA);
|
||||||
|
|
||||||
|
// Set up the charging voltage
|
||||||
|
_pmu->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V2);
|
||||||
|
|
||||||
|
_pmu->setChargingLedMode(XPOWERS_CHG_LED_CTRL_CHG);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP2101::activateLoRa() {
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_ALDO2);
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP2101::deactivateLoRa() {
|
||||||
|
_pmu->disablePowerOutput(XPOWERS_ALDO2);
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP2101::activateGPS() {
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_ALDO3);
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP2101::deactivateGPS() {
|
||||||
|
_pmu->disablePowerOutput(XPOWERS_ALDO3);
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP2101::activateOLED() {
|
||||||
|
_pmu->enablePowerOutput(XPOWERS_DCDC1);
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP2101::deactivateOLED() {
|
||||||
|
_pmu->disablePowerOutput(XPOWERS_DCDC1);
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP2101::activateMeasurement() {
|
||||||
|
_pmu->enableBattVoltageMeasure();
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
void AXP2101::deactivateMeasurement() {
|
||||||
|
_pmu->disableBattVoltageMeasure();
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
double AXP2101::getBatteryVoltage() {
|
||||||
|
return _pmu->getBattVoltage() / 1000.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction
|
||||||
|
double AXP2101::getBatteryChargeDischargeCurrent() {
|
||||||
|
return 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool AXP2101::isBatteryConnect() {
|
||||||
|
return _pmu->isBatteryConnect();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool AXP2101::isCharging() {
|
||||||
|
return _pmu->isCharging();
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,12 +1,43 @@
|
||||||
#ifndef POWER_MANAGEMENT_H_
|
#ifndef POWER_MANAGEMENT_H_
|
||||||
#define POWER_MANAGEMENT_H_
|
#define POWER_MANAGEMENT_H_
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Wire.h>
|
||||||
#include <axp20x.h>
|
#include <XPowersLibInterface.hpp>
|
||||||
|
|
||||||
class PowerManagement {
|
class PowerManagement {
|
||||||
public:
|
public:
|
||||||
PowerManagement();
|
~PowerManagement() {
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool begin(TwoWire &port) = 0;
|
||||||
|
|
||||||
|
virtual void activateLoRa() = 0;
|
||||||
|
virtual void deactivateLoRa() = 0;
|
||||||
|
|
||||||
|
virtual void activateGPS() = 0;
|
||||||
|
virtual void deactivateGPS() = 0;
|
||||||
|
|
||||||
|
virtual void activateOLED() = 0;
|
||||||
|
virtual void deactivateOLED() = 0;
|
||||||
|
|
||||||
|
virtual void activateMeasurement() = 0;
|
||||||
|
virtual void deactivateMeasurement() = 0;
|
||||||
|
|
||||||
|
virtual double getBatteryVoltage() = 0;
|
||||||
|
|
||||||
|
virtual double getBatteryChargeDischargeCurrent() = 0;
|
||||||
|
|
||||||
|
virtual bool isBatteryConnect() = 0;
|
||||||
|
virtual bool isCharging() = 0;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
XPowersLibInterface *_pmu = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
class AXP192 : public PowerManagement {
|
||||||
|
public:
|
||||||
|
AXP192();
|
||||||
|
|
||||||
bool begin(TwoWire &port);
|
bool begin(TwoWire &port);
|
||||||
|
|
||||||
void activateLoRa();
|
void activateLoRa();
|
||||||
|
@ -18,8 +49,45 @@ public:
|
||||||
void activateOLED();
|
void activateOLED();
|
||||||
void deactivateOLED();
|
void deactivateOLED();
|
||||||
|
|
||||||
private:
|
void enableChgLed();
|
||||||
AXP20X_Class axp;
|
void disableChgLed();
|
||||||
|
|
||||||
|
void activateMeasurement();
|
||||||
|
void deactivateMeasurement();
|
||||||
|
|
||||||
|
double getBatteryVoltage();
|
||||||
|
double getBatteryChargeDischargeCurrent();
|
||||||
|
|
||||||
|
bool isBatteryConnect();
|
||||||
|
bool isCharging();
|
||||||
|
};
|
||||||
|
|
||||||
|
class AXP2101 : public PowerManagement {
|
||||||
|
public:
|
||||||
|
AXP2101();
|
||||||
|
|
||||||
|
bool begin(TwoWire &port);
|
||||||
|
|
||||||
|
void activateLoRa();
|
||||||
|
void deactivateLoRa();
|
||||||
|
|
||||||
|
void activateGPS();
|
||||||
|
void deactivateGPS();
|
||||||
|
|
||||||
|
void activateOLED();
|
||||||
|
void deactivateOLED();
|
||||||
|
|
||||||
|
void enableChgLed();
|
||||||
|
void disableChgLed();
|
||||||
|
|
||||||
|
void activateMeasurement();
|
||||||
|
void deactivateMeasurement();
|
||||||
|
|
||||||
|
double getBatteryVoltage();
|
||||||
|
double getBatteryChargeDischargeCurrent();
|
||||||
|
|
||||||
|
bool isBatteryConnect();
|
||||||
|
bool isCharging();
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,6 +1,5 @@
|
||||||
; The 1.0 release of the TBEAM board
|
|
||||||
[env:tbeam]
|
[env:tbeam]
|
||||||
extends = esp32_base
|
extends = esp32_base
|
||||||
board = ttgo-t-beam
|
board = ttgo-t-beam
|
||||||
build_flags =
|
build_flags =
|
||||||
${esp32_base.build_flags} -DTBEAM_V10 -DUSE_SX1278 -DGPS_RX_PIN=34 -DGPS_TX_PIN=12
|
${esp32_base.build_flags} -DTBEAM_V10 -DUSE_SX1278 -DGPS_RX_PIN=34 -DGPS_TX_PIN=12 -DHAS_AXP192
|
||||||
|
|
|
@ -0,0 +1,5 @@
|
||||||
|
[env:tbeam_axp2101]
|
||||||
|
extends = esp32_base
|
||||||
|
board = ttgo-t-beam
|
||||||
|
build_flags =
|
||||||
|
${esp32_base.build_flags} -DTBEAM_V12_AXP2101 -DUSE_SX1278 -DGPS_RX_PIN=34 -DGPS_TX_PIN=12 -DHAS_AXP2101
|
Ładowanie…
Reference in New Issue