Merge branch 'master' into gps-fixedposboot

This commit is contained in:
Ben Meadors
2023-01-21 20:34:41 -06:00
committed by GitHub
318 changed files with 7783 additions and 7862 deletions

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "BluetoothCommon.h"
#include "configuration.h"
// NRF52 wants these constants as byte arrays
// Generated here https://yupana-engineering.com/online-uuid-to-c-array-converter - but in REVERSE BYTE ORDER

View File

@@ -1,26 +1,24 @@
#include "configuration.h"
#include "FSCommon.h"
#include "configuration.h"
#ifdef HAS_SDCARD
#include <SPI.h>
#include <SD.h>
#include <SPI.h>
#ifdef SDCARD_USE_SPI1
#ifdef SDCARD_USE_SPI1
SPIClass SPI1(HSPI);
#define SDHandler SPI1
#endif
#endif // HAS_SDCARD
#endif //HAS_SDCARD
bool copyFile(const char* from, const char* to)
bool copyFile(const char *from, const char *to)
{
#ifdef FSCom
unsigned char cbuffer[16];
File f1 = FSCom.open(from, FILE_O_READ);
if (!f1){
if (!f1) {
LOG_ERROR("Failed to open source file %s\n", from);
return false;
}
@@ -30,55 +28,55 @@ bool copyFile(const char* from, const char* to)
LOG_ERROR("Failed to open destination file %s\n", to);
return false;
}
while (f1.available() > 0) {
byte i = f1.read(cbuffer, 16);
f2.write(cbuffer, i);
}
f2.close();
f1.close();
return true;
#endif
}
bool renameFile(const char* pathFrom, const char* pathTo)
bool renameFile(const char *pathFrom, const char *pathTo)
{
#ifdef FSCom
#ifdef ARCH_ESP32
// rename was fixed for ESP32 IDF LittleFS in April
return FSCom.rename(pathFrom, pathTo);
#else
if (copyFile(pathFrom, pathTo) && FSCom.remove(pathFrom) ) {
if (copyFile(pathFrom, pathTo) && FSCom.remove(pathFrom)) {
return true;
} else{
} else {
return false;
}
#endif
#endif
}
void listDir(const char * dirname, uint8_t levels, boolean del = false)
void listDir(const char *dirname, uint8_t levels, boolean del = false)
{
#ifdef FSCom
#if (defined(ARCH_ESP32) || defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
char buffer[255];
#endif
File root = FSCom.open(dirname, FILE_O_READ);
if(!root){
if (!root) {
return;
}
if(!root.isDirectory()){
if (!root.isDirectory()) {
return;
}
File file = root.openNextFile();
while(file){
if(file.isDirectory() && !String(file.name()).endsWith(".")) {
if(levels){
while (file) {
if (file.isDirectory() && !String(file.name()).endsWith(".")) {
if (levels) {
#ifdef ARCH_ESP32
listDir(file.path(), levels -1, del);
if(del) {
listDir(file.path(), levels - 1, del);
if (del) {
LOG_DEBUG("Removing %s\n", file.path());
strncpy(buffer, file.path(), sizeof(buffer));
file.close();
@@ -87,33 +85,33 @@ void listDir(const char * dirname, uint8_t levels, boolean del = false)
file.close();
}
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
listDir(file.name(), levels -1, del);
if(del) {
listDir(file.name(), levels - 1, del);
if (del) {
LOG_DEBUG("Removing %s\n", file.name());
strncpy(buffer, file.name(), sizeof(buffer));
file.close();
FSCom.rmdir(buffer);
} else {
file.close();
}
}
#else
listDir(file.name(), levels -1, del);
listDir(file.name(), levels - 1, del);
file.close();
#endif
}
} else {
#ifdef ARCH_ESP32
if(del) {
if (del) {
LOG_DEBUG("Deleting %s\n", file.path());
strncpy(buffer, file.path(), sizeof(buffer));
file.close();
FSCom.remove(buffer);
} else {
LOG_DEBUG(" %s (%i Bytes)\n", file.path(), file.size());
LOG_DEBUG(" %s (%i Bytes)\n", file.path(), file.size());
file.close();
}
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
if(del) {
if (del) {
LOG_DEBUG("Deleting %s\n", file.name());
strncpy(buffer, file.name(), sizeof(buffer));
file.close();
@@ -125,12 +123,12 @@ void listDir(const char * dirname, uint8_t levels, boolean del = false)
#else
LOG_DEBUG(" %s (%i Bytes)\n", file.name(), file.size());
file.close();
#endif
#endif
}
file = root.openNextFile();
}
#ifdef ARCH_ESP32
if(del) {
#ifdef ARCH_ESP32
if (del) {
LOG_DEBUG("Removing %s\n", root.path());
strncpy(buffer, root.path(), sizeof(buffer));
root.close();
@@ -139,7 +137,7 @@ void listDir(const char * dirname, uint8_t levels, boolean del = false)
root.close();
}
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
if(del) {
if (del) {
LOG_DEBUG("Removing %s\n", root.name());
strncpy(buffer, root.name(), sizeof(buffer));
root.close();
@@ -153,7 +151,7 @@ void listDir(const char * dirname, uint8_t levels, boolean del = false)
#endif
}
void rmDir(const char * dirname)
void rmDir(const char *dirname)
{
#ifdef FSCom
#if (defined(ARCH_ESP32) || defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
@@ -168,8 +166,7 @@ void rmDir(const char * dirname)
void fsInit()
{
#ifdef FSCom
if (!FSBegin())
{
if (!FSBegin()) {
LOG_ERROR("Filesystem mount Failed.\n");
// assert(0); This auto-formats the partition, so no need to fail here.
}
@@ -182,7 +179,6 @@ void fsInit()
#endif
}
void setupSDCard()
{
#ifdef HAS_SDCARD
@@ -190,12 +186,12 @@ void setupSDCard()
if (!SD.begin(SDCARD_CS, SDHandler)) {
LOG_DEBUG("No SD_MMC card detected\n");
return ;
return;
}
uint8_t cardType = SD.cardType();
if (cardType == CARD_NONE) {
LOG_DEBUG("No SD_MMC card attached\n");
return ;
return;
}
LOG_DEBUG("SD_MMC Card Type: ");
if (cardType == CARD_MMC) {
@@ -214,6 +210,3 @@ void setupSDCard()
LOG_DEBUG("Used space: %llu MB\n", SD.usedBytes() / (1024 * 1024));
#endif
}

View File

@@ -40,8 +40,8 @@ using namespace Adafruit_LittleFS_Namespace;
#endif
void fsInit();
bool copyFile(const char* from, const char* to);
bool renameFile(const char* pathFrom, const char* pathTo);
void listDir(const char * dirname, uint8_t levels, boolean del);
void rmDir(const char * dirname);
bool copyFile(const char *from, const char *to);
bool renameFile(const char *pathFrom, const char *pathTo);
void listDir(const char *dirname, uint8_t levels, boolean del);
void rmDir(const char *dirname);
void setupSDCard();

View File

@@ -20,15 +20,15 @@ class GPSStatus : public Status
bool hasLock = false; // default to false, until we complete our first read
bool isConnected = false; // Do we have a GPS we are talking to
bool isPowerSaving = false; //Are we in power saving state
bool isPowerSaving = false; // Are we in power saving state
Position p = Position_init_default;
meshtastic_Position p = meshtastic_Position_init_default;
public:
GPSStatus() { statusType = STATUS_TYPE_GPS; }
// preferred method
GPSStatus(bool hasLock, bool isConnected, bool isPowerSaving, const Position &pos) : Status()
GPSStatus(bool hasLock, bool isConnected, bool isPowerSaving, const meshtastic_Position &pos) : Status()
{
this->hasLock = hasLock;
this->isConnected = isConnected;
@@ -47,7 +47,7 @@ class GPSStatus : public Status
bool getIsConnected() const { return isConnected; }
bool getIsPowerSaving() const { return isPowerSaving;}
bool getIsPowerSaving() const { return isPowerSaving; }
int32_t getLatitude() const
{
@@ -55,7 +55,7 @@ class GPSStatus : public Status
#ifdef GPS_EXTRAVERBOSE
LOG_WARN("Using fixed latitude\n");
#endif
NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
meshtastic_NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
return node->position.latitude_i;
} else {
return p.latitude_i;
@@ -68,7 +68,7 @@ class GPSStatus : public Status
#ifdef GPS_EXTRAVERBOSE
LOG_WARN("Using fixed longitude\n");
#endif
NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
meshtastic_NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
return node->position.longitude_i;
} else {
return p.longitude_i;
@@ -81,29 +81,38 @@ class GPSStatus : public Status
#ifdef GPS_EXTRAVERBOSE
LOG_WARN("Using fixed altitude\n");
#endif
NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
meshtastic_NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
return node->position.altitude;
} else {
return p.altitude;
}
}
uint32_t getDOP() const { return p.PDOP; }
uint32_t getDOP() const
{
return p.PDOP;
}
uint32_t getHeading() const { return p.ground_track; }
uint32_t getHeading() const
{
return p.ground_track;
}
uint32_t getNumSatellites() const { return p.sats_in_view; }
uint32_t getNumSatellites() const
{
return p.sats_in_view;
}
bool matches(const GPSStatus *newStatus) const
{
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("GPSStatus.match() new pos@%x to old pos@%x\n", newStatus->p.pos_timestamp, p.pos_timestamp);
#endif
return (newStatus->hasLock != hasLock || newStatus->isConnected != isConnected || newStatus->isPowerSaving !=isPowerSaving ||
newStatus->p.latitude_i != p.latitude_i || newStatus->p.longitude_i != p.longitude_i ||
newStatus->p.altitude != p.altitude || newStatus->p.altitude_hae != p.altitude_hae ||
newStatus->p.PDOP != p.PDOP || newStatus->p.ground_track != p.ground_track ||
newStatus->p.ground_speed != p.ground_speed ||
return (newStatus->hasLock != hasLock || newStatus->isConnected != isConnected ||
newStatus->isPowerSaving != isPowerSaving || newStatus->p.latitude_i != p.latitude_i ||
newStatus->p.longitude_i != p.longitude_i || newStatus->p.altitude != p.altitude ||
newStatus->p.altitude_hae != p.altitude_hae || newStatus->p.PDOP != p.PDOP ||
newStatus->p.ground_track != p.ground_track || newStatus->p.ground_speed != p.ground_speed ||
newStatus->p.sats_in_view != p.sats_in_view);
}

View File

@@ -1,83 +1,68 @@
#pragma once
#include <Arduino.h>
#include "Status.h"
#include "configuration.h"
#include <Arduino.h>
namespace meshtastic {
namespace meshtastic
{
/// Describes the state of the NodeDB system.
class NodeStatus : public Status
/// Describes the state of the NodeDB system.
class NodeStatus : public Status
{
private:
CallbackObserver<NodeStatus, const NodeStatus *> statusObserver =
CallbackObserver<NodeStatus, const NodeStatus *>(this, &NodeStatus::updateStatus);
uint8_t numOnline = 0;
uint8_t numTotal = 0;
uint8_t lastNumTotal = 0;
public:
bool forceUpdate = false;
NodeStatus() { statusType = STATUS_TYPE_NODE; }
NodeStatus(uint8_t numOnline, uint8_t numTotal, bool forceUpdate = false) : Status()
{
this->forceUpdate = forceUpdate;
this->numOnline = numOnline;
this->numTotal = numTotal;
}
NodeStatus(const NodeStatus &);
NodeStatus &operator=(const NodeStatus &);
private:
CallbackObserver<NodeStatus, const NodeStatus *> statusObserver = CallbackObserver<NodeStatus, const NodeStatus *>(this, &NodeStatus::updateStatus);
void observe(Observable<const NodeStatus *> *source) { statusObserver.observe(source); }
uint8_t numOnline = 0;
uint8_t numTotal = 0;
uint8_t getNumOnline() const { return numOnline; }
uint8_t lastNumTotal = 0;
uint8_t getNumTotal() const { return numTotal; }
public:
bool forceUpdate = false;
uint8_t getLastNumTotal() const { return lastNumTotal; }
NodeStatus() {
statusType = STATUS_TYPE_NODE;
}
NodeStatus( uint8_t numOnline, uint8_t numTotal, bool forceUpdate = false ) : Status()
bool matches(const NodeStatus *newStatus) const
{
return (newStatus->getNumOnline() != numOnline || newStatus->getNumTotal() != numTotal);
}
int updateStatus(const NodeStatus *newStatus)
{
// Only update the status if values have actually changed
lastNumTotal = numTotal;
bool isDirty;
{
this->forceUpdate = forceUpdate;
this->numOnline = numOnline;
this->numTotal = numTotal;
isDirty = matches(newStatus);
initialized = true;
numOnline = newStatus->getNumOnline();
numTotal = newStatus->getNumTotal();
}
NodeStatus(const NodeStatus &);
NodeStatus &operator=(const NodeStatus &);
void observe(Observable<const NodeStatus *> *source)
{
statusObserver.observe(source);
if (isDirty || newStatus->forceUpdate) {
LOG_DEBUG("Node status update: %d online, %d total\n", numOnline, numTotal);
onNewStatus.notifyObservers(this);
}
return 0;
}
};
uint8_t getNumOnline() const
{
return numOnline;
}
uint8_t getNumTotal() const
{
return numTotal;
}
uint8_t getLastNumTotal() const
{
return lastNumTotal;
}
bool matches(const NodeStatus *newStatus) const
{
return (
newStatus->getNumOnline() != numOnline ||
newStatus->getNumTotal() != numTotal
);
}
int updateStatus(const NodeStatus *newStatus) {
// Only update the status if values have actually changed
lastNumTotal = numTotal;
bool isDirty;
{
isDirty = matches(newStatus);
initialized = true;
numOnline = newStatus->getNumOnline();
numTotal = newStatus->getNumTotal();
}
if(isDirty || newStatus->forceUpdate) {
LOG_DEBUG("Node status update: %d online, %d total\n", numOnline, numTotal);
onNewStatus.notifyObservers(this);
}
return 0;
}
};
}
} // namespace meshtastic
extern meshtastic::NodeStatus *nodeStatus;

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "OSTimer.h"
#include "configuration.h"
/**
* Schedule a callback to run. The callback must _not_ block, though it is called from regular thread level (not ISR)

View File

@@ -1,3 +1,2 @@
#include "configuration.h"
#include "Observer.h"
#include "configuration.h"

View File

@@ -10,7 +10,7 @@ template <class T> class Observable;
*/
template <class T> class Observer
{
std::list<Observable<T> *> observed;
std::list<Observable<T> *> observed;
public:
virtual ~Observer();
@@ -87,7 +87,7 @@ template <class T> class Observable
template <class T> Observer<T>::~Observer()
{
for (typename std::list<Observable<T> *>::const_iterator iterator = observed.begin(); iterator != observed.end();
++iterator) {
++iterator) {
(*iterator)->removeObserver(this);
}
observed.clear();

View File

@@ -1,16 +1,16 @@
#include "power.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "buzz/buzz.h"
#include "configuration.h"
#include "main.h"
#include "sleep.h"
#include "utils.h"
#include "buzz/buzz.h"
#ifdef HAS_PMU
#include "XPowersLibInterface.hpp"
#include "XPowersAXP2101.tpp"
#include "XPowersAXP192.tpp"
#include "XPowersAXP2101.tpp"
#include "XPowersLibInterface.hpp"
XPowersLibInterface *PMU = NULL;
#else
// Copy of the base class defined in axp20x.h.
@@ -108,20 +108,20 @@ class AnalogBatteryLevel : public HasBatteryLevel
#ifdef BATTERY_PIN
// Override variant or default ADC_MULTIPLIER if we have the override pref
float operativeAdcMultiplier = config.power.adc_multiplier_override > 0
? config.power.adc_multiplier_override
: ADC_MULTIPLIER;
float operativeAdcMultiplier =
config.power.adc_multiplier_override > 0 ? config.power.adc_multiplier_override : ADC_MULTIPLIER;
// Do not call analogRead() often.
const uint32_t min_read_interval = 5000;
if (millis() - last_read_time_ms > min_read_interval) {
last_read_time_ms = millis();
//Set the number of samples, it has an effect of increasing sensitivity, especially in complex electromagnetic environment.
// Set the number of samples, it has an effect of increasing sensitivity, especially in complex electromagnetic
// environment.
uint32_t raw = 0;
for(uint32_t i=0; i<BATTERY_SENSE_SAMPLES; i++){
for (uint32_t i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
raw += analogRead(BATTERY_PIN);
}
raw = raw/BATTERY_SENSE_SAMPLES;
raw = raw / BATTERY_SENSE_SAMPLES;
float scaled;
#ifndef VBAT_RAW_TO_SCALED
@@ -143,15 +143,24 @@ class AnalogBatteryLevel : public HasBatteryLevel
/**
* return true if there is a battery installed in this unit
*/
virtual bool isBatteryConnect() override { return getBatteryPercent() != -1; }
virtual bool isBatteryConnect() override
{
return getBatteryPercent() != -1;
}
/// If we see a battery voltage higher than physics allows - assume charger is pumping
/// in power
virtual bool isVbusIn() override { return getBattVoltage() > chargingVolt; }
virtual bool isVbusIn() override
{
return getBattVoltage() > chargingVolt;
}
/// Assume charging if we have a battery and external power is connected.
/// we can't be smart enough to say 'full'?
virtual bool isCharging() override { return isBatteryConnect() && isVbusIn(); }
virtual bool isCharging() override
{
return isBatteryConnect() && isVbusIn();
}
private:
/// If we see a battery voltage higher than physics allows - assume charger is pumping
@@ -159,16 +168,16 @@ class AnalogBatteryLevel : public HasBatteryLevel
#ifndef BAT_FULLVOLT
#define BAT_FULLVOLT 4200
#endif
#endif
#ifndef BAT_EMPTYVOLT
#define BAT_EMPTYVOLT 3270
#endif
#endif
#ifndef BAT_CHARGINGVOLT
#define BAT_CHARGINGVOLT 4210
#endif
#endif
#ifndef BAT_NOBATVOLT
#define BAT_NOBATVOLT 2230
#endif
#endif
/// For heltecs with no battery connected, the measured voltage is 2204, so raising to 2230 from 2100
const float fullVolt = BAT_FULLVOLT, emptyVolt = BAT_EMPTYVOLT, chargingVolt = BAT_CHARGINGVOLT, noBatVolt = BAT_NOBATVOLT;
@@ -238,12 +247,12 @@ void Power::shutdown()
{
screen->setOn(false);
#if defined(USE_EINK) && defined(PIN_EINK_EN)
digitalWrite(PIN_EINK_EN, LOW); //power off backlight first
digitalWrite(PIN_EINK_EN, LOW); // power off backlight first
#endif
#ifdef HAS_PMU
LOG_INFO("Shutting down\n");
if(PMU) {
if (PMU) {
PMU->setChargingLedMode(XPOWERS_CHG_LED_OFF);
PMU->shutdown();
}
@@ -290,15 +299,16 @@ void Power::readPowerStatus()
if (lastheap != ESP.getFreeHeap()) {
LOG_DEBUG("Threads running:");
int running = 0;
for(int i = 0; i < MAX_THREADS; i++){
for (int i = 0; i < MAX_THREADS; i++) {
auto thread = concurrency::mainController.get(i);
if((thread != nullptr) && (thread->enabled)) {
if ((thread != nullptr) && (thread->enabled)) {
LOG_DEBUG(" %s", thread->ThreadName.c_str());
running++;
}
}
LOG_DEBUG("\n");
LOG_DEBUG("Heap status: %d/%d bytes free (%d), running %d/%d threads\n", ESP.getFreeHeap(), ESP.getHeapSize(), ESP.getFreeHeap() - lastheap, running, concurrency::mainController.size(false));
LOG_DEBUG("Heap status: %d/%d bytes free (%d), running %d/%d threads\n", ESP.getFreeHeap(), ESP.getHeapSize(),
ESP.getFreeHeap() - lastheap, running, concurrency::mainController.size(false));
lastheap = ESP.getFreeHeap();
}
#endif
@@ -312,7 +322,7 @@ void Power::readPowerStatus()
LOG_DEBUG("Warning RAK4631 Low voltage counter: %d/10\n", low_voltage_counter);
if (low_voltage_counter > 10) {
// We can't trigger deep sleep on NRF52, it's freezing the board
//powerFSM.trigger(EVENT_LOW_BATTERY);
// powerFSM.trigger(EVENT_LOW_BATTERY);
LOG_DEBUG("Low voltage detected, but not triggering deep sleep\n");
}
} else {
@@ -338,11 +348,11 @@ int32_t Power::runOnce()
#ifdef HAS_PMU
// WE no longer use the IRQ line to wake the CPU (due to false wakes from sleep), but we do poll
// the IRQ status by reading the registers over I2C
if(PMU) {
if (PMU) {
PMU->getIrqStatus();
if(PMU->isVbusRemoveIrq()){
if (PMU->isVbusRemoveIrq()) {
LOG_INFO("USB unplugged\n");
powerFSM.trigger(EVENT_POWER_DISCONNECTED);
}
@@ -388,24 +398,24 @@ int32_t Power::runOnce()
share the same i2c bus, instead use ssd1306 sleep mode DCDC2 -> unused DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this on!) LDO1
30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of days), can
not be turned off LDO2 200mA -> LORA LDO3 200mA -> GPS
*
*
*/
bool Power::axpChipInit()
{
#ifdef HAS_PMU
TwoWire * w = NULL;
TwoWire *w = NULL;
// Use macro to distinguish which wire is used by PMU
#ifdef PMU_USE_WIRE1
w = &Wire1;
w = &Wire1;
#else
w = &Wire;
w = &Wire;
#endif
/**
* It is not necessary to specify the wire pin,
* It is not necessary to specify the wire pin,
* just input the wire, because the wire has been initialized in main.cpp
*/
if (!PMU) {
@@ -431,11 +441,11 @@ bool Power::axpChipInit()
}
if (!PMU) {
/*
* In XPowersLib, if the XPowersAXPxxx object is released, Wire.end() will be called at the same time.
* In order not to affect other devices, if the initialization of the PMU fails, Wire needs to be re-initialized once,
* if there are multiple devices sharing the bus.
* * */
/*
* In XPowersLib, if the XPowersAXPxxx object is released, Wire.end() will be called at the same time.
* In order not to affect other devices, if the initialization of the PMU fails, Wire needs to be re-initialized once,
* if there are multiple devices sharing the bus.
* * */
#ifndef PMU_USE_WIRE1
w->begin(I2C_SDA, I2C_SCL);
#endif
@@ -445,48 +455,45 @@ bool Power::axpChipInit()
batteryLevel = PMU;
if (PMU->getChipModel() == XPOWERS_AXP192) {
// lora radio power channel
PMU->setPowerChannelVoltage(XPOWERS_LDO2, 3300);
PMU->enablePowerOutput(XPOWERS_LDO2);
// oled module power channel,
// disable it will cause abnormal communication between boot and AXP power supply,
// disable it will cause abnormal communication between boot and AXP power supply,
// do not turn it off
PMU->setPowerChannelVoltage(XPOWERS_DCDC1, 3300);
// enable oled power
PMU->enablePowerOutput(XPOWERS_DCDC1);
// gnss module power channel - now turned on in setGpsPower
PMU->setPowerChannelVoltage(XPOWERS_LDO3, 3300);
// PMU->enablePowerOutput(XPOWERS_LDO3);
//protected oled power source
// protected oled power source
PMU->setProtectedChannel(XPOWERS_DCDC1);
//protected esp32 power source
// protected esp32 power source
PMU->setProtectedChannel(XPOWERS_DCDC3);
//disable not use channel
// disable not use channel
PMU->disablePowerOutput(XPOWERS_DCDC2);
//disable all axp chip interrupt
// disable all axp chip interrupt
PMU->disableIRQ(XPOWERS_AXP192_ALL_IRQ);
// Set constant current charging current
PMU->setChargerConstantCurr(XPOWERS_AXP192_CHG_CUR_450MA);
//Set up the charging voltage
// Set up the charging voltage
PMU->setChargeTargetVoltage(XPOWERS_AXP192_CHG_VOL_4V2);
} else if (PMU->getChipModel() == XPOWERS_AXP2101) {
// t-beam s3 core
// t-beam s3 core
/**
* gnss module power channel
* gnss module power channel
* The default ALDO4 is off, you need to turn on the GNSS power first, otherwise it will be invalid during initialization
*/
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
@@ -496,51 +503,50 @@ bool Power::axpChipInit()
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
PMU->enablePowerOutput(XPOWERS_ALDO3);
// m.2 interface
// m.2 interface
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
PMU->enablePowerOutput(XPOWERS_DCDC3);
/**
* ALDO2 cannot be turned off.
* It is a necessary condition for sensor communication.
* It must be turned on to properly access the sensor and screen
* It is also responsible for the power supply of PCF8563
*/
* ALDO2 cannot be turned off.
* It is a necessary condition for sensor communication.
* It must be turned on to properly access the sensor and screen
* It is also responsible for the power supply of PCF8563
*/
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
PMU->enablePowerOutput(XPOWERS_ALDO2);
// 6-axis , magnetometer ,bme280 , oled screen power channel
// 6-axis , magnetometer ,bme280 , oled screen power channel
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
PMU->enablePowerOutput(XPOWERS_ALDO1);
// sdcard power channle
// sdcard power channle
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
PMU->enablePowerOutput(XPOWERS_BLDO1);
// PMU->setPowerChannelVoltage(XPOWERS_DCDC4, 3300);
// PMU->enablePowerOutput(XPOWERS_DCDC4);
//not use channel
PMU->disablePowerOutput(XPOWERS_DCDC2); //not elicited
PMU->disablePowerOutput(XPOWERS_DCDC5); //not elicited
PMU->disablePowerOutput(XPOWERS_DLDO1); //Invalid power channel, it does not exist
PMU->disablePowerOutput(XPOWERS_DLDO2); //Invalid power channel, it does not exist
// not use channel
PMU->disablePowerOutput(XPOWERS_DCDC2); // not elicited
PMU->disablePowerOutput(XPOWERS_DCDC5); // not elicited
PMU->disablePowerOutput(XPOWERS_DLDO1); // Invalid power channel, it does not exist
PMU->disablePowerOutput(XPOWERS_DLDO2); // Invalid power channel, it does not exist
PMU->disablePowerOutput(XPOWERS_VBACKUP);
//disable all axp chip interrupt
// disable all axp chip interrupt
PMU->disableIRQ(XPOWERS_AXP2101_ALL_IRQ);
//Set the constant current charging current of AXP2101, temporarily use 500mA by default
// Set the constant current charging current of AXP2101, temporarily use 500mA by default
PMU->setChargerConstantCurr(XPOWERS_AXP2101_CHG_CUR_500MA);
//Set up the charging voltage
// Set up the charging voltage
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V2);
}
PMU->clearIrqStatus();
// TBeam1.1 /T-Beam S3-Core has no external TS detection,
// TBeam1.1 /T-Beam S3-Core has no external TS detection,
// it needs to be disabled, otherwise it will cause abnormal charging
PMU->disableTSPinMeasure();
@@ -550,40 +556,52 @@ bool Power::axpChipInit()
LOG_DEBUG("=======================================================================\n");
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
LOG_DEBUG("DC1 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
LOG_DEBUG("DC1 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
}
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
LOG_DEBUG("DC2 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
LOG_DEBUG("DC2 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
}
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
LOG_DEBUG("DC3 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
LOG_DEBUG("DC3 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
}
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
LOG_DEBUG("DC4 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
LOG_DEBUG("DC4 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
}
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
LOG_DEBUG("LDO2 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
LOG_DEBUG("LDO2 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_LDO2));
}
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
LOG_DEBUG("LDO3 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
LOG_DEBUG("LDO3 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_LDO3));
}
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
LOG_DEBUG("ALDO1: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
LOG_DEBUG("ALDO1: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
}
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
LOG_DEBUG("ALDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
LOG_DEBUG("ALDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
}
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
LOG_DEBUG("ALDO3: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
LOG_DEBUG("ALDO3: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
}
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
LOG_DEBUG("ALDO4: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
LOG_DEBUG("ALDO4: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
}
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
LOG_DEBUG("BLDO1: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
LOG_DEBUG("BLDO1: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
}
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
LOG_DEBUG("BLDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
LOG_DEBUG("BLDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-",
PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
}
LOG_DEBUG("=======================================================================\n");
@@ -597,30 +615,29 @@ bool Power::axpChipInit()
PMU->setSysPowerDownVoltage(2600);
#endif
#ifdef PMU_IRQ
uint64_t pmuIrqMask = 0;
uint64_t pmuIrqMask = 0;
if (PMU->getChipModel() == XPOWERS_AXP192) {
pmuIrqMask = XPOWERS_AXP192_VBUS_INSERT_IRQ | XPOWERS_AXP192_BAT_INSERT_IRQ | XPOWERS_AXP192_PKEY_SHORT_IRQ;
} else if (PMU->getChipModel() == XPOWERS_AXP2101) {
pmuIrqMask = XPOWERS_AXP2101_VBUS_INSERT_IRQ | XPOWERS_AXP2101_BAT_INSERT_IRQ | XPOWERS_AXP2101_PKEY_SHORT_IRQ;
}
if (PMU->getChipModel() == XPOWERS_AXP192) {
pmuIrqMask = XPOWERS_AXP192_VBUS_INSERT_IRQ | XPOWERS_AXP192_BAT_INSERT_IRQ | XPOWERS_AXP192_PKEY_SHORT_IRQ;
} else if (PMU->getChipModel() == XPOWERS_AXP2101) {
pmuIrqMask = XPOWERS_AXP2101_VBUS_INSERT_IRQ | XPOWERS_AXP2101_BAT_INSERT_IRQ | XPOWERS_AXP2101_PKEY_SHORT_IRQ;
}
pinMode(PMU_IRQ, INPUT);
attachInterrupt(
PMU_IRQ, [] { pmu_irq = true; }, FALLING);
pinMode(PMU_IRQ, INPUT);
attachInterrupt(
PMU_IRQ, [] { pmu_irq = true; }, FALLING);
// we do not look for AXPXXX_CHARGING_FINISHED_IRQ & AXPXXX_CHARGING_IRQ because it occurs repeatedly while there is
// no battery also it could cause inadvertent waking from light sleep just because the battery filled
// we don't look for AXPXXX_BATT_REMOVED_IRQ because it occurs repeatedly while no battery installed
// we don't look at AXPXXX_VBUS_REMOVED_IRQ because we don't have anything hooked to vbus
PMU->enableIRQ(pmuIrqMask);
// we do not look for AXPXXX_CHARGING_FINISHED_IRQ & AXPXXX_CHARGING_IRQ because it occurs repeatedly while there is
// no battery also it could cause inadvertent waking from light sleep just because the battery filled
// we don't look for AXPXXX_BATT_REMOVED_IRQ because it occurs repeatedly while no battery installed
// we don't look at AXPXXX_VBUS_REMOVED_IRQ because we don't have anything hooked to vbus
PMU->enableIRQ(pmuIrqMask);
PMU->clearIrqStatus();
PMU->clearIrqStatus();
#endif /*PMU_IRQ*/
readPowerStatus();
readPowerStatus();
pmu_found = true;

View File

@@ -11,12 +11,12 @@
/// Should we behave as if we have AC power now?
static bool isPowered()
{
// Circumvent the battery sensing logic and assumes constant power if no battery pin or power mgmt IC
#if !defined(BATTERY_PIN) && !defined(HAS_AXP192) && !defined(HAS_AXP2101)
return true;
#endif
// Circumvent the battery sensing logic and assumes constant power if no battery pin or power mgmt IC
#if !defined(BATTERY_PIN) && !defined(HAS_AXP192) && !defined(HAS_AXP2101)
return true;
#endif
bool isRouter = (config.device.role == Config_DeviceConfig_Role_ROUTER ? 1 : 0);
bool isRouter = (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER ? 1 : 0);
// If we are not a router and we already have AC power go to POWER state after init, otherwise go to ON
// We assume routers might be powered all the time, but from a low current (solar) source
@@ -199,7 +199,8 @@ static void onEnter()
uint32_t now = millis();
if ((now - lastPingMs) > 30 * 1000) { // if more than a minute since our last press, ask node we are looking at to update their state
if ((now - lastPingMs) >
30 * 1000) { // if more than a minute since our last press, ask node we are looking at to update their state
if (displayedNodeNum)
service.sendNetworkPing(displayedNodeNum, true); // Refresh the currently displayed node
lastPingMs = now;
@@ -237,7 +238,7 @@ Fsm powerFSM(&stateBOOT);
void PowerFSM_setup()
{
bool isRouter = (config.device.role == Config_DeviceConfig_Role_ROUTER ? 1 : 0);
bool isRouter = (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER ? 1 : 0);
bool hasPower = isPowered();
LOG_INFO("PowerFSM init, USB power=%d\n", hasPower ? 1 : 0);
@@ -249,7 +250,8 @@ void PowerFSM_setup()
// We need this transition, because we might not transition if we were waiting to enter light-sleep, because when we wake from
// light sleep we _always_ transition to NB or dark and
powerFSM.add_transition(&stateLS, isRouter ? &stateNB : &stateDARK, EVENT_PACKET_FOR_PHONE, NULL, "Received packet, exiting light sleep");
powerFSM.add_transition(&stateLS, isRouter ? &stateNB : &stateDARK, EVENT_PACKET_FOR_PHONE, NULL,
"Received packet, exiting light sleep");
powerFSM.add_transition(&stateNB, &stateNB, EVENT_PACKET_FOR_PHONE, NULL, "Received packet, resetting win wake");
// Handle press events - note: we ignore button presses when in API mode
@@ -258,7 +260,8 @@ void PowerFSM_setup()
powerFSM.add_transition(&stateDARK, &stateON, EVENT_PRESS, NULL, "Press");
powerFSM.add_transition(&statePOWER, &statePOWER, EVENT_PRESS, screenPress, "Press");
powerFSM.add_transition(&stateON, &stateON, EVENT_PRESS, screenPress, "Press"); // reenter On to restart our timers
powerFSM.add_transition(&stateSERIAL, &stateSERIAL, EVENT_PRESS, screenPress, "Press"); // Allow button to work while in serial API
powerFSM.add_transition(&stateSERIAL, &stateSERIAL, EVENT_PRESS, screenPress,
"Press"); // Allow button to work while in serial API
// Handle critically low power battery by forcing deep sleep
powerFSM.add_transition(&stateBOOT, &stateSDS, EVENT_LOW_BATTERY, NULL, "LowBat");
@@ -324,7 +327,9 @@ void PowerFSM_setup()
powerFSM.add_transition(&stateDARK, &stateDARK, EVENT_CONTACT_FROM_PHONE, NULL, "Contact from phone");
powerFSM.add_timed_transition(&stateON, &stateDARK, getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout");
powerFSM.add_timed_transition(&stateON, &stateDARK,
getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL,
"Screen-on timeout");
#ifdef ARCH_ESP32
State *lowPowerState = &stateLS;
@@ -332,14 +337,18 @@ void PowerFSM_setup()
// See: https://github.com/meshtastic/firmware/issues/1071
if (isRouter || config.power.is_power_saving) {
powerFSM.add_timed_transition(&stateNB, &stateLS, getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, "Min wake timeout");
powerFSM.add_timed_transition(&stateDARK, &stateLS, getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), NULL, "Bluetooth timeout");
powerFSM.add_timed_transition(&stateNB, &stateLS,
getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL,
"Min wake timeout");
powerFSM.add_timed_transition(&stateDARK, &stateLS,
getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs),
NULL, "Bluetooth timeout");
}
if (config.power.sds_secs != UINT32_MAX)
powerFSM.add_timed_transition(lowPowerState, &stateSDS, getConfiguredOrDefaultMs(config.power.sds_secs), NULL, "mesh timeout");
powerFSM.add_timed_transition(lowPowerState, &stateSDS, getConfiguredOrDefaultMs(config.power.sds_secs), NULL,
"mesh timeout");
#endif
powerFSM.run_machine(); // run one interation of the state machine, so we run our on enter tasks for the initial DARK state
}

View File

@@ -19,8 +19,8 @@
#define EVENT_POWER_CONNECTED 13
#define EVENT_POWER_DISCONNECTED 14
#define EVENT_FIRMWARE_UPDATE 15 // We just received a new firmware update packet from the phone
#define EVENT_SHUTDOWN 16 //force a full shutdown now (not just sleep)
#define EVENT_INPUT 17 // input broker wants something, we need to wake up and enable screen
#define EVENT_SHUTDOWN 16 // force a full shutdown now (not just sleep)
#define EVENT_INPUT 17 // input broker wants something, we need to wake up and enable screen
extern Fsm powerFSM;
extern State statePOWER, stateSERIAL;

View File

@@ -26,9 +26,10 @@ class PowerFSMThread : public OSThread
if (powerStatus->getHasUSB()) {
timeLastPowered = millis();
} else if (config.power.on_battery_shutdown_after_secs > 0 &&
config.power.on_battery_shutdown_after_secs != UINT32_MAX &&
millis() > (timeLastPowered + getConfiguredOrDefaultMs(config.power.on_battery_shutdown_after_secs))) { // shutdown after 30 minutes unpowered
} else if (config.power.on_battery_shutdown_after_secs > 0 && config.power.on_battery_shutdown_after_secs != UINT32_MAX &&
millis() > (timeLastPowered +
getConfiguredOrDefaultMs(
config.power.on_battery_shutdown_after_secs))) { // shutdown after 30 minutes unpowered
powerFSM.trigger(EVENT_SHUTDOWN);
}

View File

@@ -1,12 +1,12 @@
#include "configuration.h"
#include "RedirectablePrint.h"
#include "RTC.h"
#include "NodeDB.h"
#include "RTC.h"
#include "concurrency/OSThread.h"
#include "configuration.h"
#include <assert.h>
#include <cstring>
#include <sys/time.h>
#include <time.h>
#include <cstring>
/**
* A printer that doesn't go anywhere
@@ -42,7 +42,8 @@ size_t RedirectablePrint::vprintf(const char *format, va_list arg)
size_t len = vsnprintf(printBuf, sizeof(printBuf), format, copy);
va_end(copy);
// If the resulting string is longer than sizeof(printBuf)-1 characters, the remaining characters are still counted for the return value
// If the resulting string is longer than sizeof(printBuf)-1 characters, the remaining characters are still counted for the
// return value
if (len > sizeof(printBuf) - 1) {
len = sizeof(printBuf) - 1;
@@ -104,30 +105,34 @@ size_t RedirectablePrint::log(const char *logLevel, const char *format, ...)
return r;
}
void RedirectablePrint::hexDump(const char *logLevel, unsigned char *buf, uint16_t len) {
const char alphabet[17] = "0123456789abcdef";
log(logLevel, " +------------------------------------------------+ +----------------+\n");
log(logLevel, " |.0 .1 .2 .3 .4 .5 .6 .7 .8 .9 .a .b .c .d .e .f | | ASCII |\n");
for (uint16_t i = 0; i < len; i += 16) {
if (i % 128 == 0)
log(logLevel, " +------------------------------------------------+ +----------------+\n");
char s[] = "| | | |\n";
uint8_t ix = 1, iy = 52;
for (uint8_t j = 0; j < 16; j++) {
if (i + j < len) {
uint8_t c = buf[i + j];
s[ix++] = alphabet[(c >> 4) & 0x0F];
s[ix++] = alphabet[c & 0x0F];
ix++;
if (c > 31 && c < 128) s[iy++] = c;
else s[iy++] = '.';
}
void RedirectablePrint::hexDump(const char *logLevel, unsigned char *buf, uint16_t len)
{
const char alphabet[17] = "0123456789abcdef";
log(logLevel, " +------------------------------------------------+ +----------------+\n");
log(logLevel, " |.0 .1 .2 .3 .4 .5 .6 .7 .8 .9 .a .b .c .d .e .f | | ASCII |\n");
for (uint16_t i = 0; i < len; i += 16) {
if (i % 128 == 0)
log(logLevel, " +------------------------------------------------+ +----------------+\n");
char s[] = "| | | |\n";
uint8_t ix = 1, iy = 52;
for (uint8_t j = 0; j < 16; j++) {
if (i + j < len) {
uint8_t c = buf[i + j];
s[ix++] = alphabet[(c >> 4) & 0x0F];
s[ix++] = alphabet[c & 0x0F];
ix++;
if (c > 31 && c < 128)
s[iy++] = c;
else
s[iy++] = '.';
}
}
uint8_t index = i / 16;
if (i < 256)
log(logLevel, " ");
log(logLevel, "%02x", index);
log(logLevel, ".");
log(logLevel, s);
}
uint8_t index = i / 16;
if (i < 256) log(logLevel, " ");
log(logLevel, "%02x",index);
log(logLevel, ".");
log(logLevel, s);
}
log(logLevel, " +------------------------------------------------+ +----------------+\n");
log(logLevel, " +------------------------------------------------+ +----------------+\n");
}

View File

@@ -29,12 +29,12 @@ class RedirectablePrint : public Print
/**
* Debug logging print message
*
*
* If the provide format string ends with a newline we assume it is the final print of a single
* log message. Otherwise we assume more prints will come before the log message ends. This
* allows you to call logDebug a few times to build up a single log message line if you wish.
*/
size_t log(const char *logLevel, const char *format, ...) __attribute__ ((format (printf, 3, 4)));
size_t log(const char *logLevel, const char *format, ...) __attribute__((format(printf, 3, 4)));
/** like printf but va_list based */
size_t vprintf(const char *format, va_list arg);

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "SPILock.h"
#include "configuration.h"
#include <Arduino.h>
#include <assert.h>

View File

@@ -49,7 +49,8 @@ int32_t SerialConsole::runOnce()
return runOncePart();
}
void SerialConsole::flush() {
void SerialConsole::flush()
{
Port.flush();
}
@@ -74,7 +75,7 @@ bool SerialConsole::handleToRadio(const uint8_t *buf, size_t len)
canWrite = true;
return StreamAPI::handleToRadio(buf, len);
}else{
} else {
return false;
}
}

View File

@@ -29,7 +29,6 @@ class SerialConsole : public StreamAPI, public RedirectablePrint, private concur
void flush();
protected:
/// Check the current underlying physical link to see if the client is currently connected
virtual bool checkIsConnected() override;
};

View File

@@ -8,65 +8,49 @@
#define STATUS_TYPE_GPS 2
#define STATUS_TYPE_NODE 3
namespace meshtastic
{
// A base class for observable status
class Status
// A base class for observable status
class Status
{
protected:
// Allows us to observe an Observable
CallbackObserver<Status, const Status *> statusObserver =
CallbackObserver<Status, const Status *>(this, &Status::updateStatus);
bool initialized = false;
// Workaround for no typeid support
int statusType = 0;
public:
// Allows us to generate observable events
Observable<const Status *> onNewStatus;
// Enable polymorphism ?
virtual ~Status() = default;
Status()
{
protected:
// Allows us to observe an Observable
CallbackObserver<Status, const Status *> statusObserver = CallbackObserver<Status, const Status *>(this, &Status::updateStatus);
bool initialized = false;
// Workaround for no typeid support
int statusType = 0;
public:
// Allows us to generate observable events
Observable<const Status *> onNewStatus;
// Enable polymorphism ?
virtual ~Status() = default;
Status() {
if (!statusType)
{
statusType = STATUS_TYPE_BASE;
}
if (!statusType) {
statusType = STATUS_TYPE_BASE;
}
}
// Prevent object copy/move
Status(const Status &) = delete;
Status &operator=(const Status &) = delete;
// Prevent object copy/move
Status(const Status &) = delete;
Status &operator=(const Status &) = delete;
// Start observing a source of data
void observe(Observable<const Status *> *source)
{
statusObserver.observe(source);
}
// Start observing a source of data
void observe(Observable<const Status *> *source) { statusObserver.observe(source); }
// Determines whether or not existing data matches the data in another Status instance
bool matches(const Status *otherStatus) const
{
return true;
}
// Determines whether or not existing data matches the data in another Status instance
bool matches(const Status *otherStatus) const { return true; }
bool isInitialized() const
{
return initialized;
}
bool isInitialized() const { return initialized; }
int getStatusType() const
{
return statusType;
}
int getStatusType() const { return statusType; }
// Called when the Observable we're observing generates a new notification
int updateStatus(const Status *newStatus)
{
return 0;
}
};
// Called when the Observable we're observing generates a new notification
int updateStatus(const Status *newStatus) { return 0; }
};
}; // namespace meshtastic

View File

@@ -34,11 +34,13 @@ uint8_t AirTime::currentPeriodIndex()
return ((getSecondsSinceBoot() / SECONDS_PER_PERIOD) % PERIODS_TO_LOG);
}
uint8_t AirTime::getPeriodUtilMinute() {
uint8_t AirTime::getPeriodUtilMinute()
{
return (getSecondsSinceBoot() / 10) % CHANNEL_UTILIZATION_PERIODS;
}
uint8_t AirTime::getPeriodUtilHour() {
uint8_t AirTime::getPeriodUtilHour()
{
return (getSecondsSinceBoot() / 60) % MINUTES_IN_HOUR;
}
@@ -119,23 +121,23 @@ float AirTime::utilizationTXPercent()
bool AirTime::isTxAllowedChannelUtil(bool polite)
{
uint8_t percentage = (polite ? polite_channel_util_percent : max_channel_util_percent);
uint8_t percentage = (polite ? polite_channel_util_percent : max_channel_util_percent);
if (channelUtilizationPercent() < percentage) {
return true;
return true;
} else {
LOG_WARN("Channel utilization is >%d percent. Skipping this opportunity to send.\n", percentage);
return false;
}
}
bool AirTime::isTxAllowedAirUtil()
bool AirTime::isTxAllowedAirUtil()
{
if (!config.lora.override_duty_cycle && myRegion->dutyCycle < 100) {
if (utilizationTXPercent() < myRegion->dutyCycle * polite_duty_cycle_percent / 100) {
return true;
return true;
} else {
LOG_WARN("Tx air utilization is >%f percent. Skipping this opportunity to send.\n", myRegion->dutyCycle * polite_duty_cycle_percent / 100);
LOG_WARN("Tx air utilization is >%f percent. Skipping this opportunity to send.\n",
myRegion->dutyCycle * polite_duty_cycle_percent / 100);
return false;
}
}
@@ -143,21 +145,19 @@ bool AirTime::isTxAllowedAirUtil()
}
// Get the amount of minutes we have to be silent before we can send again
uint8_t AirTime::getSilentMinutes(float txPercent, float dutyCycle)
{
float newTxPercent = txPercent;
for (int8_t i = MINUTES_IN_HOUR-1; i >= 0; --i) {
newTxPercent -= ((float)this->utilizationTX[i] / (MS_IN_MINUTE * MINUTES_IN_HOUR / 100));
if (newTxPercent < dutyCycle)
return MINUTES_IN_HOUR-1-i;
}
uint8_t AirTime::getSilentMinutes(float txPercent, float dutyCycle)
{
float newTxPercent = txPercent;
for (int8_t i = MINUTES_IN_HOUR - 1; i >= 0; --i) {
newTxPercent -= ((float)this->utilizationTX[i] / (MS_IN_MINUTE * MINUTES_IN_HOUR / 100));
if (newTxPercent < dutyCycle)
return MINUTES_IN_HOUR - 1 - i;
}
return MINUTES_IN_HOUR;
return MINUTES_IN_HOUR;
}
AirTime::AirTime() : concurrency::OSThread("AirTime"),airtimes({}) {
}
AirTime::AirTime() : concurrency::OSThread("AirTime"), airtimes({}) {}
int32_t AirTime::runOnce()
{
@@ -213,14 +213,14 @@ int32_t AirTime::runOnce()
// Update channel_utilization every second.
myNodeInfo.air_util_tx = airTime->utilizationTXPercent();
}
/*
LOG_DEBUG("utilPeriodTX %d TX Airtime %3.2f%\n", utilPeriodTX, airTime->utilizationTXPercent());
for (uint32_t i = 0; i < MINUTES_IN_HOUR; i++) {
LOG_DEBUG(
"%d,", this->utilizationTX[i]
);
}
LOG_DEBUG("\n");
*/
/*
LOG_DEBUG("utilPeriodTX %d TX Airtime %3.2f%\n", utilPeriodTX, airTime->utilizationTXPercent());
for (uint32_t i = 0; i < MINUTES_IN_HOUR; i++) {
LOG_DEBUG(
"%d,", this->utilizationTX[i]
);
}
LOG_DEBUG("\n");
*/
return (1000 * 1);
}

View File

@@ -1,10 +1,10 @@
#pragma once
#include "MeshRadio.h"
#include "concurrency/OSThread.h"
#include "configuration.h"
#include <Arduino.h>
#include <functional>
#include "MeshRadio.h"
/*
TX_LOG - Time on air this device has transmitted
@@ -33,7 +33,6 @@
#define MS_IN_MINUTE (SECONDS_IN_MINUTE * 1000)
#define MS_IN_HOUR (MINUTES_IN_HOUR * SECONDS_IN_MINUTE * 1000)
enum reportTypes { TX_LOG, RX_LOG, RX_ALL_LOG };
void logAirtime(reportTypes reportType, uint32_t airtime_ms);
@@ -60,7 +59,7 @@ class AirTime : private concurrency::OSThread
uint32_t getSecondsSinceBoot();
uint32_t *airtimeReport(reportTypes reportType);
uint8_t getSilentMinutes(float txPercent, float dutyCycle);
bool isTxAllowedChannelUtil(bool polite=false);
bool isTxAllowedChannelUtil(bool polite = false);
bool isTxAllowedAirUtil();
private:
@@ -70,7 +69,7 @@ class AirTime : private concurrency::OSThread
uint32_t secSinceBoot = 0;
uint8_t max_channel_util_percent = 40;
uint8_t polite_channel_util_percent = 25;
uint8_t polite_duty_cycle_percent = 50; // half of Duty Cycle allowance is ok for metadata
uint8_t polite_duty_cycle_percent = 50; // half of Duty Cycle allowance is ok for metadata
struct airtimeStruct {
uint32_t periodTX[PERIODS_TO_LOG]; // AirTime transmitted

View File

@@ -1,6 +1,6 @@
#include "buzz.h"
#include "configuration.h"
#include "NodeDB.h"
#include "configuration.h"
#if !defined(ARCH_ESP32) && !defined(ARCH_RP2040) && !defined(ARCH_PORTDUINO)
#include "Tone.h"
@@ -11,8 +11,8 @@ extern "C" void delay(uint32_t dwMs);
#endif
struct ToneDuration {
int frequency_khz;
int duration_ms;
int frequency_khz;
int duration_ms;
};
// Some common frequencies.
@@ -30,40 +30,39 @@ struct ToneDuration {
#define NOTE_B3 247
#define NOTE_CS4 277
const int DURATION_1_8 = 125; // 1/8 note
const int DURATION_1_4 = 250; // 1/4 note
const int DURATION_1_8 = 125; // 1/8 note
const int DURATION_1_4 = 250; // 1/4 note
void playTones(const ToneDuration *tone_durations, int size) {
void playTones(const ToneDuration *tone_durations, int size)
{
#ifdef PIN_BUZZER
if (!config.device.buzzer_gpio)
config.device.buzzer_gpio = PIN_BUZZER;
if (!config.device.buzzer_gpio)
config.device.buzzer_gpio = PIN_BUZZER;
#endif
if (config.device.buzzer_gpio) {
for (int i = 0; i < size; i++) {
const auto &tone_duration = tone_durations[i];
tone(config.device.buzzer_gpio, tone_duration.frequency_khz, tone_duration.duration_ms);
// to distinguish the notes, set a minimum time between them.
delay(1.3 * tone_duration.duration_ms);
if (config.device.buzzer_gpio) {
for (int i = 0; i < size; i++) {
const auto &tone_duration = tone_durations[i];
tone(config.device.buzzer_gpio, tone_duration.frequency_khz, tone_duration.duration_ms);
// to distinguish the notes, set a minimum time between them.
delay(1.3 * tone_duration.duration_ms);
}
}
}
}
void playBeep() {
ToneDuration melody[] = {{NOTE_B3, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
void playBeep()
{
ToneDuration melody[] = {{NOTE_B3, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
}
void playStartMelody() {
ToneDuration melody[] = {{NOTE_FS3, DURATION_1_8},
{NOTE_AS3, DURATION_1_8},
{NOTE_CS4, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
void playStartMelody()
{
ToneDuration melody[] = {{NOTE_FS3, DURATION_1_8}, {NOTE_AS3, DURATION_1_8}, {NOTE_CS4, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
}
void playShutdownMelody() {
ToneDuration melody[] = {{NOTE_CS4, DURATION_1_8},
{NOTE_AS3, DURATION_1_8},
{NOTE_FS3, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
void playShutdownMelody()
{
ToneDuration melody[] = {{NOTE_CS4, DURATION_1_8}, {NOTE_AS3, DURATION_1_8}, {NOTE_FS3, DURATION_1_4}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
}

View File

@@ -4,15 +4,15 @@
*/
enum class Cmd {
INVALID,
SET_ON,
SET_OFF,
ON_PRESS,
START_BLUETOOTH_PIN_SCREEN,
START_FIRMWARE_UPDATE_SCREEN,
STOP_BLUETOOTH_PIN_SCREEN,
STOP_BOOT_SCREEN,
PRINT,
START_SHUTDOWN_SCREEN,
START_REBOOT_SCREEN,
INVALID,
SET_ON,
SET_OFF,
ON_PRESS,
START_BLUETOOTH_PIN_SCREEN,
START_FIRMWARE_UPDATE_SCREEN,
STOP_BLUETOOTH_PIN_SCREEN,
STOP_BOOT_SCREEN,
PRINT,
START_SHUTDOWN_SCREEN,
START_REBOOT_SCREEN,
};

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "concurrency/BinarySemaphoreFreeRTOS.h"
#include "configuration.h"
#include <assert.h>
#ifdef HAS_FREE_RTOS

View File

@@ -1,18 +1,14 @@
#include "configuration.h"
#include "concurrency/BinarySemaphorePosix.h"
#include "configuration.h"
#ifndef HAS_FREE_RTOS
namespace concurrency
{
BinarySemaphorePosix::BinarySemaphorePosix()
{
}
BinarySemaphorePosix::BinarySemaphorePosix() {}
BinarySemaphorePosix::~BinarySemaphorePosix()
{
}
BinarySemaphorePosix::~BinarySemaphorePosix() {}
/**
* Returns false if we timed out
@@ -23,13 +19,9 @@ bool BinarySemaphorePosix::take(uint32_t msec)
return false;
}
void BinarySemaphorePosix::give()
{
}
void BinarySemaphorePosix::give() {}
IRAM_ATTR void BinarySemaphorePosix::giveFromISR(BaseType_t *pxHigherPriorityTaskWoken)
{
}
IRAM_ATTR void BinarySemaphorePosix::giveFromISR(BaseType_t *pxHigherPriorityTaskWoken) {}
} // namespace concurrency

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "concurrency/InterruptableDelay.h"
#include "configuration.h"
namespace concurrency
{

View File

@@ -2,7 +2,6 @@
#include "../freertosinc.h"
#ifdef HAS_FREE_RTOS
#include "concurrency/BinarySemaphoreFreeRTOS.h"
#define BinarySemaphore BinarySemaphoreFreeRTOS

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "Lock.h"
#include "configuration.h"
#include <cassert>
namespace concurrency

View File

@@ -1,7 +1,8 @@
#include "configuration.h"
#include "LockGuard.h"
#include "configuration.h"
namespace concurrency {
namespace concurrency
{
LockGuard::LockGuard(Lock *lock) : lock(lock)
{

View File

@@ -2,7 +2,8 @@
#include "Lock.h"
namespace concurrency {
namespace concurrency
{
/**
* @brief RAII lock guard

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "NotifiedWorkerThread.h"
#include "configuration.h"
#include "main.h"
namespace concurrency
@@ -80,11 +80,9 @@ void NotifiedWorkerThread::checkNotification()
}
}
int32_t NotifiedWorkerThread::runOnce()
{
enabled = false; // Only run once per notification
enabled = false; // Only run once per notification
checkNotification();
return RUN_SAME;

View File

@@ -41,9 +41,9 @@ class NotifiedWorkerThread : public OSThread
/// just calls checkNotification()
virtual int32_t runOnce() override;
/// Sometimes we might want to check notifications independently of when our thread was getting woken up (i.e. if we are about to change
/// radio transmit/receive modes we want to handle any pending interrupts first). You can call this method and if any notifications are currently
/// pending they will be handled immediately.
/// Sometimes we might want to check notifications independently of when our thread was getting woken up (i.e. if we are about
/// to change radio transmit/receive modes we want to handle any pending interrupts first). You can call this method and if
/// any notifications are currently pending they will be handled immediately.
void checkNotification();
private:

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "OSThread.h"
#include "configuration.h"
#include <assert.h>
namespace concurrency
@@ -76,7 +76,7 @@ void OSThread::run()
{
#ifdef DEBUG_HEAP
auto heap = ESP.getFreeHeap();
#endif
#endif
currentThread = this;
auto newDelay = runOnce();
#ifdef DEBUG_HEAP
@@ -95,11 +95,11 @@ void OSThread::run()
currentThread = NULL;
}
int32_t OSThread::disable()
int32_t OSThread::disable()
{
enabled = false;
setInterval(INT32_MAX);
return INT32_MAX;
}

View File

@@ -27,10 +27,10 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#include <Arduino.h>
#ifdef RV3028_RTC
#include "Melopero_RV3028.h"
#include "Melopero_RV3028.h"
#endif
#ifdef PCF8563_RTC
#include "pcf8563.h"
#include "pcf8563.h"
#endif
// -----------------------------------------------------------------------------
@@ -42,7 +42,8 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#error APP_VERSION must be set by the build environment
#endif
// FIXME: This is still needed by the Bluetooth Stack and needs to be replaced by something better. Remnant of the old versioning system.
// FIXME: This is still needed by the Bluetooth Stack and needs to be replaced by something better. Remnant of the old versioning
// system.
#ifndef HW_VERSION
#define HW_VERSION "1.0"
#endif
@@ -64,13 +65,13 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// Nop definition for these attributes that are specific to ESP32
#ifndef EXT_RAM_ATTR
#define EXT_RAM_ATTR
#define EXT_RAM_ATTR
#endif
#ifndef IRAM_ATTR
#define IRAM_ATTR
#define IRAM_ATTR
#endif
#ifndef RTC_DATA_ATTR
#define RTC_DATA_ATTR
#define RTC_DATA_ATTR
#endif
// -----------------------------------------------------------------------------
@@ -80,7 +81,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// Disable use of the NTP library and related features
// #define DISABLE_NTP
// Disable the welcome screen and allow
// Disable the welcome screen and allow
//#define DISABLE_WELCOME_UNSET
// -----------------------------------------------------------------------------
@@ -135,49 +136,49 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
/* Step #1: offer chance for variant-specific defines */
#include "variant.h"
/* Step #2: follow with defines common to the architecture;
/* Step #2: follow with defines common to the architecture;
also enable HAS_ option not specifically disabled by variant.h */
#include "architecture.h"
/* Step #3: mop up with disabled values for HAS_ options not handled by the above two */
#ifndef HAS_WIFI
#define HAS_WIFI 0
#define HAS_WIFI 0
#endif
#ifndef HAS_ETHERNET
#define HAS_ETHERNET 0
#define HAS_ETHERNET 0
#endif
#ifndef HAS_SCREEN
#define HAS_SCREEN 0
#define HAS_SCREEN 0
#endif
#ifndef HAS_WIRE
#define HAS_WIRE 0
#define HAS_WIRE 0
#endif
#ifndef HAS_GPS
#define HAS_GPS 0
#define HAS_GPS 0
#endif
#ifndef HAS_BUTTON
#define HAS_BUTTON 0
#define HAS_BUTTON 0
#endif
#ifndef HAS_TELEMETRY
#define HAS_TELEMETRY 0
#define HAS_TELEMETRY 0
#endif
#ifndef HAS_RADIO
#define HAS_RADIO 0
#define HAS_RADIO 0
#endif
#ifndef HAS_RTC
#define HAS_RTC 0
#define HAS_RTC 0
#endif
#ifndef HAS_CPU_SHUTDOWN
#define HAS_CPU_SHUTDOWN 0
#define HAS_CPU_SHUTDOWN 0
#endif
#ifndef HAS_BLUETOOTH
#define HAS_BLUETOOTH 0
#define HAS_BLUETOOTH 0
#endif
#include "RF95Configuration.h"
#include "DebugConfiguration.h"
#include "RF95Configuration.h"
#ifndef HW_VENDOR
#error HW_VENDOR must be defined
#error HW_VENDOR must be defined
#endif

View File

@@ -6,42 +6,49 @@
void d_writeCommand(uint8_t c)
{
SPI1.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0));
if (PIN_EINK_DC >= 0) digitalWrite(PIN_EINK_DC, LOW);
if (PIN_EINK_CS >= 0) digitalWrite(PIN_EINK_CS, LOW);
SPI1.transfer(c);
if (PIN_EINK_CS >= 0) digitalWrite(PIN_EINK_CS, HIGH);
if (PIN_EINK_DC >= 0) digitalWrite(PIN_EINK_DC, HIGH);
SPI1.endTransaction();
SPI1.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0));
if (PIN_EINK_DC >= 0)
digitalWrite(PIN_EINK_DC, LOW);
if (PIN_EINK_CS >= 0)
digitalWrite(PIN_EINK_CS, LOW);
SPI1.transfer(c);
if (PIN_EINK_CS >= 0)
digitalWrite(PIN_EINK_CS, HIGH);
if (PIN_EINK_DC >= 0)
digitalWrite(PIN_EINK_DC, HIGH);
SPI1.endTransaction();
}
void d_writeData(uint8_t d)
{
SPI1.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0));
if (PIN_EINK_CS >= 0) digitalWrite(PIN_EINK_CS, LOW);
SPI1.transfer(d);
if (PIN_EINK_CS >= 0) digitalWrite(PIN_EINK_CS, HIGH);
SPI1.endTransaction();
SPI1.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0));
if (PIN_EINK_CS >= 0)
digitalWrite(PIN_EINK_CS, LOW);
SPI1.transfer(d);
if (PIN_EINK_CS >= 0)
digitalWrite(PIN_EINK_CS, HIGH);
SPI1.endTransaction();
}
unsigned long d_waitWhileBusy(uint16_t busy_time)
{
if (PIN_EINK_BUSY >= 0)
{
delay(1); // add some margin to become active
unsigned long start = micros();
while (1)
{
if (digitalRead(PIN_EINK_BUSY) != HIGH) break;
delay(1);
if (digitalRead(PIN_EINK_BUSY) != HIGH) break;
if (micros() - start > 10000000) break;
}
unsigned long elapsed = micros() - start;
(void) start;
return elapsed;
}
else return busy_time;
if (PIN_EINK_BUSY >= 0) {
delay(1); // add some margin to become active
unsigned long start = micros();
while (1) {
if (digitalRead(PIN_EINK_BUSY) != HIGH)
break;
delay(1);
if (digitalRead(PIN_EINK_BUSY) != HIGH)
break;
if (micros() - start > 10000000)
break;
}
unsigned long elapsed = micros() - start;
(void)start;
return elapsed;
} else
return busy_time;
}
void scanEInkDevice(void)
@@ -51,10 +58,10 @@ void scanEInkDevice(void)
d_writeData(0x83);
d_writeCommand(0x20);
eink_found = (d_waitWhileBusy(150) > 0) ? true : false;
if(eink_found)
LOG_DEBUG("EInk display found\n");
if (eink_found)
LOG_DEBUG("EInk display found\n");
else
LOG_DEBUG("EInk display not found\n");
LOG_DEBUG("EInk display not found\n");
SPI1.end();
}
#endif

View File

@@ -168,13 +168,13 @@ void scanI2Cdevice()
registerValue = getRegisterValue(addr, 0xD0, 1); // GET_ID
if (registerValue == 0x61) {
LOG_INFO("BME-680 sensor found at address 0x%x\n", (uint8_t)addr);
nodeTelemetrySensorsMap[TelemetrySensorType_BME680] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_BME680] = addr;
} else if (registerValue == 0x60) {
LOG_INFO("BME-280 sensor found at address 0x%x\n", (uint8_t)addr);
nodeTelemetrySensorsMap[TelemetrySensorType_BME280] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_BME280] = addr;
} else {
LOG_INFO("BMP-280 sensor found at address 0x%x\n", (uint8_t)addr);
nodeTelemetrySensorsMap[TelemetrySensorType_BMP280] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_BMP280] = addr;
}
}
if (addr == INA_ADDR || addr == INA_ADDR_ALTERNATE) {
@@ -182,41 +182,41 @@ void scanI2Cdevice()
LOG_DEBUG("Register MFG_UID: 0x%x\n", registerValue);
if (registerValue == 0x5449) {
LOG_INFO("INA260 sensor found at address 0x%x\n", (uint8_t)addr);
nodeTelemetrySensorsMap[TelemetrySensorType_INA260] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_INA260] = addr;
} else { // Assume INA219 if INA260 ID is not found
LOG_INFO("INA219 sensor found at address 0x%x\n", (uint8_t)addr);
nodeTelemetrySensorsMap[TelemetrySensorType_INA219] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_INA219] = addr;
}
}
if (addr == MCP9808_ADDR) {
nodeTelemetrySensorsMap[TelemetrySensorType_MCP9808] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_MCP9808] = addr;
LOG_INFO("MCP9808 sensor found\n");
}
if (addr == SHT31_ADDR) {
LOG_INFO("SHT31 sensor found\n");
nodeTelemetrySensorsMap[TelemetrySensorType_SHT31] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_SHT31] = addr;
}
if (addr == SHTC3_ADDR) {
LOG_INFO("SHTC3 sensor found\n");
nodeTelemetrySensorsMap[TelemetrySensorType_SHTC3] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_SHTC3] = addr;
}
if (addr == LPS22HB_ADDR || addr == LPS22HB_ADDR_ALT) {
LOG_INFO("LPS22HB sensor found\n");
nodeTelemetrySensorsMap[TelemetrySensorType_LPS22] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_LPS22] = addr;
}
// High rate sensors, will be processed internally
if (addr == QMC6310_ADDR) {
LOG_INFO("QMC6310 Highrate 3-Axis magnetic sensor found\n");
nodeTelemetrySensorsMap[TelemetrySensorType_QMC6310] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_QMC6310] = addr;
}
if (addr == QMI8658_ADDR) {
LOG_INFO("QMI8658 Highrate 6-Axis inertial measurement sensor found\n");
nodeTelemetrySensorsMap[TelemetrySensorType_QMI8658] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_QMI8658] = addr;
}
if (addr == QMC5883L_ADDR) {
LOG_INFO("QMC5883L Highrate 3-Axis magnetic sensor found\n");
nodeTelemetrySensorsMap[TelemetrySensorType_QMC5883L] = addr;
nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_QMC5883L] = addr;
}
} else if (err == 4) {
LOG_ERROR("Unknow error at address 0x%x\n", addr);

View File

@@ -8,5 +8,5 @@
#define RECORD_CRITICALERROR(code) recordCriticalError(code, __LINE__, __FILE__)
/// Record an error that should be reported via analytics
void recordCriticalError(CriticalErrorCode code = CriticalErrorCode_UNSPECIFIED, uint32_t address = 0,
void recordCriticalError(meshtastic_CriticalErrorCode code = meshtastic_CriticalErrorCode_UNSPECIFIED, uint32_t address = 0,
const char *filename = NULL);

View File

@@ -295,6 +295,7 @@ bool GPS::setup()
notifyDeepSleepObserver.observe(&notifyDeepSleep);
notifyGPSSleepObserver.observe(&notifyGPSSleep);
}
if (config.position.gps_enabled == false && config.position.fixed_position == false) {
setAwake(false);
doGPSpowersave(false);
@@ -489,7 +490,7 @@ int32_t GPS::runOnce()
if (hasValidLocation) {
LOG_DEBUG("hasValidLocation FALLING EDGE (last read: %d)\n", gotLoc);
}
p = Position_init_default;
p = meshtastic_Position_init_default;
hasValidLocation = false;
}

View File

@@ -54,7 +54,7 @@ class GPS : private concurrency::OSThread
/** If !NULL we will use this serial port to construct our GPS */
static HardwareSerial *_serial_gps;
Position p = Position_init_default;
meshtastic_Position p = meshtastic_Position_init_default;
GPS() : concurrency::OSThread("GPS") {}

View File

@@ -1,21 +1,25 @@
#include "GeoCoord.h"
GeoCoord::GeoCoord() {
GeoCoord::GeoCoord()
{
_dirty = true;
}
GeoCoord::GeoCoord (int32_t lat, int32_t lon, int32_t alt) : _latitude(lat), _longitude(lon), _altitude(alt) {
GeoCoord::GeoCoord(int32_t lat, int32_t lon, int32_t alt) : _latitude(lat), _longitude(lon), _altitude(alt)
{
GeoCoord::setCoords();
}
GeoCoord::GeoCoord (float lat, float lon, int32_t alt) : _altitude(alt) {
GeoCoord::GeoCoord(float lat, float lon, int32_t alt) : _altitude(alt)
{
// Change decimial reprsentation to int32_t. I.e., 12.345 becomes 123450000
_latitude = int32_t(lat * 1e+7);
_longitude = int32_t(lon * 1e+7);
GeoCoord::setCoords();
}
GeoCoord::GeoCoord(double lat, double lon, int32_t alt): _altitude(alt) {
GeoCoord::GeoCoord(double lat, double lon, int32_t alt) : _altitude(alt)
{
// Change decimial reprsentation to int32_t. I.e., 12.345 becomes 123450000
_latitude = int32_t(lat * 1e+7);
_longitude = int32_t(lon * 1e+7);
@@ -23,7 +27,8 @@ GeoCoord::GeoCoord(double lat, double lon, int32_t alt): _altitude(alt) {
}
// Initialize all the coordinate systems
void GeoCoord::setCoords() {
void GeoCoord::setCoords()
{
double lat = _latitude * 1e-7;
double lon = _longitude * 1e-7;
GeoCoord::latLongToDMS(lat, lon, _dms);
@@ -34,9 +39,10 @@ void GeoCoord::setCoords() {
_dirty = false;
}
void GeoCoord::updateCoords(int32_t lat, int32_t lon, int32_t alt) {
void GeoCoord::updateCoords(int32_t lat, int32_t lon, int32_t alt)
{
// If marked dirty or new coordiantes
if(_dirty || _latitude != lat || _longitude != lon || _altitude != alt) {
if (_dirty || _latitude != lat || _longitude != lon || _altitude != alt) {
_dirty = true;
_latitude = lat;
_longitude = lon;
@@ -45,25 +51,26 @@ void GeoCoord::updateCoords(int32_t lat, int32_t lon, int32_t alt) {
}
}
void GeoCoord::updateCoords(const double lat, const double lon, const int32_t alt) {
void GeoCoord::updateCoords(const double lat, const double lon, const int32_t alt)
{
int32_t iLat = lat * 1e+7;
int32_t iLon = lon * 1e+7;
// If marked dirty or new coordiantes
if(_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
if (_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
_dirty = true;
_latitude = iLat;
_longitude = iLon;
_altitude = alt;
setCoords();
}
}
void GeoCoord::updateCoords(const float lat, const float lon, const int32_t alt) {
void GeoCoord::updateCoords(const float lat, const float lon, const int32_t alt)
{
int32_t iLat = lat * 1e+7;
int32_t iLon = lon * 1e+7;
// If marked dirty or new coordiantes
if(_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
if (_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
_dirty = true;
_latitude = iLat;
_longitude = iLon;
@@ -73,12 +80,15 @@ void GeoCoord::updateCoords(const float lat, const float lon, const int32_t alt)
}
/**
* Converts lat long coordinates from decimal degrees to degrees minutes seconds format.
* Converts lat long coordinates from decimal degrees to degrees minutes seconds format.
* DD°MM'SS"C DDD°MM'SS"C
*/
void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms) {
if (lat < 0) dms.latCP = 'S';
else dms.latCP = 'N';
void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms)
{
if (lat < 0)
dms.latCP = 'S';
else
dms.latCP = 'N';
double latDeg = lat;
@@ -90,8 +100,10 @@ void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms) {
dms.latMin = floor(latMin);
dms.latSec = (latMin - dms.latMin) * 60;
if (lon < 0) dms.lonCP = 'W';
else dms.lonCP = 'E';
if (lon < 0)
dms.lonCP = 'W';
else
dms.lonCP = 'E';
double lonDeg = lon;
@@ -108,52 +120,64 @@ void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms) {
* Converts lat long coordinates to UTM.
* based on this: https://github.com/walvok/LatLonToUTM/blob/master/latlon_utm.ino
*/
void GeoCoord::latLongToUTM(const double lat, const double lon, UTM &utm) {
void GeoCoord::latLongToUTM(const double lat, const double lon, UTM &utm)
{
const std::string latBands = "CDEFGHJKLMNPQRSTUVWXX";
utm.zone = int((lon + 180)/6 + 1);
utm.band = latBands[int(lat/8 + 10)];
double a = 6378137; // WGS84 - equatorial radius
double k0 = 0.9996; // UTM point scale on the central meridian
double eccSquared = 0.00669438; // eccentricity squared
double lonTemp = (lon + 180) - int((lon + 180)/360) * 360 - 180; //Make sure the longitude is between -180.00 .. 179.9
utm.zone = int((lon + 180) / 6 + 1);
utm.band = latBands[int(lat / 8 + 10)];
double a = 6378137; // WGS84 - equatorial radius
double k0 = 0.9996; // UTM point scale on the central meridian
double eccSquared = 0.00669438; // eccentricity squared
double lonTemp = (lon + 180) - int((lon + 180) / 360) * 360 - 180; // Make sure the longitude is between -180.00 .. 179.9
double latRad = toRadians(lat);
double lonRad = toRadians(lonTemp);
// Special Zones for Norway and Svalbard
if( lat >= 56.0 && lat < 64.0 && lonTemp >= 3.0 && lonTemp < 12.0 ) // Norway
if (lat >= 56.0 && lat < 64.0 && lonTemp >= 3.0 && lonTemp < 12.0) // Norway
utm.zone = 32;
if( lat >= 72.0 && lat < 84.0 ) { // Svalbard
if ( lonTemp >= 0.0 && lonTemp < 9.0 ) utm.zone = 31;
else if( lonTemp >= 9.0 && lonTemp < 21.0 ) utm.zone = 33;
else if( lonTemp >= 21.0 && lonTemp < 33.0 ) utm.zone = 35;
else if( lonTemp >= 33.0 && lonTemp < 42.0 ) utm.zone = 37;
if (lat >= 72.0 && lat < 84.0) { // Svalbard
if (lonTemp >= 0.0 && lonTemp < 9.0)
utm.zone = 31;
else if (lonTemp >= 9.0 && lonTemp < 21.0)
utm.zone = 33;
else if (lonTemp >= 21.0 && lonTemp < 33.0)
utm.zone = 35;
else if (lonTemp >= 33.0 && lonTemp < 42.0)
utm.zone = 37;
}
double lonOrigin = (utm.zone - 1)*6 - 180 + 3; // puts origin in middle of zone
double lonOrigin = (utm.zone - 1) * 6 - 180 + 3; // puts origin in middle of zone
double lonOriginRad = toRadians(lonOrigin);
double eccPrimeSquared = (eccSquared)/(1 - eccSquared);
double N = a/sqrt(1 - eccSquared*sin(latRad)*sin(latRad));
double T = tan(latRad)*tan(latRad);
double C = eccPrimeSquared*cos(latRad)*cos(latRad);
double A = cos(latRad)*(lonRad - lonOriginRad);
double M = a*((1 - eccSquared/4 - 3*eccSquared*eccSquared/64 - 5*eccSquared*eccSquared*eccSquared/256)*latRad
- (3*eccSquared/8 + 3*eccSquared*eccSquared/32 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(2*latRad)
+ (15*eccSquared*eccSquared/256 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(4*latRad)
- (35*eccSquared*eccSquared*eccSquared/3072)*sin(6*latRad));
utm.easting = (double)(k0*N*(A+(1-T+C)*pow(A, 3)/6 + (5-18*T+T*T+72*C-58*eccPrimeSquared)*A*A*A*A*A/120)
+ 500000.0);
utm.northing = (double)(k0*(M+N*tan(latRad)*(A*A/2+(5-T+9*C+4*C*C)*A*A*A*A/24
+ (61-58*T+T*T+600*C-330*eccPrimeSquared)*A*A*A*A*A*A/720)));
if(lat < 0)
utm.northing += 10000000.0; //10000000 meter offset for southern hemisphere
double eccPrimeSquared = (eccSquared) / (1 - eccSquared);
double N = a / sqrt(1 - eccSquared * sin(latRad) * sin(latRad));
double T = tan(latRad) * tan(latRad);
double C = eccPrimeSquared * cos(latRad) * cos(latRad);
double A = cos(latRad) * (lonRad - lonOriginRad);
double M =
a * ((1 - eccSquared / 4 - 3 * eccSquared * eccSquared / 64 - 5 * eccSquared * eccSquared * eccSquared / 256) * latRad -
(3 * eccSquared / 8 + 3 * eccSquared * eccSquared / 32 + 45 * eccSquared * eccSquared * eccSquared / 1024) *
sin(2 * latRad) +
(15 * eccSquared * eccSquared / 256 + 45 * eccSquared * eccSquared * eccSquared / 1024) * sin(4 * latRad) -
(35 * eccSquared * eccSquared * eccSquared / 3072) * sin(6 * latRad));
utm.easting = (double)(k0 * N *
(A + (1 - T + C) * pow(A, 3) / 6 +
(5 - 18 * T + T * T + 72 * C - 58 * eccPrimeSquared) * A * A * A * A * A / 120) +
500000.0);
utm.northing =
(double)(k0 * (M + N * tan(latRad) *
(A * A / 2 + (5 - T + 9 * C + 4 * C * C) * A * A * A * A / 24 +
(61 - 58 * T + T * T + 600 * C - 330 * eccPrimeSquared) * A * A * A * A * A * A / 720)));
if (lat < 0)
utm.northing += 10000000.0; // 10000000 meter offset for southern hemisphere
}
// Converts lat long coordinates to an MGRS.
void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs) {
const std::string e100kLetters[3] = { "ABCDEFGH", "JKLMNPQR", "STUVWXYZ" };
const std::string n100kLetters[2] = { "ABCDEFGHJKLMNPQRSTUV", "FGHJKLMNPQRSTUVABCDE" };
void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs)
{
const std::string e100kLetters[3] = {"ABCDEFGH", "JKLMNPQR", "STUVWXYZ"};
const std::string n100kLetters[2] = {"ABCDEFGHJKLMNPQRSTUV", "FGHJKLMNPQRSTUVABCDE"};
UTM utm;
latLongToUTM(lat, lon, utm);
mgrs.zone = utm.zone;
@@ -161,7 +185,7 @@ void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs) {
double col = floor(utm.easting / 100000);
mgrs.east100k = e100kLetters[(mgrs.zone - 1) % 3][col - 1];
double row = (int32_t)floor(utm.northing / 100000.0) % 20;
mgrs.north100k = n100kLetters[(mgrs.zone-1)%2][row];
mgrs.north100k = n100kLetters[(mgrs.zone - 1) % 2][row];
mgrs.easting = (int32_t)utm.easting % 100000;
mgrs.northing = (int32_t)utm.northing % 100000;
}
@@ -170,52 +194,54 @@ void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs) {
* Converts lat long coordinates to Ordnance Survey Grid Reference (UK National Grid Ref).
* Based on: https://www.movable-type.co.uk/scripts/latlong-os-gridref.html
*/
void GeoCoord::latLongToOSGR(const double lat, const double lon, OSGR &osgr) {
void GeoCoord::latLongToOSGR(const double lat, const double lon, OSGR &osgr)
{
const char letter[] = "ABCDEFGHJKLMNOPQRSTUVWXYZ"; // No 'I' in OSGR
double a = 6377563.396; // Airy 1830 semi-major axis
double b = 6356256.909; // Airy 1830 semi-minor axis
double f0 = 0.9996012717; // National Grid point scale factor on the central meridian
double phi0 = toRadians(49);
double a = 6377563.396; // Airy 1830 semi-major axis
double b = 6356256.909; // Airy 1830 semi-minor axis
double f0 = 0.9996012717; // National Grid point scale factor on the central meridian
double phi0 = toRadians(49);
double lambda0 = toRadians(-2);
double n0 = -100000;
double e0 = 400000;
double e2 = 1 - (b*b)/(a*a); // eccentricity squared
double n = (a - b)/(a + b);
double e2 = 1 - (b * b) / (a * a); // eccentricity squared
double n = (a - b) / (a + b);
double osgb_Latitude;
double osgb_Longitude;
convertWGS84ToOSGB36(lat, lon, osgb_Latitude, osgb_Longitude);
double phi = osgb_Latitude; // already in radians
double phi = osgb_Latitude; // already in radians
double lambda = osgb_Longitude; // already in radians
double v = a * f0 / sqrt(1 - e2 * sin(phi) * sin(phi));
double rho = a * f0 * (1 - e2) / pow(1 - e2 * sin(phi) * sin(phi), 1.5);
double eta2 = v / rho - 1;
double mA = (1 + n + (5/4)*n*n + (5/4)*n*n*n) * (phi - phi0);
double mB = (3*n + 3*n*n + (21/8)*n*n*n) * sin(phi - phi0) * cos(phi + phi0);
double mA = (1 + n + (5 / 4) * n * n + (5 / 4) * n * n * n) * (phi - phi0);
double mB = (3 * n + 3 * n * n + (21 / 8) * n * n * n) * sin(phi - phi0) * cos(phi + phi0);
// loss of precision in mC & mD due to floating point rounding can cause innaccuracy of northing by a few meters
double mC = (15/8*n*n + 15/8*n*n*n) * sin(2*(phi - phi0)) * cos(2*(phi + phi0));
double mD = (35/24)*n*n*n * sin(3*(phi - phi0)) * cos(3*(phi + phi0));
double m = b*f0*(mA - mB + mC - mD);
double mC = (15 / 8 * n * n + 15 / 8 * n * n * n) * sin(2 * (phi - phi0)) * cos(2 * (phi + phi0));
double mD = (35 / 24) * n * n * n * sin(3 * (phi - phi0)) * cos(3 * (phi + phi0));
double m = b * f0 * (mA - mB + mC - mD);
double cos3Phi = cos(phi)*cos(phi)*cos(phi);
double cos5Phi = cos3Phi*cos(phi)*cos(phi);
double tan2Phi = tan(phi)*tan(phi);
double tan4Phi = tan2Phi*tan2Phi;
double cos3Phi = cos(phi) * cos(phi) * cos(phi);
double cos5Phi = cos3Phi * cos(phi) * cos(phi);
double tan2Phi = tan(phi) * tan(phi);
double tan4Phi = tan2Phi * tan2Phi;
double I = m + n0;
double II = (v/2)*sin(phi)*cos(phi);
double III = (v/24)*sin(phi)*cos3Phi*(5 - tan2Phi + 9*eta2);
double IIIA = (v/720)*sin(phi)*cos5Phi*(61 - 58*tan2Phi + tan4Phi);
double IV = v*cos(phi);
double V = (v/6)*cos3Phi*(v/rho - tan2Phi);
double VI = (v/120)*cos5Phi*(5 - 18*tan2Phi + tan4Phi + 14*eta2 - 58*tan2Phi*eta2);
double II = (v / 2) * sin(phi) * cos(phi);
double III = (v / 24) * sin(phi) * cos3Phi * (5 - tan2Phi + 9 * eta2);
double IIIA = (v / 720) * sin(phi) * cos5Phi * (61 - 58 * tan2Phi + tan4Phi);
double IV = v * cos(phi);
double V = (v / 6) * cos3Phi * (v / rho - tan2Phi);
double VI = (v / 120) * cos5Phi * (5 - 18 * tan2Phi + tan4Phi + 14 * eta2 - 58 * tan2Phi * eta2);
double deltaLambda = lambda - lambda0;
double deltaLambda2 = deltaLambda*deltaLambda;
double northing = I + II*deltaLambda2 + III*deltaLambda2*deltaLambda2 + IIIA*deltaLambda2*deltaLambda2*deltaLambda2;
double easting = e0 + IV*deltaLambda + V*deltaLambda2*deltaLambda + VI*deltaLambda2*deltaLambda2*deltaLambda;
double deltaLambda2 = deltaLambda * deltaLambda;
double northing =
I + II * deltaLambda2 + III * deltaLambda2 * deltaLambda2 + IIIA * deltaLambda2 * deltaLambda2 * deltaLambda2;
double easting = e0 + IV * deltaLambda + V * deltaLambda2 * deltaLambda + VI * deltaLambda2 * deltaLambda2 * deltaLambda;
if (easting < 0 || easting > 700000 || northing < 0 || northing > 1300000) // Check if out of boundaries
osgr = { 'I', 'I', 0, 0 };
osgr = {'I', 'I', 0, 0};
else {
uint32_t e100k = floor(easting / 100000);
uint32_t n100k = floor(northing / 100000);
@@ -232,7 +258,8 @@ void GeoCoord::latLongToOSGR(const double lat, const double lon, OSGR &osgr) {
* Converts lat long coordinates to Open Location Code.
* Based on: https://github.com/google/open-location-code/blob/main/c/src/olc.c
*/
void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc)
{
char tempCode[] = "1234567890abc";
const char kAlphabet[] = "23456789CFGHJMPQRVWX";
double latitude;
@@ -258,7 +285,7 @@ void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
lat_val += latitude * 2.5e7;
lng_val += longitude * 8.192e6;
size_t pos = OLC_CODE_LEN;
if (OLC_CODE_LEN > 10) { // Compute grid part of code if needed
for (size_t i = 0; i < 5; i++) {
int lat_digit = lat_val % 5;
@@ -272,9 +299,9 @@ void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
lat_val /= pow(5, 5);
lng_val /= pow(4, 5);
}
pos = 10;
for (size_t i = 0; i < 5; i++) { // Compute pair section of code
int lat_ndx = lat_val % 20;
int lng_ndx = lng_val % 20;
@@ -286,7 +313,7 @@ void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
if (i == 0)
tempCode[pos--] = '+';
}
if (OLC_CODE_LEN < 9) { // Add padding if needed
for (size_t i = OLC_CODE_LEN; i < 9; i++)
tempCode[i] = '0';
@@ -300,50 +327,52 @@ void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
for (size_t i = 0; i < char_count; i++) {
olc.code[i] = tempCode[i];
}
olc.code[char_count] = '\0';
olc.code[char_count] = '\0';
}
// Converts the coordinate in WGS84 datum to the OSGB36 datum.
void GeoCoord::convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude) {
void GeoCoord::convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude)
{
// Convert lat long to cartesian
double phi = toRadians(lat);
double lambda = toRadians(lon);
double h = 0.0; // No OSTN height data used, some loss of accuracy (up to 5m)
double wgsA = 6378137; // WGS84 datum semi major axis
double h = 0.0; // No OSTN height data used, some loss of accuracy (up to 5m)
double wgsA = 6378137; // WGS84 datum semi major axis
double wgsF = 1 / 298.257223563; // WGS84 datum flattening
double ecc = 2*wgsF - wgsF*wgsF;
double ecc = 2 * wgsF - wgsF * wgsF;
double vee = wgsA / sqrt(1 - ecc * pow(sin(phi), 2));
double wgsX = (vee + h) * cos(phi) * cos(lambda);
double wgsY = (vee + h) * cos(phi) * sin(lambda);
double wgsZ = ((1 - ecc) * vee + h) * sin(phi);
// 7-parameter Helmert transform
double tx = -446.448; // x shift in meters
double ty = 125.157; // y shift in meters
double tz = -542.060; // z shift in meters
double s = 20.4894/1e6 + 1; // scale normalized parts per million to (s + 1)
double rx = toRadians(-0.1502/3600); // x rotation normalize arcseconds to radians
double ry = toRadians(-0.2470/3600); // y rotation normalize arcseconds to radians
double rz = toRadians(-0.8421/3600); // z rotation normalize arcseconds to radians
double osgbX = tx + wgsX*s - wgsY*rz + wgsZ*ry;
double osgbY = ty + wgsX*rz + wgsY*s - wgsZ*rx;
double osgbZ = tz - wgsX*ry + wgsY*rx + wgsZ*s;
double tx = -446.448; // x shift in meters
double ty = 125.157; // y shift in meters
double tz = -542.060; // z shift in meters
double s = 20.4894 / 1e6 + 1; // scale normalized parts per million to (s + 1)
double rx = toRadians(-0.1502 / 3600); // x rotation normalize arcseconds to radians
double ry = toRadians(-0.2470 / 3600); // y rotation normalize arcseconds to radians
double rz = toRadians(-0.8421 / 3600); // z rotation normalize arcseconds to radians
double osgbX = tx + wgsX * s - wgsY * rz + wgsZ * ry;
double osgbY = ty + wgsX * rz + wgsY * s - wgsZ * rx;
double osgbZ = tz - wgsX * ry + wgsY * rx + wgsZ * s;
// Convert cartesian to lat long
double airyA = 6377563.396; // Airy1830 datum semi major axis
double airyB = 6356256.909; // Airy1830 datum semi minor axis
double airyF = 1/ 299.3249646; // Airy1830 datum flattening
double airyEcc = 2*airyF - airyF*airyF;
double airyA = 6377563.396; // Airy1830 datum semi major axis
double airyB = 6356256.909; // Airy1830 datum semi minor axis
double airyF = 1 / 299.3249646; // Airy1830 datum flattening
double airyEcc = 2 * airyF - airyF * airyF;
double airyEcc2 = airyEcc / (1 - airyEcc);
double p = sqrt(osgbX*osgbX + osgbY*osgbY);
double R = sqrt(p*p + osgbZ*osgbZ);
double tanBeta = (airyB*osgbZ) / (airyA*p) * (1 + airyEcc2*airyB/R);
double sinBeta = tanBeta / sqrt(1 + tanBeta*tanBeta);
double p = sqrt(osgbX * osgbX + osgbY * osgbY);
double R = sqrt(p * p + osgbZ * osgbZ);
double tanBeta = (airyB * osgbZ) / (airyA * p) * (1 + airyEcc2 * airyB / R);
double sinBeta = tanBeta / sqrt(1 + tanBeta * tanBeta);
double cosBeta = sinBeta / tanBeta;
osgb_Latitude = atan2(osgbZ + airyEcc2*airyB*sinBeta*sinBeta*sinBeta, p - airyEcc*airyA*cosBeta*cosBeta*cosBeta); // leave in radians
osgb_Longitude = atan2(osgbY, osgbX); // leave in radians
//osgb height = p*cos(osgb.latitude) + osgbZ*sin(osgb.latitude) -
//(airyA*airyA/(airyA / sqrt(1 - airyEcc*sin(osgb.latitude)*sin(osgb.latitude)))); // Not used, no OSTN data
osgb_Latitude = atan2(osgbZ + airyEcc2 * airyB * sinBeta * sinBeta * sinBeta,
p - airyEcc * airyA * cosBeta * cosBeta * cosBeta); // leave in radians
osgb_Longitude = atan2(osgbY, osgbX); // leave in radians
// osgb height = p*cos(osgb.latitude) + osgbZ*sin(osgb.latitude) -
//(airyA*airyA/(airyA / sqrt(1 - airyEcc*sin(osgb.latitude)*sin(osgb.latitude)))); // Not used, no OSTN data
}
/// Ported from my old java code, returns distance in meters along the globe
@@ -397,12 +426,13 @@ float GeoCoord::bearing(double lat1, double lon1, double lat2, double lon2)
* @brief Convert from meters to range in radians on a great circle
* @param range_meters
* The range in meters
* @return range in radians on a great circle
* @return range in radians on a great circle
*/
float GeoCoord::rangeMetersToRadians(double range_meters) {
float GeoCoord::rangeMetersToRadians(double range_meters)
{
// 1 nm is 1852 meters
double distance_nm = range_meters * 1852;
return (PI / (180 * 60)) *distance_nm;
return (PI / (180 * 60)) * distance_nm;
}
/**
@@ -410,22 +440,27 @@ float GeoCoord::rangeMetersToRadians(double range_meters) {
* @brief Convert from radians to range in meters on a great circle
* @param range_radians
* The range in radians
* @return Range in meters on a great circle
* @return Range in meters on a great circle
*/
float GeoCoord::rangeRadiansToMeters(double range_radians) {
float GeoCoord::rangeRadiansToMeters(double range_radians)
{
double distance_nm = ((180 * 60) / PI) * range_radians;
// 1 meter is 0.000539957 nm
return distance_nm * 0.000539957;
}
// Find distance from point to passed in point
int32_t GeoCoord::distanceTo(const GeoCoord& pointB) {
return latLongToMeter(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7, pointB.getLongitude() * 1e-7);
int32_t GeoCoord::distanceTo(const GeoCoord &pointB)
{
return latLongToMeter(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7,
pointB.getLongitude() * 1e-7);
}
// Find bearing from point to passed in point
int32_t GeoCoord::bearingTo(const GeoCoord& pointB) {
return bearing(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7, pointB.getLongitude() * 1e-7);
int32_t GeoCoord::bearingTo(const GeoCoord &pointB)
{
return bearing(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7,
pointB.getLongitude() * 1e-7);
}
/**
@@ -436,8 +471,9 @@ int32_t GeoCoord::bearingTo(const GeoCoord& pointB) {
* @param range_meters
* range in meters
* @return GeoCoord object of point at bearing and range from initial point
*/
std::shared_ptr<GeoCoord> GeoCoord::pointAtDistance(double bearing, double range_meters) {
*/
std::shared_ptr<GeoCoord> GeoCoord::pointAtDistance(double bearing, double range_meters)
{
double range_radians = rangeMetersToRadians(range_meters);
double lat1 = this->getLatitude() * 1e-7;
double lon1 = this->getLongitude() * 1e-7;
@@ -446,5 +482,4 @@ std::shared_ptr<GeoCoord> GeoCoord::pointAtDistance(double bearing, double range
double lon = fmod(lon1 - dlon + PI, 2 * PI) - PI;
return std::make_shared<GeoCoord>(double(lat), double(lon), this->getAltitude());
}

View File

@@ -1,26 +1,27 @@
#pragma once
#include <algorithm>
#include <string>
#include <cstring>
#include <cstdint>
#include <cstring>
#include <math.h>
#include <stdint.h>
#include <stdexcept>
#include <memory>
#include <stdexcept>
#include <stdint.h>
#include <string>
#define PI 3.1415926535897932384626433832795
#define OLC_CODE_LEN 11
// Helper functions
// Raises a number to an exponent, handling negative exponents.
static inline double pow_neg(double base, double exponent) {
if (exponent == 0) {
return 1;
} else if (exponent > 0) {
return pow(base, exponent);
}
return 1 / pow(base, -exponent);
static inline double pow_neg(double base, double exponent)
{
if (exponent == 0) {
return 1;
} else if (exponent > 0) {
return pow(base, exponent);
}
return 1 / pow(base, -exponent);
}
static inline double toRadians(double deg)
@@ -35,8 +36,7 @@ static inline double toDegrees(double r)
// GeoCoord structs/classes
// A struct to hold the data for a DMS coordinate.
struct DMS
{
struct DMS {
uint8_t latDeg;
uint8_t latMin;
uint32_t latSec;
@@ -48,8 +48,7 @@ struct DMS
};
// A struct to hold the data for a UTM coordinate, this is also used when creating an MGRS coordinate.
struct UTM
{
struct UTM {
uint8_t zone;
char band;
uint32_t easting;
@@ -57,8 +56,7 @@ struct UTM
};
// A struct to hold the data for a MGRS coordinate.
struct MGRS
{
struct MGRS {
uint8_t zone;
char band;
char east100k;
@@ -80,85 +78,85 @@ struct OLC {
char code[OLC_CODE_LEN + 1]; // +1 for null termination
};
class GeoCoord {
private:
int32_t _latitude = 0;
int32_t _longitude = 0;
int32_t _altitude = 0;
class GeoCoord
{
private:
int32_t _latitude = 0;
int32_t _longitude = 0;
int32_t _altitude = 0;
DMS _dms = {};
UTM _utm = {};
MGRS _mgrs = {};
OSGR _osgr = {};
OLC _olc = {};
DMS _dms = {};
UTM _utm = {};
MGRS _mgrs = {};
OSGR _osgr = {};
OLC _olc = {};
bool _dirty = true;
bool _dirty = true;
void setCoords();
void setCoords();
public:
GeoCoord();
GeoCoord(int32_t lat, int32_t lon, int32_t alt);
GeoCoord(double lat, double lon, int32_t alt);
GeoCoord(float lat, float lon, int32_t alt);
public:
GeoCoord();
GeoCoord(int32_t lat, int32_t lon, int32_t alt);
GeoCoord(double lat, double lon, int32_t alt);
GeoCoord(float lat, float lon, int32_t alt);
void updateCoords(const int32_t lat, const int32_t lon, const int32_t alt);
void updateCoords(const double lat, const double lon, const int32_t alt);
void updateCoords(const float lat, const float lon, const int32_t alt);
void updateCoords(const int32_t lat, const int32_t lon, const int32_t alt);
void updateCoords(const double lat, const double lon, const int32_t alt);
void updateCoords(const float lat, const float lon, const int32_t alt);
// Conversions
static void latLongToDMS(const double lat, const double lon, DMS &dms);
static void latLongToUTM(const double lat, const double lon, UTM &utm);
static void latLongToMGRS(const double lat, const double lon, MGRS &mgrs);
static void latLongToOSGR(const double lat, const double lon, OSGR &osgr);
static void latLongToOLC(const double lat, const double lon, OLC &olc);
static void convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude);
static float latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b);
static float bearing(double lat1, double lon1, double lat2, double lon2);
static float rangeRadiansToMeters(double range_radians);
static float rangeMetersToRadians(double range_meters);
// Conversions
static void latLongToDMS(const double lat, const double lon, DMS &dms);
static void latLongToUTM(const double lat, const double lon, UTM &utm);
static void latLongToMGRS(const double lat, const double lon, MGRS &mgrs);
static void latLongToOSGR(const double lat, const double lon, OSGR &osgr);
static void latLongToOLC(const double lat, const double lon, OLC &olc);
static void convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude);
static float latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b);
static float bearing(double lat1, double lon1, double lat2, double lon2);
static float rangeRadiansToMeters(double range_radians);
static float rangeMetersToRadians(double range_meters);
// Point to point conversions
int32_t distanceTo(const GeoCoord& pointB);
int32_t bearingTo(const GeoCoord& pointB);
std::shared_ptr<GeoCoord> pointAtDistance(double bearing, double range);
// Point to point conversions
int32_t distanceTo(const GeoCoord &pointB);
int32_t bearingTo(const GeoCoord &pointB);
std::shared_ptr<GeoCoord> pointAtDistance(double bearing, double range);
// Lat lon alt getters
int32_t getLatitude() const { return _latitude; }
int32_t getLongitude() const { return _longitude; }
int32_t getAltitude() const { return _altitude; }
// Lat lon alt getters
int32_t getLatitude() const { return _latitude; }
int32_t getLongitude() const { return _longitude; }
int32_t getAltitude() const { return _altitude; }
// DMS getters
uint8_t getDMSLatDeg() const { return _dms.latDeg; }
uint8_t getDMSLatMin() const { return _dms.latMin; }
uint32_t getDMSLatSec() const { return _dms.latSec; }
char getDMSLatCP() const { return _dms.latCP; }
uint8_t getDMSLonDeg() const { return _dms.lonDeg; }
uint8_t getDMSLonMin() const { return _dms.lonMin; }
uint32_t getDMSLonSec() const { return _dms.lonSec; }
char getDMSLonCP() const { return _dms.lonCP; }
// DMS getters
uint8_t getDMSLatDeg() const { return _dms.latDeg; }
uint8_t getDMSLatMin() const { return _dms.latMin; }
uint32_t getDMSLatSec() const { return _dms.latSec; }
char getDMSLatCP() const { return _dms.latCP; }
uint8_t getDMSLonDeg() const { return _dms.lonDeg; }
uint8_t getDMSLonMin() const { return _dms.lonMin; }
uint32_t getDMSLonSec() const { return _dms.lonSec; }
char getDMSLonCP() const { return _dms.lonCP; }
// UTM getters
uint8_t getUTMZone() const { return _utm.zone; }
char getUTMBand() const { return _utm.band; }
uint32_t getUTMEasting() const { return _utm.easting; }
uint32_t getUTMNorthing() const { return _utm.northing; }
// UTM getters
uint8_t getUTMZone() const { return _utm.zone; }
char getUTMBand() const { return _utm.band; }
uint32_t getUTMEasting() const { return _utm.easting; }
uint32_t getUTMNorthing() const { return _utm.northing; }
// MGRS getters
uint8_t getMGRSZone() const { return _mgrs.zone; }
char getMGRSBand() const { return _mgrs.band; }
char getMGRSEast100k() const { return _mgrs.east100k; }
char getMGRSNorth100k() const { return _mgrs.north100k; }
uint32_t getMGRSEasting() const { return _mgrs.easting; }
uint32_t getMGRSNorthing() const { return _mgrs.northing; }
// MGRS getters
uint8_t getMGRSZone() const { return _mgrs.zone; }
char getMGRSBand() const { return _mgrs.band; }
char getMGRSEast100k() const { return _mgrs.east100k; }
char getMGRSNorth100k() const { return _mgrs.north100k; }
uint32_t getMGRSEasting() const { return _mgrs.easting; }
uint32_t getMGRSNorthing() const { return _mgrs.northing; }
// OSGR getters
char getOSGRE100k() const { return _osgr.e100k; }
char getOSGRN100k() const { return _osgr.n100k; }
uint32_t getOSGREasting() const { return _osgr.easting; }
uint32_t getOSGRNorthing() const { return _osgr.northing; }
// OSGR getters
char getOSGRE100k() const { return _osgr.e100k; }
char getOSGRN100k() const { return _osgr.n100k; }
uint32_t getOSGREasting() const { return _osgr.easting; }
uint32_t getOSGRNorthing() const { return _osgr.northing; }
// OLC getter
void getOLCCode(char* code) { strncpy(code, _olc.code, OLC_CODE_LEN + 1); } // +1 for null termination
// OLC getter
void getOLCCode(char *code) { strncpy(code, _olc.code, OLC_CODE_LEN + 1); } // +1 for null termination
};

View File

@@ -1,12 +1,12 @@
#include "configuration.h"
#include "NMEAGPS.h"
#include "RTC.h"
#include "configuration.h"
#include <TinyGPS++.h>
// GPS solutions older than this will be rejected - see TinyGPSDatum::age()
#define GPS_SOL_EXPIRY_MS 5000 // in millis. give 1 second time to combine different sentences. NMEA Frequency isn't higher anyway
#define NMEA_MSG_GXGSA "GNGSA" // GSA message (GPGSA, GNGSA etc)
#define GPS_SOL_EXPIRY_MS 5000 // in millis. give 1 second time to combine different sentences. NMEA Frequency isn't higher anyway
#define NMEA_MSG_GXGSA "GNGSA" // GSA message (GPGSA, GNGSA etc)
static int32_t toDegInt(RawDegrees d)
{
@@ -20,19 +20,18 @@ static int32_t toDegInt(RawDegrees d)
bool NMEAGPS::factoryReset()
{
#ifdef PIN_GPS_REINIT
//The L76K GNSS on the T-Echo requires the RESET pin to be pulled LOW
// The L76K GNSS on the T-Echo requires the RESET pin to be pulled LOW
digitalWrite(PIN_GPS_REINIT, 0);
pinMode(PIN_GPS_REINIT, OUTPUT);
delay(150); //The L76K datasheet calls for at least 100MS delay
delay(150); // The L76K datasheet calls for at least 100MS delay
digitalWrite(PIN_GPS_REINIT, 1);
#endif
#endif
// send the UBLOX Factory Reset Command regardless of detect state, something is very wrong, just assume it's UBLOX.
// Factory Reset
byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF,
0xFB, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xFF, 0xFF, 0x00, 0x00, 0x17, 0x2B, 0x7E};
_serial_gps->write(_message_reset,sizeof(_message_reset));
byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFB, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x17, 0x2B, 0x7E};
_serial_gps->write(_message_reset, sizeof(_message_reset));
delay(1000);
return true;
}
@@ -40,7 +39,7 @@ bool NMEAGPS::factoryReset()
bool NMEAGPS::setupGPS()
{
GPS::setupGPS();
#ifdef PIN_GPS_PPS
// pulse per second
// FIXME - move into shared GPS code
@@ -84,8 +83,9 @@ The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of s
t.tm_mon = d.month() - 1;
t.tm_year = d.year() - 1900;
t.tm_isdst = false;
if (t.tm_mon > -1){
LOG_DEBUG("NMEA GPS time %02d-%02d-%02d %02d:%02d:%02d\n", d.year(), d.month(), t.tm_mday, t.tm_hour, t.tm_min, t.tm_sec);
if (t.tm_mon > -1) {
LOG_DEBUG("NMEA GPS time %02d-%02d-%02d %02d:%02d:%02d\n", d.year(), d.month(), t.tm_mday, t.tm_hour, t.tm_min,
t.tm_sec);
perhapsSetRTC(RTCQualityGPS, t);
return true;
} else
@@ -102,47 +102,44 @@ The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of s
*/
bool NMEAGPS::lookForLocation()
{
// By default, TinyGPS++ does not parse GPGSA lines, which give us
// By default, TinyGPS++ does not parse GPGSA lines, which give us
// the 2D/3D fixType (see NMEAGPS.h)
// At a minimum, use the fixQuality indicator in GPGGA (FIXME?)
fixQual = reader.fixQuality();
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
fixType = atoi(gsafixtype.value()); // will set to zero if no data
fixType = atoi(gsafixtype.value()); // will set to zero if no data
// LOG_DEBUG("FIX QUAL=%d, TYPE=%d\n", fixQual, fixType);
#endif
// check if GPS has an acceptable lock
if (! hasLock())
if (!hasLock())
return false;
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("AGE: LOC=%d FIX=%d DATE=%d TIME=%d\n",
reader.location.age(),
LOG_DEBUG("AGE: LOC=%d FIX=%d DATE=%d TIME=%d\n", reader.location.age(),
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
gsafixtype.age(),
gsafixtype.age(),
#else
0,
0,
#endif
reader.date.age(), reader.time.age());
#endif // GPS_EXTRAVERBOSE
reader.date.age(), reader.time.age());
#endif // GPS_EXTRAVERBOSE
// check if a complete GPS solution set is available for reading
// tinyGPSDatum::age() also includes isValid() test
// FIXME
if (! ((reader.location.age() < GPS_SOL_EXPIRY_MS) &&
if (!((reader.location.age() < GPS_SOL_EXPIRY_MS) &&
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
(gsafixtype.age() < GPS_SOL_EXPIRY_MS) &&
(gsafixtype.age() < GPS_SOL_EXPIRY_MS) &&
#endif
(reader.time.age() < GPS_SOL_EXPIRY_MS) &&
(reader.date.age() < GPS_SOL_EXPIRY_MS)))
{
(reader.time.age() < GPS_SOL_EXPIRY_MS) && (reader.date.age() < GPS_SOL_EXPIRY_MS))) {
LOG_WARN("SOME data is TOO OLD: LOC %u, TIME %u, DATE %u\n", reader.location.age(), reader.time.age(), reader.date.age());
return false;
}
// Is this a new point or are we re-reading the previous one?
if (! reader.location.isUpdated())
if (!reader.location.isUpdated())
return false;
// We know the solution is fresh and valid, so just read the data
@@ -150,19 +147,19 @@ bool NMEAGPS::lookForLocation()
// Bail out EARLY to avoid overwriting previous good data (like #857)
if (toDegInt(loc.lat) > 900000000) {
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LAT %i\n",toDegInt(loc.lat));
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LAT %i\n", toDegInt(loc.lat));
#endif
return false;
}
if (toDegInt(loc.lng) > 1800000000) {
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LNG %i\n",toDegInt(loc.lng));
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LNG %i\n", toDegInt(loc.lng));
#endif
return false;
}
p.location_source = Position_LocSource_LOC_INTERNAL;
p.location_source = meshtastic_Position_LocSource_LOC_INTERNAL;
// Dilution of precision (an accuracy metric) is reported in 10^2 units, so we need to scale down when we use it
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
@@ -209,11 +206,11 @@ bool NMEAGPS::lookForLocation()
}
if (reader.course.isUpdated() && reader.course.isValid()) {
if (reader.course.value() < 36000) { // sanity check
p.ground_track = reader.course.value() * 1e3; // Scale the heading (in degrees * 10^-2) to match the expected degrees * 10^-5
if (reader.course.value() < 36000) { // sanity check
p.ground_track =
reader.course.value() * 1e3; // Scale the heading (in degrees * 10^-2) to match the expected degrees * 10^-5
} else {
LOG_WARN("BOGUS course.value() REJECTED: %d\n",
reader.course.value());
LOG_WARN("BOGUS course.value() REJECTED: %d\n", reader.course.value());
}
}
@@ -224,14 +221,13 @@ bool NMEAGPS::lookForLocation()
return true;
}
bool NMEAGPS::hasLock()
{
// Using GPGGA fix quality indicator
if (fixQual >= 1 && fixQual <= 5) {
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
// Use GPGSA fix type 2D/3D (better) if available
if (fixType == 3 || fixType == 0) // zero means "no data received"
if (fixType == 3 || fixType == 0) // zero means "no data received"
#endif
return true;
}

View File

@@ -12,14 +12,14 @@
class NMEAGPS : public GPS
{
TinyGPSPlus reader;
uint8_t fixQual = 0; // fix quality from GPGGA
uint8_t fixQual = 0; // fix quality from GPGGA
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
// (20210908) TinyGps++ can only read the GPGSA "FIX TYPE" field
// via optional feature "custom fields", currently disabled (bug #525)
TinyGPSCustom gsafixtype; // custom extract fix type from GPGSA
TinyGPSCustom gsapdop; // custom extract PDOP from GPGSA
uint8_t fixType = 0; // fix type from GPGSA
TinyGPSCustom gsafixtype; // custom extract fix type from GPGSA
TinyGPSCustom gsapdop; // custom extract PDOP from GPGSA
uint8_t fixType = 0; // fix type from GPGSA
#endif
public:
@@ -29,9 +29,9 @@ class NMEAGPS : public GPS
protected:
/** Subclasses should look for serial rx characters here and feed it to their GPS parser
*
*
* Return true if we received a valid message from the GPS
*/
*/
virtual bool whileIdle() override;
/**

View File

@@ -16,17 +16,13 @@
* -------------------------------------------
*/
uint32_t printWPL(char *buf, size_t bufsz, const Position &pos, const char *name)
uint32_t printWPL(char *buf, size_t bufsz, const meshtastic_Position &pos, const char *name)
{
GeoCoord geoCoord(pos.latitude_i,pos.longitude_i,pos.altitude);
uint32_t len = snprintf(buf, bufsz, "$GNWPL,%02d%07.4f,%c,%03d%07.4f,%c,%s",
geoCoord.getDMSLatDeg(),
(abs(geoCoord.getLatitude()) - geoCoord.getDMSLatDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLatCP(),
geoCoord.getDMSLonDeg(),
(abs(geoCoord.getLongitude()) - geoCoord.getDMSLonDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLonCP(),
name);
GeoCoord geoCoord(pos.latitude_i, pos.longitude_i, pos.altitude);
uint32_t len = snprintf(buf, bufsz, "$GNWPL,%02d%07.4f,%c,%03d%07.4f,%c,%s", geoCoord.getDMSLatDeg(),
(abs(geoCoord.getLatitude()) - geoCoord.getDMSLatDeg() * 1e+7) * 6e-6, geoCoord.getDMSLatCP(),
geoCoord.getDMSLonDeg(), (abs(geoCoord.getLongitude()) - geoCoord.getDMSLonDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLonCP(), name);
uint32_t chk = 0;
for (uint32_t i = 1; i < len; i++) {
chk ^= buf[i];
@@ -51,35 +47,21 @@ uint32_t printWPL(char *buf, size_t bufsz, const Position &pos, const char *name
* 8 Horizontal Dilution of precision (meters)
* 9 Antenna Altitude above/below mean-sea-level (geoid) (in meters)
* 10 Units of antenna altitude, meters
* 11 Geoidal separation, the difference between the WGS-84 earth ellipsoid and mean-sea-level (geoid), "-" means mean-sea-level below ellipsoid
* 12 Units of geoidal separation, meters
* 13 Age of differential GPS data, time in seconds since last SC104 type 1 or 9 update, null field when DGPS is not used
* 14 Differential reference station ID, 0000-1023
* 15 Checksum
* 11 Geoidal separation, the difference between the WGS-84 earth ellipsoid and mean-sea-level (geoid), "-" means mean-sea-level
* below ellipsoid 12 Units of geoidal separation, meters 13 Age of differential GPS data, time in seconds since last SC104 type 1
* or 9 update, null field when DGPS is not used 14 Differential reference station ID, 0000-1023 15 Checksum
* -------------------------------------------
*/
uint32_t printGGA(char *buf, size_t bufsz, const Position &pos)
uint32_t printGGA(char *buf, size_t bufsz, const meshtastic_Position &pos)
{
GeoCoord geoCoord(pos.latitude_i,pos.longitude_i,pos.altitude);
uint32_t len = snprintf(buf, bufsz, "$GNGGA,%06u.%03u,%02d%07.4f,%c,%03d%07.4f,%c,%u,%02u,%04u,%04d,%c,%04d,%c,%d,%04d",
pos.time / 1000,
pos.time % 1000,
geoCoord.getDMSLatDeg(),
(abs(geoCoord.getLatitude()) - geoCoord.getDMSLatDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLatCP(),
geoCoord.getDMSLonDeg(),
(abs(geoCoord.getLongitude()) - geoCoord.getDMSLonDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLonCP(),
pos.fix_type,
pos.sats_in_view,
pos.HDOP,
geoCoord.getAltitude(),
'M',
pos.altitude_geoidal_separation,
'M',
0,
0);
GeoCoord geoCoord(pos.latitude_i, pos.longitude_i, pos.altitude);
uint32_t len =
snprintf(buf, bufsz, "$GNGGA,%06u.%03u,%02d%07.4f,%c,%03d%07.4f,%c,%u,%02u,%04u,%04d,%c,%04d,%c,%d,%04d", pos.time / 1000,
pos.time % 1000, geoCoord.getDMSLatDeg(), (abs(geoCoord.getLatitude()) - geoCoord.getDMSLatDeg() * 1e+7) * 6e-6,
geoCoord.getDMSLatCP(), geoCoord.getDMSLonDeg(),
(abs(geoCoord.getLongitude()) - geoCoord.getDMSLonDeg() * 1e+7) * 6e-6, geoCoord.getDMSLonCP(), pos.fix_type,
pos.sats_in_view, pos.HDOP, geoCoord.getAltitude(), 'M', pos.altitude_geoidal_separation, 'M', 0, 0);
uint32_t chk = 0;
for (uint32_t i = 1; i < len; i++) {

View File

@@ -1,7 +1,7 @@
#pragma once
#include <Arduino.h>
#include "main.h"
#include <Arduino.h>
uint32_t printWPL(char *buf, size_t bufsz, const Position &pos, const char *name);
uint32_t printGGA(char *buf, size_t bufsz, const Position &pos);
uint32_t printWPL(char *buf, size_t bufsz, const meshtastic_Position &pos, const char *name);
uint32_t printGGA(char *buf, size_t bufsz, const meshtastic_Position &pos);

View File

@@ -20,7 +20,7 @@ void readFromRTC()
{
struct timeval tv; /* btw settimeofday() is helpfull here too*/
#ifdef RV3028_RTC
if(rtc_found == RV3028_RTC) {
if (rtc_found == RV3028_RTC) {
uint32_t now = millis();
Melopero_RV3028 rtc;
rtc.initI2C();
@@ -41,7 +41,7 @@ void readFromRTC()
}
}
#elif defined(PCF8563_RTC)
if(rtc_found == PCF8563_RTC) {
if (rtc_found == PCF8563_RTC) {
uint32_t now = millis();
PCF8563_Class rtc;
#ifdef RTC_USE_WIRE1
@@ -66,7 +66,7 @@ void readFromRTC()
currentQuality = RTCQualityDevice;
}
}
#else
#else
if (!gettimeofday(&tv, NULL)) {
uint32_t now = millis();
LOG_DEBUG("Read RTC time as %ld\n", tv.tv_sec);
@@ -87,12 +87,11 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
currentQuality = q;
shouldSet = true;
LOG_DEBUG("Upgrading time to RTC %ld secs (quality %d)\n", tv->tv_sec, q);
} else if(q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000UL)) {
} else if (q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000UL)) {
// Every 12 hrs we will slam in a new GPS time, to correct for local RTC clock drift
shouldSet = true;
LOG_DEBUG("Reapplying external time to correct clock drift %ld secs\n", tv->tv_sec);
}
else
} else
shouldSet = false;
if (shouldSet) {
@@ -104,24 +103,26 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
// If this platform has a setable RTC, set it
#ifdef RV3028_RTC
if(rtc_found == RV3028_RTC) {
if (rtc_found == RV3028_RTC) {
Melopero_RV3028 rtc;
rtc.initI2C();
tm *t = localtime(&tv->tv_sec);
rtc.setTime(t->tm_year + 1900, t->tm_mon + 1, t->tm_wday, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec);
LOG_DEBUG("RV3028_RTC setTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
LOG_DEBUG("RV3028_RTC setTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday,
t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
}
#elif defined(PCF8563_RTC)
if(rtc_found == PCF8563_RTC) {
if (rtc_found == PCF8563_RTC) {
PCF8563_Class rtc;
#ifdef RTC_USE_WIRE1
rtc.begin(Wire1);
rtc.begin(Wire1);
#else
rtc.begin();
rtc.begin();
#endif
tm *t = localtime(&tv->tv_sec);
rtc.setDateTime(t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec);
LOG_DEBUG("PCF8563_RTC setDateTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
LOG_DEBUG("PCF8563_RTC setDateTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday,
t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
}
#elif defined(ARCH_ESP32)
settimeofday(tv, NULL);
@@ -160,7 +161,7 @@ bool perhapsSetRTC(RTCQuality q, struct tm &t)
uint32_t getTime()
{
return (((uint32_t) millis() - timeStartMsec) / 1000) + zeroOffsetSecs;
return (((uint32_t)millis() - timeStartMsec) / 1000) + zeroOffsetSecs;
}
uint32_t getValidTime(RTCQuality minQuality)

View File

@@ -352,7 +352,7 @@ static void drawCriticalFaultFrame(OLEDDisplay *display, OLEDDisplayUiState *sta
}
// Ignore messages orginating from phone (from the current node 0x0) unless range test or store and forward module are enabled
static bool shouldDrawMessage(const MeshPacket *packet)
static bool shouldDrawMessage(const meshtastic_MeshPacket *packet)
{
return packet->from != 0 && !moduleConfig.range_test.enabled && !moduleConfig.store_forward.enabled;
}
@@ -365,8 +365,8 @@ static void drawTextMessageFrame(OLEDDisplay *display, OLEDDisplayUiState *state
// the max length of this buffer is much longer than we can possibly print
static char tempBuf[237];
MeshPacket &mp = devicestate.rx_text_message;
NodeInfo *node = nodeDB.getNode(getFrom(&mp));
meshtastic_MeshPacket &mp = devicestate.rx_text_message;
meshtastic_NodeInfo *node = nodeDB.getNode(getFrom(&mp));
// LOG_DEBUG("drawing text message from 0x%x: %s\n", mp.from,
// mp.decoded.variant.data.decoded.bytes);
@@ -375,7 +375,7 @@ static void drawTextMessageFrame(OLEDDisplay *display, OLEDDisplayUiState *state
// be wrapped. Currently only spaces and "-" are allowed for wrapping
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_INVERTED) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
display->setColor(BLACK);
}
@@ -556,7 +556,7 @@ static void drawGPSAltitude(OLEDDisplay *display, int16_t x, int16_t y, const GP
} else {
geoCoord.updateCoords(int32_t(gps->getLatitude()), int32_t(gps->getLongitude()), int32_t(gps->getAltitude()));
displayLine = "Altitude: " + String(geoCoord.getAltitude()) + "m";
if (config.display.units == Config_DisplayConfig_DisplayUnits_IMPERIAL)
if (config.display.units == meshtastic_Config_DisplayConfig_DisplayUnits_IMPERIAL)
displayLine = "Altitude: " + String(geoCoord.getAltitude() * METERS_TO_FEET) + "ft";
display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(displayLine))) / 2, y, displayLine);
}
@@ -578,21 +578,21 @@ static void drawGPScoordinates(OLEDDisplay *display, int16_t x, int16_t y, const
geoCoord.updateCoords(int32_t(gps->getLatitude()), int32_t(gps->getLongitude()), int32_t(gps->getAltitude()));
if (gpsFormat != Config_DisplayConfig_GpsCoordinateFormat_DMS) {
if (gpsFormat != meshtastic_Config_DisplayConfig_GpsCoordinateFormat_DMS) {
char coordinateLine[22];
if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_DEC) { // Decimal Degrees
if (gpsFormat == meshtastic_Config_DisplayConfig_GpsCoordinateFormat_DEC) { // Decimal Degrees
snprintf(coordinateLine, sizeof(coordinateLine), "%f %f", geoCoord.getLatitude() * 1e-7,
geoCoord.getLongitude() * 1e-7);
} else if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_UTM) { // Universal Transverse Mercator
} else if (gpsFormat == meshtastic_Config_DisplayConfig_GpsCoordinateFormat_UTM) { // Universal Transverse Mercator
snprintf(coordinateLine, sizeof(coordinateLine), "%2i%1c %06u %07u", geoCoord.getUTMZone(), geoCoord.getUTMBand(),
geoCoord.getUTMEasting(), geoCoord.getUTMNorthing());
} else if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_MGRS) { // Military Grid Reference System
} else if (gpsFormat == meshtastic_Config_DisplayConfig_GpsCoordinateFormat_MGRS) { // Military Grid Reference System
snprintf(coordinateLine, sizeof(coordinateLine), "%2i%1c %1c%1c %05u %05u", geoCoord.getMGRSZone(),
geoCoord.getMGRSBand(), geoCoord.getMGRSEast100k(), geoCoord.getMGRSNorth100k(),
geoCoord.getMGRSEasting(), geoCoord.getMGRSNorthing());
} else if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_OLC) { // Open Location Code
} else if (gpsFormat == meshtastic_Config_DisplayConfig_GpsCoordinateFormat_OLC) { // Open Location Code
geoCoord.getOLCCode(coordinateLine);
} else if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_OSGR) { // Ordnance Survey Grid Reference
} else if (gpsFormat == meshtastic_Config_DisplayConfig_GpsCoordinateFormat_OSGR) { // Ordnance Survey Grid Reference
if (geoCoord.getOSGRE100k() == 'I' || geoCoord.getOSGRN100k() == 'I') // OSGR is only valid around the UK region
snprintf(coordinateLine, sizeof(coordinateLine), "%s", "Out of Boundary");
else
@@ -699,7 +699,7 @@ static float estimatedHeading(double lat, double lon)
/// Sometimes we will have Position objects that only have a time, so check for
/// valid lat/lon
static bool hasPosition(NodeInfo *n)
static bool hasPosition(meshtastic_NodeInfo *n)
{
return n->has_position && (n->position.latitude_i != 0 || n->position.longitude_i != 0);
}
@@ -709,7 +709,7 @@ static uint16_t getCompassDiam(OLEDDisplay *display)
uint16_t diam = 0;
uint16_t offset = 0;
if (config.display.displaymode != Config_DisplayConfig_DisplayMode_DEFAULT)
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT)
offset = FONT_HEIGHT_SMALL;
// get the smaller of the 2 dimensions and subtract 20
@@ -786,7 +786,7 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_
prevFrame = state->currentFrame;
nodeIndex = (nodeIndex + 1) % nodeDB.getNumNodes();
NodeInfo *n = nodeDB.getNodeByIndex(nodeIndex);
meshtastic_NodeInfo *n = nodeDB.getNodeByIndex(nodeIndex);
if (n->num == nodeDB.getNodeNum()) {
// Don't show our node, just skip to next
nodeIndex = (nodeIndex + 1) % nodeDB.getNumNodes();
@@ -795,14 +795,14 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_
displayedNodeNum = n->num;
}
NodeInfo *node = nodeDB.getNodeByIndex(nodeIndex);
meshtastic_NodeInfo *node = nodeDB.getNodeByIndex(nodeIndex);
display->setFont(FONT_SMALL);
// The coordinates define the left starting point of the text
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_INVERTED) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
}
@@ -832,12 +832,12 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_
static char distStr[20];
strncpy(distStr, "? km", sizeof(distStr)); // might not have location data
NodeInfo *ourNode = nodeDB.getNode(nodeDB.getNodeNum());
meshtastic_NodeInfo *ourNode = nodeDB.getNode(nodeDB.getNodeNum());
const char *fields[] = {username, distStr, signalStr, lastStr, NULL};
int16_t compassX = 0, compassY = 0;
// coordinates for the center of the compass/circle
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_DEFAULT) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
compassX = x + SCREEN_WIDTH - getCompassDiam(display) / 2 - 5;
compassY = y + SCREEN_HEIGHT / 2;
} else {
@@ -847,18 +847,18 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_
bool hasNodeHeading = false;
if (ourNode && hasPosition(ourNode)) {
Position &op = ourNode->position;
meshtastic_Position &op = ourNode->position;
float myHeading = estimatedHeading(DegD(op.latitude_i), DegD(op.longitude_i));
drawCompassNorth(display, compassX, compassY, myHeading);
if (hasPosition(node)) {
// display direction toward node
hasNodeHeading = true;
Position &p = node->position;
meshtastic_Position &p = node->position;
float d =
GeoCoord::latLongToMeter(DegD(p.latitude_i), DegD(p.longitude_i), DegD(op.latitude_i), DegD(op.longitude_i));
if (config.display.units == Config_DisplayConfig_DisplayUnits_IMPERIAL) {
if (config.display.units == meshtastic_Config_DisplayConfig_DisplayUnits_IMPERIAL) {
if (d < (2 * MILES_TO_FEET))
snprintf(distStr, sizeof(distStr), "%.0f ft", d * METERS_TO_FEET);
else
@@ -887,7 +887,7 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_
}
display->drawCircle(compassX, compassY, getCompassDiam(display) / 2);
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_INVERTED) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->setColor(BLACK);
}
// Must be after distStr is populated
@@ -910,7 +910,8 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_
// #else
Screen::Screen(uint8_t address, int sda, int scl)
: OSThread("Screen"), cmdQueue(32),
dispdev(address, sda, scl, screen_model == Config_DisplayConfig_OledType_OLED_SH1107 ? GEOMETRY_128_128 : GEOMETRY_128_64),
dispdev(address, sda, scl,
screen_model == meshtastic_Config_DisplayConfig_OledType_OLED_SH1107 ? GEOMETRY_128_128 : GEOMETRY_128_64),
ui(&dispdev)
{
address_found = address;
@@ -961,8 +962,8 @@ void Screen::setup()
useDisplay = true;
#ifdef AutoOLEDWire_h
if (screen_model == Config_DisplayConfig_OledType_OLED_SH1107)
screen_model = Config_DisplayConfig_OledType_OLED_SH1106;
if (screen_model == meshtastic_Config_DisplayConfig_OledType_OLED_SH1107)
screen_model = meshtastic_Config_DisplayConfig_OledType_OLED_SH1106;
dispdev.setDetected(screen_model);
#endif
@@ -1084,7 +1085,7 @@ int32_t Screen::runOnce()
}
#ifndef DISABLE_WELCOME_UNSET
if (showingNormalScreen && config.lora.region == Config_LoRaConfig_RegionCode_UNSET) {
if (showingNormalScreen && config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_UNSET) {
setWelcomeFrames();
}
#endif
@@ -1404,7 +1405,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
// The coordinates define the left starting point of the text
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_INVERTED) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
display->setColor(BLACK);
}
@@ -1418,20 +1419,20 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
// Display power status
if (powerStatus->getHasBattery()) {
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_DEFAULT) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
drawBattery(display, x, y + 2, imgBattery, powerStatus);
} else {
drawBattery(display, x + 1, y + 3, imgBattery, powerStatus);
}
} else if (powerStatus->knowsUSB()) {
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_DEFAULT) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
display->drawFastImage(x, y + 2, 16, 8, powerStatus->getHasUSB() ? imgUSB : imgPower);
} else {
display->drawFastImage(x + 1, y + 3, 16, 8, powerStatus->getHasUSB() ? imgUSB : imgPower);
}
}
// Display nodes status
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_DEFAULT) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 2, nodeStatus);
} else {
drawNodes(display, x + (SCREEN_WIDTH * 0.25), y + 3, nodeStatus);
@@ -1444,7 +1445,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
#endif
drawGPSpowerstat(display, x, yPos, gpsStatus);
} else {
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_DEFAULT) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_DEFAULT) {
drawGPS(display, x + (SCREEN_WIDTH * 0.63), y + 2, gpsStatus);
} else {
drawGPS(display, x + (SCREEN_WIDTH * 0.63), y + 3, gpsStatus);
@@ -1517,7 +1518,7 @@ void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, i
// The coordinates define the left starting point of the text
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_INVERTED) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
display->setColor(BLACK);
}
@@ -1649,7 +1650,7 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat
// The coordinates define the left starting point of the text
display->setTextAlignment(TEXT_ALIGN_LEFT);
if (config.display.displaymode == Config_DisplayConfig_DisplayMode_INVERTED) {
if (config.display.displaymode == meshtastic_Config_DisplayConfig_DisplayMode_INVERTED) {
display->fillRect(0 + x, 0 + y, x + display->getWidth(), y + FONT_HEIGHT_SMALL);
display->setColor(BLACK);
}
@@ -1676,25 +1677,25 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat
auto mode = "";
switch (config.lora.modem_preset) {
case Config_LoRaConfig_ModemPreset_SHORT_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_SLOW:
mode = "ShortS";
break;
case Config_LoRaConfig_ModemPreset_SHORT_FAST:
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST:
mode = "ShortF";
break;
case Config_LoRaConfig_ModemPreset_MEDIUM_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_SLOW:
mode = "MedS";
break;
case Config_LoRaConfig_ModemPreset_MEDIUM_FAST:
case meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_FAST:
mode = "MedF";
break;
case Config_LoRaConfig_ModemPreset_LONG_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_LONG_SLOW:
mode = "LongS";
break;
case Config_LoRaConfig_ModemPreset_LONG_FAST:
case meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST:
mode = "LongF";
break;
case Config_LoRaConfig_ModemPreset_VERY_LONG_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_VERY_LONG_SLOW:
mode = "VeryL";
break;
default:
@@ -1756,7 +1757,8 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat
display->drawString(x + SCREEN_WIDTH - display->getStringWidth(chUtil), y + FONT_HEIGHT_SMALL * 1, chUtil);
if (config.position.gps_enabled) {
// Line 3
if (config.display.gps_format != Config_DisplayConfig_GpsCoordinateFormat_DMS) // if DMS then don't draw altitude
if (config.display.gps_format !=
meshtastic_Config_DisplayConfig_GpsCoordinateFormat_DMS) // if DMS then don't draw altitude
drawGPSAltitude(display, x, y + FONT_HEIGHT_SMALL * 2, gpsStatus);
// Line 4
@@ -1804,7 +1806,7 @@ int Screen::handleStatusUpdate(const meshtastic::Status *arg)
return 0;
}
int Screen::handleTextMessage(const MeshPacket *packet)
int Screen::handleTextMessage(const meshtastic_MeshPacket *packet)
{
if (showingNormalScreen) {
setFrames(); // Regen the list of screens (will show new text message)

View File

@@ -110,8 +110,8 @@ class Screen : public concurrency::OSThread
CallbackObserver<Screen, const meshtastic::Status *>(this, &Screen::handleStatusUpdate);
CallbackObserver<Screen, const meshtastic::Status *> nodeStatusObserver =
CallbackObserver<Screen, const meshtastic::Status *>(this, &Screen::handleStatusUpdate);
CallbackObserver<Screen, const MeshPacket *> textMessageObserver =
CallbackObserver<Screen, const MeshPacket *>(this, &Screen::handleTextMessage);
CallbackObserver<Screen, const meshtastic_MeshPacket *> textMessageObserver =
CallbackObserver<Screen, const meshtastic_MeshPacket *>(this, &Screen::handleTextMessage);
CallbackObserver<Screen, const UIFrameEvent *> uiFrameEventObserver =
CallbackObserver<Screen, const UIFrameEvent *>(this, &Screen::handleUIFrameEvent);
@@ -273,7 +273,7 @@ class Screen : public concurrency::OSThread
DebugInfo *debug_info() { return &debugInfo; }
int handleStatusUpdate(const meshtastic::Status *arg);
int handleTextMessage(const MeshPacket *arg);
int handleTextMessage(const meshtastic_MeshPacket *arg);
int handleUIFrameEvent(const UIFrameEvent *arg);
/// Used to force (super slow) eink displays to draw critical frames

View File

@@ -2,425 +2,425 @@
// Font generated or edited with the glyphEditor
const uint8_t ArialMT_Plain_10_RU[] PROGMEM = {
0x0A, // Width: 10
0x0D, // Height: 13
0x20, // First char: 32
0xE0, // Number of chars: 224
// Jump Table:
0xFF, 0xFF, 0x00, 0x0A, // 32
0x00, 0x00, 0x04, 0x03, // 33
0x00, 0x04, 0x05, 0x04, // 34
0x00, 0x09, 0x09, 0x06, // 35
0x00, 0x12, 0x0A, 0x06, // 36
0x00, 0x1C, 0x10, 0x09, // 37
0x00, 0x2C, 0x0E, 0x08, // 38
0x00, 0x3A, 0x01, 0x02, // 39
0x00, 0x3B, 0x06, 0x04, // 40
0x00, 0x41, 0x06, 0x04, // 41
0x00, 0x47, 0x05, 0x04, // 42
0x00, 0x4C, 0x09, 0x06, // 43
0x00, 0x55, 0x04, 0x03, // 44
0x00, 0x59, 0x03, 0x03, // 45
0x00, 0x5C, 0x04, 0x03, // 46
0x00, 0x60, 0x05, 0x04, // 47
0x00, 0x65, 0x0A, 0x06, // 48
0x00, 0x6F, 0x08, 0x05, // 49
0x00, 0x77, 0x0A, 0x06, // 50
0x00, 0x81, 0x0A, 0x06, // 51
0x00, 0x8B, 0x0B, 0x07, // 52
0x00, 0x96, 0x0A, 0x06, // 53
0x00, 0xA0, 0x0A, 0x06, // 54
0x00, 0xAA, 0x09, 0x06, // 55
0x00, 0xB3, 0x0A, 0x06, // 56
0x00, 0xBD, 0x0A, 0x06, // 57
0x00, 0xC7, 0x04, 0x03, // 58
0x00, 0xCB, 0x04, 0x03, // 59
0x00, 0xCF, 0x0A, 0x06, // 60
0x00, 0xD9, 0x09, 0x06, // 61
0x00, 0xE2, 0x09, 0x06, // 62
0x00, 0xEB, 0x0B, 0x07, // 63
0x00, 0xF6, 0x14, 0x0B, // 64
0x01, 0x0A, 0x0E, 0x08, // 65
0x01, 0x18, 0x0C, 0x07, // 66
0x01, 0x24, 0x0C, 0x07, // 67
0x01, 0x30, 0x0B, 0x07, // 68
0x01, 0x3B, 0x0C, 0x07, // 69
0x01, 0x47, 0x09, 0x06, // 70
0x01, 0x50, 0x0D, 0x08, // 71
0x01, 0x5D, 0x0C, 0x07, // 72
0x01, 0x69, 0x04, 0x03, // 73
0x01, 0x6D, 0x08, 0x05, // 74
0x01, 0x75, 0x0E, 0x08, // 75
0x01, 0x83, 0x0C, 0x07, // 76
0x01, 0x8F, 0x10, 0x09, // 77
0x01, 0x9F, 0x0C, 0x07, // 78
0x01, 0xAB, 0x0E, 0x08, // 79
0x01, 0xB9, 0x0B, 0x07, // 80
0x01, 0xC4, 0x0E, 0x08, // 81
0x01, 0xD2, 0x0C, 0x07, // 82
0x01, 0xDE, 0x0C, 0x07, // 83
0x01, 0xEA, 0x0B, 0x07, // 84
0x01, 0xF5, 0x0C, 0x07, // 85
0x02, 0x01, 0x0D, 0x08, // 86
0x02, 0x0E, 0x11, 0x0A, // 87
0x02, 0x1F, 0x0E, 0x08, // 88
0x02, 0x2D, 0x0D, 0x08, // 89
0x02, 0x3A, 0x0C, 0x07, // 90
0x02, 0x46, 0x06, 0x04, // 91
0x02, 0x4C, 0x06, 0x04, // 92
0x02, 0x52, 0x04, 0x03, // 93
0x02, 0x56, 0x09, 0x06, // 94
0x02, 0x5F, 0x0C, 0x07, // 95
0x02, 0x6B, 0x03, 0x03, // 96
0x02, 0x6E, 0x0A, 0x06, // 97
0x02, 0x78, 0x0A, 0x06, // 98
0x02, 0x82, 0x0A, 0x06, // 99
0x02, 0x8C, 0x0A, 0x06, // 100
0x02, 0x96, 0x0A, 0x06, // 101
0x02, 0xA0, 0x05, 0x04, // 102
0x02, 0xA5, 0x0A, 0x06, // 103
0x02, 0xAF, 0x0A, 0x06, // 104
0x02, 0xB9, 0x04, 0x03, // 105
0x02, 0xBD, 0x04, 0x03, // 106
0x02, 0xC1, 0x08, 0x05, // 107
0x02, 0xC9, 0x04, 0x03, // 108
0x02, 0xCD, 0x10, 0x09, // 109
0x02, 0xDD, 0x0A, 0x06, // 110
0x02, 0xE7, 0x0A, 0x06, // 111
0x02, 0xF1, 0x0A, 0x06, // 112
0x02, 0xFB, 0x0A, 0x06, // 113
0x03, 0x05, 0x05, 0x04, // 114
0x03, 0x0A, 0x08, 0x05, // 115
0x03, 0x12, 0x06, 0x04, // 116
0x03, 0x18, 0x0A, 0x06, // 117
0x03, 0x22, 0x09, 0x06, // 118
0x03, 0x2B, 0x0E, 0x08, // 119
0x03, 0x39, 0x0A, 0x06, // 120
0x03, 0x43, 0x09, 0x06, // 121
0x03, 0x4C, 0x0A, 0x06, // 122
0x03, 0x56, 0x06, 0x04, // 123
0x03, 0x5C, 0x04, 0x03, // 124
0x03, 0x60, 0x05, 0x04, // 125
0x03, 0x65, 0x09, 0x06, // 126
0xFF, 0xFF, 0x00, 0x0A, // 127
0xFF, 0xFF, 0x00, 0x0A, // 128
0xFF, 0xFF, 0x00, 0x0A, // 129
0xFF, 0xFF, 0x00, 0x0A, // 130
0xFF, 0xFF, 0x00, 0x0A, // 131
0xFF, 0xFF, 0x00, 0x0A, // 132
0xFF, 0xFF, 0x00, 0x0A, // 133
0xFF, 0xFF, 0x00, 0x0A, // 134
0xFF, 0xFF, 0x00, 0x0A, // 135
0xFF, 0xFF, 0x00, 0x0A, // 136
0xFF, 0xFF, 0x00, 0x0A, // 137
0xFF, 0xFF, 0x00, 0x0A, // 138
0xFF, 0xFF, 0x00, 0x0A, // 139
0xFF, 0xFF, 0x00, 0x0A, // 140
0xFF, 0xFF, 0x00, 0x0A, // 141
0xFF, 0xFF, 0x00, 0x0A, // 142
0xFF, 0xFF, 0x00, 0x0A, // 143
0xFF, 0xFF, 0x00, 0x0A, // 144
0xFF, 0xFF, 0x00, 0x0A, // 145
0xFF, 0xFF, 0x00, 0x0A, // 146
0xFF, 0xFF, 0x00, 0x0A, // 147
0xFF, 0xFF, 0x00, 0x0A, // 148
0xFF, 0xFF, 0x00, 0x0A, // 149
0xFF, 0xFF, 0x00, 0x0A, // 150
0xFF, 0xFF, 0x00, 0x0A, // 151
0xFF, 0xFF, 0x00, 0x0A, // 152
0xFF, 0xFF, 0x00, 0x0A, // 153
0xFF, 0xFF, 0x00, 0x0A, // 154
0xFF, 0xFF, 0x00, 0x0A, // 155
0xFF, 0xFF, 0x00, 0x0A, // 156
0xFF, 0xFF, 0x00, 0x0A, // 157
0xFF, 0xFF, 0x00, 0x0A, // 158
0xFF, 0xFF, 0x00, 0x0A, // 159
0xFF, 0xFF, 0x00, 0x0A, // 160
0x03, 0x6E, 0x04, 0x03, // 161
0x03, 0x72, 0x0A, 0x06, // 162
0x03, 0x7C, 0x0C, 0x07, // 163
0x03, 0x88, 0x0A, 0x06, // 164
0x03, 0x92, 0x0A, 0x06, // 165
0x03, 0x9C, 0x04, 0x03, // 166
0x03, 0xA0, 0x0A, 0x06, // 167
0x03, 0xAA, 0x0C, 0x07, // 168
0x03, 0xB6, 0x0D, 0x08, // 169
0x03, 0xC3, 0x07, 0x05, // 170
0x03, 0xCA, 0x0A, 0x06, // 171
0x03, 0xD4, 0x09, 0x06, // 172
0x03, 0xDD, 0x03, 0x03, // 173
0x03, 0xE0, 0x0D, 0x08, // 174
0x03, 0xED, 0x0B, 0x07, // 175
0x03, 0xF8, 0x07, 0x05, // 176
0x03, 0xFF, 0x0A, 0x06, // 177
0x04, 0x09, 0x05, 0x04, // 178
0x04, 0x0E, 0x05, 0x04, // 179
0x04, 0x13, 0x05, 0x04, // 180
0x04, 0x18, 0x0A, 0x06, // 181
0x04, 0x22, 0x09, 0x06, // 182
0x04, 0x2B, 0x03, 0x03, // 183
0x04, 0x2E, 0x0B, 0x07, // 184
0x04, 0x39, 0x0B, 0x07, // 185
0x04, 0x44, 0x07, 0x05, // 186
0x04, 0x4B, 0x0A, 0x06, // 187
0x04, 0x55, 0x10, 0x09, // 188
0x04, 0x65, 0x10, 0x09, // 189
0x04, 0x75, 0x10, 0x09, // 190
0x04, 0x85, 0x0A, 0x06, // 191
0x04, 0x8F, 0x0C, 0x07, // 192
0x04, 0x9B, 0x0C, 0x07, // 193
0x04, 0xA7, 0x0C, 0x07, // 194
0x04, 0xB3, 0x0B, 0x07, // 195
0x04, 0xBE, 0x0C, 0x07, // 196
0x04, 0xCA, 0x0C, 0x07, // 197
0x04, 0xD6, 0x0C, 0x07, // 198
0x04, 0xE2, 0x0C, 0x07, // 199
0x04, 0xEE, 0x0C, 0x07, // 200
0x04, 0xFA, 0x0C, 0x07, // 201
0x05, 0x06, 0x0C, 0x07, // 202
0x05, 0x12, 0x0C, 0x07, // 203
0x05, 0x1E, 0x0C, 0x07, // 204
0x05, 0x2A, 0x0C, 0x07, // 205
0x05, 0x36, 0x0C, 0x07, // 206
0x05, 0x42, 0x0C, 0x07, // 207
0x05, 0x4E, 0x0B, 0x07, // 208
0x05, 0x59, 0x0C, 0x07, // 209
0x05, 0x65, 0x0B, 0x07, // 210
0x05, 0x70, 0x0C, 0x07, // 211
0x05, 0x7C, 0x0B, 0x07, // 212
0x05, 0x87, 0x0C, 0x07, // 213
0x05, 0x93, 0x0C, 0x07, // 214
0x05, 0x9F, 0x0C, 0x07, // 215
0x05, 0xAB, 0x0C, 0x07, // 216
0x05, 0xB7, 0x0E, 0x08, // 217
0x05, 0xC5, 0x0C, 0x07, // 218
0x05, 0xD1, 0x0C, 0x07, // 219
0x05, 0xDD, 0x0C, 0x07, // 220
0x05, 0xE9, 0x0C, 0x07, // 221
0x05, 0xF5, 0x0C, 0x07, // 222
0x06, 0x01, 0x0C, 0x07, // 223
0x06, 0x0D, 0x0C, 0x07, // 224
0x06, 0x19, 0x0C, 0x07, // 225
0x06, 0x25, 0x0C, 0x07, // 226
0x06, 0x31, 0x0B, 0x07, // 227
0x06, 0x3C, 0x0C, 0x07, // 228
0x06, 0x48, 0x0B, 0x07, // 229
0x06, 0x53, 0x0C, 0x07, // 230
0x06, 0x5F, 0x0C, 0x07, // 231
0x06, 0x6B, 0x0C, 0x07, // 232
0x06, 0x77, 0x0C, 0x07, // 233
0x06, 0x83, 0x0C, 0x07, // 234
0x06, 0x8F, 0x0C, 0x07, // 235
0x06, 0x9B, 0x0C, 0x07, // 236
0x06, 0xA7, 0x0C, 0x07, // 237
0x06, 0xB3, 0x0C, 0x07, // 238
0x06, 0xBF, 0x0C, 0x07, // 239
0x06, 0xCB, 0x0B, 0x07, // 240
0x06, 0xD6, 0x0C, 0x07, // 241
0x06, 0xE2, 0x0B, 0x07, // 242
0x06, 0xED, 0x0C, 0x07, // 243
0x06, 0xF9, 0x0B, 0x07, // 244
0x07, 0x04, 0x0C, 0x07, // 245
0x07, 0x10, 0x0C, 0x07, // 246
0x07, 0x1C, 0x0C, 0x07, // 247
0x07, 0x28, 0x0C, 0x07, // 248
0x07, 0x34, 0x0E, 0x08, // 249
0x07, 0x42, 0x0C, 0x07, // 250
0x07, 0x4E, 0x0C, 0x07, // 251
0x07, 0x5A, 0x0C, 0x07, // 252
0x07, 0x66, 0x0C, 0x07, // 253
0x07, 0x72, 0x0C, 0x07, // 254
0x07, 0x7E, 0x0C, 0x07, // 255
// Font Data:
0x00, 0x00, 0xF8, 0x02, // 33
0x38, 0x00, 0x00, 0x00, 0x38, // 34
0xA0, 0x03, 0xE0, 0x00, 0xB8, 0x03, 0xE0, 0x00, 0xB8, // 35
0x30, 0x01, 0x28, 0x02, 0xF8, 0x07, 0x48, 0x02, 0x90, 0x01, // 36
0x00, 0x00, 0x30, 0x00, 0x48, 0x00, 0x30, 0x03, 0xC0, 0x00, 0xB0, 0x01, 0x48, 0x02, 0x80, 0x01, // 37
0x80, 0x01, 0x50, 0x02, 0x68, 0x02, 0xA8, 0x02, 0x18, 0x01, 0x80, 0x03, 0x80, 0x02, // 38
0x38, // 39
0xE0, 0x03, 0x10, 0x04, 0x08, 0x08, // 40
0x08, 0x08, 0x10, 0x04, 0xE0, 0x03, // 41
0x28, 0x00, 0x18, 0x00, 0x28, // 42
0x40, 0x00, 0x40, 0x00, 0xF0, 0x01, 0x40, 0x00, 0x40, // 43
0x00, 0x00, 0x00, 0x06, // 44
0x80, 0x00, 0x80, // 45
0x00, 0x00, 0x00, 0x02, // 46
0x00, 0x03, 0xE0, 0x00, 0x18, // 47
0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 48
0x00, 0x00, 0x20, 0x00, 0x10, 0x00, 0xF8, 0x03, // 49
0x10, 0x02, 0x08, 0x03, 0x88, 0x02, 0x48, 0x02, 0x30, 0x02, // 50
0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 51
0xC0, 0x00, 0xA0, 0x00, 0x90, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x80, // 52
0x60, 0x01, 0x38, 0x02, 0x28, 0x02, 0x28, 0x02, 0xC8, 0x01, // 53
0xF0, 0x01, 0x28, 0x02, 0x28, 0x02, 0x28, 0x02, 0xD0, 0x01, // 54
0x08, 0x00, 0x08, 0x03, 0xC8, 0x00, 0x38, 0x00, 0x08, // 55
0xB0, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 56
0x70, 0x01, 0x88, 0x02, 0x88, 0x02, 0x88, 0x02, 0xF0, 0x01, // 57
0x00, 0x00, 0x20, 0x02, // 58
0x00, 0x00, 0x20, 0x06, // 59
0x00, 0x00, 0x40, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x10, 0x01, // 60
0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, // 61
0x00, 0x00, 0x10, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 62
0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0xC8, 0x02, 0x48, 0x00, 0x30, // 63
0x00, 0x00, 0xC0, 0x03, 0x30, 0x04, 0xD0, 0x09, 0x28, 0x0A, 0x28, 0x0A, 0xC8, 0x0B, 0x68, 0x0A, 0x10, 0x05, 0xE0, 0x04, // 64
0x00, 0x02, 0xC0, 0x01, 0xB0, 0x00, 0x88, 0x00, 0xB0, 0x00, 0xC0, 0x01, 0x00, 0x02, // 65
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 66
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 67
0x00, 0x00, 0xF8, 0x03, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, 0xE0, // 68
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, // 69
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x08, // 70
0x00, 0x00, 0xE0, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x50, 0x01, 0xC0, // 71
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 72
0x00, 0x00, 0xF8, 0x03, // 73
0x00, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 74
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 75
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 76
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x30, 0x00, 0xF8, 0x03, // 77
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0x40, 0x00, 0x80, 0x01, 0xF8, 0x03, // 78
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 79
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 80
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x03, 0x08, 0x03, 0xF0, 0x02, // 81
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0xC8, 0x00, 0x30, 0x03, // 82
0x00, 0x00, 0x30, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x90, 0x01, // 83
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 84
0x00, 0x00, 0xF8, 0x01, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 85
0x08, 0x00, 0x70, 0x00, 0x80, 0x01, 0x00, 0x02, 0x80, 0x01, 0x70, 0x00, 0x08, // 86
0x18, 0x00, 0xE0, 0x01, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0xF0, 0x01, 0x00, 0x02, 0xE0, 0x01, 0x18, // 87
0x00, 0x02, 0x08, 0x01, 0x90, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 88
0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x20, 0x00, 0x10, 0x00, 0x08, // 89
0x08, 0x03, 0x88, 0x02, 0xC8, 0x02, 0x68, 0x02, 0x38, 0x02, 0x18, 0x02, // 90
0x00, 0x00, 0xF8, 0x0F, 0x08, 0x08, // 91
0x18, 0x00, 0xE0, 0x00, 0x00, 0x03, // 92
0x08, 0x08, 0xF8, 0x0F, // 93
0x40, 0x00, 0x30, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, // 94
0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, // 95
0x08, 0x00, 0x10, // 96
0x00, 0x00, 0x00, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xE0, 0x03, // 97
0x00, 0x00, 0xF8, 0x03, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 98
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x40, 0x01, // 99
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xF8, 0x03, // 100
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x02, // 101
0x20, 0x00, 0xF0, 0x03, 0x28, // 102
0x00, 0x00, 0xC0, 0x05, 0x20, 0x0A, 0x20, 0x0A, 0xE0, 0x07, // 103
0x00, 0x00, 0xF8, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 104
0x00, 0x00, 0xE8, 0x03, // 105
0x00, 0x08, 0xE8, 0x07, // 106
0xF8, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, // 107
0x00, 0x00, 0xF8, 0x03, // 108
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 109
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 110
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 111
0x00, 0x00, 0xE0, 0x0F, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 112
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xE0, 0x0F, // 113
0x00, 0x00, 0xE0, 0x03, 0x20, // 114
0x40, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x20, 0x01, // 115
0x20, 0x00, 0xF8, 0x03, 0x20, 0x02, // 116
0x00, 0x00, 0xE0, 0x01, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 117
0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, // 118
0xE0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xE0, 0x01, // 119
0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 120
0x20, 0x00, 0xC0, 0x09, 0x00, 0x06, 0xC0, 0x01, 0x20, // 121
0x20, 0x02, 0x20, 0x03, 0xA0, 0x02, 0x60, 0x02, 0x20, 0x02, // 122
0x80, 0x00, 0x78, 0x0F, 0x08, 0x08, // 123
0x00, 0x00, 0xF8, 0x0F, // 124
0x08, 0x08, 0x78, 0x0F, 0x80, // 125
0xC0, 0x00, 0x40, 0x00, 0xC0, 0x00, 0x80, 0x00, 0xC0, // 126
0x00, 0x00, 0xA0, 0x0F, // 161
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x0F, 0x78, 0x02, 0x40, 0x01, // 162
0x40, 0x02, 0x70, 0x03, 0xC8, 0x02, 0x48, 0x02, 0x08, 0x02, 0x10, 0x02, // 163
0x00, 0x00, 0xE0, 0x01, 0x20, 0x01, 0x20, 0x01, 0xE0, 0x01, // 164
0x48, 0x01, 0x70, 0x01, 0xC0, 0x03, 0x70, 0x01, 0x48, 0x01, // 165
0x00, 0x00, 0x38, 0x0F, // 166
0xD0, 0x04, 0x28, 0x09, 0x48, 0x09, 0x48, 0x0A, 0x90, 0x05, // 167
0x00, 0x00, 0xE0, 0x03, 0xA8, 0x02, 0xA0, 0x02, 0xA8, 0x02, 0x20, 0x02, // 168
0xE0, 0x00, 0x10, 0x01, 0x48, 0x02, 0xA8, 0x02, 0xA8, 0x02, 0x10, 0x01, 0xE0, // 169
0x68, 0x00, 0x68, 0x00, 0x68, 0x00, 0x78, // 170
0x00, 0x00, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, // 171
0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, // 172
0x80, 0x00, 0x80, // 173
0xE0, 0x00, 0x10, 0x01, 0xE8, 0x02, 0x68, 0x02, 0xC8, 0x02, 0x10, 0x01, 0xE0, // 174
0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 175
0x00, 0x00, 0x38, 0x00, 0x28, 0x00, 0x38, // 176
0x40, 0x02, 0x40, 0x02, 0xF0, 0x03, 0x40, 0x02, 0x40, 0x02, // 177
0x48, 0x00, 0x68, 0x00, 0x58, // 178
0x48, 0x00, 0x58, 0x00, 0x68, // 179
0x00, 0x00, 0x10, 0x00, 0x08, // 180
0x00, 0x00, 0xE0, 0x0F, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 181
0x70, 0x00, 0xF8, 0x0F, 0x08, 0x00, 0xF8, 0x0F, 0x08, // 182
0x00, 0x00, 0x40, // 183
0x00, 0x00, 0xC0, 0x01, 0xA8, 0x02, 0xA0, 0x02, 0xA8, 0x02, 0xC0, // 184
0x00, 0x00, 0xF0, 0x03, 0x40, 0x00, 0x80, 0x00, 0xF8, 0x03, 0x08, // 185
0x30, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 186
0x00, 0x00, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, // 187
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0xC0, 0x00, 0x20, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 188
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0x80, 0x00, 0x60, 0x00, 0x50, 0x02, 0x48, 0x03, 0xC0, 0x02, // 189
0x48, 0x00, 0x58, 0x00, 0x68, 0x03, 0x80, 0x00, 0x60, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 190
0x00, 0x00, 0x00, 0x06, 0x00, 0x09, 0xA0, 0x09, 0x00, 0x04, // 191
0x00, 0x00, 0xF0, 0x03, 0x88, 0x00, 0x88, 0x00, 0x88, 0x00, 0xF0, 0x03, // 192
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x88, 0x01, // 193
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 194
0x00, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x18, // 195
0x00, 0x00, 0x00, 0x02, 0xFC, 0x03, 0x04, 0x02, 0xFC, 0x03, 0x00, 0x02, // 196
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x08, 0x02, // 197
0x00, 0x00, 0xB8, 0x03, 0x40, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xB8, 0x03, // 198
0x00, 0x00, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 199
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0xF8, 0x03, // 200
0x00, 0x00, 0xE0, 0x03, 0x08, 0x01, 0x90, 0x00, 0x48, 0x00, 0xE0, 0x03, // 201
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xA0, 0x00, 0x10, 0x01, 0x08, 0x02, // 202
0x00, 0x00, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, // 203
0x00, 0x00, 0xF8, 0x03, 0x10, 0x00, 0x60, 0x00, 0x10, 0x00, 0xF8, 0x03, // 204
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 205
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 206
0x00, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, // 207
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 208
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 209
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 210
0x00, 0x00, 0x38, 0x00, 0x40, 0x02, 0x40, 0x02, 0x40, 0x02, 0xF8, 0x01, // 211
0x00, 0x00, 0x70, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x88, 0x00, 0x70, // 212
0x00, 0x00, 0x18, 0x03, 0xA0, 0x00, 0x40, 0x00, 0xA0, 0x00, 0x18, 0x03, // 213
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, // 214
0x00, 0x00, 0x38, 0x00, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 215
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, // 216
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x06, // 217
0x00, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, // 218
0x00, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, 0xF8, 0x03, // 219
0x00, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, // 220
0x00, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 221
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xF0, 0x01, 0x08, 0x02, 0xF0, 0x01, // 222
0x00, 0x00, 0x30, 0x02, 0x48, 0x01, 0xC8, 0x00, 0x48, 0x00, 0xF8, 0x03, // 223
0x00, 0x00, 0x00, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x03, // 224
0x00, 0x00, 0xE0, 0x01, 0x50, 0x02, 0x50, 0x02, 0x48, 0x02, 0x88, 0x01, // 225
0x00, 0x00, 0xE0, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x40, 0x01, // 226
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x60, // 227
0x00, 0x00, 0x00, 0x02, 0xC0, 0x03, 0x20, 0x02, 0xE0, 0x03, 0x00, 0x02, // 228
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, // 229
0x00, 0x00, 0x60, 0x03, 0x80, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x60, 0x03, // 230
0x00, 0x00, 0x20, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x40, 0x01, // 231
0x00, 0x00, 0xE0, 0x03, 0x00, 0x01, 0x80, 0x00, 0x40, 0x00, 0xE0, 0x03, // 232
0x00, 0x00, 0xE0, 0x03, 0x00, 0x01, 0x98, 0x00, 0x40, 0x00, 0xE0, 0x03, // 233
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 234
0x00, 0x00, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, // 235
0x00, 0x00, 0xE0, 0x03, 0x40, 0x00, 0x80, 0x00, 0x40, 0x00, 0xE0, 0x03, // 236
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0xE0, 0x03, // 237
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 238
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, // 239
0x00, 0x00, 0xE0, 0x03, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 240
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x20, 0x02, 0x40, 0x02, // 241
0x00, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, // 242
0x00, 0x00, 0x60, 0x00, 0x80, 0x02, 0x80, 0x02, 0x80, 0x02, 0xE0, 0x01, // 243
0x00, 0x00, 0xC0, 0x00, 0x20, 0x01, 0xE0, 0x03, 0x20, 0x01, 0xC0, // 244
0x00, 0x00, 0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 245
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, // 246
0x00, 0x00, 0x60, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0xE0, 0x03, // 247
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, // 248
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x06, // 249
0x00, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, // 250
0x00, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, 0xE0, 0x03, // 251
0x00, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, // 252
0x00, 0x00, 0x40, 0x01, 0x20, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x01, // 253
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, 0xC0, 0x01, // 254
0x00, 0x00, 0x40, 0x02, 0xA0, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0xE0, 0x03, // 255
0x0A, // Width: 10
0x0D, // Height: 13
0x20, // First char: 32
0xE0, // Number of chars: 224
// Jump Table:
0xFF, 0xFF, 0x00, 0x0A, // 32
0x00, 0x00, 0x04, 0x03, // 33
0x00, 0x04, 0x05, 0x04, // 34
0x00, 0x09, 0x09, 0x06, // 35
0x00, 0x12, 0x0A, 0x06, // 36
0x00, 0x1C, 0x10, 0x09, // 37
0x00, 0x2C, 0x0E, 0x08, // 38
0x00, 0x3A, 0x01, 0x02, // 39
0x00, 0x3B, 0x06, 0x04, // 40
0x00, 0x41, 0x06, 0x04, // 41
0x00, 0x47, 0x05, 0x04, // 42
0x00, 0x4C, 0x09, 0x06, // 43
0x00, 0x55, 0x04, 0x03, // 44
0x00, 0x59, 0x03, 0x03, // 45
0x00, 0x5C, 0x04, 0x03, // 46
0x00, 0x60, 0x05, 0x04, // 47
0x00, 0x65, 0x0A, 0x06, // 48
0x00, 0x6F, 0x08, 0x05, // 49
0x00, 0x77, 0x0A, 0x06, // 50
0x00, 0x81, 0x0A, 0x06, // 51
0x00, 0x8B, 0x0B, 0x07, // 52
0x00, 0x96, 0x0A, 0x06, // 53
0x00, 0xA0, 0x0A, 0x06, // 54
0x00, 0xAA, 0x09, 0x06, // 55
0x00, 0xB3, 0x0A, 0x06, // 56
0x00, 0xBD, 0x0A, 0x06, // 57
0x00, 0xC7, 0x04, 0x03, // 58
0x00, 0xCB, 0x04, 0x03, // 59
0x00, 0xCF, 0x0A, 0x06, // 60
0x00, 0xD9, 0x09, 0x06, // 61
0x00, 0xE2, 0x09, 0x06, // 62
0x00, 0xEB, 0x0B, 0x07, // 63
0x00, 0xF6, 0x14, 0x0B, // 64
0x01, 0x0A, 0x0E, 0x08, // 65
0x01, 0x18, 0x0C, 0x07, // 66
0x01, 0x24, 0x0C, 0x07, // 67
0x01, 0x30, 0x0B, 0x07, // 68
0x01, 0x3B, 0x0C, 0x07, // 69
0x01, 0x47, 0x09, 0x06, // 70
0x01, 0x50, 0x0D, 0x08, // 71
0x01, 0x5D, 0x0C, 0x07, // 72
0x01, 0x69, 0x04, 0x03, // 73
0x01, 0x6D, 0x08, 0x05, // 74
0x01, 0x75, 0x0E, 0x08, // 75
0x01, 0x83, 0x0C, 0x07, // 76
0x01, 0x8F, 0x10, 0x09, // 77
0x01, 0x9F, 0x0C, 0x07, // 78
0x01, 0xAB, 0x0E, 0x08, // 79
0x01, 0xB9, 0x0B, 0x07, // 80
0x01, 0xC4, 0x0E, 0x08, // 81
0x01, 0xD2, 0x0C, 0x07, // 82
0x01, 0xDE, 0x0C, 0x07, // 83
0x01, 0xEA, 0x0B, 0x07, // 84
0x01, 0xF5, 0x0C, 0x07, // 85
0x02, 0x01, 0x0D, 0x08, // 86
0x02, 0x0E, 0x11, 0x0A, // 87
0x02, 0x1F, 0x0E, 0x08, // 88
0x02, 0x2D, 0x0D, 0x08, // 89
0x02, 0x3A, 0x0C, 0x07, // 90
0x02, 0x46, 0x06, 0x04, // 91
0x02, 0x4C, 0x06, 0x04, // 92
0x02, 0x52, 0x04, 0x03, // 93
0x02, 0x56, 0x09, 0x06, // 94
0x02, 0x5F, 0x0C, 0x07, // 95
0x02, 0x6B, 0x03, 0x03, // 96
0x02, 0x6E, 0x0A, 0x06, // 97
0x02, 0x78, 0x0A, 0x06, // 98
0x02, 0x82, 0x0A, 0x06, // 99
0x02, 0x8C, 0x0A, 0x06, // 100
0x02, 0x96, 0x0A, 0x06, // 101
0x02, 0xA0, 0x05, 0x04, // 102
0x02, 0xA5, 0x0A, 0x06, // 103
0x02, 0xAF, 0x0A, 0x06, // 104
0x02, 0xB9, 0x04, 0x03, // 105
0x02, 0xBD, 0x04, 0x03, // 106
0x02, 0xC1, 0x08, 0x05, // 107
0x02, 0xC9, 0x04, 0x03, // 108
0x02, 0xCD, 0x10, 0x09, // 109
0x02, 0xDD, 0x0A, 0x06, // 110
0x02, 0xE7, 0x0A, 0x06, // 111
0x02, 0xF1, 0x0A, 0x06, // 112
0x02, 0xFB, 0x0A, 0x06, // 113
0x03, 0x05, 0x05, 0x04, // 114
0x03, 0x0A, 0x08, 0x05, // 115
0x03, 0x12, 0x06, 0x04, // 116
0x03, 0x18, 0x0A, 0x06, // 117
0x03, 0x22, 0x09, 0x06, // 118
0x03, 0x2B, 0x0E, 0x08, // 119
0x03, 0x39, 0x0A, 0x06, // 120
0x03, 0x43, 0x09, 0x06, // 121
0x03, 0x4C, 0x0A, 0x06, // 122
0x03, 0x56, 0x06, 0x04, // 123
0x03, 0x5C, 0x04, 0x03, // 124
0x03, 0x60, 0x05, 0x04, // 125
0x03, 0x65, 0x09, 0x06, // 126
0xFF, 0xFF, 0x00, 0x0A, // 127
0xFF, 0xFF, 0x00, 0x0A, // 128
0xFF, 0xFF, 0x00, 0x0A, // 129
0xFF, 0xFF, 0x00, 0x0A, // 130
0xFF, 0xFF, 0x00, 0x0A, // 131
0xFF, 0xFF, 0x00, 0x0A, // 132
0xFF, 0xFF, 0x00, 0x0A, // 133
0xFF, 0xFF, 0x00, 0x0A, // 134
0xFF, 0xFF, 0x00, 0x0A, // 135
0xFF, 0xFF, 0x00, 0x0A, // 136
0xFF, 0xFF, 0x00, 0x0A, // 137
0xFF, 0xFF, 0x00, 0x0A, // 138
0xFF, 0xFF, 0x00, 0x0A, // 139
0xFF, 0xFF, 0x00, 0x0A, // 140
0xFF, 0xFF, 0x00, 0x0A, // 141
0xFF, 0xFF, 0x00, 0x0A, // 142
0xFF, 0xFF, 0x00, 0x0A, // 143
0xFF, 0xFF, 0x00, 0x0A, // 144
0xFF, 0xFF, 0x00, 0x0A, // 145
0xFF, 0xFF, 0x00, 0x0A, // 146
0xFF, 0xFF, 0x00, 0x0A, // 147
0xFF, 0xFF, 0x00, 0x0A, // 148
0xFF, 0xFF, 0x00, 0x0A, // 149
0xFF, 0xFF, 0x00, 0x0A, // 150
0xFF, 0xFF, 0x00, 0x0A, // 151
0xFF, 0xFF, 0x00, 0x0A, // 152
0xFF, 0xFF, 0x00, 0x0A, // 153
0xFF, 0xFF, 0x00, 0x0A, // 154
0xFF, 0xFF, 0x00, 0x0A, // 155
0xFF, 0xFF, 0x00, 0x0A, // 156
0xFF, 0xFF, 0x00, 0x0A, // 157
0xFF, 0xFF, 0x00, 0x0A, // 158
0xFF, 0xFF, 0x00, 0x0A, // 159
0xFF, 0xFF, 0x00, 0x0A, // 160
0x03, 0x6E, 0x04, 0x03, // 161
0x03, 0x72, 0x0A, 0x06, // 162
0x03, 0x7C, 0x0C, 0x07, // 163
0x03, 0x88, 0x0A, 0x06, // 164
0x03, 0x92, 0x0A, 0x06, // 165
0x03, 0x9C, 0x04, 0x03, // 166
0x03, 0xA0, 0x0A, 0x06, // 167
0x03, 0xAA, 0x0C, 0x07, // 168
0x03, 0xB6, 0x0D, 0x08, // 169
0x03, 0xC3, 0x07, 0x05, // 170
0x03, 0xCA, 0x0A, 0x06, // 171
0x03, 0xD4, 0x09, 0x06, // 172
0x03, 0xDD, 0x03, 0x03, // 173
0x03, 0xE0, 0x0D, 0x08, // 174
0x03, 0xED, 0x0B, 0x07, // 175
0x03, 0xF8, 0x07, 0x05, // 176
0x03, 0xFF, 0x0A, 0x06, // 177
0x04, 0x09, 0x05, 0x04, // 178
0x04, 0x0E, 0x05, 0x04, // 179
0x04, 0x13, 0x05, 0x04, // 180
0x04, 0x18, 0x0A, 0x06, // 181
0x04, 0x22, 0x09, 0x06, // 182
0x04, 0x2B, 0x03, 0x03, // 183
0x04, 0x2E, 0x0B, 0x07, // 184
0x04, 0x39, 0x0B, 0x07, // 185
0x04, 0x44, 0x07, 0x05, // 186
0x04, 0x4B, 0x0A, 0x06, // 187
0x04, 0x55, 0x10, 0x09, // 188
0x04, 0x65, 0x10, 0x09, // 189
0x04, 0x75, 0x10, 0x09, // 190
0x04, 0x85, 0x0A, 0x06, // 191
0x04, 0x8F, 0x0C, 0x07, // 192
0x04, 0x9B, 0x0C, 0x07, // 193
0x04, 0xA7, 0x0C, 0x07, // 194
0x04, 0xB3, 0x0B, 0x07, // 195
0x04, 0xBE, 0x0C, 0x07, // 196
0x04, 0xCA, 0x0C, 0x07, // 197
0x04, 0xD6, 0x0C, 0x07, // 198
0x04, 0xE2, 0x0C, 0x07, // 199
0x04, 0xEE, 0x0C, 0x07, // 200
0x04, 0xFA, 0x0C, 0x07, // 201
0x05, 0x06, 0x0C, 0x07, // 202
0x05, 0x12, 0x0C, 0x07, // 203
0x05, 0x1E, 0x0C, 0x07, // 204
0x05, 0x2A, 0x0C, 0x07, // 205
0x05, 0x36, 0x0C, 0x07, // 206
0x05, 0x42, 0x0C, 0x07, // 207
0x05, 0x4E, 0x0B, 0x07, // 208
0x05, 0x59, 0x0C, 0x07, // 209
0x05, 0x65, 0x0B, 0x07, // 210
0x05, 0x70, 0x0C, 0x07, // 211
0x05, 0x7C, 0x0B, 0x07, // 212
0x05, 0x87, 0x0C, 0x07, // 213
0x05, 0x93, 0x0C, 0x07, // 214
0x05, 0x9F, 0x0C, 0x07, // 215
0x05, 0xAB, 0x0C, 0x07, // 216
0x05, 0xB7, 0x0E, 0x08, // 217
0x05, 0xC5, 0x0C, 0x07, // 218
0x05, 0xD1, 0x0C, 0x07, // 219
0x05, 0xDD, 0x0C, 0x07, // 220
0x05, 0xE9, 0x0C, 0x07, // 221
0x05, 0xF5, 0x0C, 0x07, // 222
0x06, 0x01, 0x0C, 0x07, // 223
0x06, 0x0D, 0x0C, 0x07, // 224
0x06, 0x19, 0x0C, 0x07, // 225
0x06, 0x25, 0x0C, 0x07, // 226
0x06, 0x31, 0x0B, 0x07, // 227
0x06, 0x3C, 0x0C, 0x07, // 228
0x06, 0x48, 0x0B, 0x07, // 229
0x06, 0x53, 0x0C, 0x07, // 230
0x06, 0x5F, 0x0C, 0x07, // 231
0x06, 0x6B, 0x0C, 0x07, // 232
0x06, 0x77, 0x0C, 0x07, // 233
0x06, 0x83, 0x0C, 0x07, // 234
0x06, 0x8F, 0x0C, 0x07, // 235
0x06, 0x9B, 0x0C, 0x07, // 236
0x06, 0xA7, 0x0C, 0x07, // 237
0x06, 0xB3, 0x0C, 0x07, // 238
0x06, 0xBF, 0x0C, 0x07, // 239
0x06, 0xCB, 0x0B, 0x07, // 240
0x06, 0xD6, 0x0C, 0x07, // 241
0x06, 0xE2, 0x0B, 0x07, // 242
0x06, 0xED, 0x0C, 0x07, // 243
0x06, 0xF9, 0x0B, 0x07, // 244
0x07, 0x04, 0x0C, 0x07, // 245
0x07, 0x10, 0x0C, 0x07, // 246
0x07, 0x1C, 0x0C, 0x07, // 247
0x07, 0x28, 0x0C, 0x07, // 248
0x07, 0x34, 0x0E, 0x08, // 249
0x07, 0x42, 0x0C, 0x07, // 250
0x07, 0x4E, 0x0C, 0x07, // 251
0x07, 0x5A, 0x0C, 0x07, // 252
0x07, 0x66, 0x0C, 0x07, // 253
0x07, 0x72, 0x0C, 0x07, // 254
0x07, 0x7E, 0x0C, 0x07, // 255
// Font Data:
0x00, 0x00, 0xF8, 0x02, // 33
0x38, 0x00, 0x00, 0x00, 0x38, // 34
0xA0, 0x03, 0xE0, 0x00, 0xB8, 0x03, 0xE0, 0x00, 0xB8, // 35
0x30, 0x01, 0x28, 0x02, 0xF8, 0x07, 0x48, 0x02, 0x90, 0x01, // 36
0x00, 0x00, 0x30, 0x00, 0x48, 0x00, 0x30, 0x03, 0xC0, 0x00, 0xB0, 0x01, 0x48, 0x02, 0x80, 0x01, // 37
0x80, 0x01, 0x50, 0x02, 0x68, 0x02, 0xA8, 0x02, 0x18, 0x01, 0x80, 0x03, 0x80, 0x02, // 38
0x38, // 39
0xE0, 0x03, 0x10, 0x04, 0x08, 0x08, // 40
0x08, 0x08, 0x10, 0x04, 0xE0, 0x03, // 41
0x28, 0x00, 0x18, 0x00, 0x28, // 42
0x40, 0x00, 0x40, 0x00, 0xF0, 0x01, 0x40, 0x00, 0x40, // 43
0x00, 0x00, 0x00, 0x06, // 44
0x80, 0x00, 0x80, // 45
0x00, 0x00, 0x00, 0x02, // 46
0x00, 0x03, 0xE0, 0x00, 0x18, // 47
0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 48
0x00, 0x00, 0x20, 0x00, 0x10, 0x00, 0xF8, 0x03, // 49
0x10, 0x02, 0x08, 0x03, 0x88, 0x02, 0x48, 0x02, 0x30, 0x02, // 50
0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 51
0xC0, 0x00, 0xA0, 0x00, 0x90, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x80, // 52
0x60, 0x01, 0x38, 0x02, 0x28, 0x02, 0x28, 0x02, 0xC8, 0x01, // 53
0xF0, 0x01, 0x28, 0x02, 0x28, 0x02, 0x28, 0x02, 0xD0, 0x01, // 54
0x08, 0x00, 0x08, 0x03, 0xC8, 0x00, 0x38, 0x00, 0x08, // 55
0xB0, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 56
0x70, 0x01, 0x88, 0x02, 0x88, 0x02, 0x88, 0x02, 0xF0, 0x01, // 57
0x00, 0x00, 0x20, 0x02, // 58
0x00, 0x00, 0x20, 0x06, // 59
0x00, 0x00, 0x40, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x10, 0x01, // 60
0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, // 61
0x00, 0x00, 0x10, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 62
0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0xC8, 0x02, 0x48, 0x00, 0x30, // 63
0x00, 0x00, 0xC0, 0x03, 0x30, 0x04, 0xD0, 0x09, 0x28, 0x0A, 0x28, 0x0A, 0xC8, 0x0B, 0x68, 0x0A, 0x10, 0x05, 0xE0, 0x04, // 64
0x00, 0x02, 0xC0, 0x01, 0xB0, 0x00, 0x88, 0x00, 0xB0, 0x00, 0xC0, 0x01, 0x00, 0x02, // 65
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 66
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 67
0x00, 0x00, 0xF8, 0x03, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, 0xE0, // 68
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, // 69
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x08, // 70
0x00, 0x00, 0xE0, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x50, 0x01, 0xC0, // 71
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 72
0x00, 0x00, 0xF8, 0x03, // 73
0x00, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 74
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 75
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 76
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x30, 0x00, 0xF8, 0x03, // 77
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0x40, 0x00, 0x80, 0x01, 0xF8, 0x03, // 78
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 79
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 80
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x03, 0x08, 0x03, 0xF0, 0x02, // 81
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0xC8, 0x00, 0x30, 0x03, // 82
0x00, 0x00, 0x30, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x90, 0x01, // 83
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 84
0x00, 0x00, 0xF8, 0x01, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 85
0x08, 0x00, 0x70, 0x00, 0x80, 0x01, 0x00, 0x02, 0x80, 0x01, 0x70, 0x00, 0x08, // 86
0x18, 0x00, 0xE0, 0x01, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0xF0, 0x01, 0x00, 0x02, 0xE0, 0x01, 0x18, // 87
0x00, 0x02, 0x08, 0x01, 0x90, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 88
0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x20, 0x00, 0x10, 0x00, 0x08, // 89
0x08, 0x03, 0x88, 0x02, 0xC8, 0x02, 0x68, 0x02, 0x38, 0x02, 0x18, 0x02, // 90
0x00, 0x00, 0xF8, 0x0F, 0x08, 0x08, // 91
0x18, 0x00, 0xE0, 0x00, 0x00, 0x03, // 92
0x08, 0x08, 0xF8, 0x0F, // 93
0x40, 0x00, 0x30, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, // 94
0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, // 95
0x08, 0x00, 0x10, // 96
0x00, 0x00, 0x00, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xE0, 0x03, // 97
0x00, 0x00, 0xF8, 0x03, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 98
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x40, 0x01, // 99
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xF8, 0x03, // 100
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x02, // 101
0x20, 0x00, 0xF0, 0x03, 0x28, // 102
0x00, 0x00, 0xC0, 0x05, 0x20, 0x0A, 0x20, 0x0A, 0xE0, 0x07, // 103
0x00, 0x00, 0xF8, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 104
0x00, 0x00, 0xE8, 0x03, // 105
0x00, 0x08, 0xE8, 0x07, // 106
0xF8, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, // 107
0x00, 0x00, 0xF8, 0x03, // 108
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 109
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 110
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 111
0x00, 0x00, 0xE0, 0x0F, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 112
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xE0, 0x0F, // 113
0x00, 0x00, 0xE0, 0x03, 0x20, // 114
0x40, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x20, 0x01, // 115
0x20, 0x00, 0xF8, 0x03, 0x20, 0x02, // 116
0x00, 0x00, 0xE0, 0x01, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 117
0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, // 118
0xE0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xE0, 0x01, // 119
0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 120
0x20, 0x00, 0xC0, 0x09, 0x00, 0x06, 0xC0, 0x01, 0x20, // 121
0x20, 0x02, 0x20, 0x03, 0xA0, 0x02, 0x60, 0x02, 0x20, 0x02, // 122
0x80, 0x00, 0x78, 0x0F, 0x08, 0x08, // 123
0x00, 0x00, 0xF8, 0x0F, // 124
0x08, 0x08, 0x78, 0x0F, 0x80, // 125
0xC0, 0x00, 0x40, 0x00, 0xC0, 0x00, 0x80, 0x00, 0xC0, // 126
0x00, 0x00, 0xA0, 0x0F, // 161
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x0F, 0x78, 0x02, 0x40, 0x01, // 162
0x40, 0x02, 0x70, 0x03, 0xC8, 0x02, 0x48, 0x02, 0x08, 0x02, 0x10, 0x02, // 163
0x00, 0x00, 0xE0, 0x01, 0x20, 0x01, 0x20, 0x01, 0xE0, 0x01, // 164
0x48, 0x01, 0x70, 0x01, 0xC0, 0x03, 0x70, 0x01, 0x48, 0x01, // 165
0x00, 0x00, 0x38, 0x0F, // 166
0xD0, 0x04, 0x28, 0x09, 0x48, 0x09, 0x48, 0x0A, 0x90, 0x05, // 167
0x00, 0x00, 0xE0, 0x03, 0xA8, 0x02, 0xA0, 0x02, 0xA8, 0x02, 0x20, 0x02, // 168
0xE0, 0x00, 0x10, 0x01, 0x48, 0x02, 0xA8, 0x02, 0xA8, 0x02, 0x10, 0x01, 0xE0, // 169
0x68, 0x00, 0x68, 0x00, 0x68, 0x00, 0x78, // 170
0x00, 0x00, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, // 171
0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, // 172
0x80, 0x00, 0x80, // 173
0xE0, 0x00, 0x10, 0x01, 0xE8, 0x02, 0x68, 0x02, 0xC8, 0x02, 0x10, 0x01, 0xE0, // 174
0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 175
0x00, 0x00, 0x38, 0x00, 0x28, 0x00, 0x38, // 176
0x40, 0x02, 0x40, 0x02, 0xF0, 0x03, 0x40, 0x02, 0x40, 0x02, // 177
0x48, 0x00, 0x68, 0x00, 0x58, // 178
0x48, 0x00, 0x58, 0x00, 0x68, // 179
0x00, 0x00, 0x10, 0x00, 0x08, // 180
0x00, 0x00, 0xE0, 0x0F, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 181
0x70, 0x00, 0xF8, 0x0F, 0x08, 0x00, 0xF8, 0x0F, 0x08, // 182
0x00, 0x00, 0x40, // 183
0x00, 0x00, 0xC0, 0x01, 0xA8, 0x02, 0xA0, 0x02, 0xA8, 0x02, 0xC0, // 184
0x00, 0x00, 0xF0, 0x03, 0x40, 0x00, 0x80, 0x00, 0xF8, 0x03, 0x08, // 185
0x30, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 186
0x00, 0x00, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, // 187
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0xC0, 0x00, 0x20, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 188
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0x80, 0x00, 0x60, 0x00, 0x50, 0x02, 0x48, 0x03, 0xC0, 0x02, // 189
0x48, 0x00, 0x58, 0x00, 0x68, 0x03, 0x80, 0x00, 0x60, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 190
0x00, 0x00, 0x00, 0x06, 0x00, 0x09, 0xA0, 0x09, 0x00, 0x04, // 191
0x00, 0x00, 0xF0, 0x03, 0x88, 0x00, 0x88, 0x00, 0x88, 0x00, 0xF0, 0x03, // 192
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x88, 0x01, // 193
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 194
0x00, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x18, // 195
0x00, 0x00, 0x00, 0x02, 0xFC, 0x03, 0x04, 0x02, 0xFC, 0x03, 0x00, 0x02, // 196
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x08, 0x02, // 197
0x00, 0x00, 0xB8, 0x03, 0x40, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xB8, 0x03, // 198
0x00, 0x00, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 199
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0xF8, 0x03, // 200
0x00, 0x00, 0xE0, 0x03, 0x08, 0x01, 0x90, 0x00, 0x48, 0x00, 0xE0, 0x03, // 201
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xA0, 0x00, 0x10, 0x01, 0x08, 0x02, // 202
0x00, 0x00, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, // 203
0x00, 0x00, 0xF8, 0x03, 0x10, 0x00, 0x60, 0x00, 0x10, 0x00, 0xF8, 0x03, // 204
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 205
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 206
0x00, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, // 207
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 208
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 209
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 210
0x00, 0x00, 0x38, 0x00, 0x40, 0x02, 0x40, 0x02, 0x40, 0x02, 0xF8, 0x01, // 211
0x00, 0x00, 0x70, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x88, 0x00, 0x70, // 212
0x00, 0x00, 0x18, 0x03, 0xA0, 0x00, 0x40, 0x00, 0xA0, 0x00, 0x18, 0x03, // 213
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, // 214
0x00, 0x00, 0x38, 0x00, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 215
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, // 216
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x02, 0xF8, 0x03, 0x00, 0x06, // 217
0x00, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, // 218
0x00, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, 0xF8, 0x03, // 219
0x00, 0x00, 0xF8, 0x03, 0x40, 0x02, 0x40, 0x02, 0x40, 0x02, 0x80, 0x01, // 220
0x00, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 221
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0xF0, 0x01, 0x08, 0x02, 0xF0, 0x01, // 222
0x00, 0x00, 0x30, 0x02, 0x48, 0x01, 0xC8, 0x00, 0x48, 0x00, 0xF8, 0x03, // 223
0x00, 0x00, 0x00, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x03, // 224
0x00, 0x00, 0xE0, 0x01, 0x50, 0x02, 0x50, 0x02, 0x48, 0x02, 0x88, 0x01, // 225
0x00, 0x00, 0xE0, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x40, 0x01, // 226
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x60, // 227
0x00, 0x00, 0x00, 0x02, 0xC0, 0x03, 0x20, 0x02, 0xE0, 0x03, 0x00, 0x02, // 228
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, // 229
0x00, 0x00, 0x60, 0x03, 0x80, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x60, 0x03, // 230
0x00, 0x00, 0x20, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x40, 0x01, // 231
0x00, 0x00, 0xE0, 0x03, 0x00, 0x01, 0x80, 0x00, 0x40, 0x00, 0xE0, 0x03, // 232
0x00, 0x00, 0xE0, 0x03, 0x00, 0x01, 0x98, 0x00, 0x40, 0x00, 0xE0, 0x03, // 233
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 234
0x00, 0x00, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, // 235
0x00, 0x00, 0xE0, 0x03, 0x40, 0x00, 0x80, 0x00, 0x40, 0x00, 0xE0, 0x03, // 236
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0xE0, 0x03, // 237
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 238
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, // 239
0x00, 0x00, 0xE0, 0x03, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 240
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x20, 0x02, 0x40, 0x02, // 241
0x00, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, // 242
0x00, 0x00, 0x60, 0x00, 0x80, 0x02, 0x80, 0x02, 0x80, 0x02, 0xE0, 0x01, // 243
0x00, 0x00, 0xC0, 0x00, 0x20, 0x01, 0xE0, 0x03, 0x20, 0x01, 0xC0, // 244
0x00, 0x00, 0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 245
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, // 246
0x00, 0x00, 0x60, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0xE0, 0x03, // 247
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, // 248
0x00, 0x00, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x02, 0xE0, 0x03, 0x00, 0x06, // 249
0x00, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, // 250
0x00, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, 0xE0, 0x03, // 251
0x00, 0x00, 0xE0, 0x03, 0x80, 0x02, 0x80, 0x02, 0x80, 0x02, 0x00, 0x01, // 252
0x00, 0x00, 0x40, 0x01, 0x20, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x01, // 253
0x00, 0x00, 0xE0, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, 0xC0, 0x01, // 254
0x00, 0x00, 0x40, 0x02, 0xA0, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0xE0, 0x03, // 255
};

View File

@@ -6,24 +6,27 @@ const uint8_t SATELLITE_IMAGE[] PROGMEM = {0x00, 0x08, 0x00, 0x1C, 0x00, 0x0E, 0
0xF8, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC8, 0x01, 0x9C, 0x54,
0x0E, 0x52, 0x07, 0x48, 0x02, 0x26, 0x00, 0x10, 0x00, 0x0E};
const uint8_t imgSatellite[] PROGMEM = { 0x70, 0x71, 0x22, 0xFA, 0xFA, 0x22, 0x71, 0x70 };
const uint8_t imgUSB[] PROGMEM = { 0x60, 0x60, 0x30, 0x18, 0x18, 0x18, 0x24, 0x42, 0x42, 0x42, 0x42, 0x7E, 0x24, 0x24, 0x24, 0x3C };
const uint8_t imgPower[] PROGMEM = { 0x40, 0x40, 0x40, 0x58, 0x48, 0x08, 0x08, 0x08, 0x1C, 0x22, 0x22, 0x41, 0x7F, 0x22, 0x22, 0x22 };
const uint8_t imgUser[] PROGMEM = { 0x3C, 0x42, 0x99, 0xA5, 0xA5, 0x99, 0x42, 0x3C };
const uint8_t imgPositionEmpty[] PROGMEM = { 0x20, 0x30, 0x28, 0x24, 0x42, 0xFF };
const uint8_t imgPositionSolid[] PROGMEM = { 0x20, 0x30, 0x38, 0x3C, 0x7E, 0xFF };
const uint8_t imgSatellite[] PROGMEM = {0x70, 0x71, 0x22, 0xFA, 0xFA, 0x22, 0x71, 0x70};
const uint8_t imgUSB[] PROGMEM = {0x60, 0x60, 0x30, 0x18, 0x18, 0x18, 0x24, 0x42, 0x42, 0x42, 0x42, 0x7E, 0x24, 0x24, 0x24, 0x3C};
const uint8_t imgPower[] PROGMEM = {0x40, 0x40, 0x40, 0x58, 0x48, 0x08, 0x08, 0x08,
0x1C, 0x22, 0x22, 0x41, 0x7F, 0x22, 0x22, 0x22};
const uint8_t imgUser[] PROGMEM = {0x3C, 0x42, 0x99, 0xA5, 0xA5, 0x99, 0x42, 0x3C};
const uint8_t imgPositionEmpty[] PROGMEM = {0x20, 0x30, 0x28, 0x24, 0x42, 0xFF};
const uint8_t imgPositionSolid[] PROGMEM = {0x20, 0x30, 0x38, 0x3C, 0x7E, 0xFF};
#if defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7735_CS)
const uint8_t imgQuestionL1[] PROGMEM = { 0xff, 0x01, 0x01, 0x32, 0x7b, 0x49, 0x49, 0x6f, 0x26, 0x01, 0x01, 0xff };
const uint8_t imgQuestionL2[] PROGMEM = { 0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f };
const uint8_t imgInfoL1[] PROGMEM = { 0xff, 0x01, 0x01, 0x01, 0x1e, 0x7f, 0x1e, 0x01, 0x01, 0x01, 0x01, 0xff };
const uint8_t imgInfoL2[] PROGMEM = { 0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f };
const uint8_t imgSFL1[] PROGMEM = { 0xb6, 0x8f, 0x19, 0x11, 0x31, 0xe3, 0xc2, 0x01, 0x01, 0xf9, 0xf9, 0x89, 0x89, 0x89, 0x09, 0xeb};
const uint8_t imgSFL2[] PROGMEM = { 0x0e, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x08, 0x00, 0x0f, 0x0f, 0x00, 0x08, 0x08, 0x08, 0x0f};
const uint8_t imgQuestionL1[] PROGMEM = {0xff, 0x01, 0x01, 0x32, 0x7b, 0x49, 0x49, 0x6f, 0x26, 0x01, 0x01, 0xff};
const uint8_t imgQuestionL2[] PROGMEM = {0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f};
const uint8_t imgInfoL1[] PROGMEM = {0xff, 0x01, 0x01, 0x01, 0x1e, 0x7f, 0x1e, 0x01, 0x01, 0x01, 0x01, 0xff};
const uint8_t imgInfoL2[] PROGMEM = {0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f};
const uint8_t imgSFL1[] PROGMEM = {0xb6, 0x8f, 0x19, 0x11, 0x31, 0xe3, 0xc2, 0x01,
0x01, 0xf9, 0xf9, 0x89, 0x89, 0x89, 0x09, 0xeb};
const uint8_t imgSFL2[] PROGMEM = {0x0e, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x08,
0x00, 0x0f, 0x0f, 0x00, 0x08, 0x08, 0x08, 0x0f};
#else
const uint8_t imgInfo[] PROGMEM = { 0xff, 0x81, 0x00, 0xfb, 0xfb, 0x00, 0x81, 0xff };
const uint8_t imgQuestion[] PROGMEM = { 0xbf, 0x41, 0xc0, 0x8b, 0xdb, 0x70, 0xa1, 0xdf };
const uint8_t imgSF[] PROGMEM = { 0xd2, 0xb7, 0xad, 0xbb, 0x92, 0x01, 0xfd, 0xfd, 0x15, 0x85, 0xf5};
const uint8_t imgInfo[] PROGMEM = {0xff, 0x81, 0x00, 0xfb, 0xfb, 0x00, 0x81, 0xff};
const uint8_t imgQuestion[] PROGMEM = {0xbf, 0x41, 0xc0, 0x8b, 0xdb, 0x70, 0xa1, 0xdf};
const uint8_t imgSF[] PROGMEM = {0xd2, 0xb7, 0xad, 0xbb, 0x92, 0x01, 0xfd, 0xfd, 0x15, 0x85, 0xf5};
#endif
#include "img/icon.xbm"

View File

@@ -3,9 +3,7 @@
InputBroker *inputBroker;
InputBroker::InputBroker()
{
};
InputBroker::InputBroker(){};
void InputBroker::registerSource(Observable<const InputEvent *> *source)
{
@@ -14,7 +12,7 @@ void InputBroker::registerSource(Observable<const InputEvent *> *source)
int InputBroker::handleInputEvent(const InputEvent *event)
{
powerFSM.trigger(EVENT_INPUT);
this->notifyObservers(event);
return 0;
powerFSM.trigger(EVENT_INPUT);
this->notifyObservers(event);
return 0;
}

View File

@@ -5,12 +5,11 @@
#define MATRIXKEY 0xFE
typedef struct _InputEvent {
const char* source;
const char *source;
char inputEvent;
char kbchar;
} InputEvent;
class InputBroker :
public Observable<const InputEvent *>
class InputBroker : public Observable<const InputEvent *>
{
CallbackObserver<InputBroker, const InputEvent *> inputEventObserver =
CallbackObserver<InputBroker, const InputEvent *>(this, &InputBroker::handleInputEvent);

View File

@@ -34,7 +34,7 @@ void RotaryEncoderInterruptBase::init(
int32_t RotaryEncoderInterruptBase::runOnce()
{
InputEvent e;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
e.source = this->_originName;
if (this->action == ROTARY_ACTION_PRESSED) {
@@ -48,7 +48,7 @@ int32_t RotaryEncoderInterruptBase::runOnce()
e.inputEvent = this->_eventCcw;
}
if (e.inputEvent != ModuleConfig_CannedMessageConfig_InputEventChar_NONE) {
if (e.inputEvent != meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE) {
this->notifyObservers(&e);
}

View File

@@ -33,8 +33,8 @@ class RotaryEncoderInterruptBase : public Observable<const InputEvent *>, public
private:
uint8_t _pinA = 0;
uint8_t _pinB = 0;
char _eventCw = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventCcw = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventPressed = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventCw = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventCcw = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventPressed = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
const char *_originName;
};

View File

@@ -8,8 +8,7 @@
* to your device as you wish, but you always need to have separate event
* handlers, thus you need to have a RotaryEncoderInterrupt implementation.
*/
class RotaryEncoderInterruptImpl1 :
public RotaryEncoderInterruptBase
class RotaryEncoderInterruptImpl1 : public RotaryEncoderInterruptBase
{
public:
RotaryEncoderInterruptImpl1();

View File

@@ -1,16 +1,13 @@
#include "configuration.h"
#include "UpDownInterruptBase.h"
#include "configuration.h"
UpDownInterruptBase::UpDownInterruptBase(
const char *name)
UpDownInterruptBase::UpDownInterruptBase(const char *name)
{
this->_originName = name;
}
void UpDownInterruptBase::init(
uint8_t pinDown, uint8_t pinUp, uint8_t pinPress,
char eventDown, char eventUp, char eventPressed,
void (*onIntDown)(), void (*onIntUp)(), void (*onIntPress)())
void UpDownInterruptBase::init(uint8_t pinDown, uint8_t pinUp, uint8_t pinPress, char eventDown, char eventUp, char eventPressed,
void (*onIntDown)(), void (*onIntUp)(), void (*onIntPress)())
{
this->_pinDown = pinDown;
this->_pinUp = pinUp;
@@ -26,8 +23,7 @@ void UpDownInterruptBase::init(
attachInterrupt(this->_pinDown, onIntDown, RISING);
attachInterrupt(this->_pinUp, onIntUp, RISING);
LOG_DEBUG("GPIO initialized (%d, %d, %d)\n",
this->_pinDown, this->_pinUp, pinPress);
LOG_DEBUG("GPIO initialized (%d, %d, %d)\n", this->_pinDown, this->_pinUp, pinPress);
}
void UpDownInterruptBase::intPressHandler()

View File

@@ -16,8 +16,8 @@ class UpDownInterruptBase : public Observable<const InputEvent *>
private:
uint8_t _pinDown = 0;
uint8_t _pinUp = 0;
char _eventDown = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventUp = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventPressed = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventDown = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventUp = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
char _eventPressed = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
const char *_originName;
};

View File

@@ -17,9 +17,9 @@ void UpDownInterruptImpl1::init()
uint8_t pinDown = moduleConfig.canned_message.inputbroker_pin_b;
uint8_t pinPress = moduleConfig.canned_message.inputbroker_pin_press;
char eventDown = static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_DOWN);
char eventUp = static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_UP);
char eventPressed = static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_SELECT);
char eventDown = static_cast<char>(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_DOWN);
char eventUp = static_cast<char>(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_UP);
char eventPressed = static_cast<char>(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_SELECT);
UpDownInterruptBase::init(pinDown, pinUp, pinPress, eventDown, eventUp, eventPressed, UpDownInterruptImpl1::handleIntDown,
UpDownInterruptImpl1::handleIntUp, UpDownInterruptImpl1::handleIntPressed);

View File

@@ -1,8 +1,7 @@
#pragma once
#include "UpDownInterruptBase.h"
class UpDownInterruptImpl1 :
public UpDownInterruptBase
class UpDownInterruptImpl1 : public UpDownInterruptBase
{
public:
UpDownInterruptImpl1();

View File

@@ -3,15 +3,11 @@
CardKbI2cImpl *cardKbI2cImpl;
CardKbI2cImpl::CardKbI2cImpl() :
KbI2cBase("cardKB")
{
}
CardKbI2cImpl::CardKbI2cImpl() : KbI2cBase("cardKB") {}
void CardKbI2cImpl::init()
{
if (cardkb_found != CARDKB_ADDR)
{
if (cardkb_found != CARDKB_ADDR) {
disable();
return;
}

View File

@@ -9,8 +9,7 @@
* to your device as you wish, but you always need to have separate event
* handlers, thus you need to have a RotaryEncoderInterrupt implementation.
*/
class CardKbI2cImpl :
public KbI2cBase
class CardKbI2cImpl : public KbI2cBase
{
public:
CardKbI2cImpl();

View File

@@ -12,32 +12,32 @@ KbI2cBase::KbI2cBase(const char *name) : concurrency::OSThread(name)
uint8_t read_from_14004(uint8_t reg, uint8_t *data, uint8_t length)
{
uint8_t readflag = 0;
Wire.beginTransmission(CARDKB_ADDR);
Wire.write(reg);
Wire.endTransmission(); // stop transmitting
delay(20);
Wire.requestFrom(CARDKB_ADDR, (int)length);
int i = 0;
while ( Wire.available() ) // slave may send less than requested
{
data[i++] = Wire.read(); // receive a byte as a proper uint8_t
readflag = 1;
}
return readflag;
uint8_t readflag = 0;
Wire.beginTransmission(CARDKB_ADDR);
Wire.write(reg);
Wire.endTransmission(); // stop transmitting
delay(20);
Wire.requestFrom(CARDKB_ADDR, (int)length);
int i = 0;
while (Wire.available()) // slave may send less than requested
{
data[i++] = Wire.read(); // receive a byte as a proper uint8_t
readflag = 1;
}
return readflag;
}
void write_to_14004(uint8_t reg, uint8_t data)
{
Wire.beginTransmission(CARDKB_ADDR);
Wire.write(reg);
Wire.write(data);
Wire.endTransmission(); // stop transmitting
Wire.beginTransmission(CARDKB_ADDR);
Wire.write(reg);
Wire.write(data);
Wire.endTransmission(); // stop transmitting
}
int32_t KbI2cBase::runOnce()
{
if (cardkb_found != CARDKB_ADDR){
if (cardkb_found != CARDKB_ADDR) {
// Input device is not detected.
return INT32_MAX;
}
@@ -48,7 +48,7 @@ int32_t KbI2cBase::runOnce()
uint8_t PrintDataBuf = 0;
if (read_from_14004(0x01, rDataBuf, 0x04) == 1) {
for (uint8_t aCount = 0; aCount < 0x04; aCount++) {
for (uint8_t bCount = 0; bCount < 0x04; bCount++ ) {
for (uint8_t bCount = 0; bCount < 0x04; bCount++) {
if (((rDataBuf[aCount] >> bCount) & 0x01) == 0x01) {
PrintDataBuf = aCount * 0x04 + bCount + 1;
}
@@ -70,35 +70,35 @@ int32_t KbI2cBase::runOnce()
while (Wire.available()) {
char c = Wire.read();
InputEvent e;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
e.source = this->_originName;
switch (c) {
case 0x1b: // ESC
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_CANCEL;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_CANCEL;
break;
case 0x08: // Back
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_BACK;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_BACK;
e.kbchar = c;
break;
case 0xb5: // Up
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_UP;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_UP;
break;
case 0xb6: // Down
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_DOWN;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_DOWN;
break;
case 0xb4: // Left
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_LEFT;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_LEFT;
e.kbchar = c;
break;
case 0xb7: // Right
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT;
e.kbchar = c;
break;
case 0x0d: // Enter
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_SELECT;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_SELECT;
break;
case 0x00: //nopress
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
case 0x00: // nopress
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
break;
default: // all other keys
e.inputEvent = ANYKEY;
@@ -106,7 +106,7 @@ int32_t KbI2cBase::runOnce()
break;
}
if (e.inputEvent != ModuleConfig_CannedMessageConfig_InputEventChar_NONE) {
if (e.inputEvent != meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE) {
this->notifyObservers(&e);
}
}

View File

@@ -1,11 +1,9 @@
#pragma once
#include "SinglePortModule.h" // TODO: what header file to include?
#include "InputBroker.h"
#include "SinglePortModule.h" // TODO: what header file to include?
class KbI2cBase :
public Observable<const InputEvent *>,
public concurrency::OSThread
class KbI2cBase : public Observable<const InputEvent *>, public concurrency::OSThread
{
public:
explicit KbI2cBase(const char *name);

View File

@@ -87,7 +87,7 @@ uint8_t rtc_found;
// Keystore Chips
uint8_t keystore_found;
#ifndef ARCH_PORTDUINO
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
ATECCX08A atecc;
#endif
@@ -98,7 +98,7 @@ uint32_t serialSinceMsec;
bool pmu_found;
// Array map of sensor types (as array index) and i2c address as value we'll find in the i2c scan
uint8_t nodeTelemetrySensorsMap[_TelemetrySensorType_MAX + 1] = {
uint8_t nodeTelemetrySensorsMap[_meshtastic_TelemetrySensorType_MAX + 1] = {
0}; // one is enough, missing elements will be initialized to 0 anyway.
Router *router = NULL; // Users of router don't care what sort of subclass implements that API
@@ -302,7 +302,7 @@ void setup()
playStartMelody();
// fixed screen override?
if (config.display.oled != Config_DisplayConfig_OledType_OLED_AUTO)
if (config.display.oled != meshtastic_Config_DisplayConfig_OledType_OLED_AUTO)
screen_model = config.display.oled;
#if defined(USE_SH1107)
@@ -341,7 +341,7 @@ void setup()
// Do this after service.init (because that clears error_code)
#ifdef HAS_PMU
if (!pmu_found)
RECORD_CRITICALERROR(CriticalErrorCode_NO_AXP192); // Record a hardware fault for missing hardware
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_NO_AXP192); // Record a hardware fault for missing hardware
#endif
// Don't call screen setup until after nodedb is setup (because we need
@@ -454,9 +454,9 @@ void setup()
// check if the radio chip matches the selected region
if ((config.lora.region == Config_LoRaConfig_RegionCode_LORA_24) && (!rIf->wideLora())) {
if ((config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_LORA_24) && (!rIf->wideLora())) {
LOG_WARN("Radio chip does not support 2.4GHz LoRa. Reverting to unset.\n");
config.lora.region = Config_LoRaConfig_RegionCode_UNSET;
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET;
nodeDB.saveToDisk(SEGMENT_CONFIG);
if (!rIf->reconfigure()) {
LOG_WARN("Reconfigure failed, rebooting\n");
@@ -490,13 +490,15 @@ void setup()
airTime = new AirTime();
if (!rIf)
RECORD_CRITICALERROR(CriticalErrorCode_NO_RADIO);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_NO_RADIO);
else {
router->addInterface(rIf);
// Calculate and save the bit rate to myNodeInfo
// TODO: This needs to be added what ever method changes the channel from the phone.
myNodeInfo.bitrate = (float(Constants_DATA_PAYLOAD_LEN) / (float(rIf->getPacketTime(Constants_DATA_PAYLOAD_LEN)))) * 1000;
myNodeInfo.bitrate =
(float(meshtastic_Constants_DATA_PAYLOAD_LEN) / (float(rIf->getPacketTime(meshtastic_Constants_DATA_PAYLOAD_LEN)))) *
1000;
LOG_DEBUG("myNodeInfo.bitrate = %f bytes / sec\n", myNodeInfo.bitrate);
}

View File

@@ -26,7 +26,7 @@ extern bool isUSBPowered;
extern ATECCX08A atecc;
#endif
extern uint8_t nodeTelemetrySensorsMap[_TelemetrySensorType_MAX + 1];
extern uint8_t nodeTelemetrySensorsMap[_meshtastic_TelemetrySensorType_MAX + 1];
extern int TCPPort; // set by Portduino

View File

@@ -45,23 +45,23 @@ int16_t Channels::generateHash(ChannelIndex channelNum)
/**
* Validate a channel, fixing any errors as needed
*/
Channel &Channels::fixupChannel(ChannelIndex chIndex)
meshtastic_Channel &Channels::fixupChannel(ChannelIndex chIndex)
{
Channel &ch = getByIndex(chIndex);
meshtastic_Channel &ch = getByIndex(chIndex);
ch.index = chIndex; // Preinit the index so it be ready to share with the phone (we'll never change it later)
if (!ch.has_settings) {
// No settings! Must disable and skip
ch.role = Channel_Role_DISABLED;
ch.role = meshtastic_Channel_Role_DISABLED;
memset(&ch.settings, 0, sizeof(ch.settings));
ch.has_settings = true;
} else {
ChannelSettings &channelSettings = ch.settings;
meshtastic_ChannelSettings &meshtastic_channelSettings = ch.settings;
// Convert the old string "Default" to our new short representation
if (strcmp(channelSettings.name, "Default") == 0)
*channelSettings.name = '\0';
if (strcmp(meshtastic_channelSettings.name, "Default") == 0)
*meshtastic_channelSettings.name = '\0';
}
hashes[chIndex] = generateHash(chIndex);
@@ -74,11 +74,11 @@ Channel &Channels::fixupChannel(ChannelIndex chIndex)
*/
void Channels::initDefaultChannel(ChannelIndex chIndex)
{
Channel &ch = getByIndex(chIndex);
ChannelSettings &channelSettings = ch.settings;
Config_LoRaConfig &loraConfig = config.lora;
meshtastic_Channel &ch = getByIndex(chIndex);
meshtastic_ChannelSettings &channelSettings = ch.settings;
meshtastic_Config_LoRaConfig &loraConfig = config.lora;
loraConfig.modem_preset = Config_LoRaConfig_ModemPreset_LONG_FAST; // Default to Long Range & Fast
loraConfig.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST; // Default to Long Range & Fast
loraConfig.use_preset = true;
loraConfig.tx_power = 0; // default
uint8_t defaultpskIndex = 1;
@@ -87,25 +87,25 @@ void Channels::initDefaultChannel(ChannelIndex chIndex)
strncpy(channelSettings.name, "", sizeof(channelSettings.name));
ch.has_settings = true;
ch.role = Channel_Role_PRIMARY;
ch.role = meshtastic_Channel_Role_PRIMARY;
}
CryptoKey Channels::getKey(ChannelIndex chIndex)
{
Channel &ch = getByIndex(chIndex);
const ChannelSettings &channelSettings = ch.settings;
meshtastic_Channel &ch = getByIndex(chIndex);
const meshtastic_ChannelSettings &channelSettings = ch.settings;
assert(ch.has_settings);
CryptoKey k;
memset(k.bytes, 0, sizeof(k.bytes)); // In case the user provided a short key, we want to pad the rest with zeros
if (ch.role == Channel_Role_DISABLED) {
if (ch.role == meshtastic_Channel_Role_DISABLED) {
k.length = -1; // invalid
} else {
memcpy(k.bytes, channelSettings.psk.bytes, channelSettings.psk.size);
k.length = channelSettings.psk.size;
if (k.length == 0) {
if (ch.role == Channel_Role_SECONDARY) {
if (ch.role == meshtastic_Channel_Role_SECONDARY) {
LOG_DEBUG("Unset PSK for secondary channel %s. using primary key\n", ch.settings.name);
k = getKey(primaryIndex);
} else
@@ -120,7 +120,7 @@ CryptoKey Channels::getKey(ChannelIndex chIndex)
else if (oemStore.oem_aes_key.size > 1) {
// Use the OEM key
LOG_DEBUG("Using OEM Key with %d bytes\n", oemStore.oem_aes_key.size);
memcpy(k.bytes, oemStore.oem_aes_key.bytes , oemStore.oem_aes_key.size);
memcpy(k.bytes, oemStore.oem_aes_key.bytes, oemStore.oem_aes_key.size);
k.length = oemStore.oem_aes_key.size;
// Bump up the last byte of PSK as needed
uint8_t *last = k.bytes + oemStore.oem_aes_key.size - 1;
@@ -182,24 +182,24 @@ void Channels::onConfigChanged()
{
// Make sure the phone hasn't mucked anything up
for (int i = 0; i < channelFile.channels_count; i++) {
Channel &ch = fixupChannel(i);
meshtastic_Channel &ch = fixupChannel(i);
if (ch.role == Channel_Role_PRIMARY)
if (ch.role == meshtastic_Channel_Role_PRIMARY)
primaryIndex = i;
}
}
Channel &Channels::getByIndex(ChannelIndex chIndex)
meshtastic_Channel &Channels::getByIndex(ChannelIndex chIndex)
{
// remove this assert cause malformed packets can make our firmware reboot here.
if (chIndex < channelFile.channels_count) { // This should be equal to MAX_NUM_CHANNELS
Channel *ch = channelFile.channels + chIndex;
meshtastic_Channel *ch = channelFile.channels + chIndex;
return *ch;
} else {
LOG_ERROR("Invalid channel index %d > %d, malformed packet received?\n", chIndex , channelFile.channels_count);
LOG_ERROR("Invalid channel index %d > %d, malformed packet received?\n", chIndex, channelFile.channels_count);
static Channel *ch = (Channel *)malloc(sizeof(Channel));
memset(ch, 0, sizeof(Channel));
static meshtastic_Channel *ch = (meshtastic_Channel *)malloc(sizeof(meshtastic_Channel));
memset(ch, 0, sizeof(meshtastic_Channel));
// ch.index -1 means we don't know the channel locally and need to look it up by settings.name
// not sure this is handled right everywhere
ch->index = -1;
@@ -207,7 +207,7 @@ Channel &Channels::getByIndex(ChannelIndex chIndex)
}
}
Channel &Channels::getByName(const char* chName)
meshtastic_Channel &Channels::getByName(const char *chName)
{
for (ChannelIndex i = 0; i < getNumChannels(); i++) {
if (strcasecmp(getGlobalId(i), chName) == 0) {
@@ -218,15 +218,15 @@ Channel &Channels::getByName(const char* chName)
return getByIndex(getPrimaryIndex());
}
void Channels::setChannel(const Channel &c)
void Channels::setChannel(const meshtastic_Channel &c)
{
Channel &old = getByIndex(c.index);
meshtastic_Channel &old = getByIndex(c.index);
// if this is the new primary, demote any existing roles
if (c.role == Channel_Role_PRIMARY)
if (c.role == meshtastic_Channel_Role_PRIMARY)
for (int i = 0; i < getNumChannels(); i++)
if (channelFile.channels[i].role == Channel_Role_PRIMARY)
channelFile.channels[i].role = Channel_Role_SECONDARY;
if (channelFile.channels[i].role == meshtastic_Channel_Role_PRIMARY)
channelFile.channels[i].role = meshtastic_Channel_Role_SECONDARY;
old = c; // slam in the new settings/role
}
@@ -234,7 +234,7 @@ void Channels::setChannel(const Channel &c)
const char *Channels::getName(size_t chIndex)
{
// Convert the short "" representation for Default into a usable string
const ChannelSettings &channelSettings = getByIndex(chIndex).settings;
const meshtastic_ChannelSettings &channelSettings = getByIndex(chIndex).settings;
const char *channelName = channelSettings.name;
if (!*channelName) { // emptystring
// Per mesh.proto spec, if bandwidth is specified we must ignore modemPreset enum, we assume that in that case
@@ -242,33 +242,32 @@ const char *Channels::getName(size_t chIndex)
if (config.lora.use_preset) {
switch (config.lora.modem_preset) {
case Config_LoRaConfig_ModemPreset_SHORT_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_SLOW:
channelName = "ShortSlow";
break;
case Config_LoRaConfig_ModemPreset_SHORT_FAST:
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST:
channelName = "ShortFast";
break;
case Config_LoRaConfig_ModemPreset_MEDIUM_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_SLOW:
channelName = "MediumSlow";
break;
case Config_LoRaConfig_ModemPreset_MEDIUM_FAST:
case meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_FAST:
channelName = "MediumFast";
break;
case Config_LoRaConfig_ModemPreset_LONG_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_LONG_SLOW:
channelName = "LongSlow";
break;
case Config_LoRaConfig_ModemPreset_LONG_FAST:
case meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST:
channelName = "LongFast";
break;
case Config_LoRaConfig_ModemPreset_VERY_LONG_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_VERY_LONG_SLOW:
channelName = "VLongSlow";
break;
default:
channelName = "Invalid";
break;
}
}
else {
} else {
channelName = "Custom";
}
}

View File

@@ -29,24 +29,23 @@ class Channels
int16_t hashes[MAX_NUM_CHANNELS] = {};
public:
Channels() {}
/// Well known channel names
static const char *adminChannel, *gpioChannel, *serialChannel;
const ChannelSettings &getPrimary() { return getByIndex(getPrimaryIndex()).settings; }
const meshtastic_ChannelSettings &getPrimary() { return getByIndex(getPrimaryIndex()).settings; }
/** Return the Channel for a specified index */
Channel &getByIndex(ChannelIndex chIndex);
meshtastic_Channel &getByIndex(ChannelIndex chIndex);
/** Return the Channel for a specified name, return primary if not found. */
Channel &getByName(const char* chName);
/** Return the Channel for a specified name, return primary if not found. */
meshtastic_Channel &getByName(const char *chName);
/** Using the index inside the channel, update the specified channel's settings and role. If this channel is being promoted
* to be primary, force all other channels to be secondary.
*/
void setChannel(const Channel &c);
void setChannel(const meshtastic_Channel &c);
/** Return a human friendly name for this channel (and expand any short strings as needed)
*/
@@ -125,7 +124,7 @@ class Channels
/**
* Validate a channel, fixing any errors as needed
*/
Channel &fixupChannel(ChannelIndex chIndex);
meshtastic_Channel &fixupChannel(ChannelIndex chIndex);
/**
* Write a default channel to the specified channel index

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "CryptoEngine.h"
#include "configuration.h"
void CryptoEngine::setKey(const CryptoKey &k)
{

View File

@@ -9,7 +9,7 @@ FloodingRouter::FloodingRouter() {}
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*/
ErrorCode FloodingRouter::send(MeshPacket *p)
ErrorCode FloodingRouter::send(meshtastic_MeshPacket *p)
{
// Add any messages _we_ send to the seen message list (so we will ignore all retransmissions we see)
wasSeenRecently(p); // FIXME, move this to a sniffSent method
@@ -17,7 +17,7 @@ ErrorCode FloodingRouter::send(MeshPacket *p)
return Router::send(p);
}
bool FloodingRouter::shouldFilterReceived(const MeshPacket *p)
bool FloodingRouter::shouldFilterReceived(const meshtastic_MeshPacket *p)
{
if (wasSeenRecently(p)) { // Note: this will also add a recent packet record
printPacket("Ignoring incoming msg, because we've already seen it", p);
@@ -27,23 +27,24 @@ bool FloodingRouter::shouldFilterReceived(const MeshPacket *p)
return Router::shouldFilterReceived(p);
}
void FloodingRouter::sniffReceived(const MeshPacket *p, const Routing *c)
void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c)
{
bool isAck = ((c && c->error_reason == Routing_Error_NONE)); // consider only ROUTING_APP message without error as ACK
bool isAck =
((c && c->error_reason == meshtastic_Routing_Error_NONE)); // consider only ROUTING_APP message without error as ACK
if (isAck && p->to != getNodeNum()) {
// do not flood direct message that is ACKed
// do not flood direct message that is ACKed
LOG_DEBUG("Receiving an ACK not for me, but don't need to rebroadcast this direct message anymore.\n");
Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM
}
Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM
}
if ((p->to != getNodeNum()) && (p->hop_limit > 0) && (getFrom(p) != getNodeNum())) {
if (p->id != 0) {
if (config.device.role != Config_DeviceConfig_Role_CLIENT_MUTE) {
MeshPacket *tosend = packetPool.allocCopy(*p); // keep a copy because we will be sending it
if (config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_MUTE) {
meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p); // keep a copy because we will be sending it
tosend->hop_limit--; // bump down the hop count
// If it is a traceRoute request, update the route that it went via me
if (p->which_payload_variant == MeshPacket_decoded_tag && traceRouteModule->wantPacket(p)) {
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag && traceRouteModule->wantPacket(p)) {
traceRouteModule->updateRoute(tosend);
}

View File

@@ -42,7 +42,7 @@ class FloodingRouter : public Router, protected PacketHistory
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*/
virtual ErrorCode send(MeshPacket *p) override;
virtual ErrorCode send(meshtastic_MeshPacket *p) override;
protected:
/**
@@ -51,10 +51,10 @@ class FloodingRouter : public Router, protected PacketHistory
* Called immedately on receiption, before any further processing.
* @return true to abandon the packet
*/
virtual bool shouldFilterReceived(const MeshPacket *p) override;
virtual bool shouldFilterReceived(const meshtastic_MeshPacket *p) override;
/**
* Look for broadcasts we need to rebroadcast
*/
virtual void sniffReceived(const MeshPacket *p, const Routing *c) override;
virtual void sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c) override;
};

View File

@@ -1,9 +1,9 @@
#include "SX126xInterface.h"
#include "SX126xInterface.cpp"
#include "SX128xInterface.h"
#include "SX126xInterface.h"
#include "SX128xInterface.cpp"
#include "api/ServerAPI.h"
#include "SX128xInterface.h"
#include "api/ServerAPI.cpp"
#include "api/ServerAPI.h"
// We need this declaration for proper linking in derived classes
template class SX126xInterface<SX1262>;

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "LLCC68Interface.h"
#include "configuration.h"
#include "error.h"
LLCC68Interface::LLCC68Interface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy,

View File

@@ -1,20 +1,20 @@
#include "configuration.h"
#include "MeshModule.h"
#include "Channels.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "configuration.h"
#include "modules/RoutingModule.h"
#include <assert.h>
std::vector<MeshModule *> *MeshModule::modules;
const MeshPacket *MeshModule::currentRequest;
const meshtastic_MeshPacket *MeshModule::currentRequest;
/**
* If any of the current chain of modules has already sent a reply, it will be here. This is useful to allow
* the RoutingPlugin to avoid sending redundant acks
*/
MeshPacket *MeshModule::currentReply;
meshtastic_MeshPacket *MeshModule::currentReply;
MeshModule::MeshModule(const char *_name) : name(_name)
{
@@ -32,21 +32,22 @@ MeshModule::~MeshModule()
assert(0); // FIXME - remove from list of modules once someone needs this feature
}
MeshPacket *MeshModule::allocAckNak(Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex)
meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex)
{
Routing c = Routing_init_default;
meshtastic_Routing c = meshtastic_Routing_init_default;
c.error_reason = err;
c.which_variant = Routing_error_reason_tag;
c.which_variant = meshtastic_Routing_error_reason_tag;
// Now that we have moded sendAckNak up one level into the class heirarchy we can no longer assume we are a RoutingPlugin
// So we manually call pb_encode_to_bytes and specify routing port number
// auto p = allocDataProtobuf(c);
MeshPacket *p = router->allocForSending();
p->decoded.portnum = PortNum_ROUTING_APP;
p->decoded.payload.size = pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), &Routing_msg, &c);
meshtastic_MeshPacket *p = router->allocForSending();
p->decoded.portnum = meshtastic_PortNum_ROUTING_APP;
p->decoded.payload.size =
pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), &meshtastic_Routing_msg, &c);
p->priority = MeshPacket_Priority_ACK;
p->priority = meshtastic_MeshPacket_Priority_ACK;
p->hop_limit = config.lora.hop_limit; // Flood ACK back to original sender
p->to = to;
@@ -57,7 +58,7 @@ MeshPacket *MeshModule::allocAckNak(Routing_Error err, NodeNum to, PacketId idFr
return p;
}
MeshPacket *MeshModule::allocErrorResponse(Routing_Error err, const MeshPacket *p)
meshtastic_MeshPacket *MeshModule::allocErrorResponse(meshtastic_Routing_Error err, const meshtastic_MeshPacket *p)
{
auto r = allocAckNak(err, getFrom(p), p->id, p->channel);
@@ -66,13 +67,13 @@ MeshPacket *MeshModule::allocErrorResponse(Routing_Error err, const MeshPacket *
return r;
}
void MeshModule::callPlugins(const MeshPacket &mp, RxSource src)
void MeshModule::callPlugins(const meshtastic_MeshPacket &mp, RxSource src)
{
// LOG_DEBUG("In call modules\n");
bool moduleFound = false;
// We now allow **encrypted** packets to pass through the modules
bool isDecoded = mp.which_payload_variant == MeshPacket_decoded_tag;
bool isDecoded = mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag;
currentReply = NULL; // No reply yet
@@ -101,13 +102,13 @@ void MeshModule::callPlugins(const MeshPacket &mp, RxSource src)
moduleFound = true;
/// received channel (or NULL if not decoded)
Channel *ch = isDecoded ? &channels.getByIndex(mp.channel) : NULL;
meshtastic_Channel *ch = isDecoded ? &channels.getByIndex(mp.channel) : NULL;
/// Is the channel this packet arrived on acceptable? (security check)
/// Note: we can't know channel names for encrypted packets, so those are NEVER sent to boundChannel modules
/// Also: if a packet comes in on the local PC interface, we don't check for bound channels, because it is TRUSTED and it needs to
/// to be able to fetch the initial admin packets without yet knowing any channels.
/// Also: if a packet comes in on the local PC interface, we don't check for bound channels, because it is TRUSTED and
/// it needs to to be able to fetch the initial admin packets without yet knowing any channels.
bool rxChannelOk = !pi.boundChannel || (mp.from == 0) || (strcasecmp(ch->settings.name, pi.boundChannel) == 0);
@@ -117,7 +118,7 @@ void MeshModule::callPlugins(const MeshPacket &mp, RxSource src)
if (mp.decoded.want_response) {
printPacket("packet on wrong channel, returning error", &mp);
currentReply = pi.allocErrorResponse(Routing_Error_NOT_AUTHORIZED, &mp);
currentReply = pi.allocErrorResponse(meshtastic_Routing_Error_NOT_AUTHORIZED, &mp);
} else
printPacket("packet on wrong channel, but can't respond", &mp);
} else {
@@ -161,7 +162,7 @@ void MeshModule::callPlugins(const MeshPacket &mp, RxSource src)
printPacket("Sending response", currentReply);
service.sendToMesh(currentReply);
currentReply = NULL;
} else if(mp.from != ourNodeNum) {
} else if (mp.from != ourNodeNum) {
// Note: if the message started with the local node we don't want to send a no response reply
// No one wanted to reply to this requst, tell the requster that happened
@@ -170,17 +171,16 @@ void MeshModule::callPlugins(const MeshPacket &mp, RxSource src)
// SECURITY NOTE! I considered sending back a different error code if we didn't find the psk (i.e. !isDecoded)
// but opted NOT TO. Because it is not a good idea to let remote nodes 'probe' to find out which PSKs were "good" vs
// bad.
routingModule->sendAckNak(Routing_Error_NO_RESPONSE, getFrom(&mp), mp.id, mp.channel);
routingModule->sendAckNak(meshtastic_Routing_Error_NO_RESPONSE, getFrom(&mp), mp.id, mp.channel);
}
}
if (!moduleFound)
LOG_DEBUG("No modules interested in portnum=%d, src=%s\n",
mp.decoded.portnum,
(src == RX_SRC_LOCAL) ? "LOCAL":"REMOTE");
LOG_DEBUG("No modules interested in portnum=%d, src=%s\n", mp.decoded.portnum,
(src == RX_SRC_LOCAL) ? "LOCAL" : "REMOTE");
}
MeshPacket *MeshModule::allocReply()
meshtastic_MeshPacket *MeshModule::allocReply()
{
auto r = myReply;
myReply = NULL; // Only use each reply once
@@ -191,7 +191,7 @@ MeshPacket *MeshModule::allocReply()
* so that subclasses can (optionally) send a response back to the original sender. Implementing this method
* is optional
*/
void MeshModule::sendResponse(const MeshPacket &req)
void MeshModule::sendResponse(const meshtastic_MeshPacket &req)
{
auto r = allocReply();
if (r) {
@@ -206,16 +206,16 @@ void MeshModule::sendResponse(const MeshPacket &req)
/** set the destination and packet parameters of packet p intended as a reply to a particular "to" packet
* This ensures that if the request packet was sent reliably, the reply is sent that way as well.
*/
void setReplyTo(MeshPacket *p, const MeshPacket &to)
void setReplyTo(meshtastic_MeshPacket *p, const meshtastic_MeshPacket &to)
{
assert(p->which_payload_variant == MeshPacket_decoded_tag); // Should already be set by now
assert(p->which_payload_variant == meshtastic_MeshPacket_decoded_tag); // Should already be set by now
p->to = getFrom(&to); // Make sure that if we are sending to the local node, we use our local node addr, not 0
p->channel = to.channel; // Use the same channel that the request came in on
// No need for an ack if we are just delivering locally (it just generates an ignored ack)
p->want_ack = (to.from != 0) ? to.want_ack : false;
if (p->priority == MeshPacket_Priority_UNSET)
p->priority = MeshPacket_Priority_RELIABLE;
if (p->priority == meshtastic_MeshPacket_Priority_UNSET)
p->priority = meshtastic_MeshPacket_Priority_RELIABLE;
p->decoded.request_id = to.id;
}
@@ -235,14 +235,12 @@ std::vector<MeshModule *> MeshModule::GetMeshModulesWithUIFrames()
return modulesWithUIFrames;
}
void MeshModule::observeUIEvents(
Observer<const UIFrameEvent *> *observer)
void MeshModule::observeUIEvents(Observer<const UIFrameEvent *> *observer)
{
if (modules) {
for (auto i = modules->begin(); i != modules->end(); ++i) {
auto &pi = **i;
Observable<const UIFrameEvent *> *observable =
pi.getUIFrameObservable();
Observable<const UIFrameEvent *> *observable = pi.getUIFrameObservable();
if (observable != NULL) {
LOG_DEBUG("Module wants a UI Frame\n");
observer->observe(observable);
@@ -251,24 +249,20 @@ void MeshModule::observeUIEvents(
}
}
AdminMessageHandleResult MeshModule::handleAdminMessageForAllPlugins(const MeshPacket &mp, AdminMessage *request, AdminMessage *response)
AdminMessageHandleResult MeshModule::handleAdminMessageForAllPlugins(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response)
{
AdminMessageHandleResult handled = AdminMessageHandleResult::NOT_HANDLED;
if (modules) {
for (auto i = modules->begin(); i != modules->end(); ++i) {
auto &pi = **i;
AdminMessageHandleResult h = pi.handleAdminMessageForModule(mp, request, response);
if (h == AdminMessageHandleResult::HANDLED_WITH_RESPONSE)
{
if (h == AdminMessageHandleResult::HANDLED_WITH_RESPONSE) {
// In case we have a response it always has priority.
LOG_DEBUG("Reply prepared by module '%s' of variant: %d\n",
pi.name,
response->which_payload_variant);
LOG_DEBUG("Reply prepared by module '%s' of variant: %d\n", pi.name, response->which_payload_variant);
handled = h;
}
else if ((handled != AdminMessageHandleResult::HANDLED_WITH_RESPONSE) &&
(h == AdminMessageHandleResult::HANDLED))
{
} else if ((handled != AdminMessageHandleResult::HANDLED_WITH_RESPONSE) && (h == AdminMessageHandleResult::HANDLED)) {
// In case the message is handled it should be populated, but will not overwrite
// a result with response.
handled = h;

View File

@@ -10,15 +10,14 @@
#endif
/** handleReceived return enumeration
*
*
* Use ProcessMessage::CONTINUE to allows other modules to process a message.
*
*
* Use ProcessMessage::STOP to stop further message processing.
*/
enum class ProcessMessage
{
CONTINUE = 0,
STOP = 1,
enum class ProcessMessage {
CONTINUE = 0,
STOP = 1,
};
/**
@@ -27,8 +26,7 @@ enum class ProcessMessage
* If response is also prepared for the request, then HANDLED_WITH_RESPONSE
* should be returned.
*/
enum class AdminMessageHandleResult
{
enum class AdminMessageHandleResult {
NOT_HANDLED = 0,
HANDLED = 1,
HANDLED_WITH_RESPONSE = 2,
@@ -66,14 +64,18 @@ class MeshModule
/** For use only by MeshService
*/
static void callPlugins(const MeshPacket &mp, RxSource src = RX_SRC_RADIO);
static void callPlugins(const meshtastic_MeshPacket &mp, RxSource src = RX_SRC_RADIO);
static std::vector<MeshModule *> GetMeshModulesWithUIFrames();
static void observeUIEvents(Observer<const UIFrameEvent *> *observer);
static AdminMessageHandleResult handleAdminMessageForAllPlugins(
const MeshPacket &mp, AdminMessage *request, AdminMessage *response);
static AdminMessageHandleResult handleAdminMessageForAllPlugins(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response);
#if HAS_SCREEN
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { return; }
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
return;
}
#endif
protected:
const char *name;
@@ -107,12 +109,12 @@ class MeshModule
* Note: this can be static because we are guaranteed to be processing only one
* plumodulegin at a time.
*/
static const MeshPacket *currentRequest;
static const meshtastic_MeshPacket *currentRequest;
/**
* If your handler wants to send a response, simply set currentReply and it will be sent at the end of response handling.
*/
MeshPacket *myReply = NULL;
meshtastic_MeshPacket *myReply = NULL;
/**
* Initialize your module. This setup function is called once after all hardware and mesh protocol layers have
@@ -123,13 +125,17 @@ class MeshModule
/**
* @return true if you want to receive the specified portnum
*/
virtual bool wantPacket(const MeshPacket *p) = 0;
virtual bool wantPacket(const meshtastic_MeshPacket *p) = 0;
/** Called to handle a particular incoming message
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for it
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for
it
*/
virtual ProcessMessage handleReceived(const MeshPacket &mp) { return ProcessMessage::CONTINUE; }
virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp)
{
return ProcessMessage::CONTINUE;
}
/** Messages can be received that have the want_response bit set. If set, this callback will be invoked
* so that subclasses can (optionally) send a response back to the original sender.
@@ -137,38 +143,48 @@ class MeshModule
* Note: most implementers don't need to override this, instead: If while handling a request you have a reply, just set
* the protected reply field in this instance.
* */
virtual MeshPacket *allocReply();
virtual meshtastic_MeshPacket *allocReply();
/***
* @return true if you want to be alloced a UI screen frame
*/
virtual bool wantUIFrame() { return false; }
virtual Observable<const UIFrameEvent *>* getUIFrameObservable() { return NULL; }
virtual bool wantUIFrame()
{
return false;
}
virtual Observable<const UIFrameEvent *> *getUIFrameObservable()
{
return NULL;
}
MeshPacket *allocAckNak(Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex);
meshtastic_MeshPacket *allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex);
/// Send an error response for the specified packet.
MeshPacket *allocErrorResponse(Routing_Error err, const MeshPacket *p);
meshtastic_MeshPacket *allocErrorResponse(meshtastic_Routing_Error err, const meshtastic_MeshPacket *p);
/**
* @brief An admin message arrived to AdminModule. Module was asked whether it want to handle the request.
*
* @param mp The mesh packet arrived.
* @param request The AdminMessage request extracted from the packet.
* @param response The prepared response
* @return AdminMessageHandleResult
* HANDLED if message was handled
* HANDLED_WITH_RESPONSE if a response is also prepared and to be sent.
*/
virtual AdminMessageHandleResult handleAdminMessageForModule(
const MeshPacket &mp, AdminMessage *request, AdminMessage *response) { return AdminMessageHandleResult::NOT_HANDLED; };
/**
* @brief An admin message arrived to AdminModule. Module was asked whether it want to handle the request.
*
* @param mp The mesh packet arrived.
* @param request The AdminMessage request extracted from the packet.
* @param response The prepared response
* @return AdminMessageHandleResult
* HANDLED if message was handled
* HANDLED_WITH_RESPONSE if a response is also prepared and to be sent.
*/
virtual AdminMessageHandleResult handleAdminMessageForModule(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response)
{
return AdminMessageHandleResult::NOT_HANDLED;
};
private:
/**
* If any of the current chain of modules has already sent a reply, it will be here. This is useful to allow
* the RoutingModule to avoid sending redundant acks
*/
static MeshPacket *currentReply;
static meshtastic_MeshPacket *currentReply;
friend class ReliableRouter;
@@ -176,10 +192,10 @@ class MeshModule
* so that subclasses can (optionally) send a response back to the original sender. This method calls allocReply()
* to generate the reply message, and if !NULL that message will be delivered to whoever sent req
*/
void sendResponse(const MeshPacket &req);
void sendResponse(const meshtastic_MeshPacket &req);
};
/** set the destination and packet parameters of packet p intended as a reply to a particular "to" packet
* This ensures that if the request packet was sent reliably, the reply is sent that way as well.
*/
void setReplyTo(MeshPacket *p, const MeshPacket &to);
void setReplyTo(meshtastic_MeshPacket *p, const meshtastic_MeshPacket &to);

View File

@@ -1,18 +1,18 @@
#include "configuration.h"
#include "MeshPacketQueue.h"
#include "configuration.h"
#include <assert.h>
#include <algorithm>
/// @return the priority of the specified packet
inline uint32_t getPriority(const MeshPacket *p)
inline uint32_t getPriority(const meshtastic_MeshPacket *p)
{
auto pri = p->priority;
return pri;
}
/// @return "true" if "p1" is ordered before "p2"
bool CompareMeshPacketFunc(const MeshPacket *p1, const MeshPacket *p2)
bool CompareMeshPacketFunc(const meshtastic_MeshPacket *p1, const meshtastic_MeshPacket *p2)
{
assert(p1 && p2);
auto p1p = getPriority(p1), p2p = getPriority(p2);
@@ -26,27 +26,29 @@ bool CompareMeshPacketFunc(const MeshPacket *p1, const MeshPacket *p2)
MeshPacketQueue::MeshPacketQueue(size_t _maxLen) : maxLen(_maxLen) {}
bool MeshPacketQueue::empty() {
bool MeshPacketQueue::empty()
{
return queue.empty();
}
/**
* Some clients might not properly set priority, therefore we fix it here.
*/
void fixPriority(MeshPacket *p)
void fixPriority(meshtastic_MeshPacket *p)
{
// We might receive acks from other nodes (and since generated remotely, they won't have priority assigned. Check for that
// and fix it
if (p->priority == MeshPacket_Priority_UNSET) {
if (p->priority == meshtastic_MeshPacket_Priority_UNSET) {
// if acks give high priority
// if a reliable message give a bit higher default priority
p->priority = (p->decoded.portnum == PortNum_ROUTING_APP) ? MeshPacket_Priority_ACK :
(p->want_ack ? MeshPacket_Priority_RELIABLE : MeshPacket_Priority_DEFAULT);
p->priority = (p->decoded.portnum == meshtastic_PortNum_ROUTING_APP)
? meshtastic_MeshPacket_Priority_ACK
: (p->want_ack ? meshtastic_MeshPacket_Priority_RELIABLE : meshtastic_MeshPacket_Priority_DEFAULT);
}
}
/** enqueue a packet, return false if full */
bool MeshPacketQueue::enqueue(MeshPacket *p)
bool MeshPacketQueue::enqueue(meshtastic_MeshPacket *p)
{
fixPriority(p);
@@ -60,7 +62,7 @@ bool MeshPacketQueue::enqueue(MeshPacket *p)
return true;
}
MeshPacket *MeshPacketQueue::dequeue()
meshtastic_MeshPacket *MeshPacketQueue::dequeue()
{
if (empty()) {
return NULL;
@@ -73,7 +75,7 @@ MeshPacket *MeshPacketQueue::dequeue()
return p;
}
MeshPacket *MeshPacketQueue::getFront()
meshtastic_MeshPacket *MeshPacketQueue::getFront()
{
if (empty()) {
return NULL;
@@ -84,7 +86,7 @@ MeshPacket *MeshPacketQueue::getFront()
}
/** Attempt to find and remove a packet from this queue. Returns a pointer to the removed packet, or NULL if not found */
MeshPacket *MeshPacketQueue::remove(NodeNum from, PacketId id)
meshtastic_MeshPacket *MeshPacketQueue::remove(NodeNum from, PacketId id)
{
for (auto it = queue.begin(); it != queue.end(); it++) {
auto p = (*it);
@@ -99,7 +101,8 @@ MeshPacket *MeshPacketQueue::remove(NodeNum from, PacketId id)
}
/** Attempt to find and remove a packet from this queue. Returns the packet which was removed from the queue */
bool MeshPacketQueue::replaceLowerPriorityPacket(MeshPacket *p) {
bool MeshPacketQueue::replaceLowerPriorityPacket(meshtastic_MeshPacket *p)
{
std::sort_heap(queue.begin(), queue.end(), &CompareMeshPacketFunc); // sort ascending based on priority (0 -> 127)
// find first packet which does not compare less (in priority) than parameter packet
@@ -119,7 +122,7 @@ bool MeshPacketQueue::replaceLowerPriorityPacket(MeshPacket *p) {
if (getPriority(p) > getPriority(*low)) {
packetPool.release(*low); // deallocate and drop the packet we're replacing
*low = p; // replace low-pri packet at this position with incoming packet with higher priority
*low = p; // replace low-pri packet at this position with incoming packet with higher priority
}
std::make_heap(queue.begin(), queue.end(), &CompareMeshPacketFunc);

View File

@@ -4,23 +4,23 @@
#include <queue>
/**
* A priority queue of packets
*/
class MeshPacketQueue
{
size_t maxLen;
std::vector<MeshPacket *> queue;
std::vector<meshtastic_MeshPacket *> queue;
/** Replace a lower priority package in the queue with 'mp' (provided there are lower pri packages). Return true if replaced. */
bool replaceLowerPriorityPacket(MeshPacket *mp);
/** Replace a lower priority package in the queue with 'mp' (provided there are lower pri packages). Return true if replaced.
*/
bool replaceLowerPriorityPacket(meshtastic_MeshPacket *mp);
public:
explicit MeshPacketQueue(size_t _maxLen);
/** enqueue a packet, return false if full */
bool enqueue(MeshPacket *p);
bool enqueue(meshtastic_MeshPacket *p);
/** return true if the queue is empty */
bool empty();
@@ -31,10 +31,10 @@ class MeshPacketQueue
/** return total size of the Queue */
size_t getMaxLen() { return maxLen; }
MeshPacket *dequeue();
meshtastic_MeshPacket *dequeue();
MeshPacket *getFront();
meshtastic_MeshPacket *getFront();
/** Attempt to find and remove a packet from this queue. Returns the packet which was removed from the queue */
MeshPacket *remove(NodeNum from, PacketId id);
meshtastic_MeshPacket *remove(NodeNum from, PacketId id);
};

View File

@@ -7,7 +7,7 @@
// Map from old region names to new region enums
struct RegionInfo {
Config_LoRaConfig_RegionCode code;
meshtastic_Config_LoRaConfig_RegionCode code;
float freqStart;
float freqEnd;
float dutyCycle;

View File

@@ -2,9 +2,9 @@
#include <assert.h>
#include <string>
#include "GPS.h"
#include "../concurrency/Periodic.h"
#include "BluetoothCommon.h" // needed for updateBatteryLevel, FIXME, eventually when we pull mesh out into a lib we shouldn't be whacking bluetooth from here
#include "GPS.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
@@ -51,15 +51,15 @@ FIXME in the initial proof of concept we just skip the entire want/deny flow and
MeshService service;
static MemoryDynamic<QueueStatus> staticQueueStatusPool;
static MemoryDynamic<meshtastic_QueueStatus> staticQueueStatusPool;
Allocator<QueueStatus> &queueStatusPool = staticQueueStatusPool;
Allocator<meshtastic_QueueStatus> &queueStatusPool = staticQueueStatusPool;
#include "Router.h"
MeshService::MeshService() : toPhoneQueue(MAX_RX_TOPHONE), toPhoneQueueStatusQueue(MAX_RX_TOPHONE)
{
lastQueueStatus = { 0, 0, 16, 0 };
lastQueueStatus = {0, 0, 16, 0};
}
void MeshService::init()
@@ -71,14 +71,14 @@ void MeshService::init()
gpsObserver.observe(&gps->newStatus);
}
int MeshService::handleFromRadio(const MeshPacket *mp)
int MeshService::handleFromRadio(const meshtastic_MeshPacket *mp)
{
powerFSM.trigger(EVENT_PACKET_FOR_PHONE); // Possibly keep the node from sleeping
printPacket("Forwarding to phone", mp);
nodeDB.updateFrom(*mp); // update our DB state based off sniffing every RX packet from the radio
sendToPhone((MeshPacket *)mp);
sendToPhone((meshtastic_MeshPacket *)mp);
return 0;
}
@@ -87,7 +87,7 @@ int MeshService::handleFromRadio(const MeshPacket *mp)
void MeshService::loop()
{
if (lastQueueStatus.free == 0) { // check if there is now free space in TX queue
QueueStatus qs = router->getQueueStatus();
meshtastic_QueueStatus qs = router->getQueueStatus();
if (qs.free != lastQueueStatus.free)
(void)sendQueueStatusToPhone(qs, 0, 0);
}
@@ -130,31 +130,32 @@ void MeshService::reloadOwner(bool shouldSave)
* Called by PhoneAPI.handleToRadio. Note: p is a scratch buffer, this function is allowed to write to it but it can not keep a
* reference
*/
void MeshService::handleToRadio(MeshPacket &p)
void MeshService::handleToRadio(meshtastic_MeshPacket &p)
{
#ifdef ARCH_PORTDUINO
#ifdef ARCH_PORTDUINO
// Simulates device is receiving a packet via the LoRa chip
if (p.decoded.portnum == PortNum_SIMULATOR_APP) {
if (p.decoded.portnum == meshtastic_PortNum_SIMULATOR_APP) {
// Simulator packet (=Compressed packet) is encapsulated in a MeshPacket, so need to unwrap first
Compressed scratch;
Compressed *decoded = NULL;
if (p.which_payload_variant == MeshPacket_decoded_tag) {
meshtastic_Compressed scratch;
meshtastic_Compressed *decoded = NULL;
if (p.which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
memset(&scratch, 0, sizeof(scratch));
p.decoded.payload.size = pb_decode_from_bytes(p.decoded.payload.bytes, p.decoded.payload.size, &Compressed_msg, &scratch);
p.decoded.payload.size =
pb_decode_from_bytes(p.decoded.payload.bytes, p.decoded.payload.size, &meshtastic_Compressed_msg, &scratch);
if (p.decoded.payload.size) {
decoded = &scratch;
// Extract the original payload and replace
memcpy(&p.decoded.payload, &decoded->data, sizeof(decoded->data));
// Switch the port from PortNum_SIMULATOR_APP back to the original PortNum
// Switch the port from PortNum_SIMULATOR_APP back to the original PortNum
p.decoded.portnum = decoded->portnum;
} else
LOG_ERROR("Error decoding protobuf for simulator message!\n");
}
// Let SimRadio receive as if it did via its LoRa chip
SimRadio::instance->startReceive(&p);
return;
SimRadio::instance->startReceive(&p);
return;
}
#endif
#endif
if (p.from != 0) { // We don't let phones assign nodenums to their sent messages
LOG_WARN("phone tried to pick a nodenum, we don't allow that.\n");
p.from = 0;
@@ -187,16 +188,16 @@ bool MeshService::cancelSending(PacketId id)
return router->cancelSending(nodeDB.getNodeNum(), id);
}
ErrorCode MeshService::sendQueueStatusToPhone(const QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id)
ErrorCode MeshService::sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id)
{
QueueStatus *copied = queueStatusPool.allocCopy(qs);
meshtastic_QueueStatus *copied = queueStatusPool.allocCopy(qs);
copied->res = res;
copied->mesh_packet_id = mesh_packet_id;
if (toPhoneQueueStatusQueue.numFree() == 0) {
LOG_DEBUG("NOTE: tophone queue status queue is full, discarding oldest\n");
QueueStatus *d = toPhoneQueueStatusQueue.dequeuePtr(0);
meshtastic_QueueStatus *d = toPhoneQueueStatusQueue.dequeuePtr(0);
if (d)
releaseQueueStatusToPool(d);
}
@@ -209,7 +210,7 @@ ErrorCode MeshService::sendQueueStatusToPhone(const QueueStatus &qs, ErrorCode r
return res ? ERRNO_OK : ERRNO_UNKNOWN;
}
void MeshService::sendToMesh(MeshPacket *p, RxSource src, bool ccToPhone)
void MeshService::sendToMesh(meshtastic_MeshPacket *p, RxSource src, bool ccToPhone)
{
uint32_t mesh_packet_id = p->id;
nodeDB.updateFrom(*p); // update our local DB for this packet (because phone might have sent position packets etc...)
@@ -219,7 +220,7 @@ void MeshService::sendToMesh(MeshPacket *p, RxSource src, bool ccToPhone)
/* NOTE(pboldin): Prepare and send QueueStatus message to the phone as a
* high-priority message. */
QueueStatus qs = router->getQueueStatus();
meshtastic_QueueStatus qs = router->getQueueStatus();
ErrorCode r = sendQueueStatusToPhone(qs, res, mesh_packet_id);
if (r != ERRNO_OK) {
LOG_DEBUG("Can't send status to phone");
@@ -232,7 +233,7 @@ void MeshService::sendToMesh(MeshPacket *p, RxSource src, bool ccToPhone)
void MeshService::sendNetworkPing(NodeNum dest, bool wantReplies)
{
NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
meshtastic_NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
assert(node);
if (node->has_position && (node->position.latitude_i != 0 || node->position.longitude_i != 0)) {
@@ -248,24 +249,24 @@ void MeshService::sendNetworkPing(NodeNum dest, bool wantReplies)
}
}
void MeshService::sendToPhone(MeshPacket *p)
void MeshService::sendToPhone(meshtastic_MeshPacket *p)
{
if (toPhoneQueue.numFree() == 0) {
LOG_WARN("ToPhone queue is full, discarding oldest\n");
MeshPacket *d = toPhoneQueue.dequeuePtr(0);
meshtastic_MeshPacket *d = toPhoneQueue.dequeuePtr(0);
if (d)
releaseToPool(d);
}
MeshPacket *copied = packetPool.allocCopy(*p);
meshtastic_MeshPacket *copied = packetPool.allocCopy(*p);
perhapsDecode(copied);
assert(toPhoneQueue.enqueue(copied, 0));
fromNum++;
}
NodeInfo *MeshService::refreshMyNodeInfo()
meshtastic_NodeInfo *MeshService::refreshMyNodeInfo()
{
NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
meshtastic_NodeInfo *node = nodeDB.getNode(nodeDB.getNodeNum());
assert(node);
// We might not have a position yet for our local node, in that case, at least try to send the time
@@ -274,7 +275,7 @@ NodeInfo *MeshService::refreshMyNodeInfo()
node->has_position = true;
}
Position &position = node->position;
meshtastic_Position &position = node->position;
// Update our local node info with our time (even if we don't decide to update anyone else)
node->last_heard =
@@ -290,8 +291,8 @@ NodeInfo *MeshService::refreshMyNodeInfo()
int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
{
// Update our local node info with our position (even if we don't decide to update anyone else)
NodeInfo *node = refreshMyNodeInfo();
Position pos = Position_init_default;
meshtastic_NodeInfo *node = refreshMyNodeInfo();
meshtastic_Position pos = meshtastic_Position_init_default;
if (newStatus->getHasLock()) {
// load data from GPS object, will add timestamp + battery further down
@@ -323,7 +324,7 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
return 0;
}
bool MeshService::isToPhoneQueueEmpty()
bool MeshService::isToPhoneQueueEmpty()
{
return toPhoneQueue.isEmpty();
}

View File

@@ -14,7 +14,7 @@
#include "../platform/portduino/SimRadio.h"
#endif
extern Allocator<QueueStatus> &queueStatusPool;
extern Allocator<meshtastic_QueueStatus> &queueStatusPool;
/**
* Top level app for this service. keeps the mesh, the radio config and the queue of received packets.
@@ -29,13 +29,13 @@ class MeshService
/// FIXME, change to a DropOldestQueue and keep a count of the number of dropped packets to ensure
/// we never hang because android hasn't been there in a while
/// FIXME - save this to flash on deep sleep
PointerQueue<MeshPacket> toPhoneQueue;
PointerQueue<meshtastic_MeshPacket> toPhoneQueue;
// keep list of QueueStatus packets to be send to the phone
PointerQueue<QueueStatus> toPhoneQueueStatusQueue;
PointerQueue<meshtastic_QueueStatus> toPhoneQueueStatusQueue;
// This holds the last QueueStatus send
QueueStatus lastQueueStatus;
meshtastic_QueueStatus lastQueueStatus;
/// The current nonce for the newest packet which has been queued for the phone
uint32_t fromNum = 0;
@@ -59,28 +59,28 @@ class MeshService
/// Return the next packet destined to the phone. FIXME, somehow use fromNum to allow the phone to retry the
/// last few packets if needs to.
MeshPacket *getForPhone() { return toPhoneQueue.dequeuePtr(0); }
meshtastic_MeshPacket *getForPhone() { return toPhoneQueue.dequeuePtr(0); }
/// Allows the bluetooth handler to free packets after they have been sent
void releaseToPool(MeshPacket *p) { packetPool.release(p); }
void releaseToPool(meshtastic_MeshPacket *p) { packetPool.release(p); }
/// Return the next QueueStatus packet destined to the phone.
QueueStatus *getQueueStatusForPhone() { return toPhoneQueueStatusQueue.dequeuePtr(0); }
meshtastic_QueueStatus *getQueueStatusForPhone() { return toPhoneQueueStatusQueue.dequeuePtr(0); }
// Release QueueStatus packet to pool
void releaseQueueStatusToPool(QueueStatus *p) { queueStatusPool.release(p); }
void releaseQueueStatusToPool(meshtastic_QueueStatus *p) { queueStatusPool.release(p); }
/**
* Given a ToRadio buffer parse it and properly handle it (setup radio, owner or send packet into the mesh)
* Called by PhoneAPI.handleToRadio. Note: p is a scratch buffer, this function is allowed to write to it but it can not keep
* a reference
*/
void handleToRadio(MeshPacket &p);
void handleToRadio(meshtastic_MeshPacket &p);
/** The radioConfig object just changed, call this to force the hw to change to the new settings
* @return true if client devices should be sent a new set of radio configs
*/
bool reloadConfig(int saveWhat=SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS);
bool reloadConfig(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS);
/// The owner User record just got updated, update our node DB and broadcast the info into the mesh
void reloadOwner(bool shouldSave = true);
@@ -92,16 +92,16 @@ class MeshService
/// Send a packet into the mesh - note p must have been allocated from packetPool. We will return it to that pool after
/// sending. This is the ONLY function you should use for sending messages into the mesh, because it also updates the nodedb
/// cache
void sendToMesh(MeshPacket *p, RxSource src = RX_SRC_LOCAL, bool ccToPhone = false);
void sendToMesh(meshtastic_MeshPacket *p, RxSource src = RX_SRC_LOCAL, bool ccToPhone = false);
/** Attempt to cancel a previously sent packet from this _local_ node. Returns true if a packet was found we could cancel */
bool cancelSending(PacketId id);
/// Pull the latest power and time info into my nodeinfo
NodeInfo *refreshMyNodeInfo();
meshtastic_NodeInfo *refreshMyNodeInfo();
/// Send a packet to the phone
void sendToPhone(MeshPacket *p);
/// Send a packet to the phone
void sendToPhone(meshtastic_MeshPacket *p);
bool isToPhoneQueueEmpty();
@@ -112,10 +112,10 @@ class MeshService
/// Handle a packet that just arrived from the radio. This method does _ReliableRouternot_ free the provided packet. If it
/// needs to keep the packet around it makes a copy
int handleFromRadio(const MeshPacket *p);
int handleFromRadio(const meshtastic_MeshPacket *p);
friend class RoutingModule;
ErrorCode sendQueueStatusToPhone(const QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id);
ErrorCode sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id);
};
extern MeshService service;

View File

@@ -19,9 +19,9 @@ typedef uint32_t PacketId; // A packet sequence number
* Source of a received message
*/
enum RxSource {
RX_SRC_LOCAL, // message was generated locally
RX_SRC_RADIO, // message was received from radio mesh
RX_SRC_USER // message was received from end-user device
RX_SRC_LOCAL, // message was generated locally
RX_SRC_RADIO, // message was received from radio mesh
RX_SRC_USER // message was received from end-user device
};
/**
@@ -39,10 +39,10 @@ enum RxSource {
typedef int ErrorCode;
/// Alloc and free packets to our global, ISR safe pool
extern Allocator<MeshPacket> &packetPool;
extern Allocator<meshtastic_MeshPacket> &packetPool;
/**
* Most (but not always) of the time we want to treat packets 'from' the local phone (where from == 0), as if they originated on
* the local node. If from is zero this function returns our node number instead
*/
NodeNum getFrom(const MeshPacket *p);
NodeNum getFrom(const meshtastic_MeshPacket *p);

View File

@@ -13,9 +13,9 @@
#include "error.h"
#include "main.h"
#include "mesh-pb-constants.h"
#include <ErriezCRC32.h>
#include <pb_decode.h>
#include <pb_encode.h>
#include <ErriezCRC32.h>
#ifdef ARCH_ESP32
#include "mesh/http/WiFiAPClient.h"
@@ -32,12 +32,12 @@
NodeDB nodeDB;
// we have plenty of ram so statically alloc this tempbuf (for now)
EXT_RAM_ATTR DeviceState devicestate;
MyNodeInfo &myNodeInfo = devicestate.my_node;
LocalConfig config;
LocalModuleConfig moduleConfig;
ChannelFile channelFile;
OEMStore oemStore;
EXT_RAM_ATTR meshtastic_DeviceState devicestate;
meshtastic_MyNodeInfo &myNodeInfo = devicestate.my_node;
meshtastic_LocalConfig config;
meshtastic_LocalModuleConfig moduleConfig;
meshtastic_ChannelFile channelFile;
meshtastic_OEMStore oemStore;
/** The current change # for radio settings. Starts at 0 on boot and any time the radio settings
* might have changed is incremented. Allows others to detect they might now be on a new channel.
@@ -53,7 +53,7 @@ extern void getMacAddr(uint8_t *dmac);
* But there are some special ids used when we haven't yet been configured by a user. In that case
* we use !macaddr (no colons).
*/
User &owner = devicestate.owner;
meshtastic_User &owner = devicestate.owner;
static uint8_t ourMacAddr[6];
@@ -69,7 +69,7 @@ NodeDB::NodeDB() : nodes(devicestate.node_db), numNodes(&devicestate.node_db_cou
* Most (but not always) of the time we want to treat packets 'from' the local phone (where from == 0), as if they originated on
* the local node. If from is zero this function returns our node number instead
*/
NodeNum getFrom(const MeshPacket *p)
NodeNum getFrom(const meshtastic_MeshPacket *p)
{
return (p->from == 0) ? nodeDB.getNodeNum() : p->from;
}
@@ -81,7 +81,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
radioGeneration++;
if (factory_reset) {
didFactoryReset = factoryReset();
didFactoryReset = factoryReset();
}
if (channelFile.channels_count != MAX_NUM_CHANNELS) {
@@ -102,7 +102,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
config.power.wait_bluetooth_secs = 10;
config.position.position_broadcast_secs = 6 * 60;
config.power.ls_secs = 60;
config.lora.region = Config_LoRaConfig_RegionCode_TW;
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_TW;
// Enter super deep sleep soon and stay there not very long
// radioConfig.preferences.mesh_sds_timeout_secs = 10;
@@ -121,7 +121,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
return didFactoryReset;
}
bool NodeDB::factoryReset()
bool NodeDB::factoryReset()
{
LOG_INFO("Performing factory reset!\n");
// first, remove the "/prefs" (this removes most prefs)
@@ -151,7 +151,7 @@ bool NodeDB::factoryReset()
void NodeDB::installDefaultConfig()
{
LOG_INFO("Installing default LocalConfig\n");
memset(&config, 0, sizeof(LocalConfig));
memset(&config, 0, sizeof(meshtastic_LocalConfig));
config.version = DEVICESTATE_CUR_VER;
config.has_device = true;
config.has_display = true;
@@ -160,10 +160,11 @@ void NodeDB::installDefaultConfig()
config.has_power = true;
config.has_network = true;
config.has_bluetooth = true;
config.lora.tx_enabled = true; // FIXME: maybe false in the future, and setting region to enable it. (unset region forces it off)
config.lora.override_duty_cycle = false;
config.lora.region = Config_LoRaConfig_RegionCode_UNSET;
config.lora.modem_preset = Config_LoRaConfig_ModemPreset_LONG_FAST;
config.lora.tx_enabled =
true; // FIXME: maybe false in the future, and setting region to enable it. (unset region forces it off)
config.lora.override_duty_cycle = false;
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET;
config.lora.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST;
config.lora.hop_limit = HOP_RELIABLE;
config.position.gps_enabled = true;
config.position.position_broadcast_smart_enabled = true;
@@ -178,14 +179,16 @@ void NodeDB::installDefaultConfig()
#else
bool hasScreen = screen_found;
#endif
config.bluetooth.mode = hasScreen ? Config_BluetoothConfig_PairingMode_RANDOM_PIN : Config_BluetoothConfig_PairingMode_FIXED_PIN;
config.bluetooth.mode = hasScreen ? meshtastic_Config_BluetoothConfig_PairingMode_RANDOM_PIN
: meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN;
// for backward compat, default position flags are ALT+MSL
config.position.position_flags = (Config_PositionConfig_PositionFlags_ALTITUDE | Config_PositionConfig_PositionFlags_ALTITUDE_MSL);
config.position.position_flags =
(meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE | meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE_MSL);
initConfigIntervals();
}
void NodeDB::initConfigIntervals()
void NodeDB::initConfigIntervals()
{
config.position.gps_update_interval = default_gps_update_interval;
config.position.gps_attempt_time = default_gps_attempt_time;
@@ -196,15 +199,15 @@ void NodeDB::initConfigIntervals()
config.power.min_wake_secs = default_min_wake_secs;
config.power.sds_secs = default_sds_secs;
config.power.wait_bluetooth_secs = default_wait_bluetooth_secs;
config.display.screen_on_secs = default_screen_on_secs;
}
void NodeDB::installDefaultModuleConfig()
{
LOG_INFO("Installing default ModuleConfig\n");
memset(&moduleConfig, 0, sizeof(ModuleConfig));
memset(&moduleConfig, 0, sizeof(meshtastic_ModuleConfig));
moduleConfig.version = DEVICESTATE_CUR_VER;
moduleConfig.has_mqtt = true;
moduleConfig.has_range_test = true;
@@ -221,7 +224,7 @@ void NodeDB::installDefaultModuleConfig()
initModuleConfigIntervals();
}
void NodeDB::initModuleConfigIntervals()
void NodeDB::initModuleConfigIntervals()
{
moduleConfig.telemetry.device_update_interval = default_broadcast_interval_secs;
moduleConfig.telemetry.environment_update_interval = default_broadcast_interval_secs;
@@ -230,7 +233,7 @@ void NodeDB::initModuleConfigIntervals()
void NodeDB::installDefaultChannels()
{
LOG_INFO("Installing default ChannelFile\n");
memset(&channelFile, 0, sizeof(ChannelFile));
memset(&channelFile, 0, sizeof(meshtastic_ChannelFile));
channelFile.version = DEVICESTATE_CUR_VER;
}
@@ -244,10 +247,10 @@ void NodeDB::resetNodes()
void NodeDB::installDefaultDeviceState()
{
LOG_INFO("Installing default DeviceState\n");
memset(&devicestate, 0, sizeof(DeviceState));
memset(&devicestate, 0, sizeof(meshtastic_DeviceState));
*numNodes = 0;
// init our devicestate with valid flags so protobuf writing/reading will work
devicestate.has_my_node = true;
devicestate.has_owner = true;
@@ -285,7 +288,8 @@ void NodeDB::init()
myNodeInfo.max_channels = MAX_NUM_CHANNELS; // tell others the max # of channels we can understand
myNodeInfo.error_code = CriticalErrorCode_NONE; // For the error code, only show values from this boot (discard value from flash)
myNodeInfo.error_code =
meshtastic_CriticalErrorCode_NONE; // For the error code, only show values from this boot (discard value from flash)
myNodeInfo.error_address = 0;
// likewise - we always want the app requirements to come from the running appload
@@ -299,7 +303,7 @@ void NodeDB::init()
owner.hw_model = HW_VENDOR;
// Include our owner in the node db under our nodenum
NodeInfo *info = getOrCreateNode(getNodeNum());
meshtastic_NodeInfo *info = getOrCreateNode(getNodeNum());
info->user = owner;
info->has_user = true;
@@ -348,7 +352,7 @@ void NodeDB::pickNewNodeNum()
if (r == NODENUM_BROADCAST || r < NUM_RESERVED)
r = NUM_RESERVED; // don't pick a reserved node number
NodeInfo *found;
meshtastic_NodeInfo *found;
while ((found = getNode(r)) && memcmp(found->user.macaddr, owner.macaddr, sizeof(owner.macaddr))) {
NodeNum n = random(NUM_RESERVED, NODENUM_BROADCAST); // try a new random choice
LOG_DEBUG("NOTE! Our desired nodenum 0x%x is in use, so trying for 0x%x\n", r, n);
@@ -364,7 +368,6 @@ static const char *moduleConfigFileName = "/prefs/module.proto";
static const char *channelFileName = "/prefs/channels.proto";
static const char *oemConfigFile = "/oem/oem.proto";
/** Load a protobuf from a file, return true for success */
bool NodeDB::loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, void *dest_struct)
{
@@ -400,7 +403,8 @@ bool NodeDB::loadProto(const char *filename, size_t protoSize, size_t objSize, c
void NodeDB::loadFromDisk()
{
// static DeviceState scratch; We no longer read into a tempbuf because this structure is 15KB of valuable RAM
if (!loadProto(prefFileName, DeviceState_size, sizeof(DeviceState), &DeviceState_msg, &devicestate)) {
if (!loadProto(prefFileName, meshtastic_DeviceState_size, sizeof(meshtastic_DeviceState), &meshtastic_DeviceState_msg,
&devicestate)) {
installDefaultDeviceState(); // Our in RAM copy might now be corrupt
} else {
if (devicestate.version < DEVICESTATE_MIN_VER) {
@@ -411,7 +415,8 @@ void NodeDB::loadFromDisk()
}
}
if (!loadProto(configFileName, LocalConfig_size, sizeof(LocalConfig), &LocalConfig_msg, &config)) {
if (!loadProto(configFileName, meshtastic_LocalConfig_size, sizeof(meshtastic_LocalConfig), &meshtastic_LocalConfig_msg,
&config)) {
installDefaultConfig(); // Our in RAM copy might now be corrupt
} else {
if (config.version < DEVICESTATE_MIN_VER) {
@@ -422,7 +427,8 @@ void NodeDB::loadFromDisk()
}
}
if (!loadProto(moduleConfigFileName, LocalModuleConfig_size, sizeof(LocalModuleConfig), &LocalModuleConfig_msg, &moduleConfig)) {
if (!loadProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, sizeof(meshtastic_LocalModuleConfig),
&meshtastic_LocalModuleConfig_msg, &moduleConfig)) {
installDefaultModuleConfig(); // Our in RAM copy might now be corrupt
} else {
if (moduleConfig.version < DEVICESTATE_MIN_VER) {
@@ -433,7 +439,8 @@ void NodeDB::loadFromDisk()
}
}
if (!loadProto(channelFileName, ChannelFile_size, sizeof(ChannelFile), &ChannelFile_msg, &channelFile)) {
if (!loadProto(channelFileName, meshtastic_ChannelFile_size, sizeof(meshtastic_ChannelFile), &meshtastic_ChannelFile_msg,
&channelFile)) {
installDefaultChannels(); // Our in RAM copy might now be corrupt
} else {
if (channelFile.version < DEVICESTATE_MIN_VER) {
@@ -444,7 +451,7 @@ void NodeDB::loadFromDisk()
}
}
if (loadProto(oemConfigFile, OEMStore_size, sizeof(OEMStore), &OEMStore_msg, &oemStore))
if (loadProto(oemConfigFile, meshtastic_OEMStore_size, sizeof(meshtastic_OEMStore), &meshtastic_OEMStore_msg, &oemStore))
LOG_INFO("Loaded OEMStore\n");
}
@@ -478,9 +485,9 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_
#ifdef ARCH_NRF52
static uint8_t failedCounter = 0;
failedCounter++;
if(failedCounter >= 2){
if (failedCounter >= 2) {
FSCom.format();
//After formatting, the device needs to be restarted
// After formatting, the device needs to be restarted
nodeDB.resetRadioConfig(true);
}
#endif
@@ -497,17 +504,17 @@ void NodeDB::saveChannelsToDisk()
#ifdef FSCom
FSCom.mkdir("/prefs");
#endif
saveProto(channelFileName, ChannelFile_size, &ChannelFile_msg, &channelFile);
saveProto(channelFileName, meshtastic_ChannelFile_size, &meshtastic_ChannelFile_msg, &channelFile);
}
}
void NodeDB::saveDeviceStateToDisk()
void NodeDB::saveDeviceStateToDisk()
{
if (!devicestate.no_save) {
#ifdef FSCom
FSCom.mkdir("/prefs");
#endif
saveProto(prefFileName, DeviceState_size, &DeviceState_msg, &devicestate);
saveProto(prefFileName, meshtastic_DeviceState_size, &meshtastic_DeviceState_msg, &devicestate);
}
}
@@ -529,7 +536,7 @@ void NodeDB::saveToDisk(int saveWhat)
config.has_power = true;
config.has_network = true;
config.has_bluetooth = true;
saveProto(configFileName, LocalConfig_size, &LocalConfig_msg, &config);
saveProto(configFileName, meshtastic_LocalConfig_size, &meshtastic_LocalConfig_msg, &config);
}
if (saveWhat & SEGMENT_MODULECONFIG) {
@@ -540,7 +547,7 @@ void NodeDB::saveToDisk(int saveWhat)
moduleConfig.has_serial = true;
moduleConfig.has_store_forward = true;
moduleConfig.has_telemetry = true;
saveProto(moduleConfigFileName, LocalModuleConfig_size, &LocalModuleConfig_msg, &moduleConfig);
saveProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, &meshtastic_LocalModuleConfig_msg, &moduleConfig);
}
if (saveWhat & SEGMENT_CHANNELS) {
@@ -551,7 +558,7 @@ void NodeDB::saveToDisk(int saveWhat)
}
}
const NodeInfo *NodeDB::readNextInfo()
const meshtastic_NodeInfo *NodeDB::readNextInfo()
{
if (readPointer < *numNodes)
return &nodes[readPointer++];
@@ -560,7 +567,7 @@ const NodeInfo *NodeDB::readNextInfo()
}
/// Given a node, return how many seconds in the past (vs now) that we last heard from it
uint32_t sinceLastSeen(const NodeInfo *n)
uint32_t sinceLastSeen(const meshtastic_NodeInfo *n)
{
uint32_t now = getTime();
@@ -589,9 +596,9 @@ size_t NodeDB::getNumOnlineNodes()
/** Update position info for this node based on received position data
*/
void NodeDB::updatePosition(uint32_t nodeId, const Position &p, RxSource src)
void NodeDB::updatePosition(uint32_t nodeId, const meshtastic_Position &p, RxSource src)
{
NodeInfo *info = getOrCreateNode(nodeId);
meshtastic_NodeInfo *info = getOrCreateNode(nodeId);
if (!info) {
return;
}
@@ -599,7 +606,7 @@ void NodeDB::updatePosition(uint32_t nodeId, const Position &p, RxSource src)
if (src == RX_SRC_LOCAL) {
// Local packet, fully authoritative
LOG_INFO("updatePosition LOCAL pos@%x, time=%u, latI=%d, lonI=%d, alt=%d\n", p.timestamp, p.time, p.latitude_i,
p.longitude_i, p.altitude);
p.longitude_i, p.altitude);
info->position = p;
} else if ((p.time > 0) && !p.latitude_i && !p.longitude_i && !p.timestamp && !p.location_source) {
@@ -634,11 +641,11 @@ void NodeDB::updatePosition(uint32_t nodeId, const Position &p, RxSource src)
/** Update telemetry info for this node based on received metrics
* We only care about device telemetry here
*/
void NodeDB::updateTelemetry(uint32_t nodeId, const Telemetry &t, RxSource src)
void NodeDB::updateTelemetry(uint32_t nodeId, const meshtastic_Telemetry &t, RxSource src)
{
NodeInfo *info = getOrCreateNode(nodeId);
meshtastic_NodeInfo *info = getOrCreateNode(nodeId);
// Environment metrics should never go to NodeDb but we'll safegaurd anyway
if (!info || t.which_variant != Telemetry_device_metrics_tag) {
if (!info || t.which_variant != meshtastic_Telemetry_device_metrics_tag) {
return;
}
@@ -656,9 +663,9 @@ void NodeDB::updateTelemetry(uint32_t nodeId, const Telemetry &t, RxSource src)
/** Update user info for this node based on received user data
*/
void NodeDB::updateUser(uint32_t nodeId, const User &p)
void NodeDB::updateUser(uint32_t nodeId, const meshtastic_User &p)
{
NodeInfo *info = getOrCreateNode(nodeId);
meshtastic_NodeInfo *info = getOrCreateNode(nodeId);
if (!info) {
return;
}
@@ -685,12 +692,12 @@ void NodeDB::updateUser(uint32_t nodeId, const User &p)
/// given a subpacket sniffed from the network, update our DB state
/// we updateGUI and updateGUIforNode if we think our this change is big enough for a redraw
void NodeDB::updateFrom(const MeshPacket &mp)
void NodeDB::updateFrom(const meshtastic_MeshPacket &mp)
{
if (mp.which_payload_variant == MeshPacket_decoded_tag && mp.from) {
if (mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp.from) {
LOG_DEBUG("Update DB node 0x%x, rx_time=%u\n", mp.from, mp.rx_time);
NodeInfo *info = getOrCreateNode(getFrom(&mp));
meshtastic_NodeInfo *info = getOrCreateNode(getFrom(&mp));
if (!info) {
return;
}
@@ -705,7 +712,7 @@ void NodeDB::updateFrom(const MeshPacket &mp)
/// Find a node in our DB, return null for missing
/// NOTE: This function might be called from an ISR
NodeInfo *NodeDB::getNode(NodeNum n)
meshtastic_NodeInfo *NodeDB::getNode(NodeNum n)
{
for (int i = 0; i < *numNodes; i++)
if (nodes[i].num == n)
@@ -715,9 +722,9 @@ NodeInfo *NodeDB::getNode(NodeNum n)
}
/// Find a node in our DB, create an empty NodeInfo if missing
NodeInfo *NodeDB::getOrCreateNode(NodeNum n)
meshtastic_NodeInfo *NodeDB::getOrCreateNode(NodeNum n)
{
NodeInfo *info = getNode(n);
meshtastic_NodeInfo *info = getNode(n);
if (!info) {
if (*numNodes >= MAX_NUM_NODES) {
@@ -749,7 +756,7 @@ NodeInfo *NodeDB::getOrCreateNode(NodeNum n)
}
/// Record an error that should be reported via analytics
void recordCriticalError(CriticalErrorCode code, uint32_t address, const char *filename)
void recordCriticalError(meshtastic_CriticalErrorCode code, uint32_t address, const char *filename)
{
// Print error to screen and serial port
String lcd = String("Critical error ") + code + "!\n";

View File

@@ -21,16 +21,16 @@ DeviceState versions used to be defined in the .proto file but really only this
#define DEVICESTATE_CUR_VER 20
#define DEVICESTATE_MIN_VER DEVICESTATE_CUR_VER
extern DeviceState devicestate;
extern ChannelFile channelFile;
extern MyNodeInfo &myNodeInfo;
extern LocalConfig config;
extern LocalModuleConfig moduleConfig;
extern OEMStore oemStore;
extern User &owner;
extern meshtastic_DeviceState devicestate;
extern meshtastic_ChannelFile channelFile;
extern meshtastic_MyNodeInfo &myNodeInfo;
extern meshtastic_LocalConfig config;
extern meshtastic_LocalModuleConfig moduleConfig;
extern meshtastic_OEMStore oemStore;
extern meshtastic_User &owner;
/// Given a node, return how many seconds in the past (vs now) that we last heard from it
uint32_t sinceLastSeen(const NodeInfo *n);
uint32_t sinceLastSeen(const meshtastic_NodeInfo *n);
class NodeDB
{
@@ -40,14 +40,14 @@ class NodeDB
// Eventually use a smarter datastructure
// HashMap<NodeNum, NodeInfo> nodes;
// Note: these two references just point into our static array we serialize to/from disk
NodeInfo *nodes;
meshtastic_NodeInfo *nodes;
pb_size_t *numNodes;
uint32_t readPointer = 0;
public:
bool updateGUI = false; // we think the gui should definitely be redrawn, screen will clear this once handled
NodeInfo *updateGUIforNode = NULL; // if currently showing this node, we think you should update the GUI
bool updateGUI = false; // we think the gui should definitely be redrawn, screen will clear this once handled
meshtastic_NodeInfo *updateGUIforNode = NULL; // if currently showing this node, we think you should update the GUI
Observable<const meshtastic::NodeStatus *> newStatus;
/// don't do mesh based algoritm for node id assignment (initially)
@@ -58,7 +58,8 @@ class NodeDB
void init();
/// write to flash
void saveToDisk(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS), saveChannelsToDisk(), saveDeviceStateToDisk();
void saveToDisk(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS),
saveChannelsToDisk(), saveDeviceStateToDisk();
/** Reinit radio config if needed, because either:
* a) sometimes a buggy android app might send us bogus settings or
@@ -70,19 +71,19 @@ class NodeDB
/// given a subpacket sniffed from the network, update our DB state
/// we updateGUI and updateGUIforNode if we think our this change is big enough for a redraw
void updateFrom(const MeshPacket &p);
void updateFrom(const meshtastic_MeshPacket &p);
/** Update position info for this node based on received position data
*/
void updatePosition(uint32_t nodeId, const Position &p, RxSource src = RX_SRC_RADIO);
void updatePosition(uint32_t nodeId, const meshtastic_Position &p, RxSource src = RX_SRC_RADIO);
/** Update telemetry info for this node based on received metrics
*/
void updateTelemetry(uint32_t nodeId, const Telemetry &t, RxSource src = RX_SRC_RADIO);
void updateTelemetry(uint32_t nodeId, const meshtastic_Telemetry &t, RxSource src = RX_SRC_RADIO);
/** Update user info for this node based on received user data
*/
void updateUser(uint32_t nodeId, const User &p);
void updateUser(uint32_t nodeId, const meshtastic_User &p);
/// @return our node number
NodeNum getNodeNum() { return myNodeInfo.my_node_num; }
@@ -104,15 +105,15 @@ class NodeDB
void resetReadPointer() { readPointer = 0; }
/// Allow the bluetooth layer to read our next nodeinfo record, or NULL if done reading
const NodeInfo *readNextInfo();
const meshtastic_NodeInfo *readNextInfo();
/// pick a provisional nodenum we hope no one is using
void pickNewNodeNum();
/// Find a node in our DB, return null for missing
NodeInfo *getNode(NodeNum n);
meshtastic_NodeInfo *getNode(NodeNum n);
NodeInfo *getNodeByIndex(size_t x)
meshtastic_NodeInfo *getNodeByIndex(size_t x)
{
assert(x < *numNodes);
return &nodes[x];
@@ -122,7 +123,7 @@ class NodeDB
size_t getNumOnlineNodes();
void initConfigIntervals(), initModuleConfigIntervals(), resetNodes();
bool factoryReset();
bool loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, void *dest_struct);
@@ -130,7 +131,7 @@ class NodeDB
private:
/// Find a node in our DB, create an empty NodeInfo if missing
NodeInfo *getOrCreateNode(NodeNum n);
meshtastic_NodeInfo *getOrCreateNode(NodeNum n);
/// Notify observers of changes to the DB
void notifyObservers(bool forceUpdate = false)
@@ -140,13 +141,11 @@ class NodeDB
newStatus.notifyObservers(&status);
}
/// read our db from flash
void loadFromDisk();
/// Reinit device state from scratch (not loading from disk)
void installDefaultDeviceState(), installDefaultChannels(), installDefaultConfig(),
installDefaultModuleConfig();
void installDefaultDeviceState(), installDefaultChannels(), installDefaultConfig(), installDefaultModuleConfig();
};
/**
@@ -183,7 +182,8 @@ extern NodeDB nodeDB;
// Our delay functions check for this for times that should never expire
#define NODE_DELAY_FOREVER 0xffffffff
#define IF_ROUTER(routerVal, normalVal) ((config.device.role == Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal))
#define IF_ROUTER(routerVal, normalVal) \
((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal))
#define ONE_DAY 24 * 60 * 60
@@ -203,13 +203,15 @@ extern NodeDB nodeDB;
inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval)
{
if (configuredInterval > 0) return configuredInterval * 1000;
if (configuredInterval > 0)
return configuredInterval * 1000;
return default_broadcast_interval_secs * 1000;
}
inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval)
{
if (configuredInterval > 0) return configuredInterval * 1000;
if (configuredInterval > 0)
return configuredInterval * 1000;
return defaultInterval * 1000;
}
@@ -218,4 +220,7 @@ inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t d
*/
extern uint32_t radioGeneration;
#define Module_Config_size (ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + ModuleConfig_TelemetryConfig_size + ModuleConfig_size)
#define Module_Config_size \
(ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + \
ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \
ModuleConfig_TelemetryConfig_size + ModuleConfig_size)

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "PacketHistory.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
PacketHistory::PacketHistory()
@@ -11,7 +11,7 @@ PacketHistory::PacketHistory()
/**
* Update recentBroadcasts and return true if we have already seen this packet
*/
bool PacketHistory::wasSeenRecently(const MeshPacket *p, bool withUpdate)
bool PacketHistory::wasSeenRecently(const meshtastic_MeshPacket *p, bool withUpdate)
{
if (p->id == 0) {
LOG_DEBUG("Ignoring message with zero id\n");
@@ -26,10 +26,10 @@ bool PacketHistory::wasSeenRecently(const MeshPacket *p, bool withUpdate)
r.rxTimeMsec = now;
auto found = recentPackets.find(r);
bool seenRecently = (found != recentPackets.end()); // found not equal to .end() means packet was seen recently
bool seenRecently = (found != recentPackets.end()); // found not equal to .end() means packet was seen recently
if (seenRecently && (now - found->rxTimeMsec) >= FLOOD_EXPIRE_TIME) { // Check whether found packet has already expired
recentPackets.erase(found); // Erase and pretend packet has not been seen recently
recentPackets.erase(found); // Erase and pretend packet has not been seen recently
found = recentPackets.end();
seenRecently = false;
}
@@ -58,12 +58,13 @@ bool PacketHistory::wasSeenRecently(const MeshPacket *p, bool withUpdate)
/**
* Iterate through all recent packets, and remove all older than FLOOD_EXPIRE_TIME
*/
void PacketHistory::clearExpiredRecentPackets() {
void PacketHistory::clearExpiredRecentPackets()
{
uint32_t now = millis();
LOG_DEBUG("recentPackets size=%ld\n", recentPackets.size());
for (auto it = recentPackets.begin(); it != recentPackets.end(); ) {
for (auto it = recentPackets.begin(); it != recentPackets.end();) {
if ((now - it->rxTimeMsec) >= FLOOD_EXPIRE_TIME) {
it = recentPackets.erase(it); // erase returns iterator pointing to element immediately following the one erased
} else {

View File

@@ -41,5 +41,5 @@ class PacketHistory
*
* @param withUpdate if true and not found we add an entry to recentPackets
*/
bool wasSeenRecently(const MeshPacket *p, bool withUpdate = true);
bool wasSeenRecently(const meshtastic_MeshPacket *p, bool withUpdate = true);
};

View File

@@ -80,20 +80,20 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength)
// return (lastContactMsec != 0) &&
memset(&toRadioScratch, 0, sizeof(toRadioScratch));
if (pb_decode_from_bytes(buf, bufLength, &ToRadio_msg, &toRadioScratch)) {
if (pb_decode_from_bytes(buf, bufLength, &meshtastic_ToRadio_msg, &toRadioScratch)) {
switch (toRadioScratch.which_payload_variant) {
case ToRadio_packet_tag:
case meshtastic_ToRadio_packet_tag:
return handleToRadioPacket(toRadioScratch.packet);
case ToRadio_want_config_id_tag:
case meshtastic_ToRadio_want_config_id_tag:
config_nonce = toRadioScratch.want_config_id;
LOG_INFO("Client wants config, nonce=%u\n", config_nonce);
handleStartConfig();
break;
case ToRadio_disconnect_tag:
case meshtastic_ToRadio_disconnect_tag:
LOG_INFO("Disconnecting from phone\n");
close();
break;
case ToRadio_xmodemPacket_tag:
case meshtastic_ToRadio_xmodemPacket_tag:
LOG_INFO("Got xmodem packet\n");
xModem.handlePacket(toRadioScratch.xmodemPacket);
break;
@@ -143,7 +143,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// If the user has specified they don't want our node to share its location, make sure to tell the phone
// app not to send locations on our behalf.
myNodeInfo.has_gps = gps && gps->isConnected(); // Update with latest GPS connect info
fromRadioScratch.which_payload_variant = FromRadio_my_info_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_my_info_tag;
fromRadioScratch.my_info = myNodeInfo;
state = STATE_SEND_NODEINFO;
@@ -152,13 +152,13 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
case STATE_SEND_NODEINFO: {
LOG_INFO("getFromRadio=STATE_SEND_NODEINFO\n");
const NodeInfo *info = nodeInfoForPhone;
const meshtastic_NodeInfo *info = nodeInfoForPhone;
nodeInfoForPhone = NULL; // We just consumed a nodeinfo, will need a new one next time
if (info) {
LOG_INFO("Sending nodeinfo: num=0x%x, lastseen=%u, id=%s, name=%s\n", info->num, info->last_heard, info->user.id,
info->user.long_name);
fromRadioScratch.which_payload_variant = FromRadio_node_info_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_node_info_tag;
fromRadioScratch.node_info = *info;
// Stay in current state until done sending nodeinfos
} else {
@@ -172,47 +172,47 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
case STATE_SEND_CHANNELS:
LOG_INFO("getFromRadio=STATE_SEND_CHANNELS\n");
fromRadioScratch.which_payload_variant = FromRadio_channel_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_channel_tag;
fromRadioScratch.channel = channels.getByIndex(config_state);
config_state++;
// Advance when we have sent all of our Channels
if (config_state >= MAX_NUM_CHANNELS) {
state = STATE_SEND_CONFIG;
config_state = _AdminMessage_ConfigType_MIN + 1;
config_state = _meshtastic_AdminMessage_ConfigType_MIN + 1;
}
break;
case STATE_SEND_CONFIG:
LOG_INFO("getFromRadio=STATE_SEND_CONFIG\n");
fromRadioScratch.which_payload_variant = FromRadio_config_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_tag;
switch (config_state) {
case Config_device_tag:
fromRadioScratch.config.which_payload_variant = Config_device_tag;
case meshtastic_Config_device_tag:
fromRadioScratch.config.which_payload_variant = meshtastic_Config_device_tag;
fromRadioScratch.config.payload_variant.device = config.device;
break;
case Config_position_tag:
fromRadioScratch.config.which_payload_variant = Config_position_tag;
case meshtastic_Config_position_tag:
fromRadioScratch.config.which_payload_variant = meshtastic_Config_position_tag;
fromRadioScratch.config.payload_variant.position = config.position;
break;
case Config_power_tag:
fromRadioScratch.config.which_payload_variant = Config_power_tag;
case meshtastic_Config_power_tag:
fromRadioScratch.config.which_payload_variant = meshtastic_Config_power_tag;
fromRadioScratch.config.payload_variant.power = config.power;
fromRadioScratch.config.payload_variant.power.ls_secs = default_ls_secs;
break;
case Config_network_tag:
fromRadioScratch.config.which_payload_variant = Config_network_tag;
case meshtastic_Config_network_tag:
fromRadioScratch.config.which_payload_variant = meshtastic_Config_network_tag;
fromRadioScratch.config.payload_variant.network = config.network;
break;
case Config_display_tag:
fromRadioScratch.config.which_payload_variant = Config_display_tag;
case meshtastic_Config_display_tag:
fromRadioScratch.config.which_payload_variant = meshtastic_Config_display_tag;
fromRadioScratch.config.payload_variant.display = config.display;
break;
case Config_lora_tag:
fromRadioScratch.config.which_payload_variant = Config_lora_tag;
case meshtastic_Config_lora_tag:
fromRadioScratch.config.which_payload_variant = meshtastic_Config_lora_tag;
fromRadioScratch.config.payload_variant.lora = config.lora;
break;
case Config_bluetooth_tag:
fromRadioScratch.config.which_payload_variant = Config_bluetooth_tag;
case meshtastic_Config_bluetooth_tag:
fromRadioScratch.config.which_payload_variant = meshtastic_Config_bluetooth_tag;
fromRadioScratch.config.payload_variant.bluetooth = config.bluetooth;
break;
default:
@@ -224,50 +224,50 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
config_state++;
// Advance when we have sent all of our config objects
if (config_state > (_AdminMessage_ConfigType_MAX + 1)) {
if (config_state > (_meshtastic_AdminMessage_ConfigType_MAX + 1)) {
state = STATE_SEND_MODULECONFIG;
config_state = _AdminMessage_ModuleConfigType_MIN + 1;
config_state = _meshtastic_AdminMessage_ModuleConfigType_MIN + 1;
}
break;
case STATE_SEND_MODULECONFIG:
LOG_INFO("getFromRadio=STATE_SEND_MODULECONFIG\n");
fromRadioScratch.which_payload_variant = FromRadio_moduleConfig_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_moduleConfig_tag;
switch (config_state) {
case ModuleConfig_mqtt_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_mqtt_tag;
case meshtastic_ModuleConfig_mqtt_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_mqtt_tag;
fromRadioScratch.moduleConfig.payload_variant.mqtt = moduleConfig.mqtt;
break;
case ModuleConfig_serial_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_serial_tag;
case meshtastic_ModuleConfig_serial_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_serial_tag;
fromRadioScratch.moduleConfig.payload_variant.serial = moduleConfig.serial;
break;
case ModuleConfig_external_notification_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_external_notification_tag;
case meshtastic_ModuleConfig_external_notification_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_external_notification_tag;
fromRadioScratch.moduleConfig.payload_variant.external_notification = moduleConfig.external_notification;
break;
case ModuleConfig_store_forward_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_store_forward_tag;
case meshtastic_ModuleConfig_store_forward_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_store_forward_tag;
fromRadioScratch.moduleConfig.payload_variant.store_forward = moduleConfig.store_forward;
break;
case ModuleConfig_range_test_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_range_test_tag;
case meshtastic_ModuleConfig_range_test_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_range_test_tag;
fromRadioScratch.moduleConfig.payload_variant.range_test = moduleConfig.range_test;
break;
case ModuleConfig_telemetry_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_telemetry_tag;
case meshtastic_ModuleConfig_telemetry_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_telemetry_tag;
fromRadioScratch.moduleConfig.payload_variant.telemetry = moduleConfig.telemetry;
break;
case ModuleConfig_canned_message_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_canned_message_tag;
case meshtastic_ModuleConfig_canned_message_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_canned_message_tag;
fromRadioScratch.moduleConfig.payload_variant.canned_message = moduleConfig.canned_message;
break;
case ModuleConfig_audio_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_audio_tag;
case meshtastic_ModuleConfig_audio_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_audio_tag;
fromRadioScratch.moduleConfig.payload_variant.audio = moduleConfig.audio;
break;
case ModuleConfig_remote_hardware_tag:
fromRadioScratch.moduleConfig.which_payload_variant = ModuleConfig_remote_hardware_tag;
case meshtastic_ModuleConfig_remote_hardware_tag:
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_remote_hardware_tag;
fromRadioScratch.moduleConfig.payload_variant.remote_hardware = moduleConfig.remote_hardware;
break;
default:
@@ -276,7 +276,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
config_state++;
// Advance when we have sent all of our ModuleConfig objects
if (config_state > (_AdminMessage_ModuleConfigType_MAX + 1)) {
if (config_state > (_meshtastic_AdminMessage_ModuleConfigType_MAX + 1)) {
state = STATE_SEND_COMPLETE_ID;
config_state = 0;
}
@@ -284,7 +284,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
case STATE_SEND_COMPLETE_ID:
LOG_INFO("getFromRadio=STATE_SEND_COMPLETE_ID\n");
fromRadioScratch.which_payload_variant = FromRadio_config_complete_id_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_complete_id_tag;
fromRadioScratch.config_complete_id = config_nonce;
config_nonce = 0;
state = STATE_SEND_PACKETS;
@@ -294,11 +294,11 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// Do we have a message from the mesh?
LOG_INFO("getFromRadio=STATE_SEND_PACKETS\n");
if (queueStatusPacketForPhone) {
fromRadioScratch.which_payload_variant = FromRadio_queueStatus_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_queueStatus_tag;
fromRadioScratch.queueStatus = *queueStatusPacketForPhone;
releaseQueueStatusPhonePacket();
} else if (xmodemPacketForPhone) {
fromRadioScratch.which_payload_variant = FromRadio_xmodemPacket_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_xmodemPacket_tag;
fromRadioScratch.xmodemPacket = *xmodemPacketForPhone;
free(xmodemPacketForPhone);
xmodemPacketForPhone = NULL;
@@ -306,7 +306,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
printPacket("phone downloaded packet", packetForPhone);
// Encapsulate as a FromRadio packet
fromRadioScratch.which_payload_variant = FromRadio_packet_tag;
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_packet_tag;
fromRadioScratch.packet = *packetForPhone;
releasePhonePacket();
}
@@ -319,7 +319,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// Do we have a message from the mesh?
if (fromRadioScratch.which_payload_variant != 0) {
// Encapsulate as a FromRadio packet
size_t numbytes = pb_encode_to_bytes(buf, FromRadio_size, &FromRadio_msg, &fromRadioScratch);
size_t numbytes = pb_encode_to_bytes(buf, meshtastic_FromRadio_size, &meshtastic_FromRadio_msg, &fromRadioScratch);
LOG_DEBUG("encoding toPhone packet to phone variant=%d, %d bytes\n", fromRadioScratch.which_payload_variant, numbytes);
return numbytes;
@@ -399,7 +399,7 @@ bool PhoneAPI::available()
/**
* Handle a packet that the phone wants us to send. It is our responsibility to free the packet to the pool
*/
bool PhoneAPI::handleToRadioPacket(MeshPacket &p)
bool PhoneAPI::handleToRadioPacket(meshtastic_MeshPacket &p)
{
printPacket("PACKET FROM PHONE", &p);
service.handleToRadio(p);

View File

@@ -41,18 +41,19 @@ class PhoneAPI
/// We temporarily keep the packet here between the call to available and getFromRadio. We will free it after the phone
/// downloads it
MeshPacket *packetForPhone = NULL;
meshtastic_MeshPacket *packetForPhone = NULL;
// file transfer packets destined for phone. Push it to the queue then free it.
XModem *xmodemPacketForPhone = NULL;
meshtastic_XModem *xmodemPacketForPhone = NULL;
// Keep QueueStatus packet just as packetForPhone
QueueStatus *queueStatusPacketForPhone = NULL;
meshtastic_QueueStatus *queueStatusPacketForPhone = NULL;
/// We temporarily keep the nodeInfo here between the call to available and getFromRadio
const NodeInfo *nodeInfoForPhone = NULL;
const meshtastic_NodeInfo *nodeInfoForPhone = NULL;
ToRadio toRadioScratch = {0}; // this is a static scratch object, any data must be copied elsewhere before returning
meshtastic_ToRadio toRadioScratch = {
0}; // this is a static scratch object, any data must be copied elsewhere before returning
/// Use to ensure that clients don't get confused about old messages from the radio
uint32_t config_nonce = 0;
@@ -92,7 +93,7 @@ class PhoneAPI
protected:
/// Our fromradio packet while it is being assembled
FromRadio fromRadioScratch = {};
meshtastic_FromRadio fromRadioScratch = {};
/** the last msec we heard from the client on the other side of this link */
uint32_t lastContactMsec = 0;
@@ -128,7 +129,7 @@ class PhoneAPI
* Handle a packet that the phone wants us to send. We can write to it but can not keep a reference to it
* @return true true if a packet was queued for sending
*/
bool handleToRadioPacket(MeshPacket &p);
bool handleToRadioPacket(meshtastic_MeshPacket &p);
/// If the mesh service tells us fromNum has changed, tell the phone
virtual int onNotify(uint32_t newValue) override;

View File

@@ -1,4 +1,2 @@
#include "configuration.h"
#include "ProtobufModule.h"
#include "configuration.h"

View File

@@ -16,31 +16,29 @@ template <class T> class ProtobufModule : protected SinglePortModule
/** Constructor
* name is for debugging output
*/
ProtobufModule(const char *_name, PortNum _ourPortNum, const pb_msgdesc_t *_fields)
ProtobufModule(const char *_name, meshtastic_PortNum _ourPortNum, const pb_msgdesc_t *_fields)
: SinglePortModule(_name, _ourPortNum), fields(_fields)
{
}
protected:
/**
* Handle a received message, the data field in the message is already decoded and is provided
*
* In general decoded will always be !NULL. But in some special applications (where you have handling packets
* for multiple port numbers, decoding will ONLY be attempted for packets where the portnum matches our expected ourPortNum.
*/
virtual bool handleReceivedProtobuf(const MeshPacket &mp, T *decoded) = 0;
virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, T *decoded) = 0;
/**
* Return a mesh packet which has been preinited with a particular protobuf data payload and port number.
* You can then send this packet (after customizing any of the payload fields you might need) with
* service.sendToMesh()
*/
MeshPacket *allocDataProtobuf(const T &payload)
meshtastic_MeshPacket *allocDataProtobuf(const T &payload)
{
// Update our local node info with our position (even if we don't decide to update anyone else)
MeshPacket *p = allocDataPacket();
meshtastic_MeshPacket *p = allocDataPacket();
p->decoded.payload.size =
pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), fields, &payload);
@@ -52,7 +50,7 @@ template <class T> class ProtobufModule : protected SinglePortModule
* Gets the short name from the sender of the mesh packet
* Returns "???" if unknown sender
*/
const char *getSenderShortName(const MeshPacket &mp)
const char *getSenderShortName(const meshtastic_MeshPacket &mp)
{
auto node = nodeDB.getNode(getFrom(&mp));
const char *sender = (node) ? node->user.short_name : "???";
@@ -62,20 +60,20 @@ template <class T> class ProtobufModule : protected SinglePortModule
private:
/** Called to handle a particular incoming message
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for it
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for
it
*/
virtual ProcessMessage handleReceived(const MeshPacket &mp) override
virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp) override
{
// FIXME - we currently update position data in the DB only if the message was a broadcast or destined to us
// it would be better to update even if the message was destined to others.
auto &p = mp.decoded;
LOG_INFO("Received %s from=0x%0x, id=0x%x, portnum=%d, payloadlen=%d\n", name, mp.from, mp.id, p.portnum,
p.payload.size);
LOG_INFO("Received %s from=0x%0x, id=0x%x, portnum=%d, payloadlen=%d\n", name, mp.from, mp.id, p.portnum, p.payload.size);
T scratch;
T *decoded = NULL;
if (mp.which_payload_variant == MeshPacket_decoded_tag && mp.decoded.portnum == ourPortNum) {
if (mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp.decoded.portnum == ourPortNum) {
memset(&scratch, 0, sizeof(scratch));
if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, fields, &scratch)) {
decoded = &scratch;

View File

@@ -1,7 +1,7 @@
#include "configuration.h"
#include "RF95Interface.h"
#include "MeshRadio.h" // kinda yucky, but we need to know which region we are in
#include "RadioLibRF95.h"
#include "configuration.h"
#include "error.h"
#define MAX_POWER 20
@@ -70,9 +70,9 @@ bool RF95Interface::init()
int res = lora->begin(getFreq(), bw, sf, cr, syncWord, power, currentLimit, preambleLength);
LOG_INFO("RF95 init result %d\n", res);
LOG_INFO("Frequency set to %f\n", getFreq());
LOG_INFO("Bandwidth set to %f\n", bw);
LOG_INFO("Power output set to %d\n", power);
LOG_INFO("Frequency set to %f\n", getFreq());
LOG_INFO("Bandwidth set to %f\n", bw);
LOG_INFO("Power output set to %d\n", power);
// current limit was removed from module' ctor
// override default value (60 mA)
@@ -104,15 +104,15 @@ bool RF95Interface::reconfigure()
// configure publicly accessible settings
int err = lora->setSpreadingFactor(sf);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_INVALID_RADIO_SETTING);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora->setBandwidth(bw);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_INVALID_RADIO_SETTING);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora->setCodingRate(cr);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_INVALID_RADIO_SETTING);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora->setSyncWord(syncWord);
assert(err == RADIOLIB_ERR_NONE);
@@ -125,14 +125,14 @@ bool RF95Interface::reconfigure()
err = lora->setFrequency(getFreq());
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_INVALID_RADIO_SETTING);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
if (power > MAX_POWER) // This chip has lower power limits than some
power = MAX_POWER;
err = lora->setOutputPower(power);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_INVALID_RADIO_SETTING);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
startReceive(); // restart receiving
@@ -142,11 +142,10 @@ bool RF95Interface::reconfigure()
/**
* Add SNR data to received messages
*/
void RF95Interface::addReceiveMetadata(MeshPacket *mp)
void RF95Interface::addReceiveMetadata(meshtastic_MeshPacket *mp)
{
mp->rx_snr = lora->getSNR();
mp->rx_rssi = lround(lora->getRSSI());
}
void RF95Interface::setStandby()
@@ -186,15 +185,15 @@ bool RF95Interface::isChannelActive()
// check if we can detect a LoRa preamble on the current channel
int16_t result;
setTransmitEnable(false);
setStandby(); // needed for smooth transition
setStandby(); // needed for smooth transition
result = lora->scanChannel();
if (result == RADIOLIB_PREAMBLE_DETECTED) {
// LOG_DEBUG("Channel is busy!\n");
return true;
}
assert(result != RADIOLIB_ERR_WRONG_MODEM);
// LOG_DEBUG("Channel is free!\n");
return false;
}

View File

@@ -13,8 +13,8 @@ class RF95Interface : public RadioLibInterface
public:
RF95Interface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, SPIClass &spi);
//TODO: Verify that this irq flag works with RFM95 / SX1276 radios the way it used to
// TODO: Verify that this irq flag works with RFM95 / SX1276 radios the way it used to
bool isIRQPending() override { return lora->getIRQFlags() & RADIOLIB_SX127X_MASK_IRQ_FLAG_VALID_HEADER; }
/// Initialise the Driver transport hardware and software.
@@ -55,7 +55,7 @@ class RF95Interface : public RadioLibInterface
/**
* Add SNR data to received messages
*/
virtual void addReceiveMetadata(MeshPacket *mp) override;
virtual void addReceiveMetadata(meshtastic_MeshPacket *mp) override;
virtual void setStandby() override;

View File

@@ -11,10 +11,10 @@
#include <pb_decode.h>
#include <pb_encode.h>
#define RDEF(name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, frequency_switching, wide_lora) \
#define RDEF(name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, frequency_switching, wide_lora) \
{ \
Config_LoRaConfig_RegionCode_##name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, \
frequency_switching, wide_lora, #name \
meshtastic_Config_LoRaConfig_RegionCode_##name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, \
frequency_switching, wide_lora, #name \
}
const RegionInfo regions[] = {
@@ -38,9 +38,9 @@ const RegionInfo regions[] = {
Special Note:
The link above describes LoRaWAN's band plan, stating a power limit of 16 dBm. This is their own suggested specification,
we do not need to follow it. The European Union regulations clearly state that the power limit for this frequency range is 500 mW, or 27 dBm.
It also states that we can use interference avoidance and spectrum access techniques to avoid a duty cycle.
(Please refer to section 4.21 in the following document)
we do not need to follow it. The European Union regulations clearly state that the power limit for this frequency range is
500 mW, or 27 dBm. It also states that we can use interference avoidance and spectrum access techniques to avoid a duty
cycle. (Please refer to section 4.21 in the following document)
https://ec.europa.eu/growth/tools-databases/tris/index.cfm/ro/search/?trisaction=search.detail&year=2021&num=528&dLang=EN
*/
RDEF(EU_868, 869.4f, 869.65f, 10, 0, 27, false, false, false),
@@ -94,7 +94,7 @@ const RegionInfo regions[] = {
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
*/
RDEF(TH, 920.0f, 925.0f, 100, 0, 16, true, false, false),
/*
433,05-434,7 Mhz 10 mW
https://nkrzi.gov.ua/images/upload/256/5810/PDF_UUZ_19_01_2016.pdf
@@ -127,7 +127,7 @@ static uint8_t bytes[MAX_RHPACKETLEN];
void initRegion()
{
const RegionInfo *r = regions;
for (; r->code != Config_LoRaConfig_RegionCode_UNSET && r->code != config.lora.region; r++)
for (; r->code != meshtastic_Config_LoRaConfig_RegionCode_UNSET && r->code != config.lora.region; r++)
;
myRegion = r;
LOG_INFO("Wanted region %d, using %s\n", config.lora.region, r->name);
@@ -175,29 +175,29 @@ uint32_t RadioInterface::getPacketTime(uint32_t pl)
return msecs;
}
uint32_t RadioInterface::getPacketTime(MeshPacket *p)
uint32_t RadioInterface::getPacketTime(meshtastic_MeshPacket *p)
{
uint32_t pl = 0;
if(p->which_payload_variant == MeshPacket_encrypted_tag) {
if (p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag) {
pl = p->encrypted.size + sizeof(PacketHeader);
} else {
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &Data_msg, &p->decoded);
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_Data_msg, &p->decoded);
pl = numbytes + sizeof(PacketHeader);
}
return getPacketTime(pl);
}
/** The delay to use for retransmitting dropped packets */
uint32_t RadioInterface::getRetransmissionMsec(const MeshPacket *p)
uint32_t RadioInterface::getRetransmissionMsec(const meshtastic_MeshPacket *p)
{
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &Data_msg, &p->decoded);
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_Data_msg, &p->decoded);
uint32_t packetAirtime = getPacketTime(numbytes + sizeof(PacketHeader));
// Make sure enough time has elapsed for this packet to be sent and an ACK is received.
// LOG_DEBUG("Waiting for flooding message with airtime %d and slotTime is %d\n", packetAirtime, slotTimeMsec);
float channelUtil = airTime->channelUtilizationPercent();
uint8_t CWsize = map(channelUtil, 0, 100, CWmin, CWmax);
// Assuming we pick max. of CWsize and there will be a receiver with SNR at half the range
return 2*packetAirtime + (pow(2, CWsize) + pow(2, int((CWmax+CWmin)/2))) * slotTimeMsec + PROCESSING_TIME_MSEC;
return 2 * packetAirtime + (pow(2, CWsize) + pow(2, int((CWmax + CWmin) / 2))) * slotTimeMsec + PROCESSING_TIME_MSEC;
}
/** The delay to use when we want to send something */
@@ -226,9 +226,9 @@ uint32_t RadioInterface::getTxDelayMsecWeighted(float snr)
uint32_t delay = 0;
uint8_t CWsize = map(snr, SNR_MIN, SNR_MAX, CWmin, CWmax);
// LOG_DEBUG("rx_snr of %f so setting CWsize to:%d\n", snr, CWsize);
if (config.device.role == Config_DeviceConfig_Role_ROUTER ||
config.device.role == Config_DeviceConfig_Role_ROUTER_CLIENT) {
delay = random(0, 2*CWsize) * slotTimeMsec;
if (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER ||
config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER_CLIENT) {
delay = random(0, 2 * CWsize) * slotTimeMsec;
LOG_DEBUG("rx_snr found in packet. As a router, setting tx delay:%d\n", delay);
} else {
delay = random(0, pow(2, CWsize)) * slotTimeMsec;
@@ -238,11 +238,11 @@ uint32_t RadioInterface::getTxDelayMsecWeighted(float snr)
return delay;
}
void printPacket(const char *prefix, const MeshPacket *p)
void printPacket(const char *prefix, const meshtastic_MeshPacket *p)
{
LOG_DEBUG("%s (id=0x%08x fr=0x%02x to=0x%02x, WantAck=%d, HopLim=%d Ch=0x%x", prefix, p->id, p->from & 0xff, p->to & 0xff,
p->want_ack, p->hop_limit, p->channel);
if (p->which_payload_variant == MeshPacket_decoded_tag) {
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
auto &s = p->decoded;
LOG_DEBUG(" Portnum=%d", s.portnum);
@@ -372,26 +372,26 @@ void RadioInterface::applyModemConfig()
{
// Set up default configuration
// No Sync Words in LORA mode
Config_LoRaConfig &loraConfig = config.lora;
meshtastic_Config_LoRaConfig &loraConfig = config.lora;
if (loraConfig.use_preset) {
switch (loraConfig.modem_preset) {
case Config_LoRaConfig_ModemPreset_SHORT_FAST:
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST:
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 8;
sf = 7;
break;
case Config_LoRaConfig_ModemPreset_SHORT_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_SLOW:
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 8;
sf = 8;
break;
case Config_LoRaConfig_ModemPreset_MEDIUM_FAST:
case meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_FAST:
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 8;
sf = 9;
break;
case Config_LoRaConfig_ModemPreset_MEDIUM_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_SLOW:
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 8;
sf = 10;
@@ -401,12 +401,12 @@ void RadioInterface::applyModemConfig()
cr = 8;
sf = 11;
break;
case Config_LoRaConfig_ModemPreset_LONG_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_LONG_SLOW:
bw = (myRegion->wideLora) ? 406.25 : 125;
cr = 8;
sf = 12;
break;
case Config_LoRaConfig_ModemPreset_VERY_LONG_SLOW:
case meshtastic_Config_LoRaConfig_ModemPreset_VERY_LONG_SLOW:
bw = (myRegion->wideLora) ? 203.125 : 31.25;
cr = 8;
sf = 12;
@@ -453,14 +453,16 @@ void RadioInterface::applyModemConfig()
// float freq = myRegion->freqStart + ((((myRegion->freqEnd - myRegion->freqStart) / numChannels) / 2) * channel_num);
// New frequency selection formula
float freq = myRegion->freqStart + (bw / 2000) + ( channel_num * (bw / 1000));
float freq = myRegion->freqStart + (bw / 2000) + (channel_num * (bw / 1000));
saveChannelNum(channel_num);
saveFreq(freq + config.lora.frequency_offset);
LOG_INFO("Radio freq=%.3f, config.lora.frequency_offset=%.3f\n", freq, config.lora.frequency_offset);
LOG_INFO("Set radio: region=%s, name=%s, config=%u, ch=%d, power=%d\n", myRegion->name, channelName, loraConfig.modem_preset, channel_num, power);
LOG_INFO("Radio myRegion->freqStart -> myRegion->freqEnd: %f -> %f (%f mhz)\n", myRegion->freqStart, myRegion->freqEnd, myRegion->freqEnd - myRegion->freqStart);
LOG_INFO("Set radio: region=%s, name=%s, config=%u, ch=%d, power=%d\n", myRegion->name, channelName, loraConfig.modem_preset,
channel_num, power);
LOG_INFO("Radio myRegion->freqStart -> myRegion->freqEnd: %f -> %f (%f mhz)\n", myRegion->freqStart, myRegion->freqEnd,
myRegion->freqEnd - myRegion->freqStart);
LOG_INFO("Radio myRegion->numChannels: %d x %.3fkHz\n", numChannels, bw);
LOG_INFO("Radio channel_num: %d\n", channel_num);
LOG_INFO("Radio frequency: %f\n", getFreq());
@@ -486,8 +488,7 @@ void RadioInterface::limitPower()
LOG_INFO("Set radio: final power level=%d\n", power);
}
void RadioInterface::deliverToReceiver(MeshPacket *p)
void RadioInterface::deliverToReceiver(meshtastic_MeshPacket *p)
{
if (router)
router->enqueueReceivedMessage(p);
@@ -496,12 +497,12 @@ void RadioInterface::deliverToReceiver(MeshPacket *p)
/***
* given a packet set sendingPacket and decode the protobufs into radiobuf. Returns # of payload bytes to send
*/
size_t RadioInterface::beginSending(MeshPacket *p)
size_t RadioInterface::beginSending(meshtastic_MeshPacket *p)
{
assert(!sendingPacket);
// LOG_DEBUG("sending queued packet on mesh (txGood=%d,rxGood=%d,rxBad=%d)\n", rf95.txGood(), rf95.rxGood(), rf95.rxBad());
assert(p->which_payload_variant == MeshPacket_encrypted_tag); // It should have already been encoded by now
assert(p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag); // It should have already been encoded by now
lastTxStart = millis();

View File

@@ -51,25 +51,25 @@ class RadioInterface
CallbackObserver<RadioInterface, void *> notifyDeepSleepObserver =
CallbackObserver<RadioInterface, void *>(this, &RadioInterface::notifyDeepSleepCb);
protected:
bool disabled = false;
float bw = 125;
uint8_t sf = 9;
uint8_t cr = 7;
/** Slottime is the minimum time to wait, consisting of:
- CAD duration (maximum of SX126x and SX127x);
- roundtrip air propagation time (assuming max. 30km between nodes);
/** Slottime is the minimum time to wait, consisting of:
- CAD duration (maximum of SX126x and SX127x);
- roundtrip air propagation time (assuming max. 30km between nodes);
- Tx/Rx turnaround time (maximum of SX126x and SX127x);
- MAC processing time (measured on T-beam) */
uint32_t slotTimeMsec = 8.5 * pow(2, sf)/bw + 0.2 + 0.4 + 7;
uint32_t slotTimeMsec = 8.5 * pow(2, sf) / bw + 0.2 + 0.4 + 7;
uint16_t preambleLength = 32; // 8 is default, but we use longer to increase the amount of sleep time when receiving
const uint32_t PROCESSING_TIME_MSEC = 4500; // time to construct, process and construct a packet again (empirically determined)
const uint8_t CWmin = 2; // minimum CWsize
const uint8_t CWmax = 8; // maximum CWsize
const uint32_t PROCESSING_TIME_MSEC =
4500; // time to construct, process and construct a packet again (empirically determined)
const uint8_t CWmin = 2; // minimum CWsize
const uint8_t CWmax = 8; // maximum CWsize
MeshPacket *sendingPacket = NULL; // The packet we are currently sending
meshtastic_MeshPacket *sendingPacket = NULL; // The packet we are currently sending
uint32_t lastTxStart = 0L;
/**
@@ -80,7 +80,7 @@ class RadioInterface
/**
* Enqueue a received packet for the registered receiver
*/
void deliverToReceiver(MeshPacket *p);
void deliverToReceiver(meshtastic_MeshPacket *p);
public:
/** pool is the pool we will alloc our rx packets from
@@ -113,11 +113,12 @@ class RadioInterface
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*/
virtual ErrorCode send(MeshPacket *p) = 0;
virtual ErrorCode send(meshtastic_MeshPacket *p) = 0;
/** Return TX queue status */
virtual QueueStatus getQueueStatus() {
QueueStatus qs;
virtual meshtastic_QueueStatus getQueueStatus()
{
meshtastic_QueueStatus qs;
qs.res = qs.mesh_packet_id = qs.free = qs.maxlen = 0;
return qs;
}
@@ -138,7 +139,7 @@ class RadioInterface
virtual bool reconfigure();
/** The delay to use for retransmitting dropped packets */
uint32_t getRetransmissionMsec(const MeshPacket *p);
uint32_t getRetransmissionMsec(const meshtastic_MeshPacket *p);
/** The delay to use when we want to send something */
uint32_t getTxDelayMsec();
@@ -146,7 +147,6 @@ class RadioInterface
/** The delay to use when we want to flood a message. Use a weighted scale based on SNR */
uint32_t getTxDelayMsecWeighted(float snr);
/**
* Calculate airtime per
* https://www.rs-online.com/designspark/rel-assets/ds-assets/uploads/knowledge-items/application-notes-for-the-internet-of-things/LoRa%20Design%20Guide.pdf
@@ -154,7 +154,7 @@ class RadioInterface
*
* @return num msecs for the packet
*/
uint32_t getPacketTime(MeshPacket *p);
uint32_t getPacketTime(meshtastic_MeshPacket *p);
uint32_t getPacketTime(uint32_t totalPacketLen);
/**
@@ -182,7 +182,7 @@ class RadioInterface
*
* Used as the first step of
*/
size_t beginSending(MeshPacket *p);
size_t beginSending(meshtastic_MeshPacket *p);
/**
* Some regulatory regions limit xmit power.
@@ -220,6 +220,5 @@ class RadioInterface
}
};
/// Debug printing for packets
void printPacket(const char *prefix, const MeshPacket *p);
void printPacket(const char *prefix, const meshtastic_MeshPacket *p);

View File

@@ -3,8 +3,8 @@
#include "NodeDB.h"
#include "SPILock.h"
#include "configuration.h"
#include "main.h"
#include "error.h"
#include "main.h"
#include "mesh-pb-constants.h"
#include <pb_decode.h>
#include <pb_encode.h>
@@ -87,7 +87,7 @@ bool RadioLibInterface::canSendImmediately()
// TX IRQ from the radio, the radio is probably broken.
if (busyTx && (millis() - lastTxStart > 60000)) {
LOG_ERROR("Hardware Failure! busyTx for more than 60s\n");
RECORD_CRITICALERROR(CriticalErrorCode_TRANSMIT_FAILED);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_TRANSMIT_FAILED);
// reboot in 5 seconds when this condition occurs.
rebootAtMsec = lastTxStart + 65000;
}
@@ -101,15 +101,15 @@ bool RadioLibInterface::canSendImmediately()
/// Send a packet (possibly by enquing in a private fifo). This routine will
/// later free() the packet to pool. This routine is not allowed to stall because it is called from
/// bluetooth comms code. If the txmit queue is empty it might return an error
ErrorCode RadioLibInterface::send(MeshPacket *p)
ErrorCode RadioLibInterface::send(meshtastic_MeshPacket *p)
{
#ifndef DISABLE_WELCOME_UNSET
if (config.lora.region != Config_LoRaConfig_RegionCode_UNSET) {
if (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_UNSET) {
if (disabled || !config.lora.tx_enabled) {
if (config.lora.region != Config_LoRaConfig_RegionCode_UNSET) {
if (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_UNSET) {
if (disabled || !config.lora.tx_enabled) {
LOG_WARN("send - !config.lora.tx_enabled\n");
packetPool.release(p);
@@ -134,33 +134,33 @@ ErrorCode RadioLibInterface::send(MeshPacket *p)
#endif
// Sometimes when testing it is useful to be able to never turn on the xmitter
// Sometimes when testing it is useful to be able to never turn on the xmitter
#ifndef LORA_DISABLE_SENDING
printPacket("enqueuing for send", p);
printPacket("enqueuing for send", p);
LOG_DEBUG("txGood=%d,rxGood=%d,rxBad=%d\n", txGood, rxGood, rxBad);
ErrorCode res = txQueue.enqueue(p) ? ERRNO_OK : ERRNO_UNKNOWN;
if (res != ERRNO_OK) { // we weren't able to queue it, so we must drop it to prevent leaks
packetPool.release(p);
return res;
}
// set (random) transmit delay to let others reconfigure their radio,
// to avoid collisions and implement timing-based flooding
// LOG_DEBUG("Set random delay before transmitting.\n");
setTransmitDelay();
LOG_DEBUG("txGood=%d,rxGood=%d,rxBad=%d\n", txGood, rxGood, rxBad);
ErrorCode res = txQueue.enqueue(p) ? ERRNO_OK : ERRNO_UNKNOWN;
if (res != ERRNO_OK) { // we weren't able to queue it, so we must drop it to prevent leaks
packetPool.release(p);
return res;
}
// set (random) transmit delay to let others reconfigure their radio,
// to avoid collisions and implement timing-based flooding
// LOG_DEBUG("Set random delay before transmitting.\n");
setTransmitDelay();
return res;
#else
packetPool.release(p);
return ERRNO_DISABLED;
#endif
}
}
QueueStatus RadioLibInterface::getQueueStatus()
meshtastic_QueueStatus RadioLibInterface::getQueueStatus()
{
QueueStatus qs;
meshtastic_QueueStatus qs;
qs.res = qs.mesh_packet_id = 0;
qs.free = txQueue.getFree();
@@ -169,246 +169,248 @@ QueueStatus RadioLibInterface::getQueueStatus()
return qs;
}
bool RadioLibInterface::canSleep()
{
bool res = txQueue.empty();
if (!res) // only print debug messages if we are vetoing sleep
LOG_DEBUG("radio wait to sleep, txEmpty=%d\n", res);
bool RadioLibInterface::canSleep()
{
bool res = txQueue.empty();
if (!res) // only print debug messages if we are vetoing sleep
LOG_DEBUG("radio wait to sleep, txEmpty=%d\n", res);
return res;
}
return res;
}
/** Attempt to cancel a previously sent packet. Returns true if a packet was found we could cancel */
bool RadioLibInterface::cancelSending(NodeNum from, PacketId id)
{
auto p = txQueue.remove(from, id);
if (p)
packetPool.release(p); // free the packet we just removed
/** Attempt to cancel a previously sent packet. Returns true if a packet was found we could cancel */
bool RadioLibInterface::cancelSending(NodeNum from, PacketId id)
{
auto p = txQueue.remove(from, id);
if (p)
packetPool.release(p); // free the packet we just removed
bool result = (p != NULL);
LOG_DEBUG("cancelSending id=0x%x, removed=%d\n", id, result);
return result;
}
bool result = (p != NULL);
LOG_DEBUG("cancelSending id=0x%x, removed=%d\n", id, result);
return result;
}
/** radio helper thread callback.
We never immediately transmit after any operation (either Rx or Tx). Instead we should wait a random multiple of
'slotTimes' (see definition in RadioInterface.h) taken from a contention window (CW) to lower the chance of collision.
The CW size is determined by setTransmitDelay() and depends either on the current channel utilization or SNR in case
of a flooding message. After this, we perform channel activity detection (CAD) and reset the transmit delay if it is
currently active.
*/
void RadioLibInterface::onNotify(uint32_t notification)
{
switch (notification) {
case ISR_TX:
handleTransmitInterrupt();
startReceive();
// LOG_DEBUG("tx complete - starting timer\n");
startTransmitTimer();
break;
case ISR_RX:
handleReceiveInterrupt();
startReceive();
// LOG_DEBUG("rx complete - starting timer\n");
startTransmitTimer();
break;
case TRANSMIT_DELAY_COMPLETED:
// LOG_DEBUG("delay done\n");
/** radio helper thread callback.
We never immediately transmit after any operation (either Rx or Tx). Instead we should wait a random multiple of
'slotTimes' (see definition in RadioInterface.h) taken from a contention window (CW) to lower the chance of collision.
The CW size is determined by setTransmitDelay() and depends either on the current channel utilization or SNR in case
of a flooding message. After this, we perform channel activity detection (CAD) and reset the transmit delay if it is
currently active.
*/
void RadioLibInterface::onNotify(uint32_t notification)
{
switch (notification) {
case ISR_TX:
handleTransmitInterrupt();
startReceive();
// LOG_DEBUG("tx complete - starting timer\n");
startTransmitTimer();
break;
case ISR_RX:
handleReceiveInterrupt();
startReceive();
// LOG_DEBUG("rx complete - starting timer\n");
startTransmitTimer();
break;
case TRANSMIT_DELAY_COMPLETED:
// LOG_DEBUG("delay done\n");
// If we are not currently in receive mode, then restart the random delay (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?
if (!txQueue.empty()) {
if (!canSendImmediately()) {
// LOG_DEBUG("Currently Rx/Tx-ing: set random delay\n");
setTransmitDelay(); // currently Rx/Tx-ing: reset random delay
// If we are not currently in receive mode, then restart the random delay (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?
if (!txQueue.empty()) {
if (!canSendImmediately()) {
// LOG_DEBUG("Currently Rx/Tx-ing: set random delay\n");
setTransmitDelay(); // currently Rx/Tx-ing: reset random delay
} else {
if (isChannelActive()) { // check if there is currently a LoRa packet on the channel
// LOG_DEBUG("Channel is active: set random delay\n");
setTransmitDelay(); // reset random delay
} else {
if (isChannelActive()) { // check if there is currently a LoRa packet on the channel
// LOG_DEBUG("Channel is active: set random delay\n");
setTransmitDelay(); // reset random delay
} else {
// Send any outgoing packets we have ready
MeshPacket *txp = txQueue.dequeue();
assert(txp);
startSend(txp);
// Send any outgoing packets we have ready
meshtastic_MeshPacket *txp = txQueue.dequeue();
assert(txp);
startSend(txp);
// Packet has been sent, count it toward our TX airtime utilization.
uint32_t xmitMsec = getPacketTime(txp);
airTime->logAirtime(TX_LOG, xmitMsec);
}
// Packet has been sent, count it toward our TX airtime utilization.
uint32_t xmitMsec = getPacketTime(txp);
airTime->logAirtime(TX_LOG, xmitMsec);
}
} else {
// LOG_DEBUG("done with txqueue\n");
}
break;
default:
assert(0); // We expected to receive a valid notification from the ISR
}
}
void RadioLibInterface::setTransmitDelay()
{
MeshPacket *p = txQueue.getFront();
// We want all sending/receiving to be done by our daemon thread.
// We use a delay here because this packet might have been sent in response to a packet we just received.
// So we want to make sure the other side has had a chance to reconfigure its radio.
/* We assume if rx_snr = 0 and rx_rssi = 0, the packet was generated locally.
* This assumption is valid because of the offset generated by the radio to account for the noise
* floor.
*/
if (p->rx_snr == 0 && p->rx_rssi == 0) {
startTransmitTimer(true);
} else {
// If there is a SNR, start a timer scaled based on that SNR.
LOG_DEBUG("rx_snr found. hop_limit:%d rx_snr:%f\n", p->hop_limit, p->rx_snr);
startTransmitTimerSNR(p->rx_snr);
// LOG_DEBUG("done with txqueue\n");
}
break;
default:
assert(0); // We expected to receive a valid notification from the ISR
}
}
void RadioLibInterface::setTransmitDelay()
{
meshtastic_MeshPacket *p = txQueue.getFront();
// We want all sending/receiving to be done by our daemon thread.
// We use a delay here because this packet might have been sent in response to a packet we just received.
// So we want to make sure the other side has had a chance to reconfigure its radio.
/* We assume if rx_snr = 0 and rx_rssi = 0, the packet was generated locally.
* This assumption is valid because of the offset generated by the radio to account for the noise
* floor.
*/
if (p->rx_snr == 0 && p->rx_rssi == 0) {
startTransmitTimer(true);
} else {
// If there is a SNR, start a timer scaled based on that SNR.
LOG_DEBUG("rx_snr found. hop_limit:%d rx_snr:%f\n", p->hop_limit, p->rx_snr);
startTransmitTimerSNR(p->rx_snr);
}
}
void RadioLibInterface::startTransmitTimer(bool withDelay)
{
// If we have work to do and the timer wasn't already scheduled, schedule it now
if (!txQueue.empty()) {
uint32_t delay = !withDelay ? 1 : getTxDelayMsec();
// LOG_DEBUG("xmit timer %d\n", delay);
notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
}
}
void RadioLibInterface::startTransmitTimerSNR(float snr)
{
// If we have work to do and the timer wasn't already scheduled, schedule it now
if (!txQueue.empty()) {
uint32_t delay = getTxDelayMsecWeighted(snr);
// LOG_DEBUG("xmit timer %d\n", delay);
notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
}
}
void RadioLibInterface::handleTransmitInterrupt()
{
// LOG_DEBUG("handling lora TX interrupt\n");
// This can be null if we forced the device to enter standby mode. In that case
// ignore the transmit interrupt
if (sendingPacket)
completeSending();
}
void RadioLibInterface::completeSending()
{
// We are careful to clear sending packet before calling printPacket because
// that can take a long time
auto p = sendingPacket;
sendingPacket = NULL;
if (p) {
txGood++;
printPacket("Completed sending", p);
// We are done sending that packet, release it
packetPool.release(p);
// LOG_DEBUG("Done with send\n");
}
}
void RadioLibInterface::handleReceiveInterrupt()
{
uint32_t xmitMsec;
// when this is called, we should be in receive mode - if we are not, just jump out instead of bombing. Possible Race
// Condition?
if (!isReceiving) {
LOG_DEBUG("*** WAS_ASSERT *** handleReceiveInterrupt called when not in receive mode\n");
return;
}
void RadioLibInterface::startTransmitTimer(bool withDelay)
{
// If we have work to do and the timer wasn't already scheduled, schedule it now
if (!txQueue.empty()) {
uint32_t delay = !withDelay ? 1 : getTxDelayMsec();
// LOG_DEBUG("xmit timer %d\n", delay);
notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
}
}
isReceiving = false;
void RadioLibInterface::startTransmitTimerSNR(float snr)
{
// If we have work to do and the timer wasn't already scheduled, schedule it now
if (!txQueue.empty()) {
uint32_t delay = getTxDelayMsecWeighted(snr);
// LOG_DEBUG("xmit timer %d\n", delay);
notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
}
}
// read the number of actually received bytes
size_t length = iface->getPacketLength();
void RadioLibInterface::handleTransmitInterrupt()
{
// LOG_DEBUG("handling lora TX interrupt\n");
// This can be null if we forced the device to enter standby mode. In that case
// ignore the transmit interrupt
if (sendingPacket)
completeSending();
}
xmitMsec = getPacketTime(length);
void RadioLibInterface::completeSending()
{
// We are careful to clear sending packet before calling printPacket because
// that can take a long time
auto p = sendingPacket;
sendingPacket = NULL;
int state = iface->readData(radiobuf, length);
if (state != RADIOLIB_ERR_NONE) {
LOG_ERROR("ignoring received packet due to error=%d\n", state);
rxBad++;
if (p) {
txGood++;
printPacket("Completed sending", p);
airTime->logAirtime(RX_ALL_LOG, xmitMsec);
// We are done sending that packet, release it
packetPool.release(p);
// LOG_DEBUG("Done with send\n");
}
}
} else {
// Skip the 4 headers that are at the beginning of the rxBuf
int32_t payloadLen = length - sizeof(PacketHeader);
const uint8_t *payload = radiobuf + sizeof(PacketHeader);
void RadioLibInterface::handleReceiveInterrupt()
{
uint32_t xmitMsec;
// when this is called, we should be in receive mode - if we are not, just jump out instead of bombing. Possible Race Condition?
if (!isReceiving) {
LOG_DEBUG("*** WAS_ASSERT *** handleReceiveInterrupt called when not in receive mode\n");
return;
}
isReceiving = false;
// read the number of actually received bytes
size_t length = iface->getPacketLength();
xmitMsec = getPacketTime(length);
int state = iface->readData(radiobuf, length);
if (state != RADIOLIB_ERR_NONE) {
LOG_ERROR("ignoring received packet due to error=%d\n", state);
// check for short packets
if (payloadLen < 0) {
LOG_WARN("ignoring received packet too short\n");
rxBad++;
airTime->logAirtime(RX_ALL_LOG, xmitMsec);
} else {
// Skip the 4 headers that are at the beginning of the rxBuf
int32_t payloadLen = length - sizeof(PacketHeader);
const uint8_t *payload = radiobuf + sizeof(PacketHeader);
// check for short packets
if (payloadLen < 0) {
LOG_WARN("ignoring received packet too short\n");
rxBad++;
airTime->logAirtime(RX_ALL_LOG, xmitMsec);
} else {
const PacketHeader *h = (PacketHeader *)radiobuf;
rxGood++;
// altered packet with "from == 0" can do Remote Node Administration without permission
if (h->from == 0) {
LOG_WARN("ignoring received packet without sender\n");
return;
}
// Note: we deliver _all_ packets to our router (i.e. our interface is intentionally promiscuous).
// This allows the router and other apps on our node to sniff packets (usually routing) between other
// nodes.
MeshPacket *mp = packetPool.allocZeroed();
mp->from = h->from;
mp->to = h->to;
mp->id = h->id;
mp->channel = h->channel;
assert(HOP_MAX <= PACKET_FLAGS_HOP_MASK); // If hopmax changes, carefully check this code
mp->hop_limit = h->flags & PACKET_FLAGS_HOP_MASK;
mp->want_ack = !!(h->flags & PACKET_FLAGS_WANT_ACK_MASK);
addReceiveMetadata(mp);
mp->which_payload_variant = MeshPacket_encrypted_tag; // Mark that the payload is still encrypted at this point
assert(((uint32_t)payloadLen) <= sizeof(mp->encrypted.bytes));
memcpy(mp->encrypted.bytes, payload, payloadLen);
mp->encrypted.size = payloadLen;
printPacket("Lora RX", mp);
airTime->logAirtime(RX_LOG, xmitMsec);
deliverToReceiver(mp);
}
}
}
/** start an immediate transmit */
void RadioLibInterface::startSend(MeshPacket * txp)
{
printPacket("Starting low level send", txp);
if (disabled || !config.lora.tx_enabled) {
LOG_WARN("startSend is dropping tx packet because we are disabled\n");
packetPool.release(txp);
} else {
setStandby(); // Cancel any already in process receives
configHardwareForSend(); // must be after setStandby
size_t numbytes = beginSending(txp);
int res = iface->startTransmit(radiobuf, numbytes);
if (res != RADIOLIB_ERR_NONE) {
LOG_ERROR("startTransmit failed, error=%d\n", res);
RECORD_CRITICALERROR(CriticalErrorCode_RADIO_SPI_BUG);
// This send failed, but make sure to 'complete' it properly
completeSending();
startReceive(); // Restart receive mode (because startTransmit failed to put us in xmit mode)
const PacketHeader *h = (PacketHeader *)radiobuf;
rxGood++;
// altered packet with "from == 0" can do Remote Node Administration without permission
if (h->from == 0) {
LOG_WARN("ignoring received packet without sender\n");
return;
}
// Must be done AFTER, starting transmit, because startTransmit clears (possibly stale) interrupt pending register
// bits
enableInterrupt(isrTxLevel0);
// Note: we deliver _all_ packets to our router (i.e. our interface is intentionally promiscuous).
// This allows the router and other apps on our node to sniff packets (usually routing) between other
// nodes.
meshtastic_MeshPacket *mp = packetPool.allocZeroed();
mp->from = h->from;
mp->to = h->to;
mp->id = h->id;
mp->channel = h->channel;
assert(HOP_MAX <= PACKET_FLAGS_HOP_MASK); // If hopmax changes, carefully check this code
mp->hop_limit = h->flags & PACKET_FLAGS_HOP_MASK;
mp->want_ack = !!(h->flags & PACKET_FLAGS_WANT_ACK_MASK);
addReceiveMetadata(mp);
mp->which_payload_variant =
meshtastic_MeshPacket_encrypted_tag; // Mark that the payload is still encrypted at this point
assert(((uint32_t)payloadLen) <= sizeof(mp->encrypted.bytes));
memcpy(mp->encrypted.bytes, payload, payloadLen);
mp->encrypted.size = payloadLen;
printPacket("Lora RX", mp);
airTime->logAirtime(RX_LOG, xmitMsec);
deliverToReceiver(mp);
}
}
}
/** start an immediate transmit */
void RadioLibInterface::startSend(meshtastic_MeshPacket *txp)
{
printPacket("Starting low level send", txp);
if (disabled || !config.lora.tx_enabled) {
LOG_WARN("startSend is dropping tx packet because we are disabled\n");
packetPool.release(txp);
} else {
setStandby(); // Cancel any already in process receives
configHardwareForSend(); // must be after setStandby
size_t numbytes = beginSending(txp);
int res = iface->startTransmit(radiobuf, numbytes);
if (res != RADIOLIB_ERR_NONE) {
LOG_ERROR("startTransmit failed, error=%d\n", res);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_RADIO_SPI_BUG);
// This send failed, but make sure to 'complete' it properly
completeSending();
startReceive(); // Restart receive mode (because startTransmit failed to put us in xmit mode)
}
// Must be done AFTER, starting transmit, because startTransmit clears (possibly stale) interrupt pending register
// bits
enableInterrupt(isrTxLevel0);
}
}

View File

@@ -1,8 +1,8 @@
#pragma once
#include "concurrency/NotifiedWorkerThread.h"
#include "RadioInterface.h"
#include "MeshPacketQueue.h"
#include "RadioInterface.h"
#include "concurrency/NotifiedWorkerThread.h"
#include <RadioLib.h>
@@ -39,7 +39,7 @@ class LockingModule : public Module
: Module(cs, irq, rst, gpio, spi, spiSettings)
{
}
void SPIbeginTransaction() override;
void SPIendTransaction() override;
};
@@ -62,17 +62,16 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
MeshPacketQueue txQueue = MeshPacketQueue(MAX_TX_QUEUE);
protected:
/**
* We use a meshtastic sync word, but hashed with the Channel name. For releases before 1.2 we used 0x12 (or for very old loads 0x14)
* Note: do not use 0x34 - that is reserved for lorawan
*
* We now use 0x2b (so that someday we can possibly use NOT 2b - because that would be funny pun). We will be staying with this code
* for a long time.
* We use a meshtastic sync word, but hashed with the Channel name. For releases before 1.2 we used 0x12 (or for very old
* loads 0x14) Note: do not use 0x34 - that is reserved for lorawan
*
* We now use 0x2b (so that someday we can possibly use NOT 2b - because that would be funny pun). We will be staying with
* this code for a long time.
*/
const uint8_t syncWord = 0x2b;
float currentLimit = 100; // 100mA OCP - Should be acceptable for RFM95/SX127x chipset.
float currentLimit = 100; // 100mA OCP - Should be acceptable for RFM95/SX127x chipset.
LockingModule module; // The HW interface to the radio
@@ -103,7 +102,7 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
RadioLibInterface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy, SPIClass &spi,
PhysicalLayer *iface = NULL);
virtual ErrorCode send(MeshPacket *p) override;
virtual ErrorCode send(meshtastic_MeshPacket *p) override;
/**
* Return true if we think the board can go to sleep (i.e. our tx queue is empty, we are not sending or receiving)
@@ -131,8 +130,8 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
virtual bool cancelSending(NodeNum from, PacketId id) override;
private:
/** if we have something waiting to send, start a short (random) timer so we can come check for collision before actually doing
* the transmit */
/** if we have something waiting to send, start a short (random) timer so we can come check for collision before actually
* doing the transmit */
void setTransmitDelay();
/** random timer with certain min. and max. settings */
@@ -151,12 +150,11 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
/** start an immediate transmit
* This method is virtual so subclasses can hook as needed, subclasses should not call directly
*/
virtual void startSend(MeshPacket *txp);
virtual void startSend(meshtastic_MeshPacket *txp);
QueueStatus getQueueStatus();
meshtastic_QueueStatus getQueueStatus();
protected:
/** Do any hardware setup needed on entry into send configuration for the radio. Subclasses can customize */
virtual void configHardwareForSend() {}
@@ -175,7 +173,7 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
/**
* Add SNR data to received messages
*/
virtual void addReceiveMetadata(MeshPacket *mp) = 0;
virtual void addReceiveMetadata(meshtastic_MeshPacket *mp) = 0;
virtual void setStandby() = 0;
};

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "RadioLibRF95.h"
#include "configuration.h"
#define RF95_CHIP_VERSION 0x12
#define RF95_ALT_VERSION 0x11 // Supposedly some versions of the chip have id 0x11
@@ -7,11 +7,10 @@
// From datasheet but radiolib doesn't know anything about this
#define SX127X_REG_TCXO 0x4B
RadioLibRF95::RadioLibRF95(Module *mod) : SX1278(mod) {}
int16_t RadioLibRF95::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power,
uint16_t preambleLength, uint8_t gain)
int16_t RadioLibRF95::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength,
uint8_t gain)
{
// execute common part
int16_t state = SX127x::begin(RF95_CHIP_VERSION, syncWord, preambleLength);

View File

@@ -6,9 +6,9 @@
\brief Derived class for %RFM95 modules. Overrides some methods from SX1278 due to different parameter ranges.
*/
class RadioLibRF95: public SX1278 {
class RadioLibRF95 : public SX1278
{
public:
// constructor
/*!
@@ -16,7 +16,7 @@ class RadioLibRF95: public SX1278 {
\param mod Instance of Module that will be used to communicate with the %LoRa chip.
*/
explicit RadioLibRF95(Module* mod);
explicit RadioLibRF95(Module *mod);
// basic methods
@@ -31,19 +31,21 @@ class RadioLibRF95: public SX1278 {
\param cr %LoRa link coding rate denominator. Allowed values range from 5 to 8.
\param syncWord %LoRa sync word. Can be used to distinguish different networks. Note that value 0x34 is reserved for LoRaWAN networks.
\param syncWord %LoRa sync word. Can be used to distinguish different networks. Note that value 0x34 is reserved for LoRaWAN
networks.
\param power Transmission output power in dBm. Allowed values range from 2 to 17 dBm.
\param preambleLength Length of %LoRa transmission preamble in symbols. The actual preamble length is 4.25 symbols longer than the set number.
Allowed values range from 6 to 65535.
\param preambleLength Length of %LoRa transmission preamble in symbols. The actual preamble length is 4.25 symbols longer
than the set number. Allowed values range from 6 to 65535.
\param gain Gain of receiver LNA (low-noise amplifier). Can be set to any integer in range 1 to 6 where 1 is the highest gain.
Set to 0 to enable automatic gain control (recommended).
\param gain Gain of receiver LNA (low-noise amplifier). Can be set to any integer in range 1 to 6 where 1 is the highest
gain. Set to 0 to enable automatic gain control (recommended).
\returns \ref status_codes
*/
int16_t begin(float freq = 915.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 17, uint16_t preambleLength = 8, uint8_t gain = 0);
int16_t begin(float freq = 915.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7,
uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 17, uint16_t preambleLength = 8, uint8_t gain = 0);
// configuration methods
@@ -60,11 +62,10 @@ class RadioLibRF95: public SX1278 {
bool isReceiving();
/// For debugging
uint8_t readReg(uint8_t addr);
uint8_t readReg(uint8_t addr);
protected:
// since default current limit for SX126x/127x in updated RadioLib is 60mA
// use the previous value
float currentLimit = 100;
};

View File

@@ -10,7 +10,7 @@
* If the message is want_ack, then add it to a list of packets to retransmit.
* If we run out of retransmissions, send a nak packet towards the original client to indicate failure.
*/
ErrorCode ReliableRouter::send(MeshPacket *p)
ErrorCode ReliableRouter::send(meshtastic_MeshPacket *p)
{
if (p->want_ack) {
// If someone asks for acks on broadcast, we need the hop limit to be at least one, so that first node that receives our
@@ -27,7 +27,7 @@ ErrorCode ReliableRouter::send(MeshPacket *p)
return FloodingRouter::send(p);
}
bool ReliableRouter::shouldFilterReceived(const MeshPacket *p)
bool ReliableRouter::shouldFilterReceived(const meshtastic_MeshPacket *p)
{
// Note: do not use getFrom() here, because we want to ignore messages sent from phone
if (p->from == getNodeNum()) {
@@ -38,14 +38,14 @@ bool ReliableRouter::shouldFilterReceived(const MeshPacket *p)
// the original sending process.
// This "optimization", does save lots of airtime. For DMs, you also get a real ACK back
// from the intended recipient.
// from the intended recipient.
auto key = GlobalPacketId(getFrom(p), p->id);
auto old = findPendingPacket(key);
if (old) {
LOG_DEBUG("generating implicit ack\n");
// NOTE: we do NOT check p->wantAck here because p is the INCOMING rebroadcast and that packet is not expected to be
// marked as wantAck
sendAckNak(Routing_Error_NONE, getFrom(p), p->id, old->packet->channel);
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, old->packet->channel);
stopRetransmission(key);
} else {
@@ -54,13 +54,13 @@ bool ReliableRouter::shouldFilterReceived(const MeshPacket *p)
}
/* Resend implicit ACKs for repeated packets (assuming the original packet was sent with HOP_RELIABLE)
* this way if an implicit ACK is dropped and a packet is resent we'll rebroadcast again.
* Resending real ACKs is omitted, as you might receive a packet multiple times due to flooding and
* flooding this ACK back to the original sender already adds redundancy. */
* this way if an implicit ACK is dropped and a packet is resent we'll rebroadcast again.
* Resending real ACKs is omitted, as you might receive a packet multiple times due to flooding and
* flooding this ACK back to the original sender already adds redundancy. */
if (wasSeenRecently(p, false) && p->hop_limit == HOP_RELIABLE && !MeshModule::currentReply && p->to != nodeDB.getNodeNum()) {
// retransmission on broadcast has hop_limit still equal to HOP_RELIABLE
LOG_DEBUG("Resending implicit ack for a repeated floodmsg\n");
MeshPacket *tosend = packetPool.allocCopy(*p);
meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p);
tosend->hop_limit--; // bump down the hop count
Router::send(tosend);
}
@@ -80,7 +80,7 @@ bool ReliableRouter::shouldFilterReceived(const MeshPacket *p)
*
* Otherwise, let superclass handle it.
*/
void ReliableRouter::sniffReceived(const MeshPacket *p, const Routing *c)
void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c)
{
NodeNum ourNode = getNodeNum();
@@ -88,19 +88,18 @@ void ReliableRouter::sniffReceived(const MeshPacket *p, const Routing *c)
if (p->want_ack) {
if (MeshModule::currentReply)
LOG_DEBUG("Some other module has replied to this message, no need for a 2nd ack\n");
else if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag)
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel);
else
if (p->which_payload_variant == MeshPacket_decoded_tag)
sendAckNak(Routing_Error_NONE, getFrom(p), p->id, p->channel);
else
// Send a 'NO_CHANNEL' error on the primary channel if want_ack packet destined for us cannot be decoded
sendAckNak(Routing_Error_NO_CHANNEL, getFrom(p), p->id, channels.getPrimaryIndex());
// Send a 'NO_CHANNEL' error on the primary channel if want_ack packet destined for us cannot be decoded
sendAckNak(meshtastic_Routing_Error_NO_CHANNEL, getFrom(p), p->id, channels.getPrimaryIndex());
}
// We consider an ack to be either a !routing packet with a request ID or a routing packet with !error
PacketId ackId = ((c && c->error_reason == Routing_Error_NONE) || !c) ? p->decoded.request_id : 0;
PacketId ackId = ((c && c->error_reason == meshtastic_Routing_Error_NONE) || !c) ? p->decoded.request_id : 0;
// A nak is a routing packt that has an error code
PacketId nakId = (c && c->error_reason != Routing_Error_NONE) ? p->decoded.request_id : 0;
PacketId nakId = (c && c->error_reason != meshtastic_Routing_Error_NONE) ? p->decoded.request_id : 0;
// We intentionally don't check wasSeenRecently, because it is harmless to delete non existent retransmission records
if (ackId || nakId) {
@@ -120,7 +119,7 @@ void ReliableRouter::sniffReceived(const MeshPacket *p, const Routing *c)
#define NUM_RETRANSMISSIONS 3
PendingPacket::PendingPacket(MeshPacket *p)
PendingPacket::PendingPacket(meshtastic_MeshPacket *p)
{
packet = p;
numRetransmissions = NUM_RETRANSMISSIONS - 1; // We subtract one, because we assume the user just did the first send
@@ -158,7 +157,7 @@ bool ReliableRouter::stopRetransmission(GlobalPacketId key)
/**
* Add p to the list of packets to retransmit occasionally. We will free it once we stop retransmitting.
*/
PendingPacket *ReliableRouter::startRetransmission(MeshPacket *p)
PendingPacket *ReliableRouter::startRetransmission(meshtastic_MeshPacket *p)
{
auto id = GlobalPacketId(p);
auto rec = PendingPacket(p);
@@ -192,7 +191,7 @@ int32_t ReliableRouter::doRetransmissions()
if (p.numRetransmissions == 0) {
LOG_DEBUG("Reliable send failed, returning a nak for fr=0x%x,to=0x%x,id=0x%x\n", p.packet->from, p.packet->to,
p.packet->id);
sendAckNak(Routing_Error_MAX_RETRANSMIT, getFrom(p.packet), p.packet->id, p.packet->channel);
sendAckNak(meshtastic_Routing_Error_MAX_RETRANSMIT, getFrom(p.packet), p.packet->id, p.packet->channel);
// Note: we don't stop retransmission here, instead the Nak packet gets processed in sniffReceived
stopRetransmission(it->first);
stillValid = false; // just deleted it

View File

@@ -13,7 +13,7 @@ struct GlobalPacketId {
bool operator==(const GlobalPacketId &p) const { return node == p.node && id == p.id; }
explicit GlobalPacketId(const MeshPacket *p)
explicit GlobalPacketId(const meshtastic_MeshPacket *p)
{
node = getFrom(p);
id = p->id;
@@ -30,7 +30,7 @@ struct GlobalPacketId {
* A packet queued for retransmission
*/
struct PendingPacket {
MeshPacket *packet;
meshtastic_MeshPacket *packet;
/** The next time we should try to retransmit this packet */
uint32_t nextTxMsec = 0;
@@ -39,7 +39,7 @@ struct PendingPacket {
uint8_t numRetransmissions = 0;
PendingPacket() {}
explicit PendingPacket(MeshPacket *p);
explicit PendingPacket(meshtastic_MeshPacket *p);
};
class GlobalPacketIdHashFunction
@@ -68,7 +68,7 @@ class ReliableRouter : public FloodingRouter
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*/
virtual ErrorCode send(MeshPacket *p) override;
virtual ErrorCode send(meshtastic_MeshPacket *p) override;
/** Do our retransmission handling */
virtual int32_t runOnce() override
@@ -85,7 +85,7 @@ class ReliableRouter : public FloodingRouter
/**
* Look for acks/naks or someone retransmitting us
*/
virtual void sniffReceived(const MeshPacket *p, const Routing *c) override;
virtual void sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c) override;
/**
* Try to find the pending packet record for this ID (or NULL if not found)
@@ -96,12 +96,12 @@ class ReliableRouter : public FloodingRouter
/**
* We hook this method so we can see packets before FloodingRouter says they should be discarded
*/
virtual bool shouldFilterReceived(const MeshPacket *p) override;
virtual bool shouldFilterReceived(const meshtastic_MeshPacket *p) override;
/**
* Add p to the list of packets to retransmit occasionally. We will free it once we stop retransmitting.
*/
PendingPacket *startRetransmission(MeshPacket *p);
PendingPacket *startRetransmission(meshtastic_MeshPacket *p);
private:
/**

View File

@@ -1,8 +1,8 @@
#include "Router.h"
#include "Channels.h"
#include "CryptoEngine.h"
#include "NodeDB.h"
#include "MeshRadio.h"
#include "NodeDB.h"
#include "RTC.h"
#include "configuration.h"
#include "main.h"
@@ -35,9 +35,9 @@ extern "C" {
2) // max number of packets which can be in flight (either queued from reception or queued for sending)
// static MemoryPool<MeshPacket> staticPool(MAX_PACKETS);
static MemoryDynamic<MeshPacket> staticPool;
static MemoryDynamic<meshtastic_MeshPacket> staticPool;
Allocator<MeshPacket> &packetPool = staticPool;
Allocator<meshtastic_MeshPacket> &packetPool = staticPool;
static uint8_t bytes[MAX_RHPACKETLEN];
@@ -63,7 +63,7 @@ Router::Router() : concurrency::OSThread("Router"), fromRadioQueue(MAX_RX_FROMRA
*/
int32_t Router::runOnce()
{
MeshPacket *mp;
meshtastic_MeshPacket *mp;
while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL) {
// printPacket("handle fromRadioQ", mp);
perhapsHandleReceived(mp);
@@ -77,7 +77,7 @@ int32_t Router::runOnce()
* RadioInterface calls this to queue up packets that have been received from the radio. The router is now responsible for
* freeing the packet
*/
void Router::enqueueReceivedMessage(MeshPacket *p)
void Router::enqueueReceivedMessage(meshtastic_MeshPacket *p)
{
if (fromRadioQueue.enqueue(p, 0)) { // NOWAIT - fixme, if queue is full, delete older messages
@@ -112,11 +112,11 @@ PacketId generatePacketId()
return id;
}
MeshPacket *Router::allocForSending()
meshtastic_MeshPacket *Router::allocForSending()
{
MeshPacket *p = packetPool.allocZeroed();
meshtastic_MeshPacket *p = packetPool.allocZeroed();
p->which_payload_variant = MeshPacket_decoded_tag; // Assume payload is decoded at start.
p->which_payload_variant = meshtastic_MeshPacket_decoded_tag; // Assume payload is decoded at start.
p->from = nodeDB.getNodeNum();
p->to = NODENUM_BROADCAST;
p->hop_limit = (config.lora.hop_limit >= HOP_MAX) ? HOP_MAX : config.lora.hop_limit;
@@ -130,12 +130,12 @@ MeshPacket *Router::allocForSending()
/**
* Send an ack or a nak packet back towards whoever sent idFrom
*/
void Router::sendAckNak(Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex)
void Router::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex)
{
routingModule->sendAckNak(err, to, idFrom, chIndex);
}
void Router::abortSendAndNak(Routing_Error err, MeshPacket *p)
void Router::abortSendAndNak(meshtastic_Routing_Error err, meshtastic_MeshPacket *p)
{
LOG_ERROR("Error=%d, returning NAK and dropping packet.\n", err);
sendAckNak(err, getFrom(p), p->id, p->channel);
@@ -149,12 +149,12 @@ void Router::setReceivedMessage()
runASAP = true;
}
QueueStatus Router::getQueueStatus()
meshtastic_QueueStatus Router::getQueueStatus()
{
return iface->getQueueStatus();
}
ErrorCode Router::sendLocal(MeshPacket *p, RxSource src)
ErrorCode Router::sendLocal(meshtastic_MeshPacket *p, RxSource src)
{
// No need to deliver externally if the destination is the local node
if (p->to == nodeDB.getNodeNum()) {
@@ -163,7 +163,7 @@ ErrorCode Router::sendLocal(MeshPacket *p, RxSource src)
return ERRNO_OK;
} else if (!iface) {
// We must be sending to remote nodes also, fail if no interface found
abortSendAndNak(Routing_Error_NO_INTERFACE, p);
abortSendAndNak(meshtastic_Routing_Error_NO_INTERFACE, p);
return ERRNO_NO_INTERFACES;
} else {
@@ -190,22 +190,22 @@ void printBytes(const char *label, const uint8_t *p, size_t numbytes)
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error.
*/
ErrorCode Router::send(MeshPacket *p)
ErrorCode Router::send(meshtastic_MeshPacket *p)
{
if (p->to == nodeDB.getNodeNum()) {
LOG_ERROR("BUG! send() called with packet destined for local node!\n");
packetPool.release(p);
return Routing_Error_BAD_REQUEST;
return meshtastic_Routing_Error_BAD_REQUEST;
} // should have already been handled by sendLocal
// Abort sending if we are violating the duty cycle
if (!config.lora.override_duty_cycle && myRegion->dutyCycle < 100) {
float hourlyTxPercent = airTime->utilizationTXPercent();
if (hourlyTxPercent > myRegion->dutyCycle) {
uint8_t silentMinutes = airTime->getSilentMinutes(hourlyTxPercent, myRegion->dutyCycle);
uint8_t silentMinutes = airTime->getSilentMinutes(hourlyTxPercent, myRegion->dutyCycle);
LOG_WARN("Duty cycle limit exceeded. Aborting send for now, you can send again in %d minutes.\n", silentMinutes);
Routing_Error err = Routing_Error_DUTY_CYCLE_LIMIT;
if (getFrom(p) == nodeDB.getNodeNum()) { // only send NAK to API, not to the mesh
meshtastic_Routing_Error err = meshtastic_Routing_Error_DUTY_CYCLE_LIMIT;
if (getFrom(p) == nodeDB.getNodeNum()) { // only send NAK to API, not to the mesh
abortSendAndNak(err, p);
} else {
packetPool.release(p);
@@ -228,28 +228,28 @@ ErrorCode Router::send(MeshPacket *p)
// If the packet hasn't yet been encrypted, do so now (it might already be encrypted if we are just forwarding it)
assert(p->which_payload_variant == MeshPacket_encrypted_tag ||
p->which_payload_variant == MeshPacket_decoded_tag); // I _think_ all packets should have a payload by now
assert(p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag ||
p->which_payload_variant == meshtastic_MeshPacket_decoded_tag); // I _think_ all packets should have a payload by now
// If the packet is not yet encrypted, do so now
if (p->which_payload_variant == MeshPacket_decoded_tag) {
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
ChannelIndex chIndex = p->channel; // keep as a local because we are about to change it
bool shouldActuallyEncrypt = true;
bool shouldActuallyEncrypt = true;
#if HAS_WIFI || HAS_ETHERNET
if(moduleConfig.mqtt.enabled) {
if (moduleConfig.mqtt.enabled) {
// check if we should send decrypted packets to mqtt
// truth table:
/* mqtt_server mqtt_encryption_enabled should_encrypt
* not set 0 1
* not set 1 1
* set 0 0
* set 1 1
*
* => so we only decrypt mqtt if they have a custom mqtt server AND mqtt_encryption_enabled is FALSE
*/
* not set 0 1
* not set 1 1
* set 0 0
* set 1 1
*
* => so we only decrypt mqtt if they have a custom mqtt server AND mqtt_encryption_enabled is FALSE
*/
if (*moduleConfig.mqtt.address && !moduleConfig.mqtt.encryption_enabled) {
shouldActuallyEncrypt = false;
@@ -264,7 +264,7 @@ ErrorCode Router::send(MeshPacket *p)
#endif
auto encodeResult = perhapsEncode(p);
if (encodeResult != Routing_Error_NONE) {
if (encodeResult != meshtastic_Routing_Error_NONE) {
abortSendAndNak(encodeResult, p);
return encodeResult; // FIXME - this isn't a valid ErrorCode
}
@@ -293,17 +293,17 @@ bool Router::cancelSending(NodeNum from, PacketId id)
* Every (non duplicate) packet this node receives will be passed through this method. This allows subclasses to
* update routing tables etc... based on what we overhear (even for messages not destined to our node)
*/
void Router::sniffReceived(const MeshPacket *p, const Routing *c)
void Router::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c)
{
// FIXME, update nodedb here for any packet that passes through us
}
bool perhapsDecode(MeshPacket *p)
bool perhapsDecode(meshtastic_MeshPacket *p)
{
// LOG_DEBUG("\n\n** perhapsDecode payloadVariant - %d\n\n", p->which_payloadVariant);
if (p->which_payload_variant == MeshPacket_decoded_tag)
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag)
return true; // If packet was already decoded just return
// assert(p->which_payloadVariant == MeshPacket_encrypted_tag);
@@ -323,20 +323,20 @@ bool perhapsDecode(MeshPacket *p)
// Take those raw bytes and convert them back into a well structured protobuf we can understand
memset(&p->decoded, 0, sizeof(p->decoded));
if (!pb_decode_from_bytes(bytes, rawSize, &Data_msg, &p->decoded)) {
if (!pb_decode_from_bytes(bytes, rawSize, &meshtastic_Data_msg, &p->decoded)) {
LOG_ERROR("Invalid protobufs in received mesh packet (bad psk?)!\n");
} else if (p->decoded.portnum == PortNum_UNKNOWN_APP) {
} else if (p->decoded.portnum == meshtastic_PortNum_UNKNOWN_APP) {
LOG_ERROR("Invalid portnum (bad psk?)!\n");
} else {
// parsing was successful
p->which_payload_variant = MeshPacket_decoded_tag; // change type to decoded
p->channel = chIndex; // change to store the index instead of the hash
p->which_payload_variant = meshtastic_MeshPacket_decoded_tag; // change type to decoded
p->channel = chIndex; // change to store the index instead of the hash
// Decompress if needed. jm
if (p->decoded.portnum == PortNum_TEXT_MESSAGE_COMPRESSED_APP) {
if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP) {
// Decompress the payload
char compressed_in[Constants_DATA_PAYLOAD_LEN] = {};
char decompressed_out[Constants_DATA_PAYLOAD_LEN] = {};
char compressed_in[meshtastic_Constants_DATA_PAYLOAD_LEN] = {};
char decompressed_out[meshtastic_Constants_DATA_PAYLOAD_LEN] = {};
int decompressed_len;
memcpy(compressed_in, p->decoded.payload.bytes, p->decoded.payload.size);
@@ -348,7 +348,7 @@ bool perhapsDecode(MeshPacket *p)
memcpy(p->decoded.payload.bytes, decompressed_out, decompressed_len);
// Switch the port from PortNum_TEXT_MESSAGE_COMPRESSED_APP to PortNum_TEXT_MESSAGE_APP
p->decoded.portnum = PortNum_TEXT_MESSAGE_APP;
p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP;
}
printPacket("decoded message", p);
@@ -363,21 +363,21 @@ bool perhapsDecode(MeshPacket *p)
/** Return 0 for success or a Routing_Errror code for failure
*/
Routing_Error perhapsEncode(MeshPacket *p)
meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p)
{
// If the packet is not yet encrypted, do so now
if (p->which_payload_variant == MeshPacket_decoded_tag) {
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &Data_msg, &p->decoded);
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_Data_msg, &p->decoded);
// Only allow encryption on the text message app.
// TODO: Allow modules to opt into compression.
if (p->decoded.portnum == PortNum_TEXT_MESSAGE_APP) {
if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP) {
char original_payload[Constants_DATA_PAYLOAD_LEN];
char original_payload[meshtastic_Constants_DATA_PAYLOAD_LEN];
memcpy(original_payload, p->decoded.payload.bytes, p->decoded.payload.size);
char compressed_out[Constants_DATA_PAYLOAD_LEN] = {0};
char compressed_out[meshtastic_Constants_DATA_PAYLOAD_LEN] = {0};
int compressed_len;
compressed_len = unishox2_compress_simple(original_payload, p->decoded.payload.size, compressed_out);
@@ -401,12 +401,12 @@ Routing_Error perhapsEncode(MeshPacket *p)
p->decoded.payload.size = compressed_len;
memcpy(p->decoded.payload.bytes, compressed_out, compressed_len);
p->decoded.portnum = PortNum_TEXT_MESSAGE_COMPRESSED_APP;
p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP;
}
}
if (numbytes > MAX_RHPACKETLEN)
return Routing_Error_TOO_LARGE;
return meshtastic_Routing_Error_TOO_LARGE;
// printBytes("plaintext", bytes, numbytes);
@@ -414,7 +414,7 @@ Routing_Error perhapsEncode(MeshPacket *p)
auto hash = channels.setActiveByIndex(chIndex);
if (hash < 0)
// No suitable channel could be found for sending
return Routing_Error_NO_CHANNEL;
return meshtastic_Routing_Error_NO_CHANNEL;
// Now that we are encrypting the packet channel should be the hash (no longer the index)
p->channel = hash;
@@ -423,10 +423,10 @@ Routing_Error perhapsEncode(MeshPacket *p)
// Copy back into the packet and set the variant type
memcpy(p->encrypted.bytes, bytes, numbytes);
p->encrypted.size = numbytes;
p->which_payload_variant = MeshPacket_encrypted_tag;
p->which_payload_variant = meshtastic_MeshPacket_encrypted_tag;
}
return Routing_Error_NONE;
return meshtastic_Routing_Error_NONE;
}
NodeNum Router::getNodeNum()
@@ -438,7 +438,7 @@ NodeNum Router::getNodeNum()
* Handle any packet that is received by an interface on this node.
* Note: some packets may merely being passed through this node and will be forwarded elsewhere.
*/
void Router::handleReceived(MeshPacket *p, RxSource src)
void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src)
{
// Also, we should set the time from the ISR and it should have msec level resolution
p->rx_time = getValidTime(RTCQualityFromNet); // store the arrival timestamp for the phone
@@ -461,7 +461,7 @@ void Router::handleReceived(MeshPacket *p, RxSource src)
MeshModule::callPlugins(*p, src);
}
void Router::perhapsHandleReceived(MeshPacket *p)
void Router::perhapsHandleReceived(meshtastic_MeshPacket *p)
{
// assert(radioConfig.has_preferences);
bool ignore = is_in_repeated(config.lora.ignore_incoming, p->from);

View File

@@ -16,7 +16,7 @@ class Router : protected concurrency::OSThread
private:
/// Packets which have just arrived from the radio, ready to be processed by this service and possibly
/// forwarded to the phone.
PointerQueue<MeshPacket> fromRadioQueue;
PointerQueue<meshtastic_MeshPacket> fromRadioQueue;
protected:
RadioInterface *iface = NULL;
@@ -45,7 +45,7 @@ class Router : protected concurrency::OSThread
*
* NOTE: This method will free the provided packet (even if we return an error code)
*/
ErrorCode sendLocal(MeshPacket *p, RxSource src = RX_SRC_RADIO);
ErrorCode sendLocal(meshtastic_MeshPacket *p, RxSource src = RX_SRC_RADIO);
/** Attempt to cancel a previously sent packet. Returns true if a packet was found we could cancel */
bool cancelSending(NodeNum from, PacketId id);
@@ -53,10 +53,10 @@ class Router : protected concurrency::OSThread
/** Allocate and return a meshpacket which defaults as send to broadcast from the current node.
* The returned packet is guaranteed to have a unique packet ID already assigned
*/
MeshPacket *allocForSending();
meshtastic_MeshPacket *allocForSending();
/** Return Underlying interface's TX queue status */
QueueStatus getQueueStatus();
meshtastic_QueueStatus getQueueStatus();
/**
* @return our local nodenum */
@@ -71,7 +71,7 @@ class Router : protected concurrency::OSThread
* RadioInterface calls this to queue up packets that have been received from the radio. The router is now responsible for
* freeing the packet
*/
void enqueueReceivedMessage(MeshPacket *p);
void enqueueReceivedMessage(meshtastic_MeshPacket *p);
protected:
friend class RoutingModule;
@@ -83,7 +83,7 @@ class Router : protected concurrency::OSThread
*
* NOTE: This method will free the provided packet (even if we return an error code)
*/
virtual ErrorCode send(MeshPacket *p);
virtual ErrorCode send(meshtastic_MeshPacket *p);
/**
* Should this incoming filter be dropped?
@@ -93,18 +93,18 @@ class Router : protected concurrency::OSThread
* Called immedately on receiption, before any further processing.
* @return true to abandon the packet
*/
virtual bool shouldFilterReceived(const MeshPacket *p) { return false; }
virtual bool shouldFilterReceived(const meshtastic_MeshPacket *p) { return false; }
/**
* Every (non duplicate) packet this node receives will be passed through this method. This allows subclasses to
* update routing tables etc... based on what we overhear (even for messages not destined to our node)
*/
virtual void sniffReceived(const MeshPacket *p, const Routing *c);
virtual void sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c);
/**
* Send an ack or a nak packet back towards whoever sent idFrom
*/
void sendAckNak(Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex);
void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex);
private:
/**
@@ -115,7 +115,7 @@ class Router : protected concurrency::OSThread
* Note: this packet will never be called for messages sent/generated by this node.
* Note: this method will free the provided packet.
*/
void perhapsHandleReceived(MeshPacket *p);
void perhapsHandleReceived(meshtastic_MeshPacket *p);
/**
* Called from perhapsHandleReceived() - allows subclass message delivery behavior.
@@ -125,10 +125,10 @@ class Router : protected concurrency::OSThread
* Note: this packet will never be called for messages sent/generated by this node.
* Note: this method will free the provided packet.
*/
void handleReceived(MeshPacket *p, RxSource src = RX_SRC_RADIO);
void handleReceived(meshtastic_MeshPacket *p, RxSource src = RX_SRC_RADIO);
/** Frees the provided packet, and generates a NAK indicating the speicifed error while sending */
void abortSendAndNak(Routing_Error err, MeshPacket *p);
void abortSendAndNak(meshtastic_Routing_Error err, meshtastic_MeshPacket *p);
};
/** FIXME - move this into a mesh packet class
@@ -136,11 +136,11 @@ class Router : protected concurrency::OSThread
*
* @return true for success, false for corrupt packet.
*/
bool perhapsDecode(MeshPacket *p);
bool perhapsDecode(meshtastic_MeshPacket *p);
/** Return 0 for success or a Routing_Errror code for failure
*/
Routing_Error perhapsEncode(MeshPacket *p);
meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p);
extern Router *router;

View File

@@ -1,5 +1,5 @@
#include "configuration.h"
#include "SX1262Interface.h"
#include "configuration.h"
#include "error.h"
SX1262Interface::SX1262Interface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy,

Some files were not shown because too many files have changed in this diff Show More