Refactored status handlers and merged

1.2-legacy
Professr 2020-06-28 18:17:52 -07:00
commit f5b7c33d4e
20 zmienionych plików z 426 dodań i 268 usunięć

Wyświetl plik

@ -48,7 +48,6 @@ Items after the first final candidate release.
- split out the software update utility so other projects can use it. Have the appload specify the URL for downloads.
- read the PMU battery fault indicators and blink/led/warn user on screen
- discard very old nodedb records (> 1wk)
- add a watchdog timer
- handle millis() rollover in GPS.getTime - otherwise we will break after 50 days
- report esp32 device code bugs back to the mothership via android
- change BLE bonding to something more secure. see comment by pSecurity->setAuthenticationMode(ESP_LE_AUTH_BOND)

Wyświetl plik

@ -1,79 +1,108 @@
#pragma once
#include <Arduino.h>
#include "lock.h"
#include "Status.h"
#include "configuration.h"
namespace meshtastic {
/// Describes the state of the GPS system.
struct GPSStatus
{
bool isDirty = false;
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)
};
class GPSStatusHandler
{
private:
GPSStatus status;
CallbackObserver<GPSStatusHandler, const GPSStatus> gpsObserver = CallbackObserver<GPSStatusHandler, const GPSStatus>(this, &GPSStatusHandler::updateStatus);
bool initialized = false;
/// Protects all of internal state.
Lock lock;
public:
Observable<void *> onNewStatus;
void observe(Observable<const GPSStatus> *source)
/// Describes the state of the GPS system.
class GPSStatus : public Status
{
gpsObserver.observe(source);
}
bool isInitialized() { LockGuard guard(&lock); return initialized; }
bool hasLock() { LockGuard guard(&lock); return status.hasLock; }
bool isConnected() { LockGuard guard(&lock); return status.isConnected; }
int32_t getLatitude() { LockGuard guard(&lock); return status.latitude; }
int32_t getLongitude() { LockGuard guard(&lock); return status.longitude; }
int32_t getAltitude() { LockGuard guard(&lock); return status.altitude; }
uint32_t getDOP() { LockGuard guard(&lock); return status.dop; }
private:
CallbackObserver<GPSStatus, const GPSStatus *> statusObserver = CallbackObserver<GPSStatus, const GPSStatus *>(this, &GPSStatus::updateStatus);
int updateStatus(const GPSStatus newStatus) {
// Only update the status if values have actually changed
status.isDirty = (
newStatus.hasLock != status.hasLock ||
newStatus.isConnected != status.isConnected ||
newStatus.latitude != status.latitude ||
newStatus.longitude != status.longitude ||
newStatus.altitude != status.altitude ||
newStatus.dop != status.latitude
);
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()
{
LockGuard guard(&lock);
initialized = true;
status.hasLock = newStatus.hasLock;
status.isConnected = newStatus.isConnected;
status.latitude = newStatus.latitude;
status.longitude = newStatus.longitude;
status.altitude = newStatus.altitude;
status.dop = newStatus.dop;
this->hasLock = hasLock;
this->isConnected = isConnected;
this->latitude = latitude;
this->longitude = longitude;
this->altitude = altitude;
this->dop = dop;
}
if(status.isDirty) {
DEBUG_MSG("New GPS pos lat=%f, lon=%f, alt=%d, pdop=%f\n", status.latitude * 1e-7, status.longitude * 1e-7, status.altitude, status.dop * 1e-2);
onNewStatus.notifyObservers(NULL);
}
return 0;
}
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;
extern meshtastic::GPSStatus *gpsStatus;

Wyświetl plik

@ -1,62 +1,73 @@
#pragma once
#include <Arduino.h>
#include "lock.h"
#include "Status.h"
#include "configuration.h"
namespace meshtastic {
/// Describes the state of the GPS system.
struct NodeStatus
{
bool isDirty = false;
size_t numOnline; // Number of nodes online
size_t numTotal; // Number of nodes total
};
class NodeStatusHandler
{
private:
NodeStatus status;
CallbackObserver<NodeStatusHandler, const NodeStatus> nodeObserver = CallbackObserver<NodeStatusHandler, const NodeStatus>(this, &NodeStatusHandler::updateStatus);
bool initialized = false;
/// Protects all of internal state.
Lock lock;
public:
Observable<void *> onNewStatus;
void observe(Observable<const NodeStatus> *source)
/// Describes the state of the NodeDB system.
class NodeStatus : public Status
{
nodeObserver.observe(source);
}
bool isInitialized() const { return initialized; }
size_t getNumOnline() const { return status.numOnline; }
size_t getNumTotal() const { return status.numTotal; }
private:
CallbackObserver<NodeStatus, const NodeStatus *> statusObserver = CallbackObserver<NodeStatus, const NodeStatus *>(this, &NodeStatus::updateStatus);
int updateStatus(const NodeStatus newStatus)
{
// Only update the status if values have actually changed
status.isDirty = (
newStatus.numOnline != status.numOnline ||
newStatus.numTotal != status.numTotal
);
LockGuard guard(&lock);
initialized = true;
status.numOnline = newStatus.numOnline;
status.numTotal = newStatus.numTotal;
if(status.isDirty) {
DEBUG_MSG("Node status update: %d online, %d total\n", status.numOnline, status.numTotal);
onNewStatus.notifyObservers(NULL);
uint8_t numOnline = 0;
uint8_t numTotal = 0;
public:
NodeStatus() {
statusType = STATUS_TYPE_NODE;
}
return 0;
}
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;
extern meshtastic::NodeStatus *nodeStatus;

Wyświetl plik

@ -30,25 +30,27 @@ bool Power::setup()
// TODO(girts): move this and other axp stuff to power.h/power.cpp.
void Power::readPowerStatus()
{
meshtastic::PowerStatus status;
status.hasBattery = axp.isBatteryConnect();
if (status.hasBattery) {
status.batteryVoltageMv = axp.getBattVoltage();
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) {
status.batteryChargePercent = axp.getBattPercentage();
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
status.batteryChargePercent = clamp((int)(((status.batteryVoltageMv - BAT_MILLIVOLTS_EMPTY) * 1e2) / (BAT_MILLIVOLTS_FULL - BAT_MILLIVOLTS_EMPTY)), 0, 100);
batteryChargePercent = clamp((int)(((batteryVoltageMv - BAT_MILLIVOLTS_EMPTY) * 1e2) / (BAT_MILLIVOLTS_FULL - BAT_MILLIVOLTS_EMPTY)), 0, 100);
}
}
status.hasUSB = axp.isVBUSPlug();
status.isCharging = axp.isChargeing();
newStatus.notifyObservers(status);
// 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 (status.hasBattery && !status.hasUSB &&
if (powerStatus.getHasBattery() && !powerStatus.getHasUSB() &&
axp.getBattVoltage() < MIN_BAT_MILLIVOLTS)
powerFSM.trigger(EVENT_LOW_BATTERY);
}

Wyświetl plik

@ -1,77 +1,103 @@
#pragma once
#include "lock.h"
#include <Arduino.h>
#include "Status.h"
#include "configuration.h"
namespace meshtastic
{
namespace meshtastic {
/// Describes the state of the power system.
struct PowerStatus
{
/// Whether or not values have changed since last read
bool isDirty = false;
/// 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
int batteryChargePercent;
/// Whether USB is connected
bool hasUSB;
/// Whether we are charging the battery
bool isCharging;
};
class PowerStatusHandler
{
private:
PowerStatus status;
CallbackObserver<PowerStatusHandler, const PowerStatus> powerObserver = CallbackObserver<PowerStatusHandler, const PowerStatus>(this, &PowerStatusHandler::updateStatus);
bool initialized = false;
/// Protects all of internal state.
Lock lock;
public:
Observable<void *> onNewStatus;
void observe(Observable<const PowerStatus> *source)
/// Describes the state of the GPS system.
class PowerStatus : public Status
{
powerObserver.observe(source);
}
bool isInitialized() { LockGuard guard(&lock); return initialized; }
bool isCharging() { LockGuard guard(&lock); return status.isCharging; }
bool hasUSB() { LockGuard guard(&lock); return status.hasUSB; }
bool hasBattery() { LockGuard guard(&lock); return status.hasBattery; }
int getBatteryVoltageMv() { LockGuard guard(&lock); return status.batteryVoltageMv; }
int getBatteryChargePercent() { LockGuard guard(&lock); return status.batteryChargePercent; }
private:
CallbackObserver<PowerStatus, const PowerStatus *> statusObserver = CallbackObserver<PowerStatus, const PowerStatus *>(this, &PowerStatus::updateStatus);
int updateStatus(const PowerStatus newStatus) {
// Only update the status if values have actually changed
status.isDirty = (
newStatus.hasBattery != status.hasBattery ||
newStatus.hasUSB != status.hasUSB ||
newStatus.batteryVoltageMv != status.batteryVoltageMv
);
LockGuard guard(&lock);
initialized = true;
status.hasBattery = newStatus.hasBattery;
status.batteryVoltageMv = newStatus.batteryVoltageMv;
status.batteryChargePercent = newStatus.batteryChargePercent;
status.hasUSB = newStatus.hasUSB;
status.isCharging = newStatus.isCharging;
if(status.isDirty) {
DEBUG_MSG("Battery %dmV %d%%\n", status.batteryVoltageMv, status.batteryChargePercent);
onNewStatus.notifyObservers(this);
/// 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;
}
return 0;
}
};
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 &);
} // namespace meshtastic
void observe(Observable<const PowerStatus *> *source)
{
statusObserver.observe(source);
}
extern meshtastic::PowerStatus powerStatus;
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;

72
src/Status.h 100644
Wyświetl plik

@ -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;
}
};
};

Wyświetl plik

Wyświetl plik

@ -17,8 +17,15 @@ void Thread::callRun(void *_this)
void WorkerThread::doRun()
{
startWatchdog();
while (!wantExit) {
stopWatchdog();
block();
startWatchdog();
// no need - startWatchdog is guaranteed to give us one full watchdog interval
// serviceWatchdog(); // Let our loop worker have one full watchdog interval (at least) to run
#ifdef DEBUG_STACK
static uint32_t lastPrint = 0;
@ -30,6 +37,8 @@ void WorkerThread::doRun()
loop();
}
stopWatchdog();
}
/**

Wyświetl plik

@ -1,5 +1,6 @@
#include <Arduino.h>
#include "esp_task_wdt.h"
#include "freertosinc.h"
#include <Arduino.h>
#ifdef HAS_FREE_RTOS
@ -26,6 +27,23 @@ class Thread
*/
virtual void doRun() = 0;
/**
* All thread run methods must periodically call serviceWatchdog, or the system will declare them hung and panic.
*
* this only applies after startWatchdog() has been called. If you need to sleep for a long time call stopWatchdog()
*/
void serviceWatchdog() { esp_task_wdt_reset(); }
void startWatchdog()
{
auto r = esp_task_wdt_add(taskHandle);
assert(r == ESP_OK);
}
void stopWatchdog()
{
auto r = esp_task_wdt_delete(taskHandle);
assert(r == ESP_OK);
}
private:
static void callRun(void *_this);
};

Wyświetl plik

@ -2,10 +2,11 @@
#include "MeshBluetoothService.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "esp_task_wdt.h"
#include "main.h"
#include "sleep.h"
#include "utils.h"
#include "target_specific.h"
#include "utils.h"
bool bluetoothOn;
@ -84,6 +85,15 @@ void esp32Setup()
// enableModemSleep();
// 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
auto res = esp_task_wdt_init(APP_WATCHDOG_SECS, true);
assert(res == ESP_OK);
res = esp_task_wdt_add(NULL);
assert(res == ESP_OK);
}
#if 0
@ -106,10 +116,10 @@ uint32_t axpDebugRead()
Periodic axpDebugOutput(axpDebugRead);
#endif
/// loop code specific to ESP32 targets
void esp32Loop()
{
esp_task_wdt_reset(); // service our app level watchdog
loopBLE();
// for debug printing

Wyświetl plik

@ -41,7 +41,7 @@ class GPS : public Observable<void *>
virtual ~GPS() {}
Observable<const meshtastic::GPSStatus> newStatus;
Observable<const meshtastic::GPSStatus *> newStatus;
/**
* Returns true if we succeeded

Wyświetl plik

@ -65,13 +65,9 @@ void NEMAGPS::loop()
if (hasValidLocation)
notifyObservers(NULL);
}
meshtastic::GPSStatus status;
status.hasLock = hasLock();
status.isConnected = isConnected;
status.latitude = latitude;
status.longitude = longitude;
status.altitude = altitude;
status.dop = dop;
newStatus.notifyObservers(status);
// Notify any status instances that are observing us
const meshtastic::GPSStatus status = meshtastic::GPSStatus(hasLock(), isConnected, latitude, longitude, altitude, dop);
newStatus.notifyObservers(&status);
}
}

Wyświetl plik

@ -128,14 +128,9 @@ 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;
meshtastic::GPSStatus status;
status.hasLock = hasLock();
status.isConnected = isConnected;
status.latitude = latitude;
status.longitude = longitude;
status.altitude = altitude;
status.dop = dop;
newStatus.notifyObservers(status);
// 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

Wyświetl plik

@ -57,13 +57,13 @@
meshtastic::Screen screen(SSD1306_ADDRESS);
// Global power status
meshtastic::PowerStatusHandler *powerStatusHandler = new meshtastic::PowerStatusHandler();
meshtastic::PowerStatus *powerStatus = new meshtastic::PowerStatus();
// Global GPS status
meshtastic::GPSStatusHandler *gpsStatusHandler = new meshtastic::GPSStatusHandler();
meshtastic::GPSStatus *gpsStatus = new meshtastic::GPSStatus();
// Global Node status
meshtastic::NodeStatusHandler *nodeStatusHandler = new meshtastic::NodeStatusHandler();
meshtastic::NodeStatus *nodeStatus = new meshtastic::NodeStatus();
bool ssd1306_found;
bool axp192_found;
@ -127,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 powerStatusHandler->isCharging() ? 1000 : (ledOn ? 2 : 1000);
return powerStatus->getIsCharging() ? 1000 : (ledOn ? 2 : 1000);
}
Periodic ledPeriodic(ledBlinker);
@ -231,8 +231,8 @@ void setup()
esp32Setup();
power = new Power();
power->setup();
power->setStatusHandler(powerStatusHandler);
powerStatusHandler->observe(&power->newStatus);
power->setStatusHandler(powerStatus);
powerStatus->observe(&power->newStatus);
#endif
#ifdef NRF52_SERIES
@ -263,8 +263,8 @@ void setup()
gps = new NEMAGPS();
gps->setup();
#endif
gpsStatusHandler->observe(&gps->newStatus);
nodeStatusHandler->observe(&nodeDB.newStatus);
gpsStatus->observe(&gps->newStatus);
nodeStatus->observe(&nodeDB.newStatus);
service.init();
#ifndef NO_ESP32

Wyświetl plik

@ -12,11 +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 Observable<meshtastic::PowerStatus> newPowerStatus; //TODO: move this to main-esp32.cpp somehow or a helper class
extern meshtastic::PowerStatusHandler *powerStatusHandler;
extern meshtastic::GPSStatusHandler *gpsStatusHandler;
extern meshtastic::NodeStatusHandler *nodeStatusHandler;
//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();

Wyświetl plik

@ -303,7 +303,7 @@ int MeshService::onGPSChanged(void *unused)
}
// Include our current battery voltage in our position announcement
pos.battery_level = powerStatusHandler->getBatteryChargePercent();
pos.battery_level = powerStatus->getBatteryChargePercent();
updateBatteryLevel(pos.battery_level);
// We limit our GPS broadcasts to a max rate

Wyświetl plik

@ -34,7 +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;
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
@ -97,10 +97,8 @@ class NodeDB
/// Notify observers of changes to the DB
void notifyObservers() {
// Notify observers of the current node state
meshtastic::NodeStatus status;
status.numOnline = getNumOnlineNodes();
status.numTotal = getNumNodes();
newStatus.notifyObservers(status);
const meshtastic::NodeStatus status = meshtastic::NodeStatus(getNumOnlineNodes(), getNumNodes());
newStatus.notifyObservers(&status);
}
/// read our db from flash

Wyświetl plik

@ -20,19 +20,19 @@ class Power : public PeriodicTask
public:
Observable<const meshtastic::PowerStatus> newStatus;
Observable<const meshtastic::PowerStatus *> newStatus;
void readPowerStatus();
void loop();
virtual bool setup();
virtual void doTask();
void setStatusHandler(meshtastic::PowerStatusHandler *handler)
void setStatusHandler(meshtastic::PowerStatus *handler)
{
statusHandler = handler;
}
protected:
meshtastic::PowerStatusHandler *statusHandler;
meshtastic::PowerStatus *statusHandler;
virtual void axp192Init();
};

Wyświetl plik

@ -177,7 +177,7 @@ static void drawColumns(OLEDDisplay *display, int16_t x, int16_t y, const char *
#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, PowerStatusHandler *powerStatusHandler)
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 };
@ -186,12 +186,12 @@ static void drawBattery(OLEDDisplay *display, int16_t x, int16_t y, uint8_t *img
imgBuffer[i] = 0x81;
}
// If charging, draw a charging indicator
if (powerStatusHandler->isCharging()) {
if (powerStatus->getIsCharging()) {
memcpy(imgBuffer + 3, lightning, 8);
// If not charging, Draw power bars
} else {
for (int i = 0; i < 4; i++) {
if(powerStatusHandler->getBatteryChargePercent() >= 25 * i)
if(powerStatus->getBatteryChargePercent() >= 25 * i)
memcpy(imgBuffer + 1 + (i * 3), powerBar, 3);
}
}
@ -199,23 +199,23 @@ 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, NodeStatusHandler *nodeStatusHandler)
static void drawNodes(OLEDDisplay *display, int16_t x, int16_t y, NodeStatus *nodeStatus)
{
char usersString[20];
sprintf(usersString, "%d/%d", nodeStatusHandler->getNumOnline(), nodeStatusHandler->getNumTotal());
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, GPSStatusHandler *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;
}
@ -581,9 +581,9 @@ void Screen::setup()
ui.update();
// Subscribe to status updates
powerStatusObserver.observe(&powerStatusHandler->onNewStatus);
gpsStatusObserver.observe(&gpsStatusHandler->onNewStatus);
nodeStatusObserver.observe(&nodeStatusHandler->onNewStatus);
powerStatusObserver.observe(&powerStatus->onNewStatus);
gpsStatusObserver.observe(&gpsStatus->onNewStatus);
nodeStatusObserver.observe(&nodeStatus->onNewStatus);
}
void Screen::doTask()
@ -671,7 +671,7 @@ void Screen::setFrames()
showingNormalScreen = true;
// We don't show the node info our our node (if we have it yet - we should)
size_t numnodes = nodeStatusHandler->getNumTotal();
size_t numnodes = nodeStatus->getNumTotal();
if (numnodes > 0)
numnodes--;
@ -751,14 +751,14 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
snprintf(channelStr, sizeof(channelStr), "#%s", channelName.c_str());
// Display power status
if (powerStatusHandler->hasBattery())
drawBattery(display, x, y + 2, imgBattery, powerStatusHandler);
if (powerStatus->getHasBattery())
drawBattery(display, x, y + 2, imgBattery, powerStatus);
else
display->drawFastImage(x, y + 2, 16, 8, powerStatusHandler->hasUSB() ? 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, nodeStatusHandler);
drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 2, nodeStatus);
// Display GPS status
drawGPS(display, x + (SCREEN_WIDTH * 0.66), y + 2, gpsStatusHandler);
drawGPS(display, x + (SCREEN_WIDTH * 0.66), y + 2, gpsStatus);
}
display->drawString(x, y + FONT_HEIGHT, channelStr);
@ -784,19 +784,14 @@ void Screen::adjustBrightness()
dispdev.setBrightness(brightness);
}
int Screen::handlePowerStatusUpdate(void *arg) {
//DEBUG_MSG("Screen got power status update\n");
setPeriod(1); // Update the screen right away
return 0;
}
int Screen::handleGPSStatusUpdate(void *arg) {
//DEBUG_MSG("Screen got gps status update\n");
setPeriod(1); // Update the screen right away
return 0;
}
int Screen::handleNodeStatusUpdate(void *arg) {
//DEBUG_MSG("Screen got node status update\n");
setFrames(); // Update our frames if the node database has changed
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;
}

Wyświetl plik

@ -62,9 +62,9 @@ class DebugInfo
// simultaneously).
class Screen : public PeriodicTask
{
CallbackObserver<Screen, void *> powerStatusObserver = CallbackObserver<Screen, void *>(this, &Screen::handlePowerStatusUpdate);
CallbackObserver<Screen, void *> gpsStatusObserver = CallbackObserver<Screen, void *>(this, &Screen::handleGPSStatusUpdate);
CallbackObserver<Screen, void *> nodeStatusObserver = CallbackObserver<Screen, void *>(this, &Screen::handleNodeStatusUpdate);
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);
@ -162,9 +162,7 @@ class Screen : public PeriodicTask
// Use this handle to set things like battery status, user count, GPS status, etc.
DebugInfo *debug() { return &debugInfo; }
int handlePowerStatusUpdate(void *arg);
int handleGPSStatusUpdate(void *arg);
int handleNodeStatusUpdate(void *arg);
int handleStatusUpdate(const meshtastic::Status *arg);
protected:
/// Updates the UI.