sforkowany z mirror/meshtastic-firmware
Merge pull request #237 from Professr/issue#182
Switch main display to event-driven model, abstract the three main status info categories, work on power.h1.2-legacy
commit
20a669029b
|
@ -0,0 +1,108 @@
|
|||
#pragma once
|
||||
#include <Arduino.h>
|
||||
#include "Status.h"
|
||||
#include "configuration.h"
|
||||
|
||||
namespace meshtastic {
|
||||
|
||||
/// Describes the state of the GPS system.
|
||||
class GPSStatus : public Status
|
||||
{
|
||||
|
||||
private:
|
||||
CallbackObserver<GPSStatus, const GPSStatus *> statusObserver = CallbackObserver<GPSStatus, const GPSStatus *>(this, &GPSStatus::updateStatus);
|
||||
|
||||
bool hasLock = false; // default to false, until we complete our first read
|
||||
bool isConnected = false; // Do we have a GPS we are talking to
|
||||
int32_t latitude = 0, longitude = 0; // as an int mult by 1e-7 to get value as double
|
||||
int32_t altitude = 0;
|
||||
uint32_t dop = 0; // Diminution of position; PDOP where possible (UBlox), HDOP otherwise (TinyGPS) in 10^2 units (needs scaling before use)
|
||||
|
||||
public:
|
||||
|
||||
GPSStatus() {
|
||||
statusType = STATUS_TYPE_GPS;
|
||||
}
|
||||
GPSStatus( bool hasLock, bool isConnected, int32_t latitude, int32_t longitude, int32_t altitude, uint32_t dop ) : Status()
|
||||
{
|
||||
this->hasLock = hasLock;
|
||||
this->isConnected = isConnected;
|
||||
this->latitude = latitude;
|
||||
this->longitude = longitude;
|
||||
this->altitude = altitude;
|
||||
this->dop = dop;
|
||||
}
|
||||
GPSStatus(const GPSStatus &);
|
||||
GPSStatus &operator=(const GPSStatus &);
|
||||
|
||||
void observe(Observable<const GPSStatus *> *source)
|
||||
{
|
||||
statusObserver.observe(source);
|
||||
}
|
||||
|
||||
bool getHasLock() const
|
||||
{
|
||||
return hasLock;
|
||||
}
|
||||
|
||||
bool getIsConnected() const
|
||||
{
|
||||
return isConnected;
|
||||
}
|
||||
|
||||
int32_t getLatitude() const
|
||||
{
|
||||
return latitude;
|
||||
}
|
||||
|
||||
int32_t getLongitude() const
|
||||
{
|
||||
return longitude;
|
||||
}
|
||||
|
||||
int32_t getAltitude() const
|
||||
{
|
||||
return altitude;
|
||||
}
|
||||
|
||||
uint32_t getDOP() const
|
||||
{
|
||||
return dop;
|
||||
}
|
||||
|
||||
bool matches(const GPSStatus *newStatus) const
|
||||
{
|
||||
return (
|
||||
newStatus->hasLock != hasLock ||
|
||||
newStatus->isConnected != isConnected ||
|
||||
newStatus->latitude != latitude ||
|
||||
newStatus->longitude != longitude ||
|
||||
newStatus->altitude != altitude ||
|
||||
newStatus->dop != dop
|
||||
);
|
||||
}
|
||||
int updateStatus(const GPSStatus *newStatus) {
|
||||
// Only update the status if values have actually changed
|
||||
bool isDirty;
|
||||
{
|
||||
isDirty = matches(newStatus);
|
||||
initialized = true;
|
||||
hasLock = newStatus->hasLock;
|
||||
isConnected = newStatus->isConnected;
|
||||
latitude = newStatus->latitude;
|
||||
longitude = newStatus->longitude;
|
||||
altitude = newStatus->altitude;
|
||||
dop = newStatus->dop;
|
||||
}
|
||||
if(isDirty) {
|
||||
DEBUG_MSG("New GPS pos lat=%f, lon=%f, alt=%d, pdop=%f\n", latitude * 1e-7, longitude * 1e-7, altitude, dop * 1e-2);
|
||||
onNewStatus.notifyObservers(this);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
extern meshtastic::GPSStatus *gpsStatus;
|
|
@ -0,0 +1,73 @@
|
|||
#pragma once
|
||||
#include <Arduino.h>
|
||||
#include "Status.h"
|
||||
#include "configuration.h"
|
||||
|
||||
namespace meshtastic {
|
||||
|
||||
/// Describes the state of the NodeDB system.
|
||||
class NodeStatus : public Status
|
||||
{
|
||||
|
||||
private:
|
||||
CallbackObserver<NodeStatus, const NodeStatus *> statusObserver = CallbackObserver<NodeStatus, const NodeStatus *>(this, &NodeStatus::updateStatus);
|
||||
|
||||
uint8_t numOnline = 0;
|
||||
uint8_t numTotal = 0;
|
||||
|
||||
public:
|
||||
|
||||
NodeStatus() {
|
||||
statusType = STATUS_TYPE_NODE;
|
||||
}
|
||||
NodeStatus( uint8_t numOnline, uint8_t numTotal ) : Status()
|
||||
{
|
||||
this->numOnline = numOnline;
|
||||
this->numTotal = numTotal;
|
||||
}
|
||||
NodeStatus(const NodeStatus &);
|
||||
NodeStatus &operator=(const NodeStatus &);
|
||||
|
||||
void observe(Observable<const NodeStatus *> *source)
|
||||
{
|
||||
statusObserver.observe(source);
|
||||
}
|
||||
|
||||
uint8_t getNumOnline() const
|
||||
{
|
||||
return numOnline;
|
||||
}
|
||||
|
||||
uint8_t getNumTotal() const
|
||||
{
|
||||
return numTotal;
|
||||
}
|
||||
|
||||
bool matches(const NodeStatus *newStatus) const
|
||||
{
|
||||
return (
|
||||
newStatus->getNumOnline() != numOnline ||
|
||||
newStatus->getNumTotal() != numTotal
|
||||
);
|
||||
}
|
||||
int updateStatus(const NodeStatus *newStatus) {
|
||||
// Only update the status if values have actually changed
|
||||
bool isDirty;
|
||||
{
|
||||
isDirty = matches(newStatus);
|
||||
initialized = true;
|
||||
numOnline = newStatus->getNumOnline();
|
||||
numTotal = newStatus->getNumTotal();
|
||||
}
|
||||
if(isDirty) {
|
||||
DEBUG_MSG("Node status update: %d online, %d total\n", numOnline, numTotal);
|
||||
onNewStatus.notifyObservers(this);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
extern meshtastic::NodeStatus *nodeStatus;
|
|
@ -0,0 +1,180 @@
|
|||
#include "power.h"
|
||||
#include "PowerFSM.h"
|
||||
#include "main.h"
|
||||
#include "utils.h"
|
||||
#include "sleep.h"
|
||||
|
||||
|
||||
#ifdef TBEAM_V10
|
||||
|
||||
// FIXME. nasty hack cleanup how we load axp192
|
||||
#undef AXP192_SLAVE_ADDRESS
|
||||
#include "axp20x.h"
|
||||
AXP20X_Class axp;
|
||||
bool pmu_irq = false;
|
||||
|
||||
Power *power;
|
||||
|
||||
bool Power::setup()
|
||||
{
|
||||
|
||||
axp192Init();
|
||||
PeriodicTask::setup(); // We don't start our periodic task unless we actually found the device
|
||||
setPeriod(1);
|
||||
|
||||
return axp192_found;
|
||||
}
|
||||
|
||||
/// Reads power status to powerStatus singleton.
|
||||
//
|
||||
// TODO(girts): move this and other axp stuff to power.h/power.cpp.
|
||||
void Power::readPowerStatus()
|
||||
{
|
||||
bool hasBattery = axp.isBatteryConnect();
|
||||
int batteryVoltageMv = 0;
|
||||
uint8_t batteryChargePercent = 0;
|
||||
if (hasBattery) {
|
||||
batteryVoltageMv = axp.getBattVoltage();
|
||||
// If the AXP192 returns a valid battery percentage, use it
|
||||
if (axp.getBattPercentage() >= 0) {
|
||||
batteryChargePercent = axp.getBattPercentage();
|
||||
} else {
|
||||
// If the AXP192 returns a percentage less than 0, the feature is either not supported or there is an error
|
||||
// In that case, we compute an estimate of the charge percent based on maximum and minimum voltages defined in power.h
|
||||
batteryChargePercent = clamp((int)(((batteryVoltageMv - BAT_MILLIVOLTS_EMPTY) * 1e2) / (BAT_MILLIVOLTS_FULL - BAT_MILLIVOLTS_EMPTY)), 0, 100);
|
||||
}
|
||||
}
|
||||
|
||||
// Notify any status instances that are observing us
|
||||
const meshtastic::PowerStatus powerStatus = meshtastic::PowerStatus(hasBattery, axp.isVBUSPlug(), axp.isChargeing(), batteryVoltageMv, batteryChargePercent);
|
||||
newStatus.notifyObservers(&powerStatus);
|
||||
|
||||
// If we have a battery at all and it is less than 10% full, force deep sleep
|
||||
if (powerStatus.getHasBattery() && !powerStatus.getHasUSB() &&
|
||||
axp.getBattVoltage() < MIN_BAT_MILLIVOLTS)
|
||||
powerFSM.trigger(EVENT_LOW_BATTERY);
|
||||
}
|
||||
|
||||
void Power::doTask()
|
||||
{
|
||||
readPowerStatus();
|
||||
|
||||
// Only read once every 20 seconds once the power status for the app has been initialized
|
||||
if(statusHandler && statusHandler->isInitialized())
|
||||
setPeriod(1000 * 20);
|
||||
}
|
||||
#endif // TBEAM_V10
|
||||
|
||||
#ifdef AXP192_SLAVE_ADDRESS
|
||||
/**
|
||||
* Init the power manager chip
|
||||
*
|
||||
* axp192 power
|
||||
DCDC1 0.7-3.5V @ 1200mA max -> OLED // If you turn this off you'll lose comms to the axp192 because the OLED and the axp192
|
||||
share the same i2c bus, instead use ssd1306 sleep mode DCDC2 -> unused DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this on!) LDO1
|
||||
30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of days), can
|
||||
not be turned off LDO2 200mA -> LORA LDO3 200mA -> GPS
|
||||
*/
|
||||
void Power::axp192Init()
|
||||
{
|
||||
if (axp192_found) {
|
||||
if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS)) {
|
||||
DEBUG_MSG("AXP192 Begin PASS\n");
|
||||
|
||||
// axp.setChgLEDMode(LED_BLINK_4HZ);
|
||||
DEBUG_MSG("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("LDO2: %s\n", axp.isLDO2Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("LDO3: %s\n", axp.isLDO3Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("----------------------------------------\n");
|
||||
|
||||
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); // LORA radio
|
||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // GPS main power
|
||||
axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
|
||||
axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
|
||||
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
|
||||
axp.setDCDC1Voltage(3300); // for the OLED power
|
||||
|
||||
DEBUG_MSG("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("LDO2: %s\n", axp.isLDO2Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("LDO3: %s\n", axp.isLDO3Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
|
||||
|
||||
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_1320MA); // actual limit (in HW) on the tbeam is 450mA
|
||||
#if 0
|
||||
|
||||
// Not connected
|
||||
//val = 0xfc;
|
||||
//axp._writeByte(AXP202_VHTF_CHGSET, 1, &val); // Set temperature protection
|
||||
|
||||
//not used
|
||||
//val = 0x46;
|
||||
//axp._writeByte(AXP202_OFF_CTL, 1, &val); // enable bat detection
|
||||
#endif
|
||||
axp.debugCharging();
|
||||
|
||||
#ifdef PMU_IRQ
|
||||
pinMode(PMU_IRQ, INPUT);
|
||||
attachInterrupt(
|
||||
PMU_IRQ, [] { pmu_irq = true; }, FALLING);
|
||||
|
||||
axp.adc1Enable(AXP202_BATT_CUR_ADC1, 1);
|
||||
axp.enableIRQ(AXP202_BATT_REMOVED_IRQ | AXP202_BATT_CONNECT_IRQ | AXP202_CHARGING_FINISHED_IRQ | AXP202_CHARGING_IRQ |
|
||||
AXP202_VBUS_REMOVED_IRQ | AXP202_VBUS_CONNECT_IRQ | AXP202_PEK_SHORTPRESS_IRQ,
|
||||
1);
|
||||
|
||||
axp.clearIRQ();
|
||||
#endif
|
||||
readPowerStatus();
|
||||
} else {
|
||||
DEBUG_MSG("AXP192 Begin FAIL\n");
|
||||
}
|
||||
} else {
|
||||
DEBUG_MSG("AXP192 not found\n");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void Power::loop()
|
||||
{
|
||||
|
||||
#ifdef PMU_IRQ
|
||||
if (pmu_irq) {
|
||||
pmu_irq = false;
|
||||
axp.readIRQ();
|
||||
|
||||
DEBUG_MSG("pmu irq!\n");
|
||||
|
||||
if (axp.isChargingIRQ()) {
|
||||
DEBUG_MSG("Battery start charging\n");
|
||||
}
|
||||
if (axp.isChargingDoneIRQ()) {
|
||||
DEBUG_MSG("Battery fully charged\n");
|
||||
}
|
||||
if (axp.isVbusRemoveIRQ()) {
|
||||
DEBUG_MSG("USB unplugged\n");
|
||||
}
|
||||
if (axp.isVbusPlugInIRQ()) {
|
||||
DEBUG_MSG("USB plugged In\n");
|
||||
}
|
||||
if (axp.isBattPlugInIRQ()) {
|
||||
DEBUG_MSG("Battery inserted\n");
|
||||
}
|
||||
if (axp.isBattRemoveIRQ()) {
|
||||
DEBUG_MSG("Battery removed\n");
|
||||
}
|
||||
if (axp.isPEKShortPressIRQ()) {
|
||||
DEBUG_MSG("PEK short button press\n");
|
||||
}
|
||||
|
||||
readPowerStatus();
|
||||
axp.clearIRQ();
|
||||
}
|
||||
|
||||
#endif // T_BEAM_V10
|
||||
|
||||
}
|
|
@ -0,0 +1,103 @@
|
|||
#pragma once
|
||||
#include <Arduino.h>
|
||||
#include "Status.h"
|
||||
#include "configuration.h"
|
||||
|
||||
namespace meshtastic {
|
||||
|
||||
/// Describes the state of the GPS system.
|
||||
class PowerStatus : public Status
|
||||
{
|
||||
|
||||
private:
|
||||
CallbackObserver<PowerStatus, const PowerStatus *> statusObserver = CallbackObserver<PowerStatus, const PowerStatus *>(this, &PowerStatus::updateStatus);
|
||||
|
||||
/// Whether we have a battery connected
|
||||
bool hasBattery;
|
||||
/// Battery voltage in mV, valid if haveBattery is true
|
||||
int batteryVoltageMv;
|
||||
/// Battery charge percentage, either read directly or estimated
|
||||
uint8_t batteryChargePercent;
|
||||
/// Whether USB is connected
|
||||
bool hasUSB;
|
||||
/// Whether we are charging the battery
|
||||
bool isCharging;
|
||||
|
||||
public:
|
||||
|
||||
PowerStatus() {
|
||||
statusType = STATUS_TYPE_POWER;
|
||||
}
|
||||
PowerStatus( bool hasBattery, bool hasUSB, bool isCharging, int batteryVoltageMv, uint8_t batteryChargePercent ) : Status()
|
||||
{
|
||||
this->hasBattery = hasBattery;
|
||||
this->hasUSB = hasUSB;
|
||||
this->isCharging = isCharging;
|
||||
this->batteryVoltageMv = batteryVoltageMv;
|
||||
this->batteryChargePercent = batteryChargePercent;
|
||||
}
|
||||
PowerStatus(const PowerStatus &);
|
||||
PowerStatus &operator=(const PowerStatus &);
|
||||
|
||||
void observe(Observable<const PowerStatus *> *source)
|
||||
{
|
||||
statusObserver.observe(source);
|
||||
}
|
||||
|
||||
bool getHasBattery() const
|
||||
{
|
||||
return hasBattery;
|
||||
}
|
||||
|
||||
bool getHasUSB() const
|
||||
{
|
||||
return hasUSB;
|
||||
}
|
||||
|
||||
bool getIsCharging() const
|
||||
{
|
||||
return isCharging;
|
||||
}
|
||||
|
||||
int getBatteryVoltageMv() const
|
||||
{
|
||||
return batteryVoltageMv;
|
||||
}
|
||||
|
||||
uint8_t getBatteryChargePercent() const
|
||||
{
|
||||
return batteryChargePercent;
|
||||
}
|
||||
|
||||
bool matches(const PowerStatus *newStatus) const
|
||||
{
|
||||
return (
|
||||
newStatus->getHasBattery() != hasBattery ||
|
||||
newStatus->getHasUSB() != hasUSB ||
|
||||
newStatus->getBatteryVoltageMv() != batteryVoltageMv
|
||||
);
|
||||
}
|
||||
int updateStatus(const PowerStatus *newStatus) {
|
||||
// Only update the status if values have actually changed
|
||||
bool isDirty;
|
||||
{
|
||||
isDirty = matches(newStatus);
|
||||
initialized = true;
|
||||
hasBattery = newStatus->getHasBattery();
|
||||
batteryVoltageMv = newStatus->getBatteryVoltageMv();
|
||||
batteryChargePercent = newStatus->getBatteryChargePercent();
|
||||
hasUSB = newStatus->getHasUSB();
|
||||
isCharging = newStatus->getIsCharging();
|
||||
}
|
||||
if(isDirty) {
|
||||
DEBUG_MSG("Battery %dmV %d%%\n", batteryVoltageMv, batteryChargePercent);
|
||||
onNewStatus.notifyObservers(this);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
extern meshtastic::PowerStatus *powerStatus;
|
|
@ -0,0 +1,72 @@
|
|||
#pragma once
|
||||
|
||||
#include "Observer.h"
|
||||
|
||||
// Constants for the various status types, so we can tell subclass instances apart
|
||||
#define STATUS_TYPE_BASE 0
|
||||
#define STATUS_TYPE_POWER 1
|
||||
#define STATUS_TYPE_GPS 2
|
||||
#define STATUS_TYPE_NODE 3
|
||||
|
||||
|
||||
namespace meshtastic
|
||||
{
|
||||
|
||||
// A base class for observable status
|
||||
class Status
|
||||
{
|
||||
protected:
|
||||
// Allows us to observe an Observable
|
||||
CallbackObserver<Status, const Status *> statusObserver = CallbackObserver<Status, const Status *>(this, &Status::updateStatus);
|
||||
bool initialized = false;
|
||||
// Workaround for no typeid support
|
||||
int statusType;
|
||||
|
||||
public:
|
||||
// Allows us to generate observable events
|
||||
Observable<const Status *> onNewStatus;
|
||||
|
||||
// Enable polymorphism ?
|
||||
virtual ~Status() = default;
|
||||
|
||||
Status() {
|
||||
if (!statusType)
|
||||
{
|
||||
statusType = STATUS_TYPE_BASE;
|
||||
}
|
||||
}
|
||||
|
||||
// Prevent object copy/move
|
||||
Status(const Status &) = delete;
|
||||
Status &operator=(const Status &) = delete;
|
||||
|
||||
// Start observing a source of data
|
||||
void observe(Observable<const Status *> *source)
|
||||
{
|
||||
statusObserver.observe(source);
|
||||
}
|
||||
|
||||
// Determines whether or not existing data matches the data in another Status instance
|
||||
bool matches(const Status *otherStatus) const
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
bool isInitialized() const
|
||||
{
|
||||
return initialized;
|
||||
}
|
||||
|
||||
int getStatusType() const
|
||||
{
|
||||
return statusType;
|
||||
}
|
||||
|
||||
// Called when the Observable we're observing generates a new notification
|
||||
int updateStatus(const Status *newStatus)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
};
|
||||
};
|
|
@ -4,7 +4,6 @@
|
|||
#include "configuration.h"
|
||||
#include "esp_task_wdt.h"
|
||||
#include "main.h"
|
||||
#include "power.h"
|
||||
#include "sleep.h"
|
||||
#include "target_specific.h"
|
||||
#include "utils.h"
|
||||
|
@ -61,113 +60,6 @@ void getMacAddr(uint8_t *dmac)
|
|||
assert(esp_efuse_mac_get_default(dmac) == ESP_OK);
|
||||
}
|
||||
|
||||
#ifdef TBEAM_V10
|
||||
|
||||
// FIXME. nasty hack cleanup how we load axp192
|
||||
#undef AXP192_SLAVE_ADDRESS
|
||||
#include "axp20x.h"
|
||||
AXP20X_Class axp;
|
||||
bool pmu_irq = false;
|
||||
|
||||
/// Reads power status to powerStatus singleton.
|
||||
//
|
||||
// TODO(girts): move this and other axp stuff to power.h/power.cpp.
|
||||
void readPowerStatus()
|
||||
{
|
||||
powerStatus.haveBattery = axp.isBatteryConnect();
|
||||
if (powerStatus.haveBattery) {
|
||||
powerStatus.batteryVoltageMv = axp.getBattVoltage();
|
||||
// If the AXP192 returns a valid battery percentage, use it
|
||||
if (axp.getBattPercentage() >= 0) {
|
||||
powerStatus.batteryChargePercent = axp.getBattPercentage();
|
||||
} else {
|
||||
// If the AXP192 returns a percentage less than 0, the feature is either not supported or there is an error
|
||||
// In that case, we compute an estimate of the charge percent based on maximum and minimum voltages defined in power.h
|
||||
powerStatus.batteryChargePercent = clamp((int)(((powerStatus.batteryVoltageMv - BAT_MILLIVOLTS_EMPTY) * 1e2) /
|
||||
(BAT_MILLIVOLTS_FULL - BAT_MILLIVOLTS_EMPTY)),
|
||||
0, 100);
|
||||
}
|
||||
DEBUG_MSG("Battery %dmV %d%%\n", powerStatus.batteryVoltageMv, powerStatus.batteryChargePercent);
|
||||
}
|
||||
powerStatus.usb = axp.isVBUSPlug();
|
||||
powerStatus.charging = axp.isChargeing();
|
||||
}
|
||||
#endif // TBEAM_V10
|
||||
|
||||
#ifdef AXP192_SLAVE_ADDRESS
|
||||
/**
|
||||
* Init the power manager chip
|
||||
*
|
||||
* axp192 power
|
||||
DCDC1 0.7-3.5V @ 1200mA max -> OLED // If you turn this off you'll lose comms to the axp192 because the OLED and the axp192
|
||||
share the same i2c bus, instead use ssd1306 sleep mode DCDC2 -> unused DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this on!) LDO1
|
||||
30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of days), can
|
||||
not be turned off LDO2 200mA -> LORA LDO3 200mA -> GPS
|
||||
*/
|
||||
void axp192Init()
|
||||
{
|
||||
if (axp192_found) {
|
||||
if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS)) {
|
||||
DEBUG_MSG("AXP192 Begin PASS\n");
|
||||
|
||||
// axp.setChgLEDMode(LED_BLINK_4HZ);
|
||||
DEBUG_MSG("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("LDO2: %s\n", axp.isLDO2Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("LDO3: %s\n", axp.isLDO3Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("----------------------------------------\n");
|
||||
|
||||
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); // LORA radio
|
||||
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // GPS main power
|
||||
axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
|
||||
axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
|
||||
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
|
||||
axp.setDCDC1Voltage(3300); // for the OLED power
|
||||
|
||||
DEBUG_MSG("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("LDO2: %s\n", axp.isLDO2Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("LDO3: %s\n", axp.isLDO3Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
|
||||
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
|
||||
|
||||
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_1320MA); // actual limit (in HW) on the tbeam is 450mA
|
||||
#if 0
|
||||
|
||||
// Not connected
|
||||
//val = 0xfc;
|
||||
//axp._writeByte(AXP202_VHTF_CHGSET, 1, &val); // Set temperature protection
|
||||
|
||||
//not used
|
||||
//val = 0x46;
|
||||
//axp._writeByte(AXP202_OFF_CTL, 1, &val); // enable bat detection
|
||||
#endif
|
||||
axp.debugCharging();
|
||||
|
||||
#ifdef PMU_IRQ
|
||||
pinMode(PMU_IRQ, INPUT);
|
||||
attachInterrupt(
|
||||
PMU_IRQ, [] { pmu_irq = true; }, FALLING);
|
||||
|
||||
axp.adc1Enable(AXP202_BATT_CUR_ADC1, 1);
|
||||
axp.enableIRQ(AXP202_BATT_REMOVED_IRQ | AXP202_BATT_CONNECT_IRQ | AXP202_CHARGING_FINISHED_IRQ | AXP202_CHARGING_IRQ |
|
||||
AXP202_VBUS_REMOVED_IRQ | AXP202_VBUS_CONNECT_IRQ | AXP202_PEK_SHORTPRESS_IRQ,
|
||||
1);
|
||||
|
||||
axp.clearIRQ();
|
||||
#endif
|
||||
readPowerStatus();
|
||||
} else {
|
||||
DEBUG_MSG("AXP192 Begin FAIL\n");
|
||||
}
|
||||
} else {
|
||||
DEBUG_MSG("AXP192 not found\n");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
static void printBLEinfo() {
|
||||
int dev_num = esp_ble_get_bond_device_num();
|
||||
|
@ -193,10 +85,6 @@ void esp32Setup()
|
|||
|
||||
// enableModemSleep();
|
||||
|
||||
#ifdef AXP192_SLAVE_ADDRESS
|
||||
axp192Init();
|
||||
#endif
|
||||
|
||||
// Since we are turning on watchdogs rather late in the release schedule, we really don't want to catch any
|
||||
// false positives. The wait-to-sleep timeout for shutting down radios is 30 secs, so pick 45 for now.
|
||||
#define APP_WATCHDOG_SECS 45
|
||||
|
@ -236,43 +124,4 @@ void esp32Loop()
|
|||
|
||||
// for debug printing
|
||||
// radio.radioIf.canSleep();
|
||||
|
||||
#ifdef PMU_IRQ
|
||||
if (pmu_irq) {
|
||||
pmu_irq = false;
|
||||
axp.readIRQ();
|
||||
|
||||
DEBUG_MSG("pmu irq!\n");
|
||||
|
||||
if (axp.isChargingIRQ()) {
|
||||
DEBUG_MSG("Battery start charging\n");
|
||||
}
|
||||
if (axp.isChargingDoneIRQ()) {
|
||||
DEBUG_MSG("Battery fully charged\n");
|
||||
}
|
||||
if (axp.isVbusRemoveIRQ()) {
|
||||
DEBUG_MSG("USB unplugged\n");
|
||||
}
|
||||
if (axp.isVbusPlugInIRQ()) {
|
||||
DEBUG_MSG("USB plugged In\n");
|
||||
}
|
||||
if (axp.isBattPlugInIRQ()) {
|
||||
DEBUG_MSG("Battery inserted\n");
|
||||
}
|
||||
if (axp.isBattRemoveIRQ()) {
|
||||
DEBUG_MSG("Battery removed\n");
|
||||
}
|
||||
if (axp.isPEKShortPressIRQ()) {
|
||||
DEBUG_MSG("PEK short button press\n");
|
||||
}
|
||||
|
||||
readPowerStatus();
|
||||
axp.clearIRQ();
|
||||
}
|
||||
|
||||
if (powerStatus.haveBattery && !powerStatus.usb &&
|
||||
axp.getBattVoltage() < MIN_BAT_MILLIVOLTS) // If we have a battery at all and it is less than 10% full, force deep sleep
|
||||
powerFSM.trigger(EVENT_LOW_BATTERY);
|
||||
|
||||
#endif // T_BEAM_V10
|
||||
}
|
|
@ -1,6 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "Observer.h"
|
||||
#include "GPSStatus.h"
|
||||
#include "PeriodicTask.h"
|
||||
#include "sys/time.h"
|
||||
|
||||
|
@ -40,6 +41,8 @@ class GPS : public Observable<void *>
|
|||
|
||||
virtual ~GPS() {}
|
||||
|
||||
Observable<const meshtastic::GPSStatus *> newStatus;
|
||||
|
||||
/**
|
||||
* Returns true if we succeeded
|
||||
*/
|
||||
|
|
|
@ -65,5 +65,9 @@ void NEMAGPS::loop()
|
|||
if (hasValidLocation)
|
||||
notifyObservers(NULL);
|
||||
}
|
||||
|
||||
// Notify any status instances that are observing us
|
||||
const meshtastic::GPSStatus status = meshtastic::GPSStatus(hasLock(), isConnected, latitude, longitude, altitude, dop);
|
||||
newStatus.notifyObservers(&status);
|
||||
}
|
||||
}
|
|
@ -116,7 +116,6 @@ The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of s
|
|||
longitude = ublox.getLongitude(0);
|
||||
altitude = ublox.getAltitude(0) / 1000; // in mm convert to meters
|
||||
dop = ublox.getPDOP(0); // PDOP (an accuracy metric) is reported in 10^2 units so we have to scale down when we use it
|
||||
DEBUG_MSG("new gps pos lat=%f, lon=%f, alt=%d, pdop=%f\n", latitude * 1e-7, longitude * 1e-7, altitude, dop * 1e-2);
|
||||
|
||||
// bogus lat lon is reported as 0 or 0 (can be bogus just for one)
|
||||
// Also: apparently when the GPS is initially reporting lock it can output a bogus latitude > 90 deg!
|
||||
|
@ -129,6 +128,10 @@ The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of s
|
|||
} else // we didn't get a location update, go back to sleep and hope the characters show up
|
||||
wantNewLocation = true;
|
||||
|
||||
// Notify any status instances that are observing us
|
||||
const meshtastic::GPSStatus status = meshtastic::GPSStatus(hasLock(), isConnected, latitude, longitude, altitude, dop);
|
||||
newStatus.notifyObservers(&status);
|
||||
|
||||
// Once we have sent a location once we only poll the GPS rarely, otherwise check back every 1s until we have something over
|
||||
// the serial
|
||||
setPeriod(hasValidLocation && !wantNewLocation ? 30 * 1000 : 10 * 1000);
|
||||
|
|
24
src/main.cpp
24
src/main.cpp
|
@ -56,8 +56,14 @@
|
|||
// We always create a screen object, but we only init it if we find the hardware
|
||||
meshtastic::Screen screen(SSD1306_ADDRESS);
|
||||
|
||||
// Global power status singleton
|
||||
meshtastic::PowerStatus powerStatus;
|
||||
// Global power status
|
||||
meshtastic::PowerStatus *powerStatus = new meshtastic::PowerStatus();
|
||||
|
||||
// Global GPS status
|
||||
meshtastic::GPSStatus *gpsStatus = new meshtastic::GPSStatus();
|
||||
|
||||
// Global Node status
|
||||
meshtastic::NodeStatus *nodeStatus = new meshtastic::NodeStatus();
|
||||
|
||||
bool ssd1306_found;
|
||||
bool axp192_found;
|
||||
|
@ -121,7 +127,7 @@ static uint32_t ledBlinker()
|
|||
setLed(ledOn);
|
||||
|
||||
// have a very sparse duty cycle of LED being on, unless charging, then blink 0.5Hz square wave rate to indicate that
|
||||
return powerStatus.charging ? 1000 : (ledOn ? 2 : 1000);
|
||||
return powerStatus->getIsCharging() ? 1000 : (ledOn ? 2 : 1000);
|
||||
}
|
||||
|
||||
Periodic ledPeriodic(ledBlinker);
|
||||
|
@ -223,6 +229,10 @@ void setup()
|
|||
ssd1306_found = false; // forget we even have the hardware
|
||||
|
||||
esp32Setup();
|
||||
power = new Power();
|
||||
power->setup();
|
||||
power->setStatusHandler(powerStatus);
|
||||
powerStatus->observe(&power->newStatus);
|
||||
#endif
|
||||
|
||||
#ifdef NRF52_SERIES
|
||||
|
@ -253,9 +263,10 @@ void setup()
|
|||
gps = new NEMAGPS();
|
||||
gps->setup();
|
||||
#endif
|
||||
gpsStatus->observe(&gps->newStatus);
|
||||
nodeStatus->observe(&nodeDB.newStatus);
|
||||
|
||||
service.init();
|
||||
|
||||
#ifndef NO_ESP32
|
||||
// Must be after we init the service, because the wifi settings are loaded by NodeDB (oops)
|
||||
initWifi();
|
||||
|
@ -295,6 +306,7 @@ void setup()
|
|||
// This must be _after_ service.init because we need our preferences loaded from flash to have proper timeout values
|
||||
PowerFSM_setup(); // we will transition to ON in a couple of seconds, FIXME, only do this for cold boots, not waking from SDS
|
||||
|
||||
|
||||
// setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state
|
||||
setCPUFast(false); // 80MHz is fine for our slow peripherals
|
||||
}
|
||||
|
@ -340,6 +352,7 @@ void loop()
|
|||
|
||||
#ifndef NO_ESP32
|
||||
esp32Loop();
|
||||
power->loop();
|
||||
#endif
|
||||
|
||||
#ifdef BUTTON_PIN
|
||||
|
@ -365,9 +378,8 @@ void loop()
|
|||
#endif
|
||||
|
||||
// Update the screen last, after we've figured out what to show.
|
||||
screen.debug()->setNodeNumbersStatus(nodeDB.getNumOnlineNodes(), nodeDB.getNumNodes());
|
||||
screen.debug()->setChannelNameStatus(channelSettings.name);
|
||||
screen.debug()->setPowerStatus(powerStatus);
|
||||
//screen.debug()->setPowerStatus(powerStatus);
|
||||
|
||||
// No GPS lock yet, let the OS put the main CPU in low power mode for 100ms (or until another interrupt comes in)
|
||||
// i.e. don't just keep spinning in loop as fast as we can.
|
||||
|
|
|
@ -1,6 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "screen.h"
|
||||
#include "PowerStatus.h"
|
||||
#include "GPSStatus.h"
|
||||
#include "NodeStatus.h"
|
||||
|
||||
extern bool axp192_found;
|
||||
extern bool ssd1306_found;
|
||||
|
@ -9,6 +12,11 @@ extern bool isUSBPowered;
|
|||
|
||||
// Global Screen singleton.
|
||||
extern meshtastic::Screen screen;
|
||||
//extern Observable<meshtastic::PowerStatus> newPowerStatus; //TODO: move this to main-esp32.cpp somehow or a helper class
|
||||
|
||||
//extern meshtastic::PowerStatus *powerStatus;
|
||||
//extern meshtastic::GPSStatus *gpsStatus;
|
||||
//extern meshtastic::NodeStatusHandler *nodeStatusHandler;
|
||||
|
||||
// Return a human readable string of the form "Meshtastic_ab13"
|
||||
const char *getDeviceName();
|
||||
|
|
|
@ -303,7 +303,7 @@ int MeshService::onGPSChanged(void *unused)
|
|||
}
|
||||
|
||||
// Include our current battery voltage in our position announcement
|
||||
pos.battery_level = powerStatus.batteryChargePercent;
|
||||
pos.battery_level = powerStatus->getBatteryChargePercent();
|
||||
updateBatteryLevel(pos.battery_level);
|
||||
|
||||
// We limit our GPS broadcasts to a max rate
|
||||
|
|
|
@ -342,8 +342,7 @@ void NodeDB::updateFrom(const MeshPacket &mp)
|
|||
int oldNumNodes = *numNodes;
|
||||
NodeInfo *info = getOrCreateNode(mp.from);
|
||||
|
||||
if (oldNumNodes != *numNodes)
|
||||
updateGUI = true; // we just created a nodeinfo
|
||||
notifyObservers();
|
||||
|
||||
if (mp.rx_time) { // if the packet has a valid timestamp use it to update our last_seen
|
||||
info->has_position = true; // at least the time is valid
|
||||
|
|
|
@ -2,9 +2,11 @@
|
|||
|
||||
#include <Arduino.h>
|
||||
#include <assert.h>
|
||||
#include "Observer.h"
|
||||
|
||||
#include "MeshTypes.h"
|
||||
#include "mesh-pb-constants.h"
|
||||
#include "NodeStatus.h"
|
||||
|
||||
extern DeviceState devicestate;
|
||||
extern MyNodeInfo &myNodeInfo;
|
||||
|
@ -32,6 +34,7 @@ class NodeDB
|
|||
bool updateGUI = false; // we think the gui should definitely be redrawn, screen will clear this once handled
|
||||
NodeInfo *updateGUIforNode = NULL; // if currently showing this node, we think you should update the GUI
|
||||
bool updateTextMessage = false; // if true, the GUI should show a new text message
|
||||
Observable<const meshtastic::NodeStatus *> newStatus;
|
||||
|
||||
/// don't do mesh based algoritm for node id assignment (initially)
|
||||
/// instead just store in flash - possibly even in the initial alpha release do this hack
|
||||
|
@ -91,6 +94,13 @@ class NodeDB
|
|||
/// Find a node in our DB, create an empty NodeInfo if missing
|
||||
NodeInfo *getOrCreateNode(NodeNum n);
|
||||
|
||||
/// Notify observers of changes to the DB
|
||||
void notifyObservers() {
|
||||
// Notify observers of the current node state
|
||||
const meshtastic::NodeStatus status = meshtastic::NodeStatus(getNumOnlineNodes(), getNumNodes());
|
||||
newStatus.notifyObservers(&status);
|
||||
}
|
||||
|
||||
/// read our db from flash
|
||||
void loadFromDisk();
|
||||
|
||||
|
|
37
src/power.h
37
src/power.h
|
@ -1,4 +1,6 @@
|
|||
#pragma once
|
||||
#include "PeriodicTask.h"
|
||||
#include "PowerStatus.h"
|
||||
|
||||
/**
|
||||
* Per @spattinson
|
||||
|
@ -13,23 +15,26 @@
|
|||
#define BAT_MILLIVOLTS_FULL 4100
|
||||
#define BAT_MILLIVOLTS_EMPTY 3500
|
||||
|
||||
namespace meshtastic
|
||||
class Power : public PeriodicTask
|
||||
{
|
||||
|
||||
/// Describes the state of the power system.
|
||||
struct PowerStatus {
|
||||
/// Whether we have a battery connected
|
||||
bool haveBattery;
|
||||
/// Battery voltage in mV, valid if haveBattery is true
|
||||
int batteryVoltageMv;
|
||||
/// Battery charge percentage, either read directly or estimated
|
||||
int batteryChargePercent;
|
||||
/// Whether USB is connected
|
||||
bool usb;
|
||||
/// Whether we are charging the battery
|
||||
bool charging;
|
||||
public:
|
||||
|
||||
Observable<const meshtastic::PowerStatus *> newStatus;
|
||||
|
||||
void readPowerStatus();
|
||||
void loop();
|
||||
virtual bool setup();
|
||||
virtual void doTask();
|
||||
void setStatusHandler(meshtastic::PowerStatus *handler)
|
||||
{
|
||||
statusHandler = handler;
|
||||
}
|
||||
|
||||
protected:
|
||||
meshtastic::PowerStatus *statusHandler;
|
||||
virtual void axp192Init();
|
||||
|
||||
};
|
||||
|
||||
} // namespace meshtastic
|
||||
|
||||
extern meshtastic::PowerStatus powerStatus;
|
||||
extern Power *power;
|
140
src/screen.cpp
140
src/screen.cpp
|
@ -42,7 +42,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|||
#endif
|
||||
#define SCREEN_HEIGHT 64
|
||||
#define TRANSITION_FRAMERATE 30 // fps
|
||||
#define IDLE_FRAMERATE 10 // in fps
|
||||
#define IDLE_FRAMERATE 1 // in fps
|
||||
#define COMPASS_DIAM 44
|
||||
|
||||
#define NUM_EXTRA_FRAMES 2 // text message and debug frame
|
||||
|
@ -55,7 +55,8 @@ static FrameCallback normalFrames[MAX_NUM_NODES + NUM_EXTRA_FRAMES];
|
|||
static uint32_t targetFramerate = IDLE_FRAMERATE;
|
||||
static char btPIN[16] = "888888";
|
||||
|
||||
uint8_t imgBattery[16] = {0xFF, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0xE7, 0x3C};
|
||||
uint8_t imgBattery[16] = { 0xFF, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0x81, 0xE7, 0x3C };
|
||||
static bool heartbeat = false;
|
||||
|
||||
static void drawBootScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
|
||||
{
|
||||
|
@ -143,52 +144,54 @@ static void drawColumns(OLEDDisplay *display, int16_t x, int16_t y, const char *
|
|||
}
|
||||
}
|
||||
|
||||
/// Draw a series of fields in a row, wrapping to multiple rows if needed
|
||||
/// @return the max y we ended up printing to
|
||||
static uint32_t drawRows(OLEDDisplay *display, int16_t x, int16_t y, const char **fields)
|
||||
{
|
||||
// The coordinates define the left starting point of the text
|
||||
display->setTextAlignment(TEXT_ALIGN_LEFT);
|
||||
#if 0
|
||||
/// Draw a series of fields in a row, wrapping to multiple rows if needed
|
||||
/// @return the max y we ended up printing to
|
||||
static uint32_t drawRows(OLEDDisplay *display, int16_t x, int16_t y, const char **fields)
|
||||
{
|
||||
// The coordinates define the left starting point of the text
|
||||
display->setTextAlignment(TEXT_ALIGN_LEFT);
|
||||
|
||||
const char **f = fields;
|
||||
int xo = x, yo = y;
|
||||
const int COLUMNS = 2; // hardwired for two columns per row....
|
||||
int col = 0; // track which column we are on
|
||||
while (*f) {
|
||||
display->drawString(xo, yo, *f);
|
||||
xo += SCREEN_WIDTH / COLUMNS;
|
||||
// Wrap to next row, if needed.
|
||||
if (++col >= COLUMNS) {
|
||||
xo = x;
|
||||
yo += FONT_HEIGHT;
|
||||
col = 0;
|
||||
const char **f = fields;
|
||||
int xo = x, yo = y;
|
||||
const int COLUMNS = 2; // hardwired for two columns per row....
|
||||
int col = 0; // track which column we are on
|
||||
while (*f) {
|
||||
display->drawString(xo, yo, *f);
|
||||
xo += SCREEN_WIDTH / COLUMNS;
|
||||
// Wrap to next row, if needed.
|
||||
if (++col >= COLUMNS) {
|
||||
xo = x;
|
||||
yo += FONT_HEIGHT;
|
||||
col = 0;
|
||||
}
|
||||
f++;
|
||||
}
|
||||
if (col != 0) {
|
||||
// Include last incomplete line in our total.
|
||||
yo += FONT_HEIGHT;
|
||||
}
|
||||
f++;
|
||||
}
|
||||
if (col != 0) {
|
||||
// Include last incomplete line in our total.
|
||||
yo += FONT_HEIGHT;
|
||||
}
|
||||
|
||||
return yo;
|
||||
}
|
||||
return yo;
|
||||
}
|
||||
#endif
|
||||
|
||||
// Draw power bars or a charging indicator on an image of a battery, determined by battery charge voltage or percentage.
|
||||
static void drawBattery(OLEDDisplay *display, int16_t x, int16_t y, uint8_t *imgBuffer, PowerStatus *powerStatus)
|
||||
static void drawBattery(OLEDDisplay *display, int16_t x, int16_t y, uint8_t *imgBuffer, const PowerStatus *powerStatus)
|
||||
{
|
||||
static const uint8_t powerBar[3] = {0x81, 0xBD, 0xBD};
|
||||
static const uint8_t lightning[8] = {0xA1, 0xA1, 0xA5, 0xAD, 0xB5, 0xA5, 0x85, 0x85};
|
||||
static const uint8_t powerBar[3] = { 0x81, 0xBD, 0xBD };
|
||||
static const uint8_t lightning[8] = { 0xA1, 0xA1, 0xA5, 0xAD, 0xB5, 0xA5, 0x85, 0x85 };
|
||||
// Clear the bar area on the battery image
|
||||
for (int i = 1; i < 14; i++) {
|
||||
imgBuffer[i] = 0x81;
|
||||
}
|
||||
// If charging, draw a charging indicator
|
||||
if (powerStatus->charging) {
|
||||
if (powerStatus->getIsCharging()) {
|
||||
memcpy(imgBuffer + 3, lightning, 8);
|
||||
// If not charging, Draw power bars
|
||||
} else {
|
||||
for (int i = 0; i < 4; i++) {
|
||||
if (powerStatus->batteryChargePercent >= 25 * i)
|
||||
if(powerStatus->getBatteryChargePercent() >= 25 * i)
|
||||
memcpy(imgBuffer + 1 + (i * 3), powerBar, 3);
|
||||
}
|
||||
}
|
||||
|
@ -196,47 +199,47 @@ static void drawBattery(OLEDDisplay *display, int16_t x, int16_t y, uint8_t *img
|
|||
}
|
||||
|
||||
// Draw nodes status
|
||||
static void drawNodes(OLEDDisplay *display, int16_t x, int16_t y, int nodesOnline, int nodesTotal)
|
||||
static void drawNodes(OLEDDisplay *display, int16_t x, int16_t y, NodeStatus *nodeStatus)
|
||||
{
|
||||
char usersString[20];
|
||||
sprintf(usersString, "%d/%d", nodesOnline, nodesTotal);
|
||||
sprintf(usersString, "%d/%d", nodeStatus->getNumOnline(), nodeStatus->getNumTotal());
|
||||
display->drawFastImage(x, y, 8, 8, imgUser);
|
||||
display->drawString(x + 10, y - 2, usersString);
|
||||
}
|
||||
|
||||
// Draw GPS status summary
|
||||
static void drawGPS(OLEDDisplay *display, int16_t x, int16_t y, GPS *gps)
|
||||
static void drawGPS(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus *gps)
|
||||
{
|
||||
if (!gps->isConnected) {
|
||||
if (!gps->getIsConnected()) {
|
||||
display->drawString(x, y - 2, "No GPS");
|
||||
return;
|
||||
}
|
||||
display->drawFastImage(x, y, 6, 8, gps->hasLock() ? imgPositionSolid : imgPositionEmpty);
|
||||
if (!gps->hasLock()) {
|
||||
display->drawFastImage(x, y, 6, 8, gps->getHasLock() ? imgPositionSolid : imgPositionEmpty);
|
||||
if (!gps->getHasLock()) {
|
||||
display->drawString(x + 8, y - 2, "No sats");
|
||||
return;
|
||||
}
|
||||
if (gps->dop <= 100) {
|
||||
if (gps->getDOP() <= 100) {
|
||||
display->drawString(x + 8, y - 2, "Ideal");
|
||||
return;
|
||||
}
|
||||
if (gps->dop <= 200) {
|
||||
if (gps->getDOP() <= 200) {
|
||||
display->drawString(x + 8, y - 2, "Exc.");
|
||||
return;
|
||||
}
|
||||
if (gps->dop <= 500) {
|
||||
if (gps->getDOP() <= 500) {
|
||||
display->drawString(x + 8, y - 2, "Good");
|
||||
return;
|
||||
}
|
||||
if (gps->dop <= 1000) {
|
||||
if (gps->getDOP() <= 1000) {
|
||||
display->drawString(x + 8, y - 2, "Mod.");
|
||||
return;
|
||||
}
|
||||
if (gps->dop <= 2000) {
|
||||
if (gps->getDOP() <= 2000) {
|
||||
display->drawString(x + 8, y - 2, "Fair");
|
||||
return;
|
||||
}
|
||||
if (gps->dop > 0) {
|
||||
if (gps->getDOP() > 0) {
|
||||
display->drawString(x + 8, y - 2, "Poor");
|
||||
return;
|
||||
}
|
||||
|
@ -576,6 +579,11 @@ void Screen::setup()
|
|||
// twice initially.
|
||||
ui.update();
|
||||
ui.update();
|
||||
|
||||
// Subscribe to status updates
|
||||
powerStatusObserver.observe(&powerStatus->onNewStatus);
|
||||
gpsStatusObserver.observe(&gpsStatus->onNewStatus);
|
||||
nodeStatusObserver.observe(&nodeStatus->onNewStatus);
|
||||
}
|
||||
|
||||
void Screen::doTask()
|
||||
|
@ -637,14 +645,7 @@ void Screen::doTask()
|
|||
// While showing the bootscreen or Bluetooth pair screen all of our
|
||||
// standard screen switching is stopped.
|
||||
if (showingNormalScreen) {
|
||||
// TODO(girts): decouple nodeDB from screen.
|
||||
// standard screen loop handling ehre
|
||||
// If the # nodes changes, we need to regen our list of screens
|
||||
if (nodeDB.updateGUI || nodeDB.updateTextMessage) {
|
||||
setFrames();
|
||||
nodeDB.updateGUI = false;
|
||||
nodeDB.updateTextMessage = false;
|
||||
}
|
||||
// standard screen loop handling here
|
||||
}
|
||||
|
||||
ui.update();
|
||||
|
@ -669,8 +670,8 @@ void Screen::setFrames()
|
|||
DEBUG_MSG("showing standard frames\n");
|
||||
showingNormalScreen = true;
|
||||
|
||||
size_t numnodes = nodeDB.getNumNodes();
|
||||
// We don't show the node info our our node (if we have it yet - we should)
|
||||
size_t numnodes = nodeStatus->getNumTotal();
|
||||
if (numnodes > 0)
|
||||
numnodes--;
|
||||
|
||||
|
@ -750,20 +751,24 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
|
|||
snprintf(channelStr, sizeof(channelStr), "#%s", channelName.c_str());
|
||||
|
||||
// Display power status
|
||||
if (powerStatus.haveBattery)
|
||||
drawBattery(display, x, y + 2, imgBattery, &powerStatus);
|
||||
if (powerStatus->getHasBattery())
|
||||
drawBattery(display, x, y + 2, imgBattery, powerStatus);
|
||||
else
|
||||
display->drawFastImage(x, y + 2, 16, 8, powerStatus.usb ? imgUSB : imgPower);
|
||||
display->drawFastImage(x, y + 2, 16, 8, powerStatus->getHasUSB() ? imgUSB : imgPower);
|
||||
// Display nodes status
|
||||
drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 2, nodesOnline, nodesTotal);
|
||||
drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 2, nodeStatus);
|
||||
// Display GPS status
|
||||
drawGPS(display, x + (SCREEN_WIDTH * 0.66), y + 2, gps);
|
||||
drawGPS(display, x + (SCREEN_WIDTH * 0.66), y + 2, gpsStatus);
|
||||
}
|
||||
|
||||
const char *fields[] = {channelStr, nullptr};
|
||||
uint32_t yo = drawRows(display, x, y + FONT_HEIGHT, fields);
|
||||
display->drawString(x, y + FONT_HEIGHT, channelStr);
|
||||
|
||||
display->drawLogBuffer(x, yo);
|
||||
display->drawLogBuffer(x, y + (FONT_HEIGHT * 2));
|
||||
|
||||
/* Display a heartbeat pixel that blinks every time the frame is redrawn
|
||||
if(heartbeat) display->setPixel(0, 0);
|
||||
heartbeat = !heartbeat;
|
||||
*/
|
||||
}
|
||||
|
||||
// adjust Brightness cycle trough 1 to 254 as long as attachDuringLongPress is true
|
||||
|
@ -781,4 +786,15 @@ void Screen::adjustBrightness()
|
|||
dispdev.setBrightness(brightness);
|
||||
}
|
||||
|
||||
int Screen::handleStatusUpdate(const Status *arg) {
|
||||
DEBUG_MSG("Screen got status update %d\n", arg->getStatusType());
|
||||
switch(arg->getStatusType())
|
||||
{
|
||||
case STATUS_TYPE_NODE:
|
||||
setFrames();
|
||||
break;
|
||||
}
|
||||
setPeriod(1); // Update the screen right away
|
||||
return 0;
|
||||
}
|
||||
} // namespace meshtastic
|
||||
|
|
45
src/screen.h
45
src/screen.h
|
@ -13,7 +13,10 @@
|
|||
#include "PeriodicTask.h"
|
||||
#include "TypedQueue.h"
|
||||
#include "lock.h"
|
||||
#include "power.h"
|
||||
#include "PowerStatus.h"
|
||||
#include "GPSStatus.h"
|
||||
#include "NodeStatus.h"
|
||||
#include "Observer.h"
|
||||
#include <string>
|
||||
|
||||
namespace meshtastic
|
||||
|
@ -29,14 +32,6 @@ class DebugInfo
|
|||
DebugInfo(const DebugInfo &) = delete;
|
||||
DebugInfo &operator=(const DebugInfo &) = delete;
|
||||
|
||||
/// Sets user statistics.
|
||||
void setNodeNumbersStatus(int online, int total)
|
||||
{
|
||||
LockGuard guard(&lock);
|
||||
nodesOnline = online;
|
||||
nodesTotal = total;
|
||||
}
|
||||
|
||||
/// Sets the name of the channel.
|
||||
void setChannelNameStatus(const char *name)
|
||||
{
|
||||
|
@ -44,25 +39,6 @@ class DebugInfo
|
|||
channelName = name;
|
||||
}
|
||||
|
||||
/// Sets battery/charging/etc status.
|
||||
//
|
||||
void setPowerStatus(const PowerStatus &status)
|
||||
{
|
||||
LockGuard guard(&lock);
|
||||
powerStatus = status;
|
||||
}
|
||||
|
||||
/// Sets GPS status.
|
||||
//
|
||||
// If this function never gets called, we assume GPS does not exist on this
|
||||
// device.
|
||||
// TODO(girts): figure out what the format should be.
|
||||
void setGPSStatus(const char *status)
|
||||
{
|
||||
LockGuard guard(&lock);
|
||||
gpsStatus = status;
|
||||
}
|
||||
|
||||
private:
|
||||
friend Screen;
|
||||
|
||||
|
@ -71,15 +47,8 @@ class DebugInfo
|
|||
/// Renders the debug screen.
|
||||
void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
|
||||
|
||||
int nodesOnline = 0;
|
||||
int nodesTotal = 0;
|
||||
|
||||
PowerStatus powerStatus;
|
||||
|
||||
std::string channelName;
|
||||
|
||||
std::string gpsStatus;
|
||||
|
||||
/// Protects all of internal state.
|
||||
Lock lock;
|
||||
};
|
||||
|
@ -93,6 +62,10 @@ class DebugInfo
|
|||
// simultaneously).
|
||||
class Screen : public PeriodicTask
|
||||
{
|
||||
CallbackObserver<Screen, const Status *> powerStatusObserver = CallbackObserver<Screen, const Status *>(this, &Screen::handleStatusUpdate);
|
||||
CallbackObserver<Screen, const Status *> gpsStatusObserver = CallbackObserver<Screen, const Status *>(this, &Screen::handleStatusUpdate);
|
||||
CallbackObserver<Screen, const Status *> nodeStatusObserver = CallbackObserver<Screen, const Status *>(this, &Screen::handleStatusUpdate);
|
||||
|
||||
public:
|
||||
Screen(uint8_t address, int sda = -1, int scl = -1);
|
||||
|
||||
|
@ -189,6 +162,8 @@ class Screen : public PeriodicTask
|
|||
// Use this handle to set things like battery status, user count, GPS status, etc.
|
||||
DebugInfo *debug() { return &debugInfo; }
|
||||
|
||||
int handleStatusUpdate(const meshtastic::Status *arg);
|
||||
|
||||
protected:
|
||||
/// Updates the UI.
|
||||
//
|
||||
|
|
Ładowanie…
Reference in New Issue