Merge pull request #15 from meshtastic/master

updated my branch from head
This commit is contained in:
Jm Casler
2020-10-10 22:29:09 -07:00
committed by GitHub
62 changed files with 861 additions and 858 deletions

View File

@@ -1,3 +1,3 @@
export VERSION=1.1.2 export VERSION=1.1.3

View File

@@ -38,7 +38,7 @@ From lower to higher power consumption.
- full on (ON) - Everything is on, can eventually timeout and lower to a lower power state - full on (ON) - Everything is on, can eventually timeout and lower to a lower power state
onEntry: setBluetoothOn(true), screen.setOn(true) onEntry: setBluetoothOn(true), screen.setOn(true)
onExit: screen.setOn(false) onExit: screen->setOn(false)
- has power (POWER) - Screen is on, device doesn't sleep, bluetooth on, will stay in this state as long as we have power - has power (POWER) - Screen is on, device doesn't sleep, bluetooth on, will stay in this state as long as we have power
onEntry: setBluetooth off, screen on onEntry: setBluetooth off, screen on

View File

@@ -30,6 +30,7 @@ build_flags = -Wno-missing-field-initializers -Isrc -Isrc/mesh -Isrc/gps -Ilib/n
-DHW_VERSION_${sysenv.COUNTRY} -DHW_VERSION_${sysenv.COUNTRY}
-DAPP_VERSION=${sysenv.APP_VERSION} -DAPP_VERSION=${sysenv.APP_VERSION}
-DHW_VERSION=${sysenv.HW_VERSION} -DHW_VERSION=${sysenv.HW_VERSION}
-DUSE_THREAD_NAMES
; leave this commented out to avoid breaking Windows ; leave this commented out to avoid breaking Windows
;upload_port = /dev/ttyUSB0 ;upload_port = /dev/ttyUSB0
@@ -61,7 +62,7 @@ lib_deps =
https://github.com/meshtastic/esp8266-oled-ssd1306.git ; ESP8266_SSD1306 https://github.com/meshtastic/esp8266-oled-ssd1306.git ; ESP8266_SSD1306
1260 ; OneButton library for non-blocking button debounce 1260 ; OneButton library for non-blocking button debounce
1202 ; CRC32, explicitly needed because dependency is missing in the ble ota update lib 1202 ; CRC32, explicitly needed because dependency is missing in the ble ota update lib
https://github.com/meshtastic/arduino-fsm.git https://github.com/meshtastic/arduino-fsm.git#2f106146071fc7bc620e1e8d4b88dc4e0266ce39
https://github.com/meshtastic/SparkFun_Ublox_Arduino_Library.git#31015a55e630a2df77d9d714669c621a5bf355ad https://github.com/meshtastic/SparkFun_Ublox_Arduino_Library.git#31015a55e630a2df77d9d714669c621a5bf355ad
https://github.com/meshtastic/RadioLib.git#8657380241bce681c33aab46598bbf13b11f876c https://github.com/meshtastic/RadioLib.git#8657380241bce681c33aab46598bbf13b11f876c
https://github.com/meshtastic/TinyGPSPlus.git https://github.com/meshtastic/TinyGPSPlus.git
@@ -69,6 +70,7 @@ lib_deps =
https://github.com/meshtastic/esp32_https_server.git https://github.com/meshtastic/esp32_https_server.git
Wire ; explicitly needed here because the AXP202 library forgets to add it Wire ; explicitly needed here because the AXP202 library forgets to add it
SPI SPI
https://github.com/geeksville/ArduinoThread.git#333ffd09b596977c217ba25da4258f588b462ac6
; Common settings for conventional (non Portduino) Ardino targets ; Common settings for conventional (non Portduino) Ardino targets
[arduino_base] [arduino_base]

View File

@@ -62,6 +62,8 @@ class AnalogBatteryLevel : public HasBatteryLevel
virtual bool isBatteryConnect() { return getBattVoltage() != -1; } virtual bool isBatteryConnect() { return getBattVoltage() != -1; }
} analogLevel; } analogLevel;
Power::Power() : OSThread("Power") {}
bool Power::analogInit() bool Power::analogInit()
{ {
#ifdef BATTERY_PIN #ifdef BATTERY_PIN
@@ -86,10 +88,7 @@ bool Power::setup()
if (!found) { if (!found) {
found = analogInit(); found = analogInit();
} }
if (found) { enabled = found;
concurrency::PeriodicTask::setup(); // We don't start our periodic task unless we actually found the device
setPeriod(1);
}
return found; return found;
} }
@@ -135,13 +134,46 @@ void Power::readPowerStatus()
} }
} }
void Power::doTask() int32_t Power::runOnce()
{ {
readPowerStatus(); readPowerStatus();
#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");
powerFSM.trigger(EVENT_POWER_DISCONNECTED);
}
if (axp.isVbusPlugInIRQ()) {
DEBUG_MSG("USB plugged In\n");
powerFSM.trigger(EVENT_POWER_CONNECTED);
}
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");
}
axp.clearIRQ();
}
#endif
// Only read once every 20 seconds once the power status for the app has been initialized // Only read once every 20 seconds once the power status for the app has been initialized
if (statusHandler && statusHandler->isInitialized()) return (statusHandler && statusHandler->isInitialized()) ? (1000 * 20) : RUN_SAME;
setPeriod(1000 * 20);
} }
/** /**
@@ -208,8 +240,7 @@ bool Power::axp192Init()
// no battery also it could cause inadvertent waking from light sleep just because the battery filled // no battery also it could cause inadvertent waking from light sleep just because the battery filled
// we don't look for AXP202_BATT_REMOVED_IRQ because it occurs repeatedly while no battery installed // we don't look for AXP202_BATT_REMOVED_IRQ because it occurs repeatedly while no battery installed
// we don't look at AXP202_VBUS_REMOVED_IRQ because we don't have anything hooked to vbus // we don't look at AXP202_VBUS_REMOVED_IRQ because we don't have anything hooked to vbus
axp.enableIRQ(AXP202_BATT_CONNECT_IRQ | AXP202_VBUS_CONNECT_IRQ | AXP202_PEK_SHORTPRESS_IRQ, axp.enableIRQ(AXP202_BATT_CONNECT_IRQ | AXP202_VBUS_CONNECT_IRQ | AXP202_PEK_SHORTPRESS_IRQ, 1);
1);
axp.clearIRQ(); axp.clearIRQ();
#endif #endif
@@ -226,43 +257,3 @@ bool Power::axp192Init()
return false; return false;
#endif #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");
powerFSM.trigger(EVENT_POWER_DISCONNECTED);
}
if (axp.isVbusPlugInIRQ()) {
DEBUG_MSG("USB plugged In\n");
powerFSM.trigger(EVENT_POWER_CONNECTED);
}
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
}

View File

@@ -22,7 +22,7 @@ static uint32_t secsSlept;
static void lsEnter() static void lsEnter()
{ {
DEBUG_MSG("lsEnter begin, ls_secs=%u\n", getPref_ls_secs()); DEBUG_MSG("lsEnter begin, ls_secs=%u\n", getPref_ls_secs());
screen.setOn(false); screen->setOn(false);
secsSlept = 0; // How long have we been sleeping this time secsSlept = 0; // How long have we been sleeping this time
DEBUG_MSG("lsEnter end\n"); DEBUG_MSG("lsEnter end\n");
@@ -102,7 +102,7 @@ static void lsExit()
static void nbEnter() static void nbEnter()
{ {
screen.setOn(false); screen->setOn(false);
setBluetoothEnable(false); setBluetoothEnable(false);
// FIXME - check if we already have packets for phone and immediately trigger EVENT_PACKETS_FOR_PHONE // FIXME - check if we already have packets for phone and immediately trigger EVENT_PACKETS_FOR_PHONE
@@ -111,25 +111,25 @@ static void nbEnter()
static void darkEnter() static void darkEnter()
{ {
setBluetoothEnable(true); setBluetoothEnable(true);
screen.setOn(false); screen->setOn(false);
} }
static void serialEnter() static void serialEnter()
{ {
setBluetoothEnable(false); setBluetoothEnable(false);
screen.setOn(true); screen->setOn(true);
} }
static void powerEnter() static void powerEnter()
{ {
screen.setOn(true); screen->setOn(true);
setBluetoothEnable(true); setBluetoothEnable(true);
setCPUFast(true); // Set CPU to 240mhz when we're plugged in to wall power. setCPUFast(true); // Set CPU to 240mhz when we're plugged in to wall power.
} }
static void onEnter() static void onEnter()
{ {
screen.setOn(true); screen->setOn(true);
setBluetoothEnable(true); setBluetoothEnable(true);
static uint32_t lastPingMs; static uint32_t lastPingMs;
@@ -146,7 +146,7 @@ static void onEnter()
static void screenPress() static void screenPress()
{ {
screen.onPress(); screen->onPress();
} }
static void bootEnter() {} static void bootEnter() {}

View File

@@ -20,5 +20,6 @@
#define EVENT_POWER_DISCONNECTED 14 #define EVENT_POWER_DISCONNECTED 14
extern Fsm powerFSM; extern Fsm powerFSM;
extern State statePOWER;
void PowerFSM_setup(); void PowerFSM_setup();

View File

@@ -1,44 +0,0 @@
#pragma once
#include "WorkerThread.h"
namespace concurrency {
/**
* @brief A worker thread that waits on a freertos notification
*/
class BaseNotifiedWorkerThread : public WorkerThread
{
public:
/**
* Notify this thread so it can run
*/
virtual void notify(uint32_t v = 0, eNotifyAction action = eNoAction) = 0;
/**
* Notify from an ISR
*
* This must be inline or IRAM_ATTR on ESP32
*/
virtual void notifyFromISR(BaseType_t *highPriWoken, uint32_t v = 0, eNotifyAction action = eNoAction) { notify(v, action); }
protected:
/**
* The notification that was most recently used to wake the thread. Read from loop()
*/
uint32_t notification = 0;
/**
* What notification bits should be cleared just after we read and return them in notification?
*
* Defaults to clear all of them.
*/
uint32_t clearOnRead = UINT32_MAX;
/**
* A method that should block execution - either waiting ona queue/mutex or a "task notification"
*/
virtual void block() = 0;
};
} // namespace concurrency

View File

@@ -1,12 +0,0 @@
#include "Thread.h"
#include <assert.h>
namespace concurrency
{
void BaseThread::callRun(void *_this)
{
((BaseThread *)_this)->doRun();
}
} // namespace concurrency

View File

@@ -1,47 +0,0 @@
#pragma once
#include <cstdlib>
#include <stdint.h>
#include "freertosinc.h"
namespace concurrency
{
/**
* @brief Base threading
*/
class BaseThread
{
protected:
/**
* set this to true to ask thread to cleanly exit asap
*/
volatile bool wantExit = false;
public:
virtual void start(const char *name, size_t stackSize = 1024, uint32_t priority = tskIDLE_PRIORITY) = 0;
virtual ~BaseThread() {}
// uint32_t getStackHighwaterMark() { return uxTaskGetStackHighWaterMark(taskHandle); }
protected:
/**
* The method that will be called when start is called.
*/
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()
*/
virtual void serviceWatchdog() {}
virtual void startWatchdog() {}
virtual void stopWatchdog() {}
static void callRun(void *_this);
};
} // namespace concurrency

View File

@@ -0,0 +1,39 @@
#include "concurrency/BinarySemaphoreFreeRTOS.h"
#include "configuration.h"
#ifdef HAS_FREE_RTOS
namespace concurrency
{
BinarySemaphoreFreeRTOS::BinarySemaphoreFreeRTOS()
{
semaphore = xSemaphoreCreateBinary();
}
BinarySemaphoreFreeRTOS::~BinarySemaphoreFreeRTOS()
{
vSemaphoreDelete(semaphore);
}
/**
* Returns false if we were interrupted
*/
bool BinarySemaphoreFreeRTOS::take(uint32_t msec)
{
return xSemaphoreTake(semaphore, pdMS_TO_TICKS(msec));
}
void BinarySemaphoreFreeRTOS::give()
{
xSemaphoreGive(semaphore);
}
IRAM_ATTR void BinarySemaphoreFreeRTOS::giveFromISR(BaseType_t *pxHigherPriorityTaskWoken)
{
xSemaphoreGiveFromISR(semaphore, pxHigherPriorityTaskWoken);
}
} // namespace concurrency
#endif

View File

@@ -0,0 +1,31 @@
#pragma once
#include "configuration.h"
#include "../freertosinc.h"
namespace concurrency
{
#ifdef HAS_FREE_RTOS
class BinarySemaphoreFreeRTOS
{
SemaphoreHandle_t semaphore;
public:
BinarySemaphoreFreeRTOS();
~BinarySemaphoreFreeRTOS();
/**
* Returns false if we timed out
*/
bool take(uint32_t msec);
void give();
void giveFromISR(BaseType_t *pxHigherPriorityTaskWoken);
};
#endif
}

View File

@@ -0,0 +1,36 @@
#include "concurrency/BinarySemaphorePosix.h"
#include "configuration.h"
#ifndef HAS_FREE_RTOS
namespace concurrency
{
BinarySemaphorePosix::BinarySemaphorePosix()
{
}
BinarySemaphorePosix::~BinarySemaphorePosix()
{
}
/**
* Returns false if we timed out
*/
bool BinarySemaphorePosix::take(uint32_t msec)
{
delay(msec); // FIXME
return false;
}
void BinarySemaphorePosix::give()
{
}
IRAM_ATTR void BinarySemaphorePosix::giveFromISR(BaseType_t *pxHigherPriorityTaskWoken)
{
}
} // namespace concurrency
#endif

View File

@@ -0,0 +1,31 @@
#pragma once
#include "configuration.h"
#include "../freertosinc.h"
namespace concurrency
{
#ifndef HAS_FREE_RTOS
class BinarySemaphorePosix
{
// SemaphoreHandle_t semaphore;
public:
BinarySemaphorePosix();
~BinarySemaphorePosix();
/**
* Returns false if we timed out
*/
bool take(uint32_t msec);
void give();
void giveFromISR(BaseType_t *pxHigherPriorityTaskWoken);
};
#endif
}

View File

@@ -1,23 +0,0 @@
#include "NotifiedWorkerThread.h"
#ifdef HAS_FREE_RTOS
namespace concurrency {
/**
* Notify this thread so it can run
*/
void FreeRtosNotifiedWorkerThread::notify(uint32_t v, eNotifyAction action)
{
xTaskNotify(taskHandle, v, action);
}
void FreeRtosNotifiedWorkerThread::block()
{
xTaskNotifyWait(0, // don't clear notification on entry
clearOnRead, &notification, portMAX_DELAY); // Wait forever
}
} // namespace concurrency
#endif

View File

@@ -1,40 +0,0 @@
#pragma once
#include "BaseNotifiedWorkerThread.h"
#ifdef HAS_FREE_RTOS
namespace concurrency {
/**
* @brief A worker thread that waits on a freertos notification
*/
class FreeRtosNotifiedWorkerThread : public BaseNotifiedWorkerThread
{
public:
/**
* Notify this thread so it can run
*/
void notify(uint32_t v = 0, eNotifyAction action = eNoAction);
/**
* Notify from an ISR
*
* This must be inline or IRAM_ATTR on ESP32
*/
inline void notifyFromISR(BaseType_t *highPriWoken, uint32_t v = 0, eNotifyAction action = eNoAction)
{
xTaskNotifyFromISR(taskHandle, v, action, highPriWoken);
}
protected:
/**
* A method that should block execution - either waiting ona queue/mutex or a "task notification"
*/
virtual void block();
};
} // namespace concurrency
#endif

View File

@@ -1,45 +0,0 @@
#include "FreeRtosThread.h"
#ifdef HAS_FREE_RTOS
#include <assert.h>
#ifdef ARDUINO_ARCH_ESP32
#include "esp_task_wdt.h"
#endif
namespace concurrency
{
void FreeRtosThread::start(const char *name, size_t stackSize, uint32_t priority)
{
auto r = xTaskCreate(callRun, name, stackSize, this, priority, &taskHandle);
assert(r == pdPASS);
}
void FreeRtosThread::serviceWatchdog()
{
#ifdef ARDUINO_ARCH_ESP32
esp_task_wdt_reset();
#endif
}
void FreeRtosThread::startWatchdog()
{
#ifdef ARDUINO_ARCH_ESP32
auto r = esp_task_wdt_add(taskHandle);
assert(r == ESP_OK);
#endif
}
void FreeRtosThread::stopWatchdog()
{
#ifdef ARDUINO_ARCH_ESP32
auto r = esp_task_wdt_delete(taskHandle);
assert(r == ESP_OK);
#endif
}
} // namespace concurrency
#endif

View File

@@ -1,44 +0,0 @@
#pragma once
#include "BaseThread.h"
#include "freertosinc.h"
#ifdef HAS_FREE_RTOS
namespace concurrency
{
/**
* @brief Base threading
*/
class FreeRtosThread : public BaseThread
{
protected:
TaskHandle_t taskHandle = NULL;
public:
void start(const char *name, size_t stackSize = 1024, uint32_t priority = tskIDLE_PRIORITY);
virtual ~FreeRtosThread() { vTaskDelete(taskHandle); }
// uint32_t getStackHighwaterMark() { return uxTaskGetStackHighWaterMark(taskHandle); }
protected:
/**
* The method that will be called when start is called.
*/
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();
void startWatchdog();
void stopWatchdog();
};
} // namespace concurrency
#endif

View File

@@ -0,0 +1,43 @@
#include "concurrency/InterruptableDelay.h"
#include "configuration.h"
namespace concurrency
{
InterruptableDelay::InterruptableDelay()
{
}
InterruptableDelay::~InterruptableDelay()
{
}
/**
* Returns false if we were interrupted
*/
bool InterruptableDelay::delay(uint32_t msec)
{
if (msec) {
// DEBUG_MSG("delay %u ", msec);
// sem take will return false if we timed out (i.e. were not interrupted)
bool r = semaphore.take(msec);
// DEBUG_MSG("interrupt=%d\n", r);
return !r;
} else {
return true;
}
}
void InterruptableDelay::interrupt()
{
semaphore.give();
}
IRAM_ATTR void InterruptableDelay::interruptFromISR(BaseType_t *pxHigherPriorityTaskWoken)
{
semaphore.giveFromISR(pxHigherPriorityTaskWoken);
}
} // namespace concurrency

View File

@@ -0,0 +1,42 @@
#pragma once
#include "../freertosinc.h"
#ifdef HAS_FREE_RTOS
#include "concurrency/BinarySemaphoreFreeRTOS.h"
#define BinarySemaphore BinarySemaphoreFreeRTOS
#else
#include "concurrency/BinarySemaphorePosix.h"
#define BinarySemaphore BinarySemaphorePosix
#endif
namespace concurrency
{
/**
* An object that provides delay(msec) like functionality, but can be interrupted by calling interrupt().
*
* Useful for they top level loop() delay call to keep the CPU powered down until our next scheduled event or some external event.
*
* This is implmented for FreeRTOS but should be easy to port to other operating systems.
*/
class InterruptableDelay
{
BinarySemaphore semaphore;
public:
InterruptableDelay();
~InterruptableDelay();
/**
* Returns false if we were interrupted
*/
bool delay(uint32_t msec);
void interrupt();
void interruptFromISR(BaseType_t *pxHigherPriorityTaskWoken);
};
} // namespace concurrency

View File

@@ -0,0 +1,85 @@
#include "NotifiedWorkerThread.h"
#include "configuration.h"
#include <assert.h>
namespace concurrency
{
static bool debugNotification;
/**
* Notify this thread so it can run
*/
bool NotifiedWorkerThread::notify(uint32_t v, bool overwrite)
{
bool r = notifyCommon(v, overwrite);
if (r)
mainDelay.interrupt();
return r;
}
/**
* Notify this thread so it can run
*/
IRAM_ATTR bool NotifiedWorkerThread::notifyCommon(uint32_t v, bool overwrite)
{
if (overwrite || notification == 0) {
enabled = true;
setInterval(0); // Run ASAP
notification = v;
if (debugNotification)
DEBUG_MSG("setting notification %d\n", v);
return true;
} else {
if (debugNotification)
DEBUG_MSG("dropping notification %d\n", v);
return false;
}
}
/**
* Notify from an ISR
*
* This must be inline or IRAM_ATTR on ESP32
*/
IRAM_ATTR bool NotifiedWorkerThread::notifyFromISR(BaseType_t *highPriWoken, uint32_t v, bool overwrite)
{
bool r = notifyCommon(v, overwrite);
if (r)
mainDelay.interruptFromISR(highPriWoken);
return r;
}
/**
* Schedule a notification to fire in delay msecs
*/
bool NotifiedWorkerThread::notifyLater(uint32_t delay, uint32_t v, bool overwrite)
{
bool didIt = notify(v, overwrite);
if (didIt) { // If we didn't already have something queued, override the delay to be larger
setIntervalFromNow(delay); // a new version of setInterval relative to the current time
if (debugNotification)
DEBUG_MSG("delaying notification %u\n", delay);
}
return didIt;
}
int32_t NotifiedWorkerThread::runOnce()
{
auto n = notification;
enabled = false; // Only run once per notification
notification = 0; // clear notification
if (n) {
onNotify(n);
}
return RUN_SAME;
}
} // namespace concurrency

View File

@@ -1,17 +1,50 @@
#pragma once #pragma once
#include "FreeRtosNotifiedWorkerThread.h" #include "OSThread.h"
#include "PosixNotifiedWorkerThread.h"
namespace concurrency namespace concurrency
{ {
#ifdef HAS_FREE_RTOS /**
typedef FreeRtosNotifiedWorkerThread NotifiedWorkerThread; * @brief A worker thread that waits on a freertos notification
#endif */
class NotifiedWorkerThread : public OSThread
{
/**
* The notification that was most recently used to wake the thread. Read from runOnce()
*/
uint32_t notification = 0;
#ifdef __unix__ public:
typedef PosixNotifiedWorkerThread NotifiedWorkerThread; NotifiedWorkerThread(const char *name) : OSThread(name) {}
#endif
/**
* Notify this thread so it can run
*/
bool notify(uint32_t v, bool overwrite);
/**
* Notify from an ISR
*
* This must be inline or IRAM_ATTR on ESP32
*/
bool notifyFromISR(BaseType_t *highPriWoken, uint32_t v, bool overwrite);
/**
* Schedule a notification to fire in delay msecs
*/
bool notifyLater(uint32_t delay, uint32_t v, bool overwrite);
protected:
virtual void onNotify(uint32_t notification) = 0;
virtual int32_t runOnce();
private:
/**
* Notify this thread so it can run
*/
bool notifyCommon(uint32_t v, bool overwrite);
};
} // namespace concurrency } // namespace concurrency

View File

@@ -0,0 +1,79 @@
#include "OSThread.h"
#include "configuration.h"
#include <assert.h>
namespace concurrency
{
/// Show debugging info for disabled threads
bool OSThread::showDisabled;
/// Show debugging info for threads when we run them
bool OSThread::showRun = false;
/// Show debugging info for threads we decide not to run;
bool OSThread::showWaiting = false;
ThreadController mainController, timerController;
InterruptableDelay mainDelay;
void OSThread::setup()
{
mainController.ThreadName = "mainController";
timerController.ThreadName = "timerController";
}
OSThread::OSThread(const char *_name, uint32_t period, ThreadController *_controller)
: Thread(NULL, period), controller(_controller)
{
ThreadName = _name;
if (controller)
controller->add(this);
}
OSThread::~OSThread()
{
if (controller)
controller->remove(this);
}
/**
* Wait a specified number msecs starting from the current time (rather than the last time we were run)
*/
void OSThread::setIntervalFromNow(unsigned long _interval)
{
// Save interval
interval = _interval;
// Cache the next run based on the last_run
_cached_next_run = millis() + interval;
}
bool OSThread::shouldRun(unsigned long time)
{
bool r = Thread::shouldRun(time);
if (showRun && r)
DEBUG_MSG("Thread %s: run\n", ThreadName.c_str());
if (showWaiting && enabled && !r)
DEBUG_MSG("Thread %s: wait %lu\n", ThreadName.c_str(), interval);
if (showDisabled && !enabled)
DEBUG_MSG("Thread %s: disabled\n", ThreadName.c_str());
return r;
}
void OSThread::run()
{
auto newDelay = runOnce();
runned();
if (newDelay >= 0)
setInterval(newDelay);
}
} // namespace concurrency

View File

@@ -0,0 +1,70 @@
#pragma once
#include <cstdlib>
#include <stdint.h>
#include "Thread.h"
#include "ThreadController.h"
#include "concurrency/InterruptableDelay.h"
namespace concurrency
{
extern ThreadController mainController, timerController;
extern InterruptableDelay mainDelay;
#define RUN_SAME -1
/**
* @brief Base threading
*
* This is a pseudo threading layer that is super easy to port, well suited to our slow network and very ram & power efficient.
*
* TODO FIXME @geeksville
*
* move more things into OSThreads
* remove lock/lockguard
*
* move typedQueue into concurrency
* remove freertos from typedqueue
*/
class OSThread : public Thread
{
ThreadController *controller;
/// Show debugging info for disabled threads
static bool showDisabled;
/// Show debugging info for threads when we run them
static bool showRun;
/// Show debugging info for threads we decide not to run;
static bool showWaiting;
public:
OSThread(const char *name, uint32_t period = 0, ThreadController *controller = &mainController);
virtual ~OSThread();
virtual bool shouldRun(unsigned long time);
static void setup();
/**
* Wait a specified number msecs starting from the current time (rather than the last time we were run)
*/
void setIntervalFromNow(unsigned long _interval);
protected:
/**
* The method that will be called each time our thread gets a chance to run
*
* Returns desired period for next invocation (or RUN_SAME for no change)
*/
virtual int32_t runOnce() = 0;
// Do not override this
virtual void run();
};
} // namespace concurrency

View File

@@ -1,26 +1,24 @@
#pragma once #pragma once
#include "PeriodicTask.h" #include "concurrency/OSThread.h"
namespace concurrency { namespace concurrency
{
/** /**
* @brief Periodically invoke a callback. This just provides C-style callback conventions * @brief Periodically invoke a callback. This just provides C-style callback conventions
* rather than a virtual function - FIXME, remove? * rather than a virtual function - FIXME, remove?
*/ */
class Periodic : public PeriodicTask class Periodic : public OSThread
{ {
uint32_t (*callback)(); int32_t (*callback)();
public: public:
// callback returns the period for the next callback invocation (or 0 if we should no longer be called) // callback returns the period for the next callback invocation (or 0 if we should no longer be called)
Periodic(uint32_t (*_callback)()) : callback(_callback) {} Periodic(const char *name, int32_t (*_callback)()) : OSThread(name), callback(_callback) {}
protected: protected:
void doTask() { int32_t runOnce() { return callback(); }
uint32_t p = callback();
setPeriod(p);
}
}; };
} // namespace concurrency } // namespace concurrency

View File

@@ -1,34 +0,0 @@
#include "PeriodicScheduler.h"
#include "PeriodicTask.h"
#include "LockGuard.h"
namespace concurrency {
/// call this from loop
void PeriodicScheduler::loop()
{
LockGuard lg(&lock);
uint32_t now = millis();
for (auto t : tasks) {
if (t->period && (now - t->lastMsec) >= t->period) {
t->doTask();
t->lastMsec = now;
}
}
}
void PeriodicScheduler::schedule(PeriodicTask *t)
{
LockGuard lg(&lock);
tasks.insert(t);
}
void PeriodicScheduler::unschedule(PeriodicTask *t)
{
LockGuard lg(&lock);
tasks.erase(t);
}
} // namespace concurrency

View File

@@ -1,40 +0,0 @@
#pragma once
#include "Lock.h"
#include <cstdint>
#include <unordered_set>
namespace concurrency {
class PeriodicTask;
/**
* @brief Runs all PeriodicTasks in the system. Currently called from main loop()
* but eventually should be its own thread blocked on a freertos timer.
*/
class PeriodicScheduler
{
friend class PeriodicTask;
/**
* This really should be some form of heap, and when the period gets changed on a task it should get
* rescheduled in that heap. Currently it is just a dumb array and everytime we run loop() we check
* _every_ tasks. If it was a heap we'd only have to check the first task.
*/
std::unordered_set<PeriodicTask *> tasks;
// Protects the above variables.
Lock lock;
public:
/// Run any next tasks which are due for execution
void loop();
private:
void schedule(PeriodicTask *t);
void unschedule(PeriodicTask *t);
};
extern PeriodicScheduler periodicScheduler;
} // namespace concurrency

View File

@@ -1,16 +0,0 @@
#include "PeriodicTask.h"
#include "Periodic.h"
#include "LockGuard.h"
namespace concurrency {
PeriodicScheduler periodicScheduler;
PeriodicTask::PeriodicTask(uint32_t initialPeriod) : period(initialPeriod) {}
void PeriodicTask::setup()
{
periodicScheduler.schedule(this);
}
} // namespace concurrency

View File

@@ -1,56 +0,0 @@
#pragma once
#include <Arduino.h>
#include "PeriodicScheduler.h"
namespace concurrency {
/**
* @brief A base class for tasks that want their doTask() method invoked periodically
*
* @todo currently just syntatic sugar for polling in loop (you must call .loop), but eventually
* generalize with the freertos scheduler so we can save lots of power by having everything either in
* something like this or triggered off of an irq.
*/
class PeriodicTask
{
friend class PeriodicScheduler;
uint32_t lastMsec = 0;
uint32_t period = 1; // call soon after creation
public:
virtual ~PeriodicTask() { periodicScheduler.unschedule(this); }
/**
* Constructor (will schedule with the global PeriodicScheduler)
*/
PeriodicTask(uint32_t initialPeriod = 1);
/**
* MUST be be called once at startup (but after threading is running - i.e. not from a constructor)
*/
void setup();
/**
* Set a new period in msecs (can be called from doTask or elsewhere and the scheduler will cope)
* While zero this task is disabled and will not run
*/
void setPeriod(uint32_t p)
{
lastMsec = millis(); // reset starting from now
period = p;
}
uint32_t getPeriod() const { return period; }
/**
* Syntatic sugar for suspending tasks
*/
void disable() { setPeriod(0); }
protected:
virtual void doTask() = 0;
};
} // namespace concurrency

View File

@@ -1,19 +0,0 @@
#include "PosixNotifiedWorkerThread.h"
#ifdef __unix__
#include <Utility.h>
using namespace concurrency;
/**
* Notify this thread so it can run
*/
void PosixNotifiedWorkerThread::notify(uint32_t v, eNotifyAction action) NOT_IMPLEMENTED("notify");
/**
* A method that should block execution - either waiting ona queue/mutex or a "task notification"
*/
void PosixNotifiedWorkerThread::block() NOT_IMPLEMENTED("block");
#endif

View File

@@ -1,26 +0,0 @@
#pragma once
#include "BaseNotifiedWorkerThread.h"
namespace concurrency {
/**
* @brief A worker thread that waits on a freertos notification
*/
class PosixNotifiedWorkerThread : public BaseNotifiedWorkerThread
{
public:
/**
* Notify this thread so it can run
*/
void notify(uint32_t v = 0, eNotifyAction action = eNoAction);
protected:
/**
* A method that should block execution - either waiting ona queue/mutex or a "task notification"
*/
virtual void block();
};
} // namespace concurrency

View File

@@ -1,33 +0,0 @@
#pragma once
#include "BaseThread.h"
#ifdef __unix__
namespace concurrency
{
/**
* @brief Base threading
*/
class PosixThread : public BaseThread
{
protected:
public:
void start(const char *name, size_t stackSize = 1024, uint32_t priority = tskIDLE_PRIORITY) {}
virtual ~PosixThread() {}
// uint32_t getStackHighwaterMark() { return uxTaskGetStackHighWaterMark(taskHandle); }
protected:
/**
* The method that will be called when start is called.
*/
virtual void doRun() = 0;
};
} // namespace concurrency
#endif

View File

@@ -1,17 +0,0 @@
#pragma once
#include "FreeRtosThread.h"
#include "PosixThread.h"
namespace concurrency
{
#ifdef HAS_FREE_RTOS
typedef FreeRtosThread Thread;
#endif
#ifdef __unix__
typedef PosixThread Thread;
#endif
} // namespace concurrency

View File

@@ -1,31 +0,0 @@
#include "WorkerThread.h"
namespace concurrency {
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;
if (millis() - lastPrint > 10 * 1000L) {
lastPrint = millis();
meshtastic::printThreadInfo("net");
}
#endif
loop();
}
stopWatchdog();
}
} // namespace concurrency

View File

@@ -1,29 +0,0 @@
#pragma once
#include "Thread.h"
namespace concurrency {
/**
* @brief This wraps threading (FreeRTOS for now) with a blocking API intended for efficiently converting
* old-school arduino loop() code. Use as a mixin base class for the classes you want to convert.
*
* @link https://www.freertos.org/RTOS_Task_Notification_As_Mailbox.html
*/
class WorkerThread : public Thread
{
protected:
/**
* A method that should block execution - either waiting ona queue/mutex or a "task notification"
*/
virtual void block() = 0;
virtual void loop() = 0;
/**
* The method that will be called when start is called.
*/
virtual void doRun();
};
} // namespace concurrency

View File

@@ -40,7 +40,7 @@ void WiFiServerAPI::loop()
#define MESHTASTIC_PORTNUM 4403 #define MESHTASTIC_PORTNUM 4403
WiFiServerPort::WiFiServerPort() : WiFiServer(MESHTASTIC_PORTNUM) {} WiFiServerPort::WiFiServerPort() : WiFiServer(MESHTASTIC_PORTNUM), concurrency::OSThread("ApiServer") {}
void WiFiServerPort::init() void WiFiServerPort::init()
{ {
@@ -48,7 +48,7 @@ void WiFiServerPort::init()
begin(); begin();
} }
void WiFiServerPort::loop() int32_t WiFiServerPort::runOnce()
{ {
auto client = available(); auto client = available();
if (client) { if (client) {
@@ -59,7 +59,10 @@ void WiFiServerPort::loop()
openAPI = new WiFiServerAPI(client); openAPI = new WiFiServerAPI(client);
} }
if (openAPI) if (openAPI) {
// Allow idle processing so the API can read from its incoming stream // Allow idle processing so the API can read from its incoming stream
openAPI->loop(); openAPI->loop();
return 0; // run fast while our API server is running
} else
return 100; // only check occasionally for incoming connections
} }

View File

@@ -1,6 +1,7 @@
#pragma once #pragma once
#include "StreamAPI.h" #include "StreamAPI.h"
#include "concurrency/OSThread.h"
#include <WiFi.h> #include <WiFi.h>
/** /**
@@ -27,7 +28,7 @@ class WiFiServerAPI : public StreamAPI
/** /**
* Listens for incoming connections and does accepts and creates instances of WiFiServerAPI as needed * Listens for incoming connections and does accepts and creates instances of WiFiServerAPI as needed
*/ */
class WiFiServerPort : public WiFiServer class WiFiServerPort : public WiFiServer, private concurrency::OSThread
{ {
/** The currently open port /** The currently open port
* *
@@ -41,5 +42,5 @@ class WiFiServerPort : public WiFiServer
void init(); void init();
void loop(); int32_t runOnce();
}; };

View File

@@ -36,6 +36,23 @@ bool GPS::setup()
return ok; return ok;
} }
/// Record that we have a GPS
void GPS::setConnected()
{
if (!hasGPS) {
hasGPS = true;
shouldPublish = true;
}
}
void GPS::setNumSatellites(uint8_t n)
{
if (n != numSatellites) {
numSatellites = n;
shouldPublish = true;
}
}
/** /**
* Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode * Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode
* *
@@ -114,19 +131,23 @@ uint32_t GPS::getSleepTime() const
void GPS::publishUpdate() void GPS::publishUpdate()
{ {
DEBUG_MSG("publishing GPS lock=%d\n", hasLock()); if (shouldPublish) {
shouldPublish = false;
// Notify any status instances that are observing us DEBUG_MSG("publishing GPS lock=%d\n", hasLock());
const meshtastic::GPSStatus status =
meshtastic::GPSStatus(hasLock(), isConnected, latitude, longitude, altitude, dop, heading, numSatellites); // Notify any status instances that are observing us
newStatus.notifyObservers(&status); const meshtastic::GPSStatus status =
meshtastic::GPSStatus(hasLock(), isConnected(), latitude, longitude, altitude, dop, heading, numSatellites);
newStatus.notifyObservers(&status);
}
} }
void GPS::loop() int32_t GPS::runOnce()
{ {
if (whileIdle()) { if (whileIdle()) {
// if we have received valid NMEA claim we are connected // if we have received valid NMEA claim we are connected
isConnected = true; setConnected();
} }
// If we are overdue for an update, turn on the GPS and at least publish the current status // If we are overdue for an update, turn on the GPS and at least publish the current status
@@ -147,8 +168,17 @@ void GPS::loop()
} }
// If we've already set time from the GPS, no need to ask the GPS // If we've already set time from the GPS, no need to ask the GPS
bool gotTime = (getRTCQuality() >= RTCQualityGPS) || lookForTime(); bool gotTime = (getRTCQuality() >= RTCQualityGPS);
if (!gotTime && lookForTime()) { // Note: we count on this && short-circuiting and not resetting the RTC time
gotTime = true;
shouldPublish = true;
}
bool gotLoc = lookForLocation(); bool gotLoc = lookForLocation();
if (gotLoc && !hasValidLocation) { // declare that we have location ASAP
hasValidLocation = true;
shouldPublish = true;
}
// We've been awake too long - force sleep // We've been awake too long - force sleep
auto wakeTime = getWakeTime(); auto wakeTime = getWakeTime();
@@ -158,8 +188,6 @@ void GPS::loop()
// or if we got a time and we are in GpsOpTimeOnly mode // or if we got a time and we are in GpsOpTimeOnly mode
// DEBUG_MSG("gotLoc %d, tooLong %d, gotTime %d\n", gotLoc, tooLong, gotTime); // DEBUG_MSG("gotLoc %d, tooLong %d, gotTime %d\n", gotLoc, tooLong, gotTime);
if ((gotLoc && gotTime) || tooLong || (gotTime && getGpsOp() == GpsOperation_GpsOpTimeOnly)) { if ((gotLoc && gotTime) || tooLong || (gotTime && getGpsOp() == GpsOperation_GpsOpTimeOnly)) {
if (gotLoc)
hasValidLocation = true;
if (tooLong) { if (tooLong) {
// we didn't get a location during this ack window, therefore declare loss of lock // we didn't get a location during this ack window, therefore declare loss of lock
@@ -167,9 +195,16 @@ void GPS::loop()
} }
setAwake(false); setAwake(false);
publishUpdate(); // publish our update for this just finished acquisition window shouldPublish = true; // publish our update for this just finished acquisition window
} }
} }
// If state has changed do a publish
publishUpdate();
// 9600bps is approx 1 byte per msec, so considering our buffer size we never need to wake more often than 200ms
// if not awake we can run super infrquently (once every 5 secs?) to see if we need to wake.
return isAwake ? 100 : 5000;
} }
void GPS::forceWake(bool on) void GPS::forceWake(bool on)

View File

@@ -2,6 +2,7 @@
#include "GPSStatus.h" #include "GPSStatus.h"
#include "Observer.h" #include "Observer.h"
#include "concurrency/OSThread.h"
// Generate a string representation of DOP // Generate a string representation of DOP
const char *getDOPString(uint32_t dop); const char *getDOPString(uint32_t dop);
@@ -11,7 +12,7 @@ const char *getDOPString(uint32_t dop);
* *
* When new data is available it will notify observers. * When new data is available it will notify observers.
*/ */
class GPS class GPS : private concurrency::OSThread
{ {
private: private:
uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0, lastWhileActiveMsec = 0; uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0, lastWhileActiveMsec = 0;
@@ -22,9 +23,14 @@ class GPS
bool wakeAllowed = true; // false if gps must be forced to sleep regardless of what time it is bool wakeAllowed = true; // false if gps must be forced to sleep regardless of what time it is
bool shouldPublish = false; // If we've changed GPS state, this will force a publish the next loop()
bool hasGPS = false; // Do we have a GPS we are talking to
uint8_t numSatellites = 0;
CallbackObserver<GPS, void *> notifySleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareSleep); CallbackObserver<GPS, void *> notifySleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareSleep);
protected:
public: public:
/** If !NULL we will use this serial port to construct our GPS */ /** If !NULL we will use this serial port to construct our GPS */
static HardwareSerial *_serial_gps; static HardwareSerial *_serial_gps;
@@ -37,9 +43,8 @@ class GPS
uint32_t dop = 0; // Diminution of position; PDOP where possible (UBlox), HDOP otherwise (TinyGPS) in 10^2 units (needs uint32_t dop = 0; // Diminution of position; PDOP where possible (UBlox), HDOP otherwise (TinyGPS) in 10^2 units (needs
// scaling before use) // scaling before use)
uint32_t heading = 0; // Heading of motion, in degrees * 10^-5 uint32_t heading = 0; // Heading of motion, in degrees * 10^-5
uint32_t numSatellites = 0;
bool isConnected = false; // Do we have a GPS we are talking to GPS() : concurrency::OSThread("GPS") {}
virtual ~GPS() {} // FIXME, we really should unregister our sleep observer virtual ~GPS() {} // FIXME, we really should unregister our sleep observer
@@ -51,11 +56,12 @@ class GPS
*/ */
virtual bool setup(); virtual bool setup();
virtual void loop();
/// Returns ture if we have acquired GPS lock. /// Returns ture if we have acquired GPS lock.
bool hasLock() const { return hasValidLocation; } bool hasLock() const { return hasValidLocation; }
/// Return true if we are connected to a GPS
bool isConnected() const { return hasGPS; }
/** /**
* Restart our lock attempt - try to get and broadcast a GPS reading ASAP * Restart our lock attempt - try to get and broadcast a GPS reading ASAP
* called after the CPU wakes from light-sleep state * called after the CPU wakes from light-sleep state
@@ -99,6 +105,11 @@ class GPS
*/ */
virtual bool lookForLocation() = 0; virtual bool lookForLocation() = 0;
/// Record that we have a GPS
void setConnected();
void setNumSatellites(uint8_t n);
private: private:
/// Prepare the GPS for the cpu entering deep or light sleep, expect to be gone for at least 100s of msecs /// Prepare the GPS for the cpu entering deep or light sleep, expect to be gone for at least 100s of msecs
/// always returns 0 to indicate okay to sleep /// always returns 0 to indicate okay to sleep
@@ -125,6 +136,8 @@ class GPS
* Tell users we have new GPS readings * Tell users we have new GPS readings
*/ */
void publishUpdate(); void publishUpdate();
virtual int32_t runOnce();
}; };
extern GPS *gps; extern GPS *gps;

View File

@@ -84,7 +84,7 @@ bool NMEAGPS::lookForLocation()
heading = reader.course.value() * 1e3; // Scale the heading (in degrees * 10^-2) to match the expected degrees * 10^-5 heading = reader.course.value() * 1e3; // Scale the heading (in degrees * 10^-2) to match the expected degrees * 10^-5
} }
if (reader.satellites.isValid()) { if (reader.satellites.isValid()) {
numSatellites = reader.satellites.value(); setNumSatellites(reader.satellites.value());
} }
// expect gps pos lat=37.520825, lon=-122.309162, alt=158 // expect gps pos lat=37.520825, lon=-122.309162, alt=158

View File

@@ -1,6 +1,5 @@
#pragma once #pragma once
#include "../concurrency/PeriodicTask.h"
#include "GPS.h" #include "GPS.h"
#include "Observer.h" #include "Observer.h"
#include "TinyGPS++.h" #include "TinyGPS++.h"

View File

@@ -8,20 +8,23 @@ UBloxGPS::UBloxGPS() {}
bool UBloxGPS::tryConnect() bool UBloxGPS::tryConnect()
{ {
isConnected = false; bool c = false;
if (_serial_gps) if (_serial_gps)
isConnected = ublox.begin(*_serial_gps); c = ublox.begin(*_serial_gps);
if (!isConnected && i2cAddress) { if (!c && i2cAddress) {
extern bool neo6M; // Super skanky - if we are talking to the device i2c we assume it is a neo7 on a RAK815, which extern bool neo6M; // Super skanky - if we are talking to the device i2c we assume it is a neo7 on a RAK815, which
// supports the newer API // supports the newer API
neo6M = true; neo6M = true;
isConnected = ublox.begin(Wire, i2cAddress); c = ublox.begin(Wire, i2cAddress);
} }
return isConnected; if (c)
setConnected();
return c;
} }
bool UBloxGPS::setupGPS() bool UBloxGPS::setupGPS()
@@ -45,7 +48,7 @@ bool UBloxGPS::setupGPS()
for (int i = 0; (i < 3) && !tryConnect(); i++) for (int i = 0; (i < 3) && !tryConnect(); i++)
delay(500); delay(500);
if (isConnected) { if (isConnected()) {
DEBUG_MSG("Connected to UBLOX GPS successfully\n"); DEBUG_MSG("Connected to UBLOX GPS successfully\n");
if (!setUBXMode()) if (!setUBXMode())
@@ -106,8 +109,8 @@ bool UBloxGPS::factoryReset()
for (int i = 0; (i < 3) && !tryConnect(); i++) for (int i = 0; (i < 3) && !tryConnect(); i++)
delay(500); delay(500);
DEBUG_MSG("GPS Factory reset success=%d\n", isConnected); DEBUG_MSG("GPS Factory reset success=%d\n", isConnected());
if (isConnected) if (isConnected())
ok = setUBXMode(); ok = setUBXMode();
return ok; return ok;
@@ -127,7 +130,7 @@ void UBloxGPS::whileActive()
// Update fixtype // Update fixtype
if (ublox.moduleQueried.fixType) { if (ublox.moduleQueried.fixType) {
fixType = ublox.getFixType(0); fixType = ublox.getFixType(0);
DEBUG_MSG("GPS fix type %d, numSats %d\n", fixType, numSatellites); // DEBUG_MSG("GPS fix type %d, numSats %d\n", fixType, numSatellites);
} }
} }
@@ -170,7 +173,7 @@ bool UBloxGPS::lookForLocation()
bool foundLocation = false; bool foundLocation = false;
if (ublox.moduleQueried.SIV) if (ublox.moduleQueried.SIV)
numSatellites = ublox.getSIV(0); setNumSatellites(ublox.getSIV(0));
if (ublox.moduleQueried.pDOP) if (ublox.moduleQueried.pDOP)
dop = ublox.getPDOP(0); // PDOP (an accuracy metric) is reported in 10^2 units so we have to scale down when we use it dop = ublox.getPDOP(0); // PDOP (an accuracy metric) is reported in 10^2 units so we have to scale down when we use it
@@ -189,8 +192,7 @@ bool UBloxGPS::lookForLocation()
// bogus lat lon is reported as 0 or 0 (can be bogus just for one) // 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! // Also: apparently when the GPS is initially reporting lock it can output a bogus latitude > 90 deg!
foundLocation = foundLocation = (latitude != 0) && (longitude != 0) && (latitude <= 900000000 && latitude >= -900000000);
(latitude != 0) && (longitude != 0) && (latitude <= 900000000 && latitude >= -900000000) && (numSatellites > 0);
} }
} }

View File

@@ -561,7 +561,9 @@ void _screen_header()
} }
#endif #endif
Screen::Screen(uint8_t address, int sda, int scl) : cmdQueue(32), dispdev(address, sda, scl), ui(&dispdev) {} Screen::Screen(uint8_t address, int sda, int scl) : OSThread("Screen"), cmdQueue(32), dispdev(address, sda, scl), ui(&dispdev) {
cmdQueue.setReader(this);
}
void Screen::handleSetOn(bool on) void Screen::handleSetOn(bool on)
{ {
@@ -573,9 +575,12 @@ void Screen::handleSetOn(bool on)
DEBUG_MSG("Turning on screen\n"); DEBUG_MSG("Turning on screen\n");
dispdev.displayOn(); dispdev.displayOn();
dispdev.displayOn(); dispdev.displayOn();
enabled = true;
setInterval(0); // Draw ASAP
} else { } else {
DEBUG_MSG("Turning off screen\n"); DEBUG_MSG("Turning off screen\n");
dispdev.displayOff(); dispdev.displayOff();
enabled = false;
} }
screenOn = on; screenOn = on;
} }
@@ -583,8 +588,6 @@ void Screen::handleSetOn(bool on)
void Screen::setup() void Screen::setup()
{ {
concurrency::PeriodicTask::setup();
// We don't set useDisplay until setup() is called, because some boards have a declaration of this object but the device // We don't set useDisplay until setup() is called, because some boards have a declaration of this object but the device
// is never found when probing i2c and therefore we don't call setup and never want to do (invalid) accesses to this device. // is never found when probing i2c and therefore we don't call setup and never want to do (invalid) accesses to this device.
useDisplay = true; useDisplay = true;
@@ -642,14 +645,24 @@ void Screen::setup()
nodeStatusObserver.observe(&nodeStatus->onNewStatus); nodeStatusObserver.observe(&nodeStatus->onNewStatus);
} }
void Screen::doTask() int32_t Screen::runOnce()
{ {
// If we don't have a screen, don't ever spend any CPU for us. // If we don't have a screen, don't ever spend any CPU for us.
if (!useDisplay) { if (!useDisplay) {
setPeriod(0); enabled = false;
return; return RUN_SAME;
} }
// Show boot screen for first 3 seconds, then switch to normal operation.
static bool showingBootScreen = true;
if (showingBootScreen && (millis() > 3000)) {
stopBootScreen();
showingBootScreen = false;
}
// Update the screen last, after we've figured out what to show.
debug_info()->setChannelNameStatus(getChannelName());
// Process incoming commands. // Process incoming commands.
for (;;) { for (;;) {
ScreenCmd cmd; ScreenCmd cmd;
@@ -684,8 +697,8 @@ void Screen::doTask()
if (!screenOn) { // If we didn't just wake and the screen is still off, then if (!screenOn) { // If we didn't just wake and the screen is still off, then
// stop updating until it is on again // stop updating until it is on again
setPeriod(0); enabled = false;
return; return 0;
} }
// Switch to a low framerate (to save CPU) when we are not in transition // Switch to a low framerate (to save CPU) when we are not in transition
@@ -711,7 +724,7 @@ void Screen::doTask()
// soon, otherwise just 1 fps (to save CPU) We also ask to be called twice // soon, otherwise just 1 fps (to save CPU) We also ask to be called twice
// as fast as we really need so that any rounding errors still result with // as fast as we really need so that any rounding errors still result with
// the correct framerate // the correct framerate
setPeriod(1000 / targetFramerate); return (1000 / targetFramerate);
} }
void Screen::drawDebugInfoTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) void Screen::drawDebugInfoTrampoline(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
@@ -801,7 +814,7 @@ void Screen::handleOnPress()
// If screen was off, just wake it, otherwise advance to next frame // If screen was off, just wake it, otherwise advance to next frame
// If we are in a transition, the press must have bounced, drop it. // If we are in a transition, the press must have bounced, drop it.
if (ui.getUiState()->frameState == FIXED) { if (ui.getUiState()->frameState == FIXED) {
setPeriod(1); // redraw ASAP setInterval(0); // redraw ASAP
ui.nextFrame(); ui.nextFrame();
DEBUG_MSG("Setting fast framerate\n"); DEBUG_MSG("Setting fast framerate\n");
@@ -1068,7 +1081,7 @@ int Screen::handleStatusUpdate(const meshtastic::Status *arg)
if (nodeDB.updateTextMessage || nodeStatus->getLastNumTotal() != nodeStatus->getNumTotal()) { if (nodeDB.updateTextMessage || nodeStatus->getLastNumTotal() != nodeStatus->getNumTotal()) {
setFrames(); // Regen the list of screens setFrames(); // Regen the list of screens
prevFrame = -1; // Force a GUI update prevFrame = -1; // Force a GUI update
setPeriod(1); // Update the screen right away setInterval(0); // Update the screen right away
} }
nodeDB.updateGUI = false; nodeDB.updateGUI = false;
nodeDB.updateTextMessage = false; nodeDB.updateTextMessage = false;

View File

@@ -15,7 +15,7 @@
#include "TypedQueue.h" #include "TypedQueue.h"
#include "commands.h" #include "commands.h"
#include "concurrency/LockGuard.h" #include "concurrency/LockGuard.h"
#include "concurrency/PeriodicTask.h" #include "concurrency/OSThread.h"
#include "power.h" #include "power.h"
#include <string> #include <string>
@@ -62,7 +62,7 @@ class DebugInfo
* multiple times simultaneously. All state-changing calls are queued and executed * multiple times simultaneously. All state-changing calls are queued and executed
* when the main loop calls us. * when the main loop calls us.
*/ */
class Screen : public concurrency::PeriodicTask class Screen : public concurrency::OSThread
{ {
CallbackObserver<Screen, const meshtastic::Status *> powerStatusObserver = CallbackObserver<Screen, const meshtastic::Status *> powerStatusObserver =
CallbackObserver<Screen, const meshtastic::Status *>(this, &Screen::handleStatusUpdate); CallbackObserver<Screen, const meshtastic::Status *>(this, &Screen::handleStatusUpdate);
@@ -184,7 +184,7 @@ class Screen : public concurrency::PeriodicTask
/// Updates the UI. /// Updates the UI.
// //
// Called periodically from the main loop. // Called periodically from the main loop.
void doTask() final; int32_t runOnce() final;
private: private:
struct ScreenCmd { struct ScreenCmd {
@@ -202,7 +202,7 @@ class Screen : public concurrency::PeriodicTask
return true; // claim success if our display is not in use return true; // claim success if our display is not in use
else { else {
bool success = cmdQueue.enqueue(cmd, 0); bool success = cmdQueue.enqueue(cmd, 0);
setPeriod(1); // handle ASAP setInterval(0); // handle ASAP
return success; return success;
} }
} }

View File

@@ -1,25 +1,3 @@
/*
Main module
# Modified by Kyle T. Gabriel to fix issue with incorrect GPS data for TTNMapper
Copyright (C) 2018 by Xose Pérez <xose dot perez at gmail dot com>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "Air530GPS.h" #include "Air530GPS.h"
#include "MeshRadio.h" #include "MeshRadio.h"
@@ -27,7 +5,6 @@
#include "NodeDB.h" #include "NodeDB.h"
#include "PowerFSM.h" #include "PowerFSM.h"
#include "UBloxGPS.h" #include "UBloxGPS.h"
#include "concurrency/Periodic.h"
#include "configuration.h" #include "configuration.h"
#include "error.h" #include "error.h"
#include "power.h" #include "power.h"
@@ -36,6 +13,8 @@
// #include "debug.h" // #include "debug.h"
#include "RTC.h" #include "RTC.h"
#include "SPILock.h" #include "SPILock.h"
#include "concurrency/OSThread.h"
#include "concurrency/Periodic.h"
#include "graphics/Screen.h" #include "graphics/Screen.h"
#include "main.h" #include "main.h"
#include "meshwifi/meshhttp.h" #include "meshwifi/meshhttp.h"
@@ -57,8 +36,10 @@
#include "variant.h" #include "variant.h"
#endif #endif
using namespace concurrency;
// We always create a screen object, but we only init it if we find the hardware // We always create a screen object, but we only init it if we find the hardware
graphics::Screen screen(SSD1306_ADDRESS); graphics::Screen *screen;
// Global power status // Global power status
meshtastic::PowerStatus *powerStatus = new meshtastic::PowerStatus(); meshtastic::PowerStatus *powerStatus = new meshtastic::PowerStatus();
@@ -72,8 +53,7 @@ meshtastic::NodeStatus *nodeStatus = new meshtastic::NodeStatus();
bool ssd1306_found; bool ssd1306_found;
bool axp192_found; bool axp192_found;
DSRRouter realRouter; Router *router = NULL; // Users of router don't care what sort of subclass implements that API
Router &router = realRouter; // Users of router don't care what sort of subclass implements that API
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
// Application // Application
@@ -123,7 +103,7 @@ const char *getDeviceName()
return name; return name;
} }
static uint32_t ledBlinker() static int32_t ledBlinker()
{ {
static bool ledOn; static bool ledOn;
ledOn ^= 1; ledOn ^= 1;
@@ -131,10 +111,31 @@ static uint32_t ledBlinker()
setLed(ledOn); setLed(ledOn);
// have a very sparse duty cycle of LED being on, unless charging, then blink 0.5Hz square wave rate to indicate that // have a very sparse duty cycle of LED being on, unless charging, then blink 0.5Hz square wave rate to indicate that
return powerStatus->getIsCharging() ? 1000 : (ledOn ? 2 : 1000); return powerStatus->getIsCharging() ? 1000 : (ledOn ? 1 : 1000);
} }
concurrency::Periodic ledPeriodic(ledBlinker); /// Wrapper to convert our powerFSM stuff into a 'thread'
class PowerFSMThread : public OSThread
{
public:
// callback returns the period for the next callback invocation (or 0 if we should no longer be called)
PowerFSMThread() : OSThread("PowerFSM") {}
protected:
int32_t runOnce()
{
powerFSM.run_machine();
/// If we are in power state we force the CPU to wake every 10ms to check for serial characters (we don't yet wake
/// cpu for serial rx - FIXME)
canSleep = (powerFSM.getState() != &statePOWER);
return 10;
}
};
static Periodic *ledPeriodic;
static OSThread *powerFSMthread;
// Prepare for button presses // Prepare for button presses
#ifdef BUTTON_PIN #ifdef BUTTON_PIN
@@ -149,7 +150,22 @@ void userButtonPressed()
} }
void userButtonPressedLong() void userButtonPressedLong()
{ {
screen.adjustBrightness(); screen->adjustBrightness();
}
/**
* Watch a GPIO and if we get an IRQ, wake the main thread.
* Use to add wake on button press
*/
void wakeOnIrq(int irq, int mode)
{
attachInterrupt(
irq,
[] {
BaseType_t higherWake = 0;
mainDelay.interruptFromISR(&higherWake);
},
FALLING);
} }
RadioInterface *rIf = NULL; RadioInterface *rIf = NULL;
@@ -177,6 +193,12 @@ void setup()
digitalWrite(RESET_OLED, 1); digitalWrite(RESET_OLED, 1);
#endif #endif
OSThread::setup();
ledPeriodic = new Periodic("Blink", ledBlinker);
router = new DSRRouter();
#ifdef I2C_SDA #ifdef I2C_SDA
Wire.begin(I2C_SDA, I2C_SCL); Wire.begin(I2C_SDA, I2C_SCL);
#else #else
@@ -192,19 +214,19 @@ void setup()
userButton = OneButton(BUTTON_PIN, true, true); userButton = OneButton(BUTTON_PIN, true, true);
userButton.attachClick(userButtonPressed); userButton.attachClick(userButtonPressed);
userButton.attachDuringLongPress(userButtonPressedLong); userButton.attachDuringLongPress(userButtonPressedLong);
wakeOnIrq(BUTTON_PIN, FALLING);
#endif #endif
#ifdef BUTTON_PIN_ALT #ifdef BUTTON_PIN_ALT
userButtonAlt = OneButton(BUTTON_PIN_ALT, true, true); userButtonAlt = OneButton(BUTTON_PIN_ALT, true, true);
userButtonAlt.attachClick(userButtonPressed); userButtonAlt.attachClick(userButtonPressed);
userButton.attachDuringLongPress(userButtonPressedLong); userButton.attachDuringLongPress(userButtonPressedLong);
wakeOnIrq(BUTTON_PIN_ALT, FALLING);
#endif #endif
#ifdef LED_PIN #ifdef LED_PIN
pinMode(LED_PIN, OUTPUT); pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, 1 ^ LED_INVERTED); // turn on for now digitalWrite(LED_PIN, 1 ^ LED_INVERTED); // turn on for now
#endif #endif
ledPeriodic.setup();
// Hello // Hello
DEBUG_MSG("Meshtastic swver=%s, hwver=%s\n", optstr(APP_VERSION), optstr(HW_VERSION)); DEBUG_MSG("Meshtastic swver=%s, hwver=%s\n", optstr(APP_VERSION), optstr(HW_VERSION));
@@ -237,14 +259,15 @@ void setup()
#endif #endif
// Initialize the screen first so we can show the logo while we start up everything else. // Initialize the screen first so we can show the logo while we start up everything else.
screen = new graphics::Screen(SSD1306_ADDRESS);
#if defined(ST7735_CS) || defined(HAS_EINK) #if defined(ST7735_CS) || defined(HAS_EINK)
screen.setup(); screen->setup();
#else #else
if (ssd1306_found) if (ssd1306_found)
screen.setup(); screen->setup();
#endif #endif
screen.print("Started...\n"); screen->print("Started...\n");
readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time) readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time)
@@ -343,10 +366,11 @@ void setup()
if (!rIf) if (!rIf)
recordCriticalError(ErrNoRadio); recordCriticalError(ErrNoRadio);
else else
router.addInterface(rIf); router->addInterface(rIf);
// This must be _after_ service.init because we need our preferences loaded from flash to have proper timeout values // 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 PowerFSM_setup(); // we will transition to ON in a couple of seconds, FIXME, only do this for cold boots, not waking from SDS
powerFSMthread = new PowerFSMThread();
// setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state // setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state
setCPUFast(false); // 80MHz is fine for our slow peripherals setCPUFast(false); // 80MHz is fine for our slow peripherals
@@ -369,21 +393,12 @@ uint32_t axpDebugRead()
return 30 * 1000; return 30 * 1000;
} }
concurrency::Periodic axpDebugOutput(axpDebugRead); Periodic axpDebugOutput(axpDebugRead);
axpDebugOutput.setup(); axpDebugOutput.setup();
#endif #endif
void loop() void loop()
{ {
uint32_t msecstosleep = 1000 * 30; // How long can we sleep before we again need to service the main loop?
if (gps)
gps->loop(); // FIXME, remove from main, instead block on read
router.loop();
powerFSM.run_machine();
service.loop();
concurrency::periodicScheduler.loop();
// axpDebugOutput.loop(); // axpDebugOutput.loop();
#ifdef DEBUG_PORT #ifdef DEBUG_PORT
@@ -395,9 +410,6 @@ void loop()
#ifndef NO_ESP32 #ifndef NO_ESP32
esp32Loop(); esp32Loop();
#endif #endif
#ifdef TBEAM_V10
power->loop();
#endif
#ifdef BUTTON_PIN #ifdef BUTTON_PIN
userButton.tick(); userButton.tick();
@@ -406,18 +418,9 @@ void loop()
userButtonAlt.tick(); userButtonAlt.tick();
#endif #endif
loopWifi();
// For debugging // For debugging
// if (rIf) ((RadioLibInterface *)rIf)->isActivelyReceiving(); // if (rIf) ((RadioLibInterface *)rIf)->isActivelyReceiving();
// Show boot screen for first 3 seconds, then switch to normal operation.
static bool showingBootScreen = true;
if (showingBootScreen && (millis() > 3000)) {
screen.stopBootScreen();
showingBootScreen = false;
}
#ifdef DEBUG_STACK #ifdef DEBUG_STACK
static uint32_t lastPrint = 0; static uint32_t lastPrint = 0;
if (millis() - lastPrint > 10 * 1000L) { if (millis() - lastPrint > 10 * 1000L) {
@@ -426,19 +429,18 @@ void loop()
} }
#endif #endif
// Update the screen last, after we've figured out what to show.
screen.debug_info()->setChannelNameStatus(getChannelName());
// 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.
// DEBUG_MSG("msecs %d\n", msecstosleep);
// FIXME - until button press handling is done by interrupt (see polling above) we can't sleep very long at all or buttons
// feel slow
msecstosleep = 10; // FIXME, stop early if something happens and sleep much longer
// TODO: This should go into a thread handled by FreeRTOS. // TODO: This should go into a thread handled by FreeRTOS.
handleWebResponse(); handleWebResponse();
delay(msecstosleep); service.loop();
long delayMsec = mainController.runOrDelay();
/* if (mainController.nextThread && delayMsec)
DEBUG_MSG("Next %s in %ld\n", mainController.nextThread->ThreadName.c_str(),
mainController.nextThread->tillRun(millis()));
*/
// We want to sleep as long as possible here - because it saves power
mainDelay.delay(delayMsec);
} }

View File

@@ -1,28 +1,24 @@
#pragma once #pragma once
#include "graphics/Screen.h"
#include "PowerStatus.h"
#include "GPSStatus.h" #include "GPSStatus.h"
#include "NodeStatus.h" #include "NodeStatus.h"
#include "PowerStatus.h"
#include "graphics/Screen.h"
extern bool axp192_found; extern bool axp192_found;
extern bool ssd1306_found; extern bool ssd1306_found;
extern bool isCharging; extern bool isCharging;
extern bool isUSBPowered; extern bool isUSBPowered;
// Global Screen singleton. // Global Screen singleton.
extern graphics::Screen screen; extern graphics::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::PowerStatus *powerStatus; // extern meshtastic::PowerStatus *powerStatus;
//extern meshtastic::GPSStatus *gpsStatus; // extern meshtastic::GPSStatus *gpsStatus;
//extern meshtastic::NodeStatusHandler *nodeStatusHandler; // extern meshtastic::NodeStatusHandler *nodeStatusHandler;
// Return a human readable string of the form "Meshtastic_ab13" // Return a human readable string of the form "Meshtastic_ab13"
const char *getDeviceName(); const char *getDeviceName();
void nrf52Setup(), esp32Setup(), nrf52Loop(), esp32Loop(); void nrf52Setup(), esp32Setup(), nrf52Loop(), esp32Loop();

View File

@@ -1,7 +1,6 @@
#pragma once #pragma once
#include "PacketHistory.h" #include "PacketHistory.h"
#include "../concurrency/PeriodicTask.h"
#include "Router.h" #include "Router.h"
/** /**

View File

@@ -49,14 +49,14 @@ MeshService service;
#include "Router.h" #include "Router.h"
static uint32_t sendOwnerCb() static int32_t sendOwnerCb()
{ {
service.sendOurOwner(); service.sendOurOwner();
return getPref_send_owner_interval() * getPref_position_broadcast_secs() * 1000; return getPref_send_owner_interval() * getPref_position_broadcast_secs() * 1000;
} }
static concurrency::Periodic sendOwnerPeriod(sendOwnerCb); static concurrency::Periodic *sendOwnerPeriod;
MeshService::MeshService() : toPhoneQueue(MAX_RX_TOPHONE) MeshService::MeshService() : toPhoneQueue(MAX_RX_TOPHONE)
{ {
@@ -65,17 +65,18 @@ MeshService::MeshService() : toPhoneQueue(MAX_RX_TOPHONE)
void MeshService::init() void MeshService::init()
{ {
sendOwnerPeriod.setup(); sendOwnerPeriod = new concurrency::Periodic("SendOwner", sendOwnerCb);
nodeDB.init(); nodeDB.init();
if (gps) if (gps)
gpsObserver.observe(&gps->newStatus); gpsObserver.observe(&gps->newStatus);
packetReceivedObserver.observe(&router.notifyPacketReceived); packetReceivedObserver.observe(&router->notifyPacketReceived);
} }
void MeshService::sendOurOwner(NodeNum dest, bool wantReplies) void MeshService::sendOurOwner(NodeNum dest, bool wantReplies)
{ {
MeshPacket *p = router.allocForSending(); MeshPacket *p = router->allocForSending();
p->to = dest; p->to = dest;
p->decoded.want_response = wantReplies; p->decoded.want_response = wantReplies;
p->decoded.which_payload = SubPacket_user_tag; p->decoded.which_payload = SubPacket_user_tag;
@@ -122,7 +123,7 @@ const MeshPacket *MeshService::handleFromRadioUser(const MeshPacket *mp)
sendOurOwner(mp->from); sendOurOwner(mp->from);
String lcd = String("Joined: ") + mp->decoded.user.long_name + "\n"; String lcd = String("Joined: ") + mp->decoded.user.long_name + "\n";
screen.print(lcd.c_str()); screen->print(lcd.c_str());
} }
return mp; return mp;
@@ -227,7 +228,7 @@ void MeshService::handleToRadio(MeshPacket &p)
p.id = generatePacketId(); // If the phone didn't supply one, then pick one p.id = generatePacketId(); // If the phone didn't supply one, then pick one
p.rx_time = getValidTime(RTCQualityFromNet); // Record the time the packet arrived from the phone p.rx_time = getValidTime(RTCQualityFromNet); // Record the time the packet arrived from the phone
// (so we update our nodedb for the local node) // (so we update our nodedb for the local node)
// Send the packet into the mesh // Send the packet into the mesh
@@ -247,10 +248,10 @@ void MeshService::sendToMesh(MeshPacket *p)
nodeDB.updateFrom(*p); // update our local DB for this packet (because phone might have sent position packets etc...) nodeDB.updateFrom(*p); // update our local DB for this packet (because phone might have sent position packets etc...)
// Strip out any time information before sending packets to other nodes - to keep the wire size small (and because other // Strip out any time information before sending packets to other nodes - to keep the wire size small (and because other
// nodes shouldn't trust it anyways) Note: for now, we allow a device with a local GPS to include the time, so that gpsless // nodes shouldn't trust it anyways) Note: we allow a device with a local GPS to include the time, so that gpsless
// devices can get time. // devices can get time.
if (p->which_payload == MeshPacket_decoded_tag && p->decoded.which_payload == SubPacket_position_tag) { if (p->which_payload == MeshPacket_decoded_tag && p->decoded.which_payload == SubPacket_position_tag) {
if (!gps->isConnected) { if (getRTCQuality() < RTCQualityGPS) {
DEBUG_MSG("Stripping time %u from position send\n", p->decoded.position.time); DEBUG_MSG("Stripping time %u from position send\n", p->decoded.position.time);
p->decoded.position.time = 0; p->decoded.position.time = 0;
} else } else
@@ -258,7 +259,7 @@ void MeshService::sendToMesh(MeshPacket *p)
} }
// Note: We might return !OK if our fifo was full, at that point the only option we have is to drop it // Note: We might return !OK if our fifo was full, at that point the only option we have is to drop it
router.sendLocal(p); router->sendLocal(p);
} }
void MeshService::sendNetworkPing(NodeNum dest, bool wantReplies) void MeshService::sendNetworkPing(NodeNum dest, bool wantReplies)
@@ -280,12 +281,13 @@ void MeshService::sendOurPosition(NodeNum dest, bool wantReplies)
assert(node->has_position); assert(node->has_position);
// Update our local node info with our position (even if we don't decide to update anyone else) // Update our local node info with our position (even if we don't decide to update anyone else)
MeshPacket *p = router.allocForSending(); MeshPacket *p = router->allocForSending();
p->to = dest; p->to = dest;
p->decoded.which_payload = SubPacket_position_tag; p->decoded.which_payload = SubPacket_position_tag;
p->decoded.position = node->position; p->decoded.position = node->position;
p->decoded.want_response = wantReplies; p->decoded.want_response = wantReplies;
p->decoded.position.time = getValidTime(RTCQualityGPS); // This nodedb timestamp might be stale, so update it if our clock is valid. p->decoded.position.time =
getValidTime(RTCQualityGPS); // This nodedb timestamp might be stale, so update it if our clock is valid.
sendToMesh(p); sendToMesh(p);
} }
@@ -293,7 +295,7 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *unused)
{ {
// Update our local node info with our position (even if we don't decide to update anyone else) // Update our local node info with our position (even if we don't decide to update anyone else)
MeshPacket *p = router.allocForSending(); MeshPacket *p = router->allocForSending();
p->decoded.which_payload = SubPacket_position_tag; p->decoded.which_payload = SubPacket_position_tag;
Position &pos = p->decoded.position; Position &pos = p->decoded.position;

View File

@@ -113,7 +113,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// app not to send locations on our behalf. // app not to send locations on our behalf.
myNodeInfo.has_gps = (radioConfig.preferences.location_share == LocationSharing_LocDisabled) myNodeInfo.has_gps = (radioConfig.preferences.location_share == LocationSharing_LocDisabled)
? true ? true
: (gps && gps->isConnected); // Update with latest GPS connect info : (gps && gps->isConnected()); // Update with latest GPS connect info
fromRadioScratch.which_variant = FromRadio_my_info_tag; fromRadioScratch.which_variant = FromRadio_my_info_tag;
fromRadioScratch.variant.my_info = myNodeInfo; fromRadioScratch.variant.my_info = myNodeInfo;
state = STATE_SEND_RADIO; state = STATE_SEND_RADIO;

View File

@@ -91,7 +91,7 @@ void printPacket(const char *prefix, const MeshPacket *p)
DEBUG_MSG(")\n"); DEBUG_MSG(")\n");
} }
RadioInterface::RadioInterface() RadioInterface::RadioInterface()
{ {
assert(sizeof(PacketHeader) == 4 || sizeof(PacketHeader) == 16); // make sure the compiler did what we expected assert(sizeof(PacketHeader) == 4 || sizeof(PacketHeader) == 16); // make sure the compiler did what we expected
@@ -120,10 +120,7 @@ bool RadioInterface::init()
// we now expect interfaces to operate in promiscous mode // we now expect interfaces to operate in promiscous mode
// radioIf.setThisAddress(nodeDB.getNodeNum()); // Note: we must do this here, because the nodenum isn't inited at constructor // radioIf.setThisAddress(nodeDB.getNodeNum()); // Note: we must do this here, because the nodenum isn't inited at constructor
// time. // time.
// we want this thread to run at very high priority, because it is effectively running as a user space ISR
start("radio", RADIO_STACK_SIZE, configMAX_PRIORITIES - 1); // Start our worker thread
return true; return true;
} }

View File

@@ -36,7 +36,7 @@ typedef struct {
* *
* This defines the SOLE API for talking to radios (because soon we will have alternate radio implementations) * This defines the SOLE API for talking to radios (because soon we will have alternate radio implementations)
*/ */
class RadioInterface : protected concurrency::NotifiedWorkerThread class RadioInterface
{ {
friend class MeshRadio; // for debugging we let that class touch pool friend class MeshRadio; // for debugging we let that class touch pool
PointerQueue<MeshPacket> *rxDest = NULL; PointerQueue<MeshPacket> *rxDest = NULL;
@@ -72,6 +72,8 @@ class RadioInterface : protected concurrency::NotifiedWorkerThread
*/ */
RadioInterface(); RadioInterface();
virtual ~RadioInterface() {}
/** /**
* Set where to deliver received packets. This method should only be used by the Router class * Set where to deliver received packets. This method should only be used by the Router class
*/ */
@@ -117,8 +119,6 @@ class RadioInterface : protected concurrency::NotifiedWorkerThread
*/ */
size_t beginSending(MeshPacket *p); size_t beginSending(MeshPacket *p);
virtual void loop() {} // Idle processing
/** /**
* Some regulatory regions limit xmit power. * Some regulatory regions limit xmit power.
* This function should be called by subclasses after setting their desired power. It might lower it * This function should be called by subclasses after setting their desired power. It might lower it

View File

@@ -19,17 +19,11 @@ void LockingModule::SPItransfer(uint8_t cmd, uint8_t reg, uint8_t *dataOut, uint
RadioLibInterface::RadioLibInterface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy, RadioLibInterface::RadioLibInterface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy,
SPIClass &spi, PhysicalLayer *_iface) SPIClass &spi, PhysicalLayer *_iface)
: concurrency::PeriodicTask(0), module(cs, irq, rst, busy, spi, spiSettings), iface(_iface) : NotifiedWorkerThread("RadioIf"), module(cs, irq, rst, busy, spi, spiSettings), iface(_iface)
{ {
instance = this; instance = this;
} }
bool RadioLibInterface::init()
{
setup(); // init our timer
return RadioInterface::init();
}
#ifndef NO_ESP32 #ifndef NO_ESP32
// ESP32 doesn't use that flag // ESP32 doesn't use that flag
#define YIELD_FROM_ISR(x) portYIELD_FROM_ISR() #define YIELD_FROM_ISR(x) portYIELD_FROM_ISR()
@@ -41,9 +35,8 @@ void INTERRUPT_ATTR RadioLibInterface::isrLevel0Common(PendingISR cause)
{ {
instance->disableInterrupt(); instance->disableInterrupt();
instance->pending = cause;
BaseType_t xHigherPriorityTaskWoken; BaseType_t xHigherPriorityTaskWoken;
instance->notifyFromISR(&xHigherPriorityTaskWoken, cause, eSetValueWithOverwrite); instance->notifyFromISR(&xHigherPriorityTaskWoken, cause, true);
/* Force a context switch if xHigherPriorityTaskWoken is now set to pdTRUE. /* Force a context switch if xHigherPriorityTaskWoken is now set to pdTRUE.
The macro used to do this is dependent on the port and may be called The macro used to do this is dependent on the port and may be called
@@ -191,10 +184,8 @@ transmitters that we are potentially stomping on. Requires further thought.
FIXME, the MIN_TX_WAIT_MSEC and MAX_TX_WAIT_MSEC values should be tuned via logic analyzer later. FIXME, the MIN_TX_WAIT_MSEC and MAX_TX_WAIT_MSEC values should be tuned via logic analyzer later.
*/ */
void RadioLibInterface::loop() void RadioLibInterface::onNotify(uint32_t notification)
{ {
pending = ISR_NONE;
switch (notification) { switch (notification) {
case ISR_TX: case ISR_TX:
handleTransmitInterrupt(); handleTransmitInterrupt();
@@ -209,6 +200,8 @@ void RadioLibInterface::loop()
startTransmitTimer(); startTransmitTimer();
break; break;
case TRANSMIT_DELAY_COMPLETED: case TRANSMIT_DELAY_COMPLETED:
// DEBUG_MSG("delay done\n");
// If we are not currently in receive mode, then restart the timer and try again later (this can happen if the main thread // If we are not currently in receive mode, then restart the timer and try again later (this can happen if the main thread
// has placed the unit into standby) FIXME, how will this work if the chipset is in sleep mode? // has placed the unit into standby) FIXME, how will this work if the chipset is in sleep mode?
if (!txQueue.isEmpty()) { if (!txQueue.isEmpty()) {
@@ -229,25 +222,14 @@ void RadioLibInterface::loop()
} }
} }
void RadioLibInterface::doTask()
{
disable(); // Don't call this callback again
// We use without overwrite, so that if there is already an interrupt pending to be handled, that gets handle properly (the
// ISR handler will restart our timer)
notify(TRANSMIT_DELAY_COMPLETED, eSetValueWithoutOverwrite);
}
void RadioLibInterface::startTransmitTimer(bool withDelay) void RadioLibInterface::startTransmitTimer(bool withDelay)
{ {
// If we have work to do and the timer wasn't already scheduled, schedule it now // If we have work to do and the timer wasn't already scheduled, schedule it now
if (getPeriod() == 0 && !txQueue.isEmpty()) { if (!txQueue.isEmpty()) {
uint32_t delay = uint32_t delay =
!withDelay ? 1 : random(MIN_TX_WAIT_MSEC, MAX_TX_WAIT_MSEC); // See documentation for loop() wrt these values !withDelay ? 1 : random(MIN_TX_WAIT_MSEC, MAX_TX_WAIT_MSEC); // See documentation for loop() wrt these values
// DEBUG_MSG("xmit timer %d\n", delay); // DEBUG_MSG("xmit timer %d\n", delay);
// DEBUG_MSG("delaying %u\n", delay); notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
setPeriod(delay);
} }
} }

View File

@@ -1,6 +1,6 @@
#pragma once #pragma once
#include "../concurrency/PeriodicTask.h" #include "../concurrency/OSThread.h"
#include "RadioInterface.h" #include "RadioInterface.h"
#ifdef CubeCell_BoardPlus #ifdef CubeCell_BoardPlus
@@ -59,13 +59,11 @@ class LockingModule : public Module
virtual void SPItransfer(uint8_t cmd, uint8_t reg, uint8_t *dataOut, uint8_t *dataIn, uint8_t numBytes); virtual void SPItransfer(uint8_t cmd, uint8_t reg, uint8_t *dataOut, uint8_t *dataIn, uint8_t numBytes);
}; };
class RadioLibInterface : public RadioInterface, private concurrency::PeriodicTask class RadioLibInterface : public RadioInterface, protected concurrency::NotifiedWorkerThread
{ {
/// Used as our notification from the ISR /// Used as our notification from the ISR
enum PendingISR { ISR_NONE = 0, ISR_RX, ISR_TX, TRANSMIT_DELAY_COMPLETED }; enum PendingISR { ISR_NONE = 0, ISR_RX, ISR_TX, TRANSMIT_DELAY_COMPLETED };
volatile PendingISR pending = ISR_NONE;
/** /**
* Raw ISR handler that just calls our polymorphic method * Raw ISR handler that just calls our polymorphic method
*/ */
@@ -155,7 +153,7 @@ class RadioLibInterface : public RadioInterface, private concurrency::PeriodicTa
static void timerCallback(void *p1, uint32_t p2); static void timerCallback(void *p1, uint32_t p2);
virtual void doTask(); virtual void onNotify(uint32_t notification);
/** start an immediate transmit /** start an immediate transmit
* This method is virtual so subclasses can hook as needed, subclasses should not call directly * This method is virtual so subclasses can hook as needed, subclasses should not call directly
@@ -163,10 +161,6 @@ class RadioLibInterface : public RadioInterface, private concurrency::PeriodicTa
virtual void startSend(MeshPacket *txp); virtual void startSend(MeshPacket *txp);
protected: protected:
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool init();
/** Do any hardware setup needed on entry into send configuration for the radio. Subclasses can customize */ /** Do any hardware setup needed on entry into send configuration for the radio. Subclasses can customize */
virtual void configHardwareForSend() {} virtual void configHardwareForSend() {}
@@ -195,7 +189,5 @@ class RadioLibInterface : public RadioInterface, private concurrency::PeriodicTa
*/ */
virtual void addReceiveMetadata(MeshPacket *mp) = 0; virtual void addReceiveMetadata(MeshPacket *mp) = 0;
virtual void loop(); // Idle processing
virtual void setStandby() = 0; virtual void setStandby() = 0;
}; };

View File

@@ -160,9 +160,10 @@ PendingPacket *ReliableRouter::startRetransmission(MeshPacket *p)
/** /**
* Do any retransmissions that are scheduled (FIXME - for the time being called from loop) * Do any retransmissions that are scheduled (FIXME - for the time being called from loop)
*/ */
void ReliableRouter::doRetransmissions() int32_t ReliableRouter::doRetransmissions()
{ {
uint32_t now = millis(); uint32_t now = millis();
int32_t d = INT32_MAX;
// FIXME, we should use a better datastructure rather than walking through this map. // FIXME, we should use a better datastructure rather than walking through this map.
// for(auto el: pending) { // for(auto el: pending) {
@@ -192,5 +193,13 @@ void ReliableRouter::doRetransmissions()
p.setNextTx(); p.setNextTx();
} }
} }
else {
// Not yet time
int32_t t = p.nextTxMsec - now;
d = min(t, d);
}
} }
return d;
} }

View File

@@ -1,7 +1,6 @@
#pragma once #pragma once
#include "FloodingRouter.h" #include "FloodingRouter.h"
#include "../concurrency/PeriodicTask.h"
#include <unordered_map> #include <unordered_map>
/** /**
@@ -80,10 +79,13 @@ class ReliableRouter : public FloodingRouter
virtual ErrorCode send(MeshPacket *p); virtual ErrorCode send(MeshPacket *p);
/** Do our retransmission handling */ /** Do our retransmission handling */
virtual void loop() virtual int32_t runOnce()
{ {
doRetransmissions(); auto d = FloodingRouter::runOnce();
FloodingRouter::loop();
int32_t r = doRetransmissions();
return min(d, r);
} }
protected: protected:
@@ -124,6 +126,8 @@ class ReliableRouter : public FloodingRouter
/** /**
* Do any retransmissions that are scheduled (FIXME - for the time being called from loop) * Do any retransmissions that are scheduled (FIXME - for the time being called from loop)
*
* @return the number of msecs until our next retransmission or MAXINT if none scheduled
*/ */
void doRetransmissions(); int32_t doRetransmissions();
}; };

View File

@@ -34,25 +34,29 @@ Allocator<MeshPacket> &packetPool = staticPool;
* *
* Currently we only allow one interface, that may change in the future * Currently we only allow one interface, that may change in the future
*/ */
Router::Router() : fromRadioQueue(MAX_RX_FROMRADIO) Router::Router() : concurrency::OSThread("Router"), fromRadioQueue(MAX_RX_FROMRADIO)
{ {
// This is called pre main(), don't touch anything here, the following code is not safe // This is called pre main(), don't touch anything here, the following code is not safe
/* DEBUG_MSG("Size of NodeInfo %d\n", sizeof(NodeInfo)); /* DEBUG_MSG("Size of NodeInfo %d\n", sizeof(NodeInfo));
DEBUG_MSG("Size of SubPacket %d\n", sizeof(SubPacket)); DEBUG_MSG("Size of SubPacket %d\n", sizeof(SubPacket));
DEBUG_MSG("Size of MeshPacket %d\n", sizeof(MeshPacket)); */ DEBUG_MSG("Size of MeshPacket %d\n", sizeof(MeshPacket)); */
fromRadioQueue.setReader(this);
} }
/** /**
* do idle processing * do idle processing
* Mostly looking in our incoming rxPacket queue and calling handleReceived. * Mostly looking in our incoming rxPacket queue and calling handleReceived.
*/ */
void Router::loop() int32_t Router::runOnce()
{ {
MeshPacket *mp; MeshPacket *mp;
while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL) { while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL) {
perhapsHandleReceived(mp); perhapsHandleReceived(mp);
} }
return INT32_MAX; // Wait a long time - until we get woken for the message queue
} }
/// Generate a unique packet id /// Generate a unique packet id

View File

@@ -5,12 +5,13 @@
#include "Observer.h" #include "Observer.h"
#include "PointerQueue.h" #include "PointerQueue.h"
#include "RadioInterface.h" #include "RadioInterface.h"
#include "concurrency/OSThread.h"
#include "mesh.pb.h" #include "mesh.pb.h"
/** /**
* A mesh aware router that supports multiple interfaces. * A mesh aware router that supports multiple interfaces.
*/ */
class Router class Router : protected concurrency::OSThread
{ {
private: private:
RadioInterface *iface; RadioInterface *iface;
@@ -44,7 +45,7 @@ class Router
* do idle processing * do idle processing
* Mostly looking in our incoming rxPacket queue and calling handleReceived. * Mostly looking in our incoming rxPacket queue and calling handleReceived.
*/ */
virtual void loop(); virtual int32_t runOnce();
/** /**
* Works like send, but if we are sending to the local node, we directly put the message in the receive queue * Works like send, but if we are sending to the local node, we directly put the message in the receive queue
@@ -113,7 +114,7 @@ class Router
void handleReceived(MeshPacket *p); void handleReceived(MeshPacket *p);
}; };
extern Router &router; extern Router *router;
/// Generate a unique packet id /// Generate a unique packet id
// FIXME, move this someplace better // FIXME, move this someplace better

View File

@@ -3,6 +3,7 @@
#include <cassert> #include <cassert>
#include <type_traits> #include <type_traits>
#include "concurrency/OSThread.h"
#include "freertosinc.h" #include "freertosinc.h"
#ifdef HAS_FREE_RTOS #ifdef HAS_FREE_RTOS
@@ -15,6 +16,7 @@ template <class T> class TypedQueue
{ {
static_assert(std::is_pod<T>::value, "T must be pod"); static_assert(std::is_pod<T>::value, "T must be pod");
QueueHandle_t h; QueueHandle_t h;
concurrency::OSThread *reader = NULL;
public: public:
TypedQueue(int maxElements) TypedQueue(int maxElements)
@@ -29,13 +31,35 @@ template <class T> class TypedQueue
bool isEmpty() { return uxQueueMessagesWaiting(h) == 0; } bool isEmpty() { return uxQueueMessagesWaiting(h) == 0; }
bool enqueue(T x, TickType_t maxWait = portMAX_DELAY) { return xQueueSendToBack(h, &x, maxWait) == pdTRUE; } bool enqueue(T x, TickType_t maxWait = portMAX_DELAY)
{
if (reader) {
reader->setInterval(0);
concurrency::mainDelay.interrupt();
}
return xQueueSendToBack(h, &x, maxWait) == pdTRUE;
}
bool enqueueFromISR(T x, BaseType_t *higherPriWoken) { return xQueueSendToBackFromISR(h, &x, higherPriWoken) == pdTRUE; } bool enqueueFromISR(T x, BaseType_t *higherPriWoken)
{
if (reader) {
reader->setInterval(0);
concurrency::mainDelay.interruptFromISR(higherPriWoken);
}
return xQueueSendToBackFromISR(h, &x, higherPriWoken) == pdTRUE;
}
bool dequeue(T *p, TickType_t maxWait = portMAX_DELAY) { return xQueueReceive(h, p, maxWait) == pdTRUE; } bool dequeue(T *p, TickType_t maxWait = portMAX_DELAY) { return xQueueReceive(h, p, maxWait) == pdTRUE; }
bool dequeueFromISR(T *p, BaseType_t *higherPriWoken) { return xQueueReceiveFromISR(h, p, higherPriWoken); } bool dequeueFromISR(T *p, BaseType_t *higherPriWoken) { return xQueueReceiveFromISR(h, p, higherPriWoken); }
/**
* Set a thread that is reading from this queue
* If a message is pushed to this queue that thread will be scheduled to run ASAP.
*
* Note: thread will not be automatically enabled, just have its interval set to 0
*/
void setReader(concurrency::OSThread *t) { reader = t; }
}; };
#else #else
@@ -49,6 +73,7 @@ template <class T> class TypedQueue
template <class T> class TypedQueue template <class T> class TypedQueue
{ {
std::queue<T> q; std::queue<T> q;
concurrency::OSThread *reader = NULL;
public: public:
TypedQueue(int maxElements) {} TypedQueue(int maxElements) {}
@@ -59,6 +84,11 @@ template <class T> class TypedQueue
bool enqueue(T x, TickType_t maxWait = portMAX_DELAY) bool enqueue(T x, TickType_t maxWait = portMAX_DELAY)
{ {
if (reader) {
reader->setInterval(0);
concurrency::mainDelay.interrupt();
}
q.push(x); q.push(x);
return true; return true;
} }
@@ -77,5 +107,7 @@ template <class T> class TypedQueue
} }
// bool dequeueFromISR(T *p, BaseType_t *higherPriWoken) { return xQueueReceiveFromISR(h, p, higherPriWoken); } // bool dequeueFromISR(T *p, BaseType_t *higherPriWoken) { return xQueueReceiveFromISR(h, p, higherPriWoken); }
void setReader(concurrency::OSThread *t) { reader = t; }
}; };
#endif #endif

View File

@@ -121,13 +121,7 @@ void initWifi()
DEBUG_MSG("Not using WIFI\n"); DEBUG_MSG("Not using WIFI\n");
} }
/// Perform idle loop processing required by the wifi layer
void loopWifi()
{
// FIXME, once we have coroutines - just use a coroutine instead of this nasty loopWifi()
if (apiPort)
apiPort->loop();
}
static void initApiServer() static void initApiServer()
{ {

View File

@@ -12,9 +12,6 @@
void initWifi(); void initWifi();
void deinitWifi(); void deinitWifi();
/// Perform idle loop processing required by the wifi layer
void loopWifi();
bool isWifiAvailable(); bool isWifiAvailable();
void handleDNSResponse(); void handleDNSResponse();

View File

@@ -3,16 +3,16 @@
#include "NimbleBluetoothAPI.h" #include "NimbleBluetoothAPI.h"
#include "PhoneAPI.h" #include "PhoneAPI.h"
#include "PowerFSM.h" #include "PowerFSM.h"
#include <WiFi.h>
#include "configuration.h" #include "configuration.h"
#include "esp_bt.h" #include "esp_bt.h"
#include "host/util/util.h" #include "host/util/util.h"
#include "main.h" #include "main.h"
#include "meshwifi/meshwifi.h"
#include "nimble/NimbleDefs.h" #include "nimble/NimbleDefs.h"
#include "services/gap/ble_svc_gap.h" #include "services/gap/ble_svc_gap.h"
#include "services/gatt/ble_svc_gatt.h" #include "services/gatt/ble_svc_gatt.h"
#include <Arduino.h> #include <Arduino.h>
#include "meshwifi/meshwifi.h" #include <WiFi.h>
static bool pinShowing; static bool pinShowing;
@@ -20,14 +20,14 @@ static void startCb(uint32_t pin)
{ {
pinShowing = true; pinShowing = true;
powerFSM.trigger(EVENT_BLUETOOTH_PAIR); powerFSM.trigger(EVENT_BLUETOOTH_PAIR);
screen.startBluetoothPinScreen(pin); screen->startBluetoothPinScreen(pin);
}; };
static void stopCb() static void stopCb()
{ {
if (pinShowing) { if (pinShowing) {
pinShowing = false; pinShowing = false;
screen.stopBluetoothPinScreen(); screen->stopBluetoothPinScreen();
} }
}; };
@@ -533,7 +533,7 @@ void setBluetoothEnable(bool on)
return; return;
} }
*/ */
// shutdown wifi // shutdown wifi
deinitWifi(); deinitWifi();

View File

@@ -1,6 +1,6 @@
#pragma once #pragma once
#include "PowerStatus.h" #include "PowerStatus.h"
#include "concurrency/PeriodicTask.h" #include "concurrency/OSThread.h"
/** /**
* Per @spattinson * Per @spattinson
@@ -15,16 +15,17 @@
#define BAT_MILLIVOLTS_FULL 4100 #define BAT_MILLIVOLTS_FULL 4100
#define BAT_MILLIVOLTS_EMPTY 3500 #define BAT_MILLIVOLTS_EMPTY 3500
class Power : public concurrency::PeriodicTask class Power : private concurrency::OSThread
{ {
public: public:
Observable<const meshtastic::PowerStatus *> newStatus; Observable<const meshtastic::PowerStatus *> newStatus;
Power();
void readPowerStatus(); void readPowerStatus();
void loop();
virtual bool setup(); virtual bool setup();
virtual void doTask(); virtual int32_t runOnce();
void setStatusHandler(meshtastic::PowerStatus *handler) { statusHandler = handler; } void setStatusHandler(meshtastic::PowerStatus *handler) { statusHandler = handler; }
protected: protected:

View File

@@ -151,7 +151,7 @@ void doDeepSleep(uint64_t msecToWake)
notifySleep.notifyObservers(NULL); // also tell the regular sleep handlers notifySleep.notifyObservers(NULL); // also tell the regular sleep handlers
notifyDeepSleep.notifyObservers(NULL); notifyDeepSleep.notifyObservers(NULL);
screen.setOn(false); // datasheet says this will draw only 10ua screen->setOn(false); // datasheet says this will draw only 10ua
nodeDB.saveToDisk(); nodeDB.saveToDisk();