coroutines: wip compiles but does not link

This commit is contained in:
Kevin Hester
2020-10-09 14:16:51 +08:00
parent 10f64590a9
commit 2044427e97
23 changed files with 132 additions and 299 deletions

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

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() uint32_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) : 0;
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

@@ -1,37 +1,45 @@
#pragma once #pragma once
#include "WorkerThread.h" #include "OSThread.h"
namespace concurrency { namespace concurrency
{
/** /**
* @brief A worker thread that waits on a freertos notification * @brief A worker thread that waits on a freertos notification
*/ */
class NotifiedWorkerThread : public WorkerThread class NotifiedWorkerThread : public OSThread
{ {
public: public:
NotifiedWorkerThread(const char *name) : OSThread(name) {}
/** /**
* Notify this thread so it can run * Notify this thread so it can run
*/ */
virtual void notify(uint32_t v = 0, eNotifyAction action = eNoAction) = 0; void notify(uint32_t v, bool overwrite);
/** /**
* Notify from an ISR * Notify from an ISR
* *
* This must be inline or IRAM_ATTR on ESP32 * 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); } void notifyFromISR(BaseType_t *highPriWoken, uint32_t v, bool overwrite) { notify(v, overwrite); }
protected:
/**
* The notification that was most recently used to wake the thread. Read from loop()
*/
uint32_t notification = 0;
/** /**
* A method that should block execution - either waiting ona queue/mutex or a "task notification" * Schedule a notification to fire in delay msecs
*/ */
virtual void block() = 0; void notifyLater(uint32_t delay, uint32_t v, bool overwrite);
protected:
virtual void onNotify(uint32_t notification) = 0;
virtual uint32_t runOnce();
private:
/**
* The notification that was most recently used to wake the thread. Read from runOnce()
*/
uint32_t notification = 0;
}; };
} // namespace concurrency } // namespace concurrency

View File

@@ -4,11 +4,13 @@
#include <stdint.h> #include <stdint.h>
#include "Thread.h" #include "Thread.h"
#include "freertosinc.h" #include "ThreadController.h"
namespace concurrency namespace concurrency
{ {
extern ThreadController mainController, timerController;
/** /**
* @brief Base threading * @brief Base threading
* *
@@ -17,23 +19,32 @@ namespace concurrency
* sleeping the correct amount of time in main * sleeping the correct amount of time in main
* NotifiedWorkerThread set/clears enabled * NotifiedWorkerThread set/clears enabled
* *
* notifyLater should start now - not relative to last start time
* clear notification before calling handler
*
* stopping sleep instantly as soon as an event occurs. * stopping sleep instantly as soon as an event occurs.
* use global functions delayTillWakeEvent(time), doWakeEvent(isInISR) - use freertos mutex or somesuch * use global functions delayTillWakeEvent(time), doWakeEvent(isInISR) - use freertos mutex or somesuch
* *
* have router thread block on its message queue in runOnce
*
* remove lock/lockguard * remove lock/lockguard
*/ */
class OSThread class OSThread : public Thread
{ {
public: ThreadController *controller;
virtual ~OSThread() {}
// uint32_t getStackHighwaterMark() { return uxTaskGetStackHighWaterMark(taskHandle); } public:
OSThread(const char *name, uint32_t period = 0, ThreadController *controller = &mainController);
virtual ~OSThread();
protected: protected:
/** /**
* The method that will be called each time our thread gets a chance to run * The method that will be called each time our thread gets a chance to run
*
* Returns desired period for next invocation (or 0 for no change)
*/ */
virtual void runOnce() = 0; virtual uint32_t runOnce() = 0;
}; };
} // namespace concurrency } // 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)(); uint32_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, uint32_t (*_callback)()) : OSThread(name), callback(_callback) {}
protected: protected:
void doTask() { uint32_t runOnce() { return callback(); }
uint32_t p = callback();
setPeriod(p);
}
}; };
} // namespace concurrency } // 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,54 +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
{
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();
protected:
virtual void doTask() = 0;
};
} // 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,25 +0,0 @@
#pragma once
#include "OSThread.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 OSThread
{
protected:
/**
* Return true if this thread is ready to run - either waiting ona queue/mutex or a "task notification"
*/
virtual bool shouldRun() = 0;
virtual void loop() = 0;
};
} // namespace concurrency

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

@@ -561,7 +561,7 @@ 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) {}
void Screen::handleSetOn(bool on) void Screen::handleSetOn(bool on)
{ {
@@ -573,9 +573,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 +586,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,12 +643,12 @@ void Screen::setup()
nodeStatusObserver.observe(&nodeStatus->onNewStatus); nodeStatusObserver.observe(&nodeStatus->onNewStatus);
} }
void Screen::doTask() uint32_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 0;
} }
// Process incoming commands. // Process incoming commands.
@@ -684,8 +685,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 +712,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 +802,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");
@@ -1062,7 +1063,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; uint32_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,7 @@
// #include "debug.h" // #include "debug.h"
#include "RTC.h" #include "RTC.h"
#include "SPILock.h" #include "SPILock.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"
@@ -134,7 +112,7 @@ static uint32_t ledBlinker()
return powerStatus->getIsCharging() ? 1000 : (ledOn ? 2 : 1000); return powerStatus->getIsCharging() ? 1000 : (ledOn ? 2 : 1000);
} }
concurrency::Periodic ledPeriodic(ledBlinker); concurrency::Periodic ledPeriodic("Blink", ledBlinker);
// Prepare for button presses // Prepare for button presses
#ifdef BUTTON_PIN #ifdef BUTTON_PIN
@@ -203,8 +181,6 @@ void setup()
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));
@@ -378,11 +354,8 @@ void loop()
if (gps) if (gps)
gps->loop(); // FIXME, remove from main, instead block on read gps->loop(); // FIXME, remove from main, instead block on read
router.loop();
powerFSM.run_machine(); powerFSM.run_machine();
service.loop();
concurrency::periodicScheduler.loop();
// axpDebugOutput.loop(); // axpDebugOutput.loop();
#ifdef DEBUG_PORT #ifdef DEBUG_PORT
@@ -394,9 +367,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();

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

@@ -56,7 +56,7 @@ static uint32_t sendOwnerCb()
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("SendOwner", sendOwnerCb);
MeshService::MeshService() : toPhoneQueue(MAX_RX_TOPHONE) MeshService::MeshService() : toPhoneQueue(MAX_RX_TOPHONE)
{ {
@@ -65,7 +65,6 @@ MeshService::MeshService() : toPhoneQueue(MAX_RX_TOPHONE)
void MeshService::init() void MeshService::init()
{ {
sendOwnerPeriod.setup();
nodeDB.init(); nodeDB.init();
if (gps) if (gps)
@@ -227,7 +226,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
@@ -285,7 +284,8 @@ void MeshService::sendOurPosition(NodeNum dest, bool wantReplies)
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);
} }

View File

@@ -91,7 +91,7 @@ void printPacket(const char *prefix, const MeshPacket *p)
DEBUG_MSG(")\n"); DEBUG_MSG(")\n");
} }
RadioInterface::RadioInterface() RadioInterface::RadioInterface() : NotifiedWorkerThread("RadioIf")
{ {
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

@@ -117,8 +117,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,7 +19,7 @@ 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) : module(cs, irq, rst, busy, spi, spiSettings), iface(_iface)
{ {
instance = this; instance = this;
} }
@@ -41,7 +41,6 @@ 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, eSetValueWithOverwrite);
@@ -191,10 +190,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();
@@ -229,25 +226,15 @@ 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); DEBUG_MSG("delaying %u\n", delay);
setPeriod(delay); notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
} }
} }

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
{ {
/// 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
@@ -195,7 +193,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

@@ -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,10 @@ 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 uint32_t runOnce()
{ {
doRetransmissions(); doRetransmissions();
FloodingRouter::loop(); return FloodingRouter::runOnce();
} }
protected: protected:

View File

@@ -34,7 +34,7 @@ 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
@@ -47,12 +47,14 @@ Router::Router() : fromRadioQueue(MAX_RX_FROMRADIO)
* 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() uint32_t Router::runOnce()
{ {
MeshPacket *mp; MeshPacket *mp;
while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL) { while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL) {
perhapsHandleReceived(mp); perhapsHandleReceived(mp);
} }
return 0;
} }
/// 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 uint32_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

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 uint32_t runOnce();
void setStatusHandler(meshtastic::PowerStatus *handler) { statusHandler = handler; } void setStatusHandler(meshtastic::PowerStatus *handler) { statusHandler = handler; }
protected: protected: