Finish config transition

pull/1444/head^2
Sacha Weatherstone 2022-05-07 20:31:21 +10:00
rodzic c07976438b
commit 6b0ce6b729
Nie znaleziono w bazie danych klucza dla tego podpisu
ID klucza GPG: 7AB2D7E206124B31
55 zmienionych plików z 1417 dodań i 2027 usunięć

2
proto

@ -1 +1 @@
Subproject commit cb8c31bdd9ff17e3cbc904c86a6caf927b2021c5
Subproject commit 23d43efaf119c19e9e7c5a0839560778d5ac20a3

Wyświetl plik

@ -1,10 +1,10 @@
#include "configuration.h"
#include "concurrency/OSThread.h"
#include "PowerFSM.h"
#include "RadioLibInterface.h"
#include "buzz.h"
#include "concurrency/OSThread.h"
#include "configuration.h"
#include "graphics/Screen.h"
#include "power.h"
#include "buzz.h"
#include <OneButton.h>
#ifndef NO_ESP32
@ -85,7 +85,6 @@ class ButtonThread : public concurrency::OSThread
userButtonTouch.attachClick(touchPressed);
wakeOnIrq(BUTTON_PIN_TOUCH, FALLING);
#endif
}
protected:
@ -114,16 +113,17 @@ class ButtonThread : public concurrency::OSThread
private:
static void touchPressed()
{
{
screen->forceDisplay();
DEBUG_MSG("touch press!\n");
DEBUG_MSG("touch press!\n");
}
static void userButtonPressed()
{
// DEBUG_MSG("press!\n");
#ifdef BUTTON_PIN
if ((BUTTON_PIN != radioConfig.preferences.inputbroker_pin_press) || !radioConfig.preferences.canned_message_module_enabled) {
if ((BUTTON_PIN != moduleConfig.payloadVariant.canned_message.inputbroker_pin_press) ||
!moduleConfig.payloadVariant.canned_message.enabled) {
powerFSM.trigger(EVENT_PRESS);
}
#endif
@ -144,7 +144,7 @@ class ButtonThread : public concurrency::OSThread
#elif NRF52_SERIES
// Do actual shutdown when button released, otherwise the button release
// may wake the board immediatedly.
if ((!shutdown_on_long_stop) && (millis() > 30 * 1000)) {
if ((!shutdown_on_long_stop) && (millis() > 30 * 1000)) {
screen->startShutdownScreen();
DEBUG_MSG("Shutdown from long press");
playBeep();
@ -163,7 +163,7 @@ class ButtonThread : public concurrency::OSThread
#ifndef NO_ESP32
disablePin();
#elif defined(HAS_EINK)
digitalWrite(PIN_EINK_EN,digitalRead(PIN_EINK_EN) == LOW);
digitalWrite(PIN_EINK_EN, digitalRead(PIN_EINK_EN) == LOW);
#endif
}
@ -177,7 +177,6 @@ class ButtonThread : public concurrency::OSThread
#endif
}
static void userButtonPressedLongStart()
{
if (millis() > 30 * 1000) {
@ -188,7 +187,7 @@ class ButtonThread : public concurrency::OSThread
static void userButtonPressedLongStop()
{
if (millis() > 30 * 1000){
if (millis() > 30 * 1000) {
DEBUG_MSG("Long press stop!\n");
longPressTime = 0;
if (shutdown_on_long_stop) {
@ -200,4 +199,4 @@ class ButtonThread : public concurrency::OSThread
}
};
}
} // namespace concurrency

Wyświetl plik

@ -1,7 +1,7 @@
#pragma once
#include "NodeDB.h"
#include "Status.h"
#include "configuration.h"
#include "NodeDB.h"
#include <Arduino.h>
extern NodeDB nodeDB;
@ -17,8 +17,8 @@ class GPSStatus : public Status
CallbackObserver<GPSStatus, const GPSStatus *> statusObserver =
CallbackObserver<GPSStatus, const GPSStatus *>(this, &GPSStatus::updateStatus);
bool hasLock = false; // default to false, until we complete our first read
bool isConnected = false; // Do we have a GPS we are talking to
bool hasLock = false; // default to false, until we complete our first read
bool isConnected = false; // Do we have a GPS we are talking to
Position p = Position_init_default;
@ -42,8 +42,7 @@ class GPSStatus : public Status
}
// preferred method
GPSStatus(bool hasLock, bool isConnected, const Position& pos)
: Status()
GPSStatus(bool hasLock, bool isConnected, const Position &pos) : Status()
{
this->hasLock = hasLock;
this->isConnected = isConnected;
@ -61,8 +60,9 @@ class GPSStatus : public Status
bool getIsConnected() const { return isConnected; }
int32_t getLatitude() const {
if (radioConfig.preferences.fixed_position){
int32_t getLatitude() const
{
if (config.payloadVariant.position.fixed_position) {
#ifdef GPS_EXTRAVERBOSE
DEBUG_MSG("WARNING: Using fixed latitude\n");
#endif
@ -73,8 +73,9 @@ class GPSStatus : public Status
}
}
int32_t getLongitude() const {
if (radioConfig.preferences.fixed_position){
int32_t getLongitude() const
{
if (config.payloadVariant.position.fixed_position) {
#ifdef GPS_EXTRAVERBOSE
DEBUG_MSG("WARNING: Using fixed longitude\n");
#endif
@ -85,8 +86,9 @@ class GPSStatus : public Status
}
}
int32_t getAltitude() const {
if (radioConfig.preferences.fixed_position){
int32_t getAltitude() const
{
if (config.payloadVariant.position.fixed_position) {
#ifdef GPS_EXTRAVERBOSE
DEBUG_MSG("WARNING: Using fixed altitude\n");
#endif
@ -106,17 +108,12 @@ class GPSStatus : public Status
bool matches(const GPSStatus *newStatus) const
{
#ifdef GPS_EXTRAVERBOSE
DEBUG_MSG("GPSStatus.match() new pos@%x to old pos@%x\n",
newStatus->p.pos_timestamp, p.pos_timestamp);
DEBUG_MSG("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->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 ||
return (newStatus->hasLock != hasLock || newStatus->isConnected != isConnected ||
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.sats_in_view != p.sats_in_view);
}
@ -125,8 +122,7 @@ class GPSStatus : public Status
// Only update the status if values have actually changed
bool isDirty = matches(newStatus);
if (isDirty && p.pos_timestamp &&
(newStatus->p.pos_timestamp == p.pos_timestamp)) {
if (isDirty && p.pos_timestamp && (newStatus->p.pos_timestamp == p.pos_timestamp)) {
// We can NEVER be in two locations at the same time! (also PR #886)
DEBUG_MSG("BUG!! positional timestamp unchanged from prev solution\n");
}
@ -140,11 +136,9 @@ class GPSStatus : public Status
if (isDirty) {
if (hasLock) {
// In debug logs, identify position by @timestamp:stage (stage 3 = notify)
DEBUG_MSG("New GPS pos@%x:3 lat=%f, lon=%f, alt=%d, pdop=%.2f, track=%.2f, sats=%d\n",
p.pos_timestamp,
p.latitude_i * 1e-7, p.longitude_i * 1e-7,
p.altitude, p.PDOP * 1e-2, p.ground_track * 1e-5,
p.sats_in_view);
DEBUG_MSG("New GPS pos@%x:3 lat=%f, lon=%f, alt=%d, pdop=%.2f, track=%.2f, sats=%d\n", p.pos_timestamp,
p.latitude_i * 1e-7, p.longitude_i * 1e-7, p.altitude, p.PDOP * 1e-2, p.ground_track * 1e-5,
p.sats_in_view);
} else
DEBUG_MSG("No GPS lock\n");
onNewStatus.notifyObservers(this);

Wyświetl plik

@ -1,7 +1,7 @@
#include "configuration.h"
#include "power.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "main.h"
#include "sleep.h"
#include "utils.h"
@ -13,27 +13,28 @@
AXP20X_Class axp;
#else
// Copy of the base class defined in axp20x.h.
// Copy of the base class defined in axp20x.h.
// I'd rather not inlude axp20x.h as it brings Wire dependency.
class HasBatteryLevel {
public:
/**
* Battery state of charge, from 0 to 100 or -1 for unknown
*/
virtual int getBattPercentage() { return -1; }
class HasBatteryLevel
{
public:
/**
* Battery state of charge, from 0 to 100 or -1 for unknown
*/
virtual int getBattPercentage() { return -1; }
/**
* The raw voltage of the battery or NAN if unknown
*/
virtual float getBattVoltage() { return NAN; }
/**
* The raw voltage of the battery or NAN if unknown
*/
virtual float getBattVoltage() { return NAN; }
/**
* return true if there is a battery installed in this unit
*/
virtual bool isBatteryConnect() { return false; }
/**
* return true if there is a battery installed in this unit
*/
virtual bool isBatteryConnect() { return false; }
virtual bool isVBUSPlug() { return false; }
virtual bool isChargeing() { return false; }
virtual bool isVBUSPlug() { return false; }
virtual bool isChargeing() { return false; }
};
#endif
@ -99,23 +100,24 @@ class AnalogBatteryLevel : public HasBatteryLevel
#ifndef ADC_MULTIPLIER
#define ADC_MULTIPLIER 2.0
#endif
#endif
#ifdef BATTERY_PIN
// Override variant or default ADC_MULTIPLIER if we have the override pref
float operativeAdcMultiplier = radioConfig.preferences.adc_multiplier_override > 0 ?
radioConfig.preferences.adc_multiplier_override : ADC_MULTIPLIER;
// Do not call analogRead() often.
float operativeAdcMultiplier = radioConfig.preferences.adc_multiplier_override > 0
? radioConfig.preferences.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();
uint32_t raw = analogRead(BATTERY_PIN);
float scaled;
#ifndef VBAT_RAW_TO_SCALED
#ifndef VBAT_RAW_TO_SCALED
scaled = 1000.0 * operativeAdcMultiplier * (AREF_VOLTAGE / 1024.0) * raw;
#else
scaled = VBAT_RAW_TO_SCALED(raw); //defined in variant.h
#endif
#else
scaled = VBAT_RAW_TO_SCALED(raw); // defined in variant.h
#endif
// DEBUG_MSG("battery gpio %d raw val=%u scaled=%u\n", BATTERY_PIN, raw, (uint32_t)(scaled));
last_read_value = scaled;
return scaled;
@ -152,7 +154,8 @@ class AnalogBatteryLevel : public HasBatteryLevel
AnalogBatteryLevel analogLevel;
Power::Power() : OSThread("Power") {
Power::Power() : OSThread("Power")
{
statusHandler = {};
low_voltage_counter = 0;
}
@ -171,7 +174,7 @@ bool Power::analogInit()
#endif
#ifdef NRF52_SERIES
#ifdef VBAT_AR_INTERNAL
analogReference(VBAT_AR_INTERNAL);
analogReference(VBAT_AR_INTERNAL);
#else
analogReference(AR_INTERNAL); // 3.6V
#endif
@ -180,9 +183,10 @@ bool Power::analogInit()
#ifndef BATTERY_SENSE_RESOLUTION_BITS
#define BATTERY_SENSE_RESOLUTION_BITS 10
#endif
// adcStart(BATTERY_PIN);
analogReadResolution(BATTERY_SENSE_RESOLUTION_BITS); // Default of 12 is not very linear. Recommended to use 10 or 11 depending on needed resolution.
analogReadResolution(BATTERY_SENSE_RESOLUTION_BITS); // Default of 12 is not very linear. Recommended to use 10 or 11
// depending on needed resolution.
batteryLevel = &analogLevel;
return true;
#else
@ -245,24 +249,23 @@ void Power::readPowerStatus()
powerStatus2.getIsCharging(), powerStatus2.getBatteryVoltageMv(), powerStatus2.getBatteryChargePercent());
newStatus.notifyObservers(&powerStatus2);
// If we have a battery at all and it is less than 10% full, force deep sleep if we have more than 3 low readings in a row
// Supect fluctuating voltage on the RAK4631 to force it to deep sleep even if battery is at 85% after only a few days
#ifdef NRF52_SERIES
if (powerStatus2.getHasBattery() && !powerStatus2.getHasUSB()){
if (batteryLevel->getBattVoltage() < MIN_BAT_MILLIVOLTS){
// If we have a battery at all and it is less than 10% full, force deep sleep if we have more than 3 low readings in a row
// Supect fluctuating voltage on the RAK4631 to force it to deep sleep even if battery is at 85% after only a few days
#ifdef NRF52_SERIES
if (powerStatus2.getHasBattery() && !powerStatus2.getHasUSB()) {
if (batteryLevel->getBattVoltage() < MIN_BAT_MILLIVOLTS) {
low_voltage_counter++;
if (low_voltage_counter>3)
if (low_voltage_counter > 3)
powerFSM.trigger(EVENT_LOW_BATTERY);
} else {
low_voltage_counter = 0;
}
}
#else
#else
// If we have a battery at all and it is less than 10% full, force deep sleep
if (powerStatus2.getHasBattery() && !powerStatus2.getHasUSB() && batteryLevel->getBattVoltage() < MIN_BAT_MILLIVOLTS)
powerFSM.trigger(EVENT_LOW_BATTERY);
#endif
#endif
} else {
// No power sensing on this board - tell everyone else we have no idea what is happening
const PowerStatus powerStatus3 = PowerStatus(OptUnknown, OptUnknown, OptUnknown, -1, -1);
@ -354,40 +357,58 @@ bool Power::axp192Init()
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
if (radioConfig.preferences.charge_current == ChargeCurrent_MAUnset) {
switch (config.payloadVariant.power.charge_current) {
case Config_PowerConfig_ChargeCurrent_MAUnset:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_450MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA100) {
break;
case Config_PowerConfig_ChargeCurrent_MA100:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_100MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA190) {
break;
case Config_PowerConfig_ChargeCurrent_MA190:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_190MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA280) {
break;
case Config_PowerConfig_ChargeCurrent_MA280:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_280MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA360) {
break;
case Config_PowerConfig_ChargeCurrent_MA360:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_360MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA450) {
break;
case Config_PowerConfig_ChargeCurrent_MA450:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_450MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA550) {
break;
case Config_PowerConfig_ChargeCurrent_MA550:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_550MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA630) {
break;
case Config_PowerConfig_ChargeCurrent_MA630:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_630MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA700) {
break;
case Config_PowerConfig_ChargeCurrent_MA700:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_700MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA780) {
break;
case Config_PowerConfig_ChargeCurrent_MA780:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_780MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA880) {
break;
case Config_PowerConfig_ChargeCurrent_MA880:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_880MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA960) {
break;
case Config_PowerConfig_ChargeCurrent_MA960:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_960MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA1000) {
break;
case Config_PowerConfig_ChargeCurrent_MA1000:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_1000MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA1080) {
break;
case Config_PowerConfig_ChargeCurrent_MA1080:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_1080MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA1160) {
break;
case Config_PowerConfig_ChargeCurrent_MA1160:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_1160MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA1240) {
break;
case Config_PowerConfig_ChargeCurrent_MA1240:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_1240MA);
} else if (radioConfig.preferences.charge_current == ChargeCurrent_MA1320) {
break;
case Config_PowerConfig_ChargeCurrent_MA1320:
axp.setChargeControlCur(AXP1XX_CHARGE_CUR_1320MA);
break;
}
#if 0

Wyświetl plik

@ -12,15 +12,15 @@
static bool isPowered()
{
// Completely circumvents the battery / power sensing logic and assumes constant power source
if (radioConfig.preferences.is_always_powered) {
if (config.payloadVariant.power.is_always_powered) {
return true;
}
bool isRouter = (radioConfig.preferences.role == Role_Router ? 1 : 0);
bool isRouter = (config.payloadVariant.device.role == 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
bool isLowPower = radioConfig.preferences.is_low_power || isRouter;
bool isLowPower = config.payloadVariant.power.is_low_power || isRouter;
/* To determine if we're externally powered, assumptions
1) If we're powered up and there's no battery, we must be getting power externally. (because we'd be dead otherwise)
@ -34,7 +34,7 @@ static void sdsEnter()
{
DEBUG_MSG("Enter state: SDS\n");
// FIXME - make sure GPS and LORA radio are off first - because we want close to zero current draw
doDeepSleep(getPref_sds_secs() * 1000LL);
doDeepSleep(config.payloadVariant.power.sds_secs ? config.payloadVariant.power.sds_secs : default_sds_secs * 1000LL);
}
extern Power *power;
@ -51,7 +51,8 @@ static uint32_t secsSlept;
static void lsEnter()
{
DEBUG_MSG("lsEnter begin, ls_secs=%u\n", getPref_ls_secs());
DEBUG_MSG("lsEnter begin, ls_secs=%u\n",
config.payloadVariant.power.ls_secs ? config.payloadVariant.power.ls_secs : default_ls_secs);
screen->setOn(false);
secsSlept = 0; // How long have we been sleeping this time
@ -65,7 +66,7 @@ static void lsIdle()
#ifndef NO_ESP32
// Do we have more sleeping to do?
if (secsSlept < getPref_ls_secs()) {
if (secsSlept < config.payloadVariant.power.ls_secs ? config.payloadVariant.power.ls_secs : default_ls_secs * 1000) {
// Briefly come out of sleep long enough to blink the led once every few seconds
uint32_t sleepTime = 30;
@ -78,7 +79,7 @@ static void lsIdle()
case ESP_SLEEP_WAKEUP_TIMER:
// Normal case: timer expired, we should just go back to sleep ASAP
setLed(true); // briefly turn on led
setLed(true); // briefly turn on led
wakeCause2 = doLightSleep(1); // leave led on for 1ms
secsSlept += sleepTime;
@ -238,7 +239,7 @@ Fsm powerFSM(&stateBOOT);
void PowerFSM_setup()
{
bool isRouter = (radioConfig.preferences.role == Role_Router ? 1 : 0);
bool isRouter = (config.payloadVariant.device.role == Config_DeviceConfig_Role_Router ? 1 : 0);
bool hasPower = isPowered();
DEBUG_MSG("PowerFSM init, USB power=%d\n", hasPower);
@ -332,7 +333,10 @@ void PowerFSM_setup()
powerFSM.add_transition(&stateDARK, &stateON, EVENT_FIRMWARE_UPDATE, NULL, "Got firmware update");
powerFSM.add_transition(&stateON, &stateON, EVENT_FIRMWARE_UPDATE, NULL, "Got firmware update");
powerFSM.add_timed_transition(&stateON, &stateDARK, getPref_screen_on_secs() * 1000, NULL, "Screen-on timeout");
powerFSM.add_timed_transition(&stateON, &stateDARK,
config.payloadVariant.display.screen_on_secs ? config.payloadVariant.display.screen_on_secs
: 60 * 1000,
NULL, "Screen-on timeout");
// On most boards we use light-sleep to be our main state, but on NRF52 we just stay in DARK
State *lowPowerState = &stateLS;
@ -343,13 +347,21 @@ void PowerFSM_setup()
// We never enter light-sleep or NB states on NRF52 (because the CPU uses so little power normally)
// See: https://github.com/meshtastic/Meshtastic-device/issues/1071
if (isRouter || radioConfig.preferences.is_power_saving) {
if (isRouter || config.payloadVariant.power.is_power_saving) {
// I don't think this transition is correct, turning off for now - @geeksville
// powerFSM.add_timed_transition(&stateDARK, &stateNB, getPref_phone_timeout_secs() * 1000, NULL, "Phone timeout");
powerFSM.add_timed_transition(&stateNB, &stateLS, getPref_min_wake_secs() * 1000, NULL, "Min wake timeout");
powerFSM.add_timed_transition(&stateDARK, &stateLS, getPref_wait_bluetooth_secs() * 1000, NULL, "Bluetooth timeout");
meshSds = getPref_mesh_sds_timeout_secs();
powerFSM.add_timed_transition(&stateNB, &stateLS,
config.payloadVariant.power.min_wake_secs ? config.payloadVariant.power.min_wake_secs
: default_min_wake_secs * 1000,
NULL, "Min wake timeout");
powerFSM.add_timed_transition(&stateDARK, &stateLS,
config.payloadVariant.power.wait_bluetooth_secs
? config.payloadVariant.power.wait_bluetooth_secs
: default_wait_bluetooth_secs * 1000,
NULL, "Bluetooth timeout");
meshSds = config.payloadVariant.power.mesh_sds_timeout_secs ? config.payloadVariant.power.mesh_sds_timeout_secs
: default_mesh_sds_timeout_secs;
} else {

Wyświetl plik

@ -1,9 +1,9 @@
#include "configuration.h"
#include "concurrency/OSThread.h"
#include "main.h"
#include "PowerFSM.h"
#include "power.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "concurrency/OSThread.h"
#include "configuration.h"
#include "main.h"
#include "power.h"
namespace concurrency
{
@ -26,13 +26,16 @@ class PowerFSMThread : public OSThread
if (powerStatus->getHasUSB()) {
timeLastPowered = millis();
} else if (radioConfig.preferences.on_battery_shutdown_after_secs > 0 &&
millis() > timeLastPowered + (1000 * radioConfig.preferences.on_battery_shutdown_after_secs)) { //shutdown after 30 minutes unpowered
} else if (config.payloadVariant.power.on_battery_shutdown_after_secs > 0 &&
millis() >
timeLastPowered +
(1000 *
config.payloadVariant.power.on_battery_shutdown_after_secs)) { // shutdown after 30 minutes unpowered
powerFSM.trigger(EVENT_SHUTDOWN);
}
return 10;
}
};
}
} // namespace concurrency

Wyświetl plik

@ -1,7 +1,7 @@
#include "configuration.h"
#include "SerialConsole.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#define Port Serial
@ -45,7 +45,9 @@ SerialConsole::SerialConsole() : StreamAPI(&Port), RedirectablePrint(&Port)
bool SerialConsole::checkIsConnected()
{
uint32_t now = millis();
return (now - lastContactMsec) < getPref_phone_timeout_secs() * 1000UL;
return (now - lastContactMsec) < config.payloadVariant.power.phone_timeout_secs
? config.payloadVariant.power.phone_timeout_secs
: default_phone_timeout_secs * 1000UL;
}
/**
@ -55,10 +57,9 @@ bool SerialConsole::checkIsConnected()
bool SerialConsole::handleToRadio(const uint8_t *buf, size_t len)
{
// Turn off debug serial printing once the API is activated, because other threads could print and corrupt packets
if (!radioConfig.preferences.debug_log_enabled)
if (!config.payloadVariant.device.debug_log_enabled)
setDestination(&noopPrint);
canWrite = true;
return StreamAPI::handleToRadio(buf, len);
}

Wyświetl plik

@ -1,7 +1,7 @@
#include "configuration.h"
#include "GPS.h"
#include "NodeDB.h"
#include "RTC.h"
#include "configuration.h"
#include "sleep.h"
#include <assert.h>
@ -57,52 +57,39 @@ bool GPS::setupGPS()
#endif
#ifdef GPS_UBLOX
// Set the UART port to output NMEA only
byte _message_nmea[] = {0xB5, 0x62, 0x06, 0x00, 0x14, 0x00,
0x01, 0x00, 0x00, 0x00, 0xC0, 0x08, 0x00, 0x00, 0x80, 0x25, 0x00, 0x00, 0x07, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00,
0x91, 0xAF};
_serial_gps->write(_message_nmea,sizeof(_message_nmea));
byte _message_nmea[] = {0xB5, 0x62, 0x06, 0x00, 0x14, 0x00, 0x01, 0x00, 0x00, 0x00, 0xC0, 0x08, 0x00, 0x00,
0x80, 0x25, 0x00, 0x00, 0x07, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x91, 0xAF};
_serial_gps->write(_message_nmea, sizeof(_message_nmea));
delay(250);
// disable GGL
byte _message_GGL[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00,
0xF0, 0x01, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01,
0x05,0x3A};
_serial_gps->write(_message_GGL,sizeof(_message_GGL));
byte _message_GGL[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x01, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x05, 0x3A};
_serial_gps->write(_message_GGL, sizeof(_message_GGL));
delay(250);
// disable GSA
byte _message_GSA[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00,
0xF0, 0x02, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01,
0x06,0x41};
_serial_gps->write(_message_GSA,sizeof(_message_GSA));
byte _message_GSA[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x02, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x06, 0x41};
_serial_gps->write(_message_GSA, sizeof(_message_GSA));
delay(250);
// disable GSV
byte _message_GSV[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00,
0xF0, 0x03, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01,
0x07,0x48};
_serial_gps->write(_message_GSV,sizeof(_message_GSV));
byte _message_GSV[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x03, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x07, 0x48};
_serial_gps->write(_message_GSV, sizeof(_message_GSV));
delay(250);
// disable VTG
byte _message_VTG[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00,
0xF0, 0x05, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01,
0x09,0x56};
_serial_gps->write(_message_VTG,sizeof(_message_VTG));
byte _message_VTG[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x05, 0x01, 0x00, 0x01, 0x01, 0x01, 0x01, 0x09, 0x56};
_serial_gps->write(_message_VTG, sizeof(_message_VTG));
delay(250);
// enable RMC
byte _message_RMC[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00,
0xF0, 0x04, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01,
0x09,0x54};
_serial_gps->write(_message_RMC,sizeof(_message_RMC));
byte _message_RMC[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x04, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x09, 0x54};
_serial_gps->write(_message_RMC, sizeof(_message_RMC));
delay(250);
// enable GGA
byte _message_GGA[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00,
0xF0, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01,
0x05, 0x38};
_serial_gps->write(_message_GGA,sizeof(_message_GGA));
byte _message_GGA[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x05, 0x38};
_serial_gps->write(_message_GGA, sizeof(_message_GGA));
delay(250);
#endif
}
@ -143,7 +130,10 @@ GPS::~GPS()
notifyDeepSleepObserver.unobserve(&notifyDeepSleep);
}
bool GPS::hasLock() { return hasValidLocation; }
bool GPS::hasLock()
{
return hasValidLocation;
}
// Allow defining the polarity of the WAKE output. default is active high
#ifndef GPS_WAKE_ACTIVE
@ -213,14 +203,16 @@ void GPS::setAwake(bool on)
*/
uint32_t GPS::getWakeTime() const
{
uint32_t t = radioConfig.preferences.gps_attempt_time;
uint32_t t = config.payloadVariant.position.gps_attempt_time;
if (t == UINT32_MAX)
return t; // already maxint
if (t == 0)
t = (radioConfig.preferences.role == Role_Router) ? 5 * 60 : 15 * 60; // Allow up to 15 mins for each attempt (probably will be much
// less if we can find sats) or less if a router
t = (config.payloadVariant.device.role == Config_DeviceConfig_Role_Router)
? 5 * 60
: 15 * 60; // Allow up to 15 mins for each attempt (probably will be much
// less if we can find sats) or less if a router
t *= 1000; // msecs
@ -231,9 +223,9 @@ uint32_t GPS::getWakeTime() const
*/
uint32_t GPS::getSleepTime() const
{
uint32_t t = radioConfig.preferences.gps_update_interval;
bool gps_disabled = radioConfig.preferences.gps_disabled;
bool loc_share_disabled = radioConfig.preferences.location_share_disabled;
uint32_t t = config.payloadVariant.position.gps_update_interval;
bool gps_disabled = config.payloadVariant.position.gps_disabled;
bool loc_share_disabled = config.payloadVariant.position.location_share_disabled;
if (gps_disabled || loc_share_disabled)
t = UINT32_MAX; // Sleep forever now
@ -241,8 +233,9 @@ uint32_t GPS::getSleepTime() const
if (t == UINT32_MAX)
return t; // already maxint
if (t == 0) // default - unset in preferences
t = (radioConfig.preferences.role == Role_Router) ? 24 * 60 * 60 : 2 * 60; // 2 mins or once per day for routers
if (t == 0) // default - unset in preferences
t = (config.payloadVariant.device.role == Config_DeviceConfig_Role_Router) ? 24 * 60 * 60
: 2 * 60; // 2 mins or once per day for routers
t *= 1000;
@ -255,12 +248,10 @@ void GPS::publishUpdate()
shouldPublish = false;
// In debug logs, identify position by @timestamp:stage (stage 2 = publish)
DEBUG_MSG("publishing pos@%x:2, hasVal=%d, GPSlock=%d\n",
p.pos_timestamp, hasValidLocation, hasLock());
DEBUG_MSG("publishing pos@%x:2, hasVal=%d, GPSlock=%d\n", p.pos_timestamp, hasValidLocation, hasLock());
// Notify any status instances that are observing us
const meshtastic::GPSStatus status =
meshtastic::GPSStatus(hasValidLocation, isConnected(), p);
const meshtastic::GPSStatus status = meshtastic::GPSStatus(hasValidLocation, isConnected(), p);
newStatus.notifyObservers(&status);
}
}
@ -379,7 +370,7 @@ GPS *createGps()
#ifdef NO_GPS
return nullptr;
#else
if (!radioConfig.preferences.gps_disabled){
if (!config.payloadVariant.position.gps_disabled) {
#ifdef GPS_ALTITUDE_HAE
DEBUG_MSG("Using HAE altitude model\n");
#else

Wyświetl plik

@ -353,8 +353,8 @@ 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)
{
return packet->from != 0 && !radioConfig.preferences.range_test_module_enabled &&
!radioConfig.preferences.store_forward_module_enabled;
return packet->from != 0 && !moduleConfig.payloadVariant.range_test.enabled &&
!moduleConfig.payloadVariant.store_forward.enabled;
}
/// Draw the last text message we received
@ -468,7 +468,7 @@ static void drawNodes(OLEDDisplay *display, int16_t x, int16_t y, NodeStatus *no
// Draw GPS status summary
static void drawGPS(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus *gps)
{
if (radioConfig.preferences.fixed_position) {
if (config.payloadVariant.position.fixed_position) {
// GPS coordinates are currently fixed
display->drawString(x - 1, y - 2, "Fixed GPS");
return;
@ -507,10 +507,10 @@ static void drawGPS(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus
static void drawGPSAltitude(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus *gps)
{
String displayLine = "";
if (!gps->getIsConnected() && !radioConfig.preferences.fixed_position) {
if (!gps->getIsConnected() && !config.payloadVariant.position.fixed_position) {
// displayLine = "No GPS Module";
// display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(displayLine))) / 2, y, displayLine);
} else if (!gps->getHasLock() && !radioConfig.preferences.fixed_position) {
} else if (!gps->getHasLock() && !config.payloadVariant.position.fixed_position) {
// displayLine = "No GPS Lock";
// display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(displayLine))) / 2, y, displayLine);
} else {
@ -523,32 +523,32 @@ static void drawGPSAltitude(OLEDDisplay *display, int16_t x, int16_t y, const GP
// Draw GPS status coordinates
static void drawGPScoordinates(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus *gps)
{
auto gpsFormat = radioConfig.preferences.gps_format;
auto gpsFormat = config.payloadVariant.display.gps_format;
String displayLine = "";
if (!gps->getIsConnected() && !radioConfig.preferences.fixed_position) {
if (!gps->getIsConnected() && !config.payloadVariant.position.fixed_position) {
displayLine = "No GPS Module";
display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(displayLine))) / 2, y, displayLine);
} else if (!gps->getHasLock() && !radioConfig.preferences.fixed_position) {
} else if (!gps->getHasLock() && !config.payloadVariant.position.fixed_position) {
displayLine = "No GPS Lock";
display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(displayLine))) / 2, y, displayLine);
} else {
if (gpsFormat != GpsCoordinateFormat_GpsFormatDMS) {
if (gpsFormat != Config_DisplayConfig_GpsCoordinateFormat_GpsFormatDMS) {
char coordinateLine[22];
geoCoord.updateCoords(int32_t(gps->getLatitude()), int32_t(gps->getLongitude()), int32_t(gps->getAltitude()));
if (gpsFormat == GpsCoordinateFormat_GpsFormatDec) { // Decimal Degrees
if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_GpsFormatDec) { // Decimal Degrees
sprintf(coordinateLine, "%f %f", geoCoord.getLatitude() * 1e-7, geoCoord.getLongitude() * 1e-7);
} else if (gpsFormat == GpsCoordinateFormat_GpsFormatUTM) { // Universal Transverse Mercator
} else if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_GpsFormatUTM) { // Universal Transverse Mercator
sprintf(coordinateLine, "%2i%1c %06u %07u", geoCoord.getUTMZone(), geoCoord.getUTMBand(),
geoCoord.getUTMEasting(), geoCoord.getUTMNorthing());
} else if (gpsFormat == GpsCoordinateFormat_GpsFormatMGRS) { // Military Grid Reference System
} else if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_GpsFormatMGRS) { // Military Grid Reference System
sprintf(coordinateLine, "%2i%1c %1c%1c %05u %05u", geoCoord.getMGRSZone(), geoCoord.getMGRSBand(),
geoCoord.getMGRSEast100k(), geoCoord.getMGRSNorth100k(), geoCoord.getMGRSEasting(),
geoCoord.getMGRSNorthing());
} else if (gpsFormat == GpsCoordinateFormat_GpsFormatOLC) { // Open Location Code
} else if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_GpsFormatOLC) { // Open Location Code
geoCoord.getOLCCode(coordinateLine);
} else if (gpsFormat == GpsCoordinateFormat_GpsFormatOSGR) { // Ordnance Survey Grid Reference
} else if (gpsFormat == Config_DisplayConfig_GpsCoordinateFormat_GpsFormatOSGR) { // Ordnance Survey Grid Reference
if (geoCoord.getOSGRE100k() == 'I' || geoCoord.getOSGRN100k() == 'I') // OSGR is only valid around the UK region
sprintf(coordinateLine, "%s", "Out of Boundary");
else
@ -557,7 +557,7 @@ static void drawGPScoordinates(OLEDDisplay *display, int16_t x, int16_t y, const
}
// If fixed position, display text "Fixed GPS" alternating with the coordinates.
if (radioConfig.preferences.fixed_position) {
if (config.payloadVariant.position.fixed_position) {
if ((millis() / 10000) % 2) {
display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(coordinateLine))) / 2, y, coordinateLine);
} else {
@ -994,7 +994,7 @@ int32_t Screen::runOnce()
}
#ifndef DISABLE_WELCOME_UNSET
if (showingNormalScreen && radioConfig.preferences.region == RegionCode_Unset) {
if (showingNormalScreen && config.payloadVariant.lora.region == Config_LoRaConfig_RegionCode_Unset) {
setWelcomeFrames();
}
#endif
@ -1067,8 +1067,8 @@ int32_t Screen::runOnce()
// standard screen switching is stopped.
if (showingNormalScreen) {
// standard screen loop handling here
if (radioConfig.preferences.auto_screen_carousel_secs > 0 &&
(millis() - lastScreenTransition) > (radioConfig.preferences.auto_screen_carousel_secs * 1000)) {
if (config.payloadVariant.display.auto_screen_carousel_secs > 0 &&
(millis() - lastScreenTransition) > (config.payloadVariant.display.auto_screen_carousel_secs * 1000)) {
DEBUG_MSG("LastScreenTransition exceeded %ums transitioning to next frame\n", (millis() - lastScreenTransition));
handleOnPress();
}
@ -1343,8 +1343,8 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
#ifdef HAS_WIFI
const char *wifiName = radioConfig.preferences.wifi_ssid;
const char *wifiPsw = radioConfig.preferences.wifi_password;
const char *wifiName = config.payloadVariant.wifi.ssid;
const char *wifiPsw = config.payloadVariant.wifi.psk;
displayedNodeNum = 0; // Not currently showing a node pane
@ -1355,7 +1355,7 @@ void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, i
if (isSoftAPForced()) {
display->drawString(x, y, String("WiFi: Software AP (Admin)"));
} else if (radioConfig.preferences.wifi_ap_mode) {
} else if (config.payloadVariant.wifi.ap_mode) {
display->drawString(x, y, String("WiFi: Software AP"));
} else if (WiFi.status() != WL_CONNECTED) {
display->drawString(x, y, String("WiFi: Not Connected"));
@ -1378,8 +1378,8 @@ void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, i
- WL_NO_SHIELD: assigned when no WiFi shield is present;
*/
if (WiFi.status() == WL_CONNECTED || isSoftAPForced() || radioConfig.preferences.wifi_ap_mode) {
if (radioConfig.preferences.wifi_ap_mode || isSoftAPForced()) {
if (WiFi.status() == WL_CONNECTED || isSoftAPForced() || config.payloadVariant.wifi.ap_mode) {
if (config.payloadVariant.wifi.ap_mode || isSoftAPForced()) {
display->drawString(x, y + FONT_HEIGHT_SMALL * 1, "IP: " + String(WiFi.softAPIP().toString().c_str()));
// Number of connections to the AP. Default max for the esp32 is 4
@ -1471,7 +1471,7 @@ void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, i
}
} else {
if (radioConfig.preferences.wifi_ap_mode) {
if (config.payloadVariant.wifi.ap_mode) {
if ((millis() / 10000) % 2) {
display->drawString(x, y + FONT_HEIGHT_SMALL * 2, "SSID: " + String(wifiName));
} else {
@ -1518,28 +1518,28 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat
auto mode = "";
Config_LoRaConfig &loraConfig = config.payloadVariant.lora_config;
Config_LoRaConfig &loraConfig = config.payloadVariant.lora;
switch (loraConfig.modem_config) {
case Config_LoRaConfig_ModemConfig_ShortSlow:
switch (loraConfig.modem_preset) {
case Config_LoRaConfig_ModemPreset_ShortSlow:
mode = "ShortSlow";
break;
case Config_LoRaConfig_ModemConfig_ShortFast:
case Config_LoRaConfig_ModemPreset_ShortFast:
mode = "ShortFast";
break;
case Config_LoRaConfig_ModemConfig_MidSlow:
case Config_LoRaConfig_ModemPreset_MidSlow:
mode = "MediumSlow";
break;
case Config_LoRaConfig_ModemConfig_MidFast:
case Config_LoRaConfig_ModemPreset_MidFast:
mode = "MediumFast";
break;
case Config_LoRaConfig_ModemConfig_LongFast:
case Config_LoRaConfig_ModemPreset_LongFast:
mode = "LongFast";
break;
case Config_LoRaConfig_ModemConfig_LongSlow:
case Config_LoRaConfig_ModemPreset_LongSlow:
mode = "LongSlow";
break;
case Config_LoRaConfig_ModemConfig_VLongSlow:
case Config_LoRaConfig_ModemPreset_VLongSlow:
mode = "VLongSlow";
break;
default:
@ -1597,7 +1597,8 @@ void DebugInfo::drawFrameSettings(OLEDDisplay *display, OLEDDisplayUiState *stat
display->drawString(x + SCREEN_WIDTH - display->getStringWidth(chUtil), y + FONT_HEIGHT_SMALL * 1, chUtil);
// Line 3
if (radioConfig.preferences.gps_format != GpsCoordinateFormat_GpsFormatDMS) // if DMS then don't draw altitude
if (config.payloadVariant.display.gps_format !=
Config_DisplayConfig_GpsCoordinateFormat_GpsFormatDMS) // if DMS then don't draw altitude
drawGPSAltitude(display, x, y + FONT_HEIGHT_SMALL * 2, gpsStatus);
// Line 4

Wyświetl plik

@ -1,17 +1,14 @@
#include "configuration.h"
#include "RotaryEncoderInterruptBase.h"
#include "configuration.h"
RotaryEncoderInterruptBase::RotaryEncoderInterruptBase(
const char *name) :
concurrency::OSThread(name)
RotaryEncoderInterruptBase::RotaryEncoderInterruptBase(const char *name) : concurrency::OSThread(name)
{
this->_originName = name;
}
void RotaryEncoderInterruptBase::init(
uint8_t pinA, uint8_t pinB, uint8_t pinPress,
char eventCw, char eventCcw, char eventPressed,
// std::function<void(void)> onIntA, std::function<void(void)> onIntB, std::function<void(void)> onIntPress) :
uint8_t pinA, uint8_t pinB, uint8_t pinPress, char eventCw, char eventCcw, char eventPressed,
// std::function<void(void)> onIntA, std::function<void(void)> onIntB, std::function<void(void)> onIntPress) :
void (*onIntA)(), void (*onIntB)(), void (*onIntPress)())
{
this->_pinA = pinA;
@ -24,42 +21,34 @@ void RotaryEncoderInterruptBase::init(
pinMode(this->_pinA, INPUT_PULLUP);
pinMode(this->_pinB, INPUT_PULLUP);
// attachInterrupt(pinPress, onIntPress, RISING);
// attachInterrupt(pinPress, onIntPress, RISING);
attachInterrupt(pinPress, onIntPress, RISING);
attachInterrupt(this->_pinA, onIntA, CHANGE);
attachInterrupt(this->_pinB, onIntB, CHANGE);
this->rotaryLevelA = digitalRead(this->_pinA);
this->rotaryLevelB = digitalRead(this->_pinB);
DEBUG_MSG("Rotary initialized (%d, %d, %d)\n",
this->_pinA, this->_pinB, pinPress);
DEBUG_MSG("Rotary initialized (%d, %d, %d)\n", this->_pinA, this->_pinB, pinPress);
}
int32_t RotaryEncoderInterruptBase::runOnce()
{
InputEvent e;
e.inputEvent = InputEventChar_KEY_NONE;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE;
e.source = this->_originName;
if (this->action == ROTARY_ACTION_PRESSED)
{
if (this->action == ROTARY_ACTION_PRESSED) {
DEBUG_MSG("Rotary event Press\n");
e.inputEvent = this->_eventPressed;
}
else if (this->action == ROTARY_ACTION_CW)
{
} else if (this->action == ROTARY_ACTION_CW) {
DEBUG_MSG("Rotary event CW\n");
e.inputEvent = this->_eventCw;
}
else if (this->action == ROTARY_ACTION_CCW)
{
} else if (this->action == ROTARY_ACTION_CCW) {
DEBUG_MSG("Rotary event CCW\n");
e.inputEvent = this->_eventCcw;
}
if (e.inputEvent != InputEventChar_KEY_NONE)
{
if (e.inputEvent != ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE) {
this->notifyObservers(&e);
}
@ -68,7 +57,6 @@ int32_t RotaryEncoderInterruptBase::runOnce()
return 30000; // TODO: technically this can be MAX_INT
}
void RotaryEncoderInterruptBase::intPressHandler()
{
this->action = ROTARY_ACTION_PRESSED;
@ -79,66 +67,47 @@ void RotaryEncoderInterruptBase::intAHandler()
{
// CW rotation (at least on most common rotary encoders)
int currentLevelA = digitalRead(this->_pinA);
if (this->rotaryLevelA == currentLevelA)
{
if (this->rotaryLevelA == currentLevelA) {
return;
}
this->rotaryLevelA = currentLevelA;
this->rotaryStateCCW = intHandler(
currentLevelA == HIGH,
this->rotaryLevelB,
ROTARY_ACTION_CCW,
this->rotaryStateCCW);
this->rotaryStateCCW = intHandler(currentLevelA == HIGH, this->rotaryLevelB, ROTARY_ACTION_CCW, this->rotaryStateCCW);
}
void RotaryEncoderInterruptBase::intBHandler()
{
// CW rotation (at least on most common rotary encoders)
int currentLevelB = digitalRead(this->_pinB);
if (this->rotaryLevelB == currentLevelB)
{
if (this->rotaryLevelB == currentLevelB) {
return;
}
this->rotaryLevelB = currentLevelB;
this->rotaryStateCW = intHandler(
currentLevelB == HIGH,
this->rotaryLevelA,
ROTARY_ACTION_CW,
this->rotaryStateCW);
this->rotaryStateCW = intHandler(currentLevelB == HIGH, this->rotaryLevelA, ROTARY_ACTION_CW, this->rotaryStateCW);
}
/**
* @brief Rotary action implementation.
* We assume, the following pin setup:
* A --||
* GND --||]========
* GND --||]========
* B --||
*
*
* @return The new state for rotary pin.
*/
RotaryEncoderInterruptBaseStateType RotaryEncoderInterruptBase::intHandler(
bool actualPinRaising,
int otherPinLevel,
RotaryEncoderInterruptBaseActionType action,
RotaryEncoderInterruptBaseStateType state)
RotaryEncoderInterruptBaseStateType RotaryEncoderInterruptBase::intHandler(bool actualPinRaising, int otherPinLevel,
RotaryEncoderInterruptBaseActionType action,
RotaryEncoderInterruptBaseStateType state)
{
RotaryEncoderInterruptBaseStateType newState =
state;
if (actualPinRaising && (otherPinLevel == LOW))
{
if (state == ROTARY_EVENT_CLEARED)
{
RotaryEncoderInterruptBaseStateType newState = state;
if (actualPinRaising && (otherPinLevel == LOW)) {
if (state == ROTARY_EVENT_CLEARED) {
newState = ROTARY_EVENT_OCCURRED;
if ((this->action != ROTARY_ACTION_PRESSED)
&& (this->action != action))
{
if ((this->action != ROTARY_ACTION_PRESSED) && (this->action != action)) {
this->action = action;
DEBUG_MSG("Rotary action\n");
}
}
}
else if (!actualPinRaising && (otherPinLevel == HIGH))
{
} else if (!actualPinRaising && (otherPinLevel == HIGH)) {
// Logic to prevent bouncing.
newState = ROTARY_EVENT_CLEARED;
}

Wyświetl plik

@ -1,45 +1,28 @@
#pragma once
#include "SinglePortModule.h" // TODO: what header file to include?
#include "InputBroker.h"
#include "SinglePortModule.h" // TODO: what header file to include?
enum RotaryEncoderInterruptBaseStateType
{
ROTARY_EVENT_OCCURRED,
ROTARY_EVENT_CLEARED
};
enum RotaryEncoderInterruptBaseStateType { ROTARY_EVENT_OCCURRED, ROTARY_EVENT_CLEARED };
enum RotaryEncoderInterruptBaseActionType
{
ROTARY_ACTION_NONE,
ROTARY_ACTION_PRESSED,
ROTARY_ACTION_CW,
ROTARY_ACTION_CCW
};
enum RotaryEncoderInterruptBaseActionType { ROTARY_ACTION_NONE, ROTARY_ACTION_PRESSED, ROTARY_ACTION_CW, ROTARY_ACTION_CCW };
class RotaryEncoderInterruptBase :
public Observable<const InputEvent *>,
private concurrency::OSThread
class RotaryEncoderInterruptBase : public Observable<const InputEvent *>, private concurrency::OSThread
{
public:
explicit RotaryEncoderInterruptBase(
const char *name);
void init(
uint8_t pinA, uint8_t pinB, uint8_t pinPress,
char eventCw, char eventCcw, char eventPressed,
// std::function<void(void)> onIntA, std::function<void(void)> onIntB, std::function<void(void)> onIntPress);
void (*onIntA)(), void (*onIntB)(), void (*onIntPress)());
explicit RotaryEncoderInterruptBase(const char *name);
void init(uint8_t pinA, uint8_t pinB, uint8_t pinPress, char eventCw, char eventCcw, char eventPressed,
// std::function<void(void)> onIntA, std::function<void(void)> onIntB, std::function<void(void)> onIntPress);
void (*onIntA)(), void (*onIntB)(), void (*onIntPress)());
void intPressHandler();
void intAHandler();
void intBHandler();
protected:
virtual int32_t runOnce() override;
RotaryEncoderInterruptBaseStateType intHandler(
bool actualPinRaising,
int otherPinLevel,
RotaryEncoderInterruptBaseActionType action,
RotaryEncoderInterruptBaseStateType state);
RotaryEncoderInterruptBaseStateType intHandler(bool actualPinRaising, int otherPinLevel,
RotaryEncoderInterruptBaseActionType action,
RotaryEncoderInterruptBaseStateType state);
volatile RotaryEncoderInterruptBaseStateType rotaryStateCW = ROTARY_EVENT_CLEARED;
volatile RotaryEncoderInterruptBaseStateType rotaryStateCCW = ROTARY_EVENT_CLEARED;
@ -50,8 +33,8 @@ class RotaryEncoderInterruptBase :
private:
uint8_t _pinA = 0;
uint8_t _pinB = 0;
char _eventCw = InputEventChar_KEY_NONE;
char _eventCcw = InputEventChar_KEY_NONE;
char _eventPressed = InputEventChar_KEY_NONE;
char _eventCw = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE;
char _eventCcw = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE;
char _eventPressed = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE;
const char *_originName;
};

Wyświetl plik

@ -3,37 +3,26 @@
RotaryEncoderInterruptImpl1 *rotaryEncoderInterruptImpl1;
RotaryEncoderInterruptImpl1::RotaryEncoderInterruptImpl1() :
RotaryEncoderInterruptBase(
"rotEnc1")
{
}
RotaryEncoderInterruptImpl1::RotaryEncoderInterruptImpl1() : RotaryEncoderInterruptBase("rotEnc1") {}
void RotaryEncoderInterruptImpl1::init()
{
if (!radioConfig.preferences.rotary1_enabled)
{
if (!moduleConfig.payloadVariant.canned_message.rotary1_enabled) {
// Input device is disabled.
return;
}
uint8_t pinA = radioConfig.preferences.inputbroker_pin_a;
uint8_t pinB = radioConfig.preferences.inputbroker_pin_b;
uint8_t pinPress = radioConfig.preferences.inputbroker_pin_press;
char eventCw =
static_cast<char>(radioConfig.preferences.inputbroker_event_cw);
char eventCcw =
static_cast<char>(radioConfig.preferences.inputbroker_event_ccw);
char eventPressed =
static_cast<char>(radioConfig.preferences.inputbroker_event_press);
uint8_t pinA = moduleConfig.payloadVariant.canned_message.inputbroker_pin_a;
uint8_t pinB = moduleConfig.payloadVariant.canned_message.inputbroker_pin_b;
uint8_t pinPress = moduleConfig.payloadVariant.canned_message.inputbroker_pin_press;
char eventCw = static_cast<char>(moduleConfig.payloadVariant.canned_message.inputbroker_event_cw);
char eventCcw = static_cast<char>(moduleConfig.payloadVariant.canned_message.inputbroker_event_ccw);
char eventPressed = static_cast<char>(moduleConfig.payloadVariant.canned_message.inputbroker_event_press);
//radioConfig.preferences.ext_notification_module_output
RotaryEncoderInterruptBase::init(
pinA, pinB, pinPress,
eventCw, eventCcw, eventPressed,
RotaryEncoderInterruptImpl1::handleIntA,
RotaryEncoderInterruptImpl1::handleIntB,
RotaryEncoderInterruptImpl1::handleIntPressed);
// moduleConfig.payloadVariant.canned_message.ext_notification_module_output
RotaryEncoderInterruptBase::init(pinA, pinB, pinPress, eventCw, eventCcw, eventPressed,
RotaryEncoderInterruptImpl1::handleIntA, RotaryEncoderInterruptImpl1::handleIntB,
RotaryEncoderInterruptImpl1::handleIntPressed);
inputBroker->registerSource(this);
}

Wyświetl plik

@ -1,18 +1,14 @@
#pragma once
#include "SinglePortModule.h" // TODO: what header file to include?
#include "InputBroker.h"
#include "SinglePortModule.h" // TODO: what header file to include?
class UpDownInterruptBase :
public Observable<const InputEvent *>
class UpDownInterruptBase : public Observable<const InputEvent *>
{
public:
explicit UpDownInterruptBase(
const char *name);
void init(
uint8_t pinDown, uint8_t pinUp, uint8_t pinPress,
char eventDown, char eventUp, char eventPressed,
void (*onIntDown)(), void (*onIntUp)(), void (*onIntPress)());
explicit UpDownInterruptBase(const char *name);
void init(uint8_t pinDown, uint8_t pinUp, uint8_t pinPress, char eventDown, char eventUp, char eventPressed,
void (*onIntDown)(), void (*onIntUp)(), void (*onIntPress)());
void intPressHandler();
void intDownHandler();
void intUpHandler();
@ -20,8 +16,8 @@ class UpDownInterruptBase :
private:
uint8_t _pinDown = 0;
uint8_t _pinUp = 0;
char _eventDown = InputEventChar_KEY_NONE;
char _eventUp = InputEventChar_KEY_NONE;
char _eventPressed = InputEventChar_KEY_NONE;
char _eventDown = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE;
char _eventUp = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE;
char _eventPressed = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE;
const char *_originName;
};

Wyświetl plik

@ -3,38 +3,26 @@
UpDownInterruptImpl1 *upDownInterruptImpl1;
UpDownInterruptImpl1::UpDownInterruptImpl1() :
UpDownInterruptBase(
"upDown1")
{
}
UpDownInterruptImpl1::UpDownInterruptImpl1() : UpDownInterruptBase("upDown1") {}
void UpDownInterruptImpl1::init()
{
if (!radioConfig.preferences.updown1_enabled)
{
if (!moduleConfig.payloadVariant.canned_message.updown1_enabled) {
// Input device is disabled.
return;
}
uint8_t pinUp = radioConfig.preferences.inputbroker_pin_a;
uint8_t pinDown = radioConfig.preferences.inputbroker_pin_b;
uint8_t pinPress = radioConfig.preferences.inputbroker_pin_press;
uint8_t pinUp = moduleConfig.payloadVariant.canned_message.inputbroker_pin_a;
uint8_t pinDown = moduleConfig.payloadVariant.canned_message.inputbroker_pin_b;
uint8_t pinPress = moduleConfig.payloadVariant.canned_message.inputbroker_pin_press;
char eventDown =
static_cast<char>(InputEventChar_KEY_DOWN);
char eventUp =
static_cast<char>(InputEventChar_KEY_UP);
char eventPressed =
static_cast<char>(InputEventChar_KEY_SELECT);
char eventDown = static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_KEY_DOWN);
char eventUp = static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_KEY_UP);
char eventPressed = static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_KEY_SELECT);
UpDownInterruptBase::init(
pinDown, pinUp, pinPress,
eventDown, eventUp, eventPressed,
UpDownInterruptImpl1::handleIntDown,
UpDownInterruptImpl1::handleIntUp,
UpDownInterruptImpl1::handleIntPressed);
UpDownInterruptBase::init(pinDown, pinUp, pinPress, eventDown, eventUp, eventPressed, UpDownInterruptImpl1::handleIntDown,
UpDownInterruptImpl1::handleIntUp, UpDownInterruptImpl1::handleIntPressed);
inputBroker->registerSource(this);
}

Wyświetl plik

@ -1,5 +1,5 @@
#include "configuration.h"
#include "kbI2cBase.h"
#include "configuration.h"
#include <Wire.h>
KbI2cBase::KbI2cBase(const char *name) : concurrency::OSThread(name)
@ -10,40 +10,39 @@ KbI2cBase::KbI2cBase(const char *name) : concurrency::OSThread(name)
int32_t KbI2cBase::runOnce()
{
InputEvent e;
e.inputEvent = InputEventChar_KEY_NONE;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE;
e.source = this->_originName;
Wire.requestFrom(CARDKB_ADDR, 1);
while(Wire.available()) {
while (Wire.available()) {
char c = Wire.read();
switch(c) {
switch (c) {
case 0x1b: // ESC
e.inputEvent = InputEventChar_KEY_CANCEL;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_CANCEL;
break;
case 0x08: // Back
e.inputEvent = InputEventChar_KEY_BACK;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_BACK;
break;
case 0xb5: // Up
e.inputEvent = InputEventChar_KEY_UP;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_UP;
break;
case 0xb6: // Down
e.inputEvent = InputEventChar_KEY_DOWN;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_DOWN;
break;
case 0xb4: // Left
e.inputEvent = InputEventChar_KEY_LEFT;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_LEFT;
break;
case 0xb7: // Right
e.inputEvent = InputEventChar_KEY_RIGHT;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_RIGHT;
break;
case 0x0d: // Enter
e.inputEvent = InputEventChar_KEY_SELECT;
e.inputEvent = ModuleConfig_CannedMessageConfig_InputEventChar_KEY_SELECT;
break;
}
}
if (e.inputEvent != InputEventChar_KEY_NONE)
{
if (e.inputEvent != ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE) {
this->notifyObservers(&e);
}
return 500;

Wyświetl plik

@ -1,4 +1,3 @@
#include "configuration.h"
#include "GPS.h"
#include "MeshRadio.h"
#include "MeshService.h"
@ -6,6 +5,7 @@
#include "PowerFSM.h"
#include "airtime.h"
#include "buzz.h"
#include "configuration.h"
#include "error.h"
#include "power.h"
// #include "rom/rtc.h"
@ -17,28 +17,28 @@
#include "SPILock.h"
#include "concurrency/OSThread.h"
#include "concurrency/Periodic.h"
#include "debug/axpDebug.h"
#include "debug/einkScan.h"
#include "debug/i2cScan.h"
#include "graphics/Screen.h"
#include "main.h"
#include "modules/Modules.h"
#include "sleep.h"
#include "shutdown.h"
#include "sleep.h"
#include "target_specific.h"
#include "debug/i2cScan.h"
#include "debug/einkScan.h"
#include "debug/axpDebug.h"
#include <Wire.h>
// #include <driver/rtc_io.h>
#include "mesh/http/WiFiAPClient.h"
#ifndef NO_ESP32
#include "mesh/http/WebServer.h"
#include "mesh/http/WebServer.h"
#ifdef USE_NEW_ESP32_BLUETOOTH
#include "esp32/ESP32Bluetooth.h"
#else
#include "nimble/BluetoothUtil.h"
#endif
#ifdef USE_NEW_ESP32_BLUETOOTH
#include "esp32/ESP32Bluetooth.h"
#else
#include "nimble/BluetoothUtil.h"
#endif
#endif
@ -47,10 +47,10 @@
#include "mqtt/MQTT.h"
#endif
#include "LLCC68Interface.h"
#include "RF95Interface.h"
#include "SX1262Interface.h"
#include "SX1268Interface.h"
#include "LLCC68Interface.h"
#include "ButtonThread.h"
#include "PowerFSMThread.h"
@ -126,7 +126,8 @@ RadioInterface *rIf = NULL;
/**
* Some platforms (nrf52) might provide an alterate version that supresses calling delay from sleep.
*/
__attribute__ ((weak, noinline)) bool loopCanSleep() {
__attribute__((weak, noinline)) bool loopCanSleep()
{
return true;
}
@ -145,18 +146,18 @@ void setup()
#endif
#ifdef DEBUG_PORT
if (!radioConfig.preferences.serial_disabled) {
if (!config.payloadVariant.device.serial_disabled) {
consoleInit(); // Set serial baud rate and init our mesh console
}
#endif
serialSinceMsec = millis();
DEBUG_MSG("\n\n//\\ E S H T /\\ S T / C\n\n");
initDeepSleep();
// Testing this fix für erratic T-Echo boot behaviour
// Testing this fix für erratic T-Echo boot behaviour
#if defined(TTGO_T_ECHO) && defined(PIN_EINK_PWR_ON)
pinMode(PIN_EINK_PWR_ON, OUTPUT);
digitalWrite(PIN_EINK_PWR_ON, HIGH);
@ -201,7 +202,7 @@ void setup()
fsInit();
//router = new DSRRouter();
// router = new DSRRouter();
router = new ReliableRouter();
#ifdef I2C_SDA
@ -407,14 +408,12 @@ void setup()
if (!rIf)
RECORD_CRITICALERROR(CriticalErrorCode_NoRadio);
else{
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(Constants_DATA_PAYLOAD_LEN) / (float(rIf->getPacketTime(Constants_DATA_PAYLOAD_LEN)))) * 1000;
DEBUG_MSG("myNodeInfo.bitrate = %f bytes / sec\n", myNodeInfo.bitrate);
}
@ -426,7 +425,7 @@ void setup()
setCPUFast(false); // 80MHz is fine for our slow peripherals
}
uint32_t rebootAtMsec; // If not zero we will reboot at this time (used to reboot shortly after the update completes)
uint32_t rebootAtMsec; // If not zero we will reboot at this time (used to reboot shortly after the update completes)
uint32_t shutdownAtMsec; // If not zero we will shutdown at this time (used to shutdown from python or mobile client)
// If a thread does something that might need for it to be rescheduled ASAP it can set this flag

Wyświetl plik

@ -83,9 +83,9 @@ void Channels::initDefaultChannel(ChannelIndex chIndex)
{
Channel &ch = getByIndex(chIndex);
ChannelSettings &channelSettings = ch.settings;
Config_LoRaConfig &loraConfig = config.payloadVariant.lora_config;
Config_LoRaConfig &loraConfig = config.payloadVariant.lora;
loraConfig.modem_config = Config_LoRaConfig_ModemConfig_LongFast; // Default to Long Range & Fast
loraConfig.modem_preset = Config_LoRaConfig_ModemPreset_LongFast; // Default to Long Range & Fast
loraConfig.tx_power = 0; // default
uint8_t defaultpskIndex = 1;
@ -203,37 +203,37 @@ void Channels::setChannel(const Channel &c)
const char *Channels::getName(size_t chIndex)
{
Config_LoRaConfig &loraConfig = config.payloadVariant.lora_config;
Config_LoRaConfig &loraConfig = config.payloadVariant.lora;
// Convert the short "" representation for Default into a usable string
const ChannelSettings &channelSettings = getByIndex(chIndex).settings;
const char *channelName = channelSettings.name;
if (!*channelName) { // emptystring
// Per mesh.proto spec, if bandwidth is specified we must ignore modemConfig enum, we assume that in that case
// Per mesh.proto spec, if bandwidth is specified we must ignore modemPreset enum, we assume that in that case
// the app fucked up and forgot to set channelSettings.name
if (loraConfig.bandwidth != 0)
channelName = "Unset";
else
switch (loraConfig.modem_config) {
case Config_LoRaConfig_ModemConfig_ShortSlow:
switch (loraConfig.modem_preset) {
case Config_LoRaConfig_ModemPreset_ShortSlow:
channelName = "ShortSlow";
break;
case Config_LoRaConfig_ModemConfig_ShortFast:
case Config_LoRaConfig_ModemPreset_ShortFast:
channelName = "ShortFast";
break;
case Config_LoRaConfig_ModemConfig_MidSlow:
case Config_LoRaConfig_ModemPreset_MidSlow:
channelName = "MediumSlow";
break;
case Config_LoRaConfig_ModemConfig_MidFast:
case Config_LoRaConfig_ModemPreset_MidFast:
channelName = "MediumFast";
break;
case Config_LoRaConfig_ModemConfig_LongFast:
case Config_LoRaConfig_ModemPreset_LongFast:
channelName = "LongFast";
break;
case Config_LoRaConfig_ModemConfig_LongSlow:
case Config_LoRaConfig_ModemPreset_LongSlow:
channelName = "LongSlow";
break;
case Config_LoRaConfig_ModemConfig_VLongSlow:
case Config_LoRaConfig_ModemPreset_VLongSlow:
channelName = "VLongSlow";
break;
default:

Wyświetl plik

@ -32,7 +32,7 @@ void FloodingRouter::sniffReceived(const MeshPacket *p, const Routing *c)
if ((p->to == NODENUM_BROADCAST) && (p->hop_limit > 0) && (getFrom(p) != getNodeNum())) {
if (p->id != 0) {
if (radioConfig.preferences.role != Role_ClientMute) {
if (config.payloadVariant.device.role != Config_DeviceConfig_Role_ClientMute) {
MeshPacket *tosend = packetPool.allocCopy(*p); // keep a copy because we will be sending it
tosend->hop_limit--; // bump down the hop count

Wyświetl plik

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

Wyświetl plik

@ -181,7 +181,8 @@ void MeshService::sendNetworkPing(NodeNum dest, bool wantReplies)
}
}
void MeshService::sendToPhone(MeshPacket *p) {
void MeshService::sendToPhone(MeshPacket *p)
{
if (toPhoneQueue.numFree() == 0) {
DEBUG_MSG("NOTE: tophone queue is full, discarding oldest\n");
MeshPacket *d = toPhoneQueue.dequeuePtr(0);
@ -235,7 +236,7 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
#ifdef GPS_EXTRAVERBOSE
DEBUG_MSG("onGPSchanged() - lost validLocation\n");
#endif
if (radioConfig.preferences.fixed_position) {
if (config.payloadVariant.position.fixed_position) {
DEBUG_MSG("WARNING: Using fixed position\n");
pos = node->position;
}
@ -247,8 +248,8 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
pos.time = getValidTime(RTCQualityGPS);
// In debug logs, identify position by @timestamp:stage (stage 4 = nodeDB)
DEBUG_MSG("onGPSChanged() pos@%x, time=%u, lat=%d, lon=%d, alt=%d\n",
pos.pos_timestamp, pos.time, pos.latitude_i, pos.longitude_i, pos.altitude);
DEBUG_MSG("onGPSChanged() pos@%x, time=%u, lat=%d, lon=%d, alt=%d\n", pos.pos_timestamp, pos.time, pos.latitude_i,
pos.longitude_i, pos.altitude);
// Update our current position in the local DB
nodeDB.updatePosition(nodeDB.getNodeNum(), pos, RX_SRC_LOCAL);

Wyświetl plik

@ -34,7 +34,6 @@ NodeDB nodeDB;
// we have plenty of ram so statically alloc this tempbuf (for now)
EXT_RAM_ATTR DeviceState devicestate;
MyNodeInfo &myNodeInfo = devicestate.my_node;
RadioConfig radioConfig;
Config config;
ModuleConfig moduleConfig;
ChannelFile channelFile;
@ -88,8 +87,8 @@ bool NodeDB::resetRadioConfig()
radioGeneration++;
radioConfig.has_preferences = true;
if (radioConfig.preferences.factory_reset) {
// radioConfig.has_preferences = true;
if (config.payloadVariant.device.factory_reset) {
DEBUG_MSG("Performing factory reset!\n");
installDefaultDeviceState();
#ifndef NO_ESP32
@ -127,11 +126,11 @@ bool NodeDB::resetRadioConfig()
DEBUG_MSG("***** DEVELOPMENT MODE - DO NOT RELEASE *****\n");
// Sleep quite frequently to stress test the BLE comms, broadcast position every 6 mins
radioConfig.preferences.screen_on_secs = 10;
radioConfig.preferences.wait_bluetooth_secs = 10;
radioConfig.preferences.position_broadcast_secs = 6 * 60;
radioConfig.preferences.ls_secs = 60;
radioConfig.preferences.region = RegionCode_TW;
config.payloadVariant.display.screen_on_secs = 10;
config.payloadVariant.power.wait_bluetooth_secs = 10;
config.payloadVariant.position.position_broadcast_secs = 6 * 60;
config.payloadVariant.power.ls_secs = 60;
config.payloadVariant.lora.region = Config_LoRaConfig_RegionCode_TW;
// Enter super deep sleep soon and stay there not very long
// radioConfig.preferences.mesh_sds_timeout_secs = 10;
@ -154,15 +153,17 @@ void NodeDB::installDefaultModuleConfig()
memset(&moduleConfig, 0, sizeof(moduleConfig));
}
void NodeDB::installDefaultRadioConfig()
{
memset(&radioConfig, 0, sizeof(radioConfig));
radioConfig.has_preferences = true;
resetRadioConfig();
// void NodeDB::installDefaultRadioConfig()
// {
// memset(&radioConfig, 0, sizeof(radioConfig));
// radioConfig.has_preferences = true;
// resetRadioConfig();
// for backward compat, default position flags are BAT+ALT+MSL (0x23 = 35)
radioConfig.preferences.position_flags = (PositionFlags_POS_BATTERY | PositionFlags_POS_ALTITUDE | PositionFlags_POS_ALT_MSL);
}
// // for backward compat, default position flags are BAT+ALT+MSL (0x23 = 35)
// config.payloadVariant.position.position_flags =
// (Config_PositionConfig_PositionFlags_POS_BATTERY | Config_PositionConfig_PositionFlags_POS_ALTITUDE |
// Config_PositionConfig_PositionFlags_POS_ALT_MSL);
// }
void NodeDB::installDefaultChannels()
{
@ -173,7 +174,7 @@ void NodeDB::installDefaultDeviceState()
{
// We try to preserve the region setting because it will really bum users out if we discard it
String oldRegion = myNodeInfo.region;
RegionCode oldRegionCode = radioConfig.preferences.region;
Config_LoRaConfig_RegionCode oldRegionCode = config.payloadVariant.lora.region;
memset(&devicestate, 0, sizeof(devicestate));
@ -203,13 +204,12 @@ void NodeDB::installDefaultDeviceState()
memcpy(owner.macaddr, ourMacAddr, sizeof(owner.macaddr));
// Restore region if possible
if (oldRegionCode != RegionCode_Unset)
radioConfig.preferences.region = oldRegionCode;
if (oldRegionCode != Config_LoRaConfig_RegionCode_Unset)
config.payloadVariant.lora.region = oldRegionCode;
if (oldRegion.length()) // If the old style region was set, try to keep it up-to-date
strcpy(myNodeInfo.region, oldRegion.c_str());
installDefaultChannels();
installDefaultRadioConfig();
installDefaultConfig();
}
@ -259,7 +259,7 @@ void NodeDB::init()
resetRadioConfig(); // If bogus settings got saved, then fix them
DEBUG_MSG("region=%d, NODENUM=0x%x, dbsize=%d\n", radioConfig.preferences.region, myNodeInfo.my_node_num, *numNodes);
DEBUG_MSG("region=%d, NODENUM=0x%x, dbsize=%d\n", config.payloadVariant.lora.region, myNodeInfo.my_node_num, *numNodes);
}
// We reserve a few nodenums for future use
@ -292,7 +292,7 @@ void NodeDB::pickNewNodeNum()
static const char *preffile = "/prefs/db.proto";
static const char *radiofile = "/prefs/radio.proto";
static const char *configfile = "/prefs/config.proto";
static const char *moduleConfigfile = "/prefs/module_config.proto";
static const char *moduleConfigfile = "/prefs/module.proto";
static const char *channelfile = "/prefs/channels.proto";
/** Load a protobuf from a file, return true for success */
@ -341,10 +341,6 @@ void NodeDB::loadFromDisk()
}
}
if (!loadProto(radiofile, RadioConfig_size, sizeof(RadioConfig), RadioConfig_fields, &radioConfig)) {
installDefaultRadioConfig(); // Our in RAM copy might now be corrupt
}
if (!loadProto(configfile, Config_size, sizeof(Config), Config_fields, &config)) {
installDefaultConfig(); // Our in RAM copy might now be corrupt
}
@ -410,7 +406,6 @@ void NodeDB::saveToDisk()
FSCom.mkdir("/prefs");
#endif
saveProto(preffile, DeviceState_size, sizeof(devicestate), DeviceState_fields, &devicestate);
saveProto(radiofile, RadioConfig_size, sizeof(RadioConfig), RadioConfig_fields, &radioConfig);
saveProto(configfile, Config_size, sizeof(Config), Config_fields, &config);
saveProto(moduleConfigfile, Module_Config_size, sizeof(ModuleConfig), ModuleConfig_fields, &moduleConfig);
saveChannelsToDisk();

Wyświetl plik

@ -11,7 +11,6 @@
extern DeviceState devicestate;
extern ChannelFile channelFile;
extern MyNodeInfo &myNodeInfo;
extern RadioConfig radioConfig;
extern Config config;
extern ModuleConfig moduleConfig;
extern User &owner;
@ -124,7 +123,7 @@ class NodeDB
void loadFromDisk();
/// Reinit device state from scratch (not loading from disk)
void installDefaultDeviceState(), installDefaultRadioConfig(), installDefaultChannels(), installDefaultConfig(),
void installDefaultDeviceState(), installDefaultChannels(), installDefaultConfig(),
installDefaultModuleConfig();
};
@ -162,9 +161,16 @@ 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) ((radioConfig.preferences.role == Role_Router) ? (routerVal) : (normalVal))
#define IF_ROUTER(routerVal, normalVal) ((config.payloadVariant.device.role == Config_DeviceConfig_Role_Router) ? (routerVal) : (normalVal))
#define default_broadcast_interval_secs IF_ROUTER(12 * 60 * 60, 15 * 60)
#define default_wait_bluetooth_secs IF_ROUTER(1, 60)
#define default_mesh_sds_timeout_secs IF_ROUTER(NODE_DELAY_FOREVER, 2 * 60 * 60)
#define default_sds_secs 365 * 24 * 60 * 60
#define default_ls_secs IF_ROUTER(24 * 60 * 60, 5 * 60)
#define default_phone_timeout_secs 15 * 60
#define default_min_wake_secs 10
inline uint32_t getIntervalOrDefaultMs(uint32_t interval)
{
@ -173,31 +179,9 @@ inline uint32_t getIntervalOrDefaultMs(uint32_t interval)
return default_broadcast_interval_secs * 1000;
}
#define PREF_GET(name, defaultVal) \
inline uint32_t getPref_##name() { return radioConfig.preferences.name ? radioConfig.preferences.name : (defaultVal); }
PREF_GET(position_broadcast_secs, IF_ROUTER(12 * 60 * 60, 15 * 60))
// Each time we wake into the DARK state allow 1 minute to send and receive BLE packets to the phone
PREF_GET(wait_bluetooth_secs, IF_ROUTER(1, 60))
PREF_GET(screen_on_secs, 60)
PREF_GET(mesh_sds_timeout_secs, IF_ROUTER(NODE_DELAY_FOREVER, 2 * 60 * 60))
PREF_GET(sds_secs, 365 * 24 * 60 * 60)
// We default to sleeping (with bluetooth off for 5 minutes at a time). This seems to be a good tradeoff between
// latency for the user sending messages and power savings because of not having to run (expensive) ESP32 bluetooth
PREF_GET(ls_secs, IF_ROUTER(24 * 60 * 60, 5 * 60))
PREF_GET(phone_timeout_secs, 15 * 60)
PREF_GET(min_wake_secs, 10)
/** 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.
*/
extern uint32_t radioGeneration;
// Config doesn't have a nanopb generated full size constant
#define Config_size (Config_DeviceConfig_size + Config_DisplayConfig_size + Config_GpsConfig_size + Config_LoRaConfig_size + Config_PowerConfig_size)
#define Module_Config_size (Config_ModuleConfig_CannedMessageConfig_size + Config_ModuleConfig_ExternalNotificationConfig_size + Config_ModuleConfig_MQTTConfig_size + Config_ModuleConfig_RangeTestConfig_size + Config_ModuleConfig_SerialConfig_size + Config_ModuleConfig_StoreForwardConfig_size + Config_ModuleConfig_TelemetryConfig_size + Config_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)

Wyświetl plik

@ -13,7 +13,8 @@
#define RDEF(name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, frequency_switching) \
{ \
RegionCode_##name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, frequency_switching, #name \
Config_LoRaConfig_RegionCode_##name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, \
frequency_switching, #name \
}
const RegionInfo regions[] = {
@ -99,10 +100,10 @@ const RegionInfo *myRegion;
void initRegion()
{
const RegionInfo *r = regions;
for (; r->code != RegionCode_Unset && r->code != radioConfig.preferences.region; r++)
for (; r->code != Config_LoRaConfig_RegionCode_Unset && r->code != config.payloadVariant.lora.region; r++)
;
myRegion = r;
DEBUG_MSG("Wanted region %d, using %s\n", radioConfig.preferences.region, r->name);
DEBUG_MSG("Wanted region %d, using %s\n", config.payloadVariant.lora.region, r->name);
}
/**
@ -201,7 +202,8 @@ uint32_t RadioInterface::getTxDelayMsecWeighted(float snr)
// low SNR = Short Delay
uint32_t delay = 0;
if (radioConfig.preferences.role == Role_Router || radioConfig.preferences.role == Role_RouterClient) {
if (config.payloadVariant.device.role == Config_DeviceConfig_Role_Router ||
config.payloadVariant.device.role == Config_DeviceConfig_Role_RouterClient) {
delay = map(snr, SNR_MIN, SNR_MAX, MIN_TX_WAIT_MSEC, (MIN_TX_WAIT_MSEC + (shortPacketMsec / 2)));
DEBUG_MSG("rx_snr found in packet. As a router, setting tx delay:%d\n", delay);
} else {
@ -349,41 +351,41 @@ void RadioInterface::applyModemConfig()
{
// Set up default configuration
// No Sync Words in LORA mode
Config_LoRaConfig &loraConfig = config.payloadVariant.lora_config;
Config_LoRaConfig &loraConfig = config.payloadVariant.lora;
auto channelSettings = channels.getPrimary();
if (loraConfig.spread_factor == 0) {
switch (loraConfig.modem_config) {
case Config_LoRaConfig_ModemConfig_ShortFast:
switch (loraConfig.modem_preset) {
case Config_LoRaConfig_ModemPreset_ShortFast:
bw = 250;
cr = 8;
sf = 7;
break;
case Config_LoRaConfig_ModemConfig_ShortSlow:
case Config_LoRaConfig_ModemPreset_ShortSlow:
bw = 250;
cr = 8;
sf = 8;
break;
case Config_LoRaConfig_ModemConfig_MidFast:
case Config_LoRaConfig_ModemPreset_MidFast:
bw = 250;
cr = 8;
sf = 9;
break;
case Config_LoRaConfig_ModemConfig_MidSlow:
case Config_LoRaConfig_ModemPreset_MidSlow:
bw = 250;
cr = 8;
sf = 10;
break;
case Config_LoRaConfig_ModemConfig_LongFast:
case Config_LoRaConfig_ModemPreset_LongFast:
bw = 250;
cr = 8;
sf = 11;
break;
case Config_LoRaConfig_ModemConfig_LongSlow:
case Config_LoRaConfig_ModemPreset_LongSlow:
bw = 125;
cr = 8;
sf = 12;
break;
case Config_LoRaConfig_ModemConfig_VLongSlow:
case Config_LoRaConfig_ModemPreset_VLongSlow:
bw = 31.25;
cr = 8;
sf = 12;
@ -417,7 +419,7 @@ void RadioInterface::applyModemConfig()
saveChannelNum(channel_num);
saveFreq(freq);
DEBUG_MSG("Set radio: name=%s, config=%u, ch=%d, power=%d\n", channelName, loraConfig.modem_config, channel_num, power);
DEBUG_MSG("Set radio: name=%s, config=%u, ch=%d, power=%d\n", channelName, loraConfig.modem_preset, channel_num, power);
DEBUG_MSG("Radio myRegion->freqStart / myRegion->freqEnd: %f -> %f (%f mhz)\n", myRegion->freqStart, myRegion->freqEnd,
myRegion->freqEnd - myRegion->freqStart);
DEBUG_MSG("Radio myRegion->numChannels: %d\n", numChannels);

Wyświetl plik

@ -93,8 +93,8 @@ bool RadioLibInterface::canSendImmediately()
/// bluetooth comms code. If the txmit queue is empty it might return an error
ErrorCode RadioLibInterface::send(MeshPacket *p)
{
if (radioConfig.preferences.region != RegionCode_Unset) {
if (disabled || radioConfig.preferences.is_lora_tx_disabled) {
if (config.payloadVariant.lora.region != Config_LoRaConfig_RegionCode_Unset) {
if (disabled || config.payloadVariant.lora.tx_disabled) {
DEBUG_MSG("send - lora_tx_disabled\n");
packetPool.release(p);
return ERRNO_DISABLED;
@ -121,7 +121,7 @@ ErrorCode RadioLibInterface::send(MeshPacket *p)
// set (random) transmit delay to let others reconfigure their radio,
// to avoid collisions and implement timing-based flooding
// DEBUG_MSG("Set random delay before transmitting.\n");
setTransmitDelay();
setTransmitDelay();
return res;
#else
@ -154,10 +154,10 @@ bool RadioLibInterface::cancelSending(NodeNum from, PacketId id)
/** radio helper thread callback.
We never immediately transmit after any operation (either rx or tx). Instead we should start receiving and
wait a random delay of 100ms to 100ms+shortPacketMsec to make sure we are not stomping on someone else. The 100ms delay at the beginning ensures all
possible listeners have had time to finish processing the previous packet and now have their radio in RX state. The up to 100ms+shortPacketMsec
random delay gives a chance for all possible senders to have high odds of detecting that someone else started transmitting first
and then they will wait until that packet finishes.
wait a random delay of 100ms to 100ms+shortPacketMsec to make sure we are not stomping on someone else. The 100ms delay at the
beginning ensures all possible listeners have had time to finish processing the previous packet and now have their radio in RX
state. The up to 100ms+shortPacketMsec random delay gives a chance for all possible senders to have high odds of detecting that
someone else started transmitting first and then they will wait until that packet finishes.
NOTE: the large flood rebroadcast delay might still be needed even with this approach. Because we might not be able to hear other
transmitters that we are potentially stomping on. Requires further thought.
@ -215,7 +215,7 @@ void RadioLibInterface::onNotify(uint32_t notification)
void RadioLibInterface::setTransmitDelay()
{
MeshPacket *p = txQueue.getFront();
// We want all sending/receiving to be done by our daemon thread.
// 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.
@ -345,7 +345,7 @@ void RadioLibInterface::handleReceiveInterrupt()
void RadioLibInterface::startSend(MeshPacket *txp)
{
printPacket("Starting low level send", txp);
if (disabled || radioConfig.preferences.is_lora_tx_disabled) {
if (disabled || config.payloadVariant.lora.tx_disabled) {
DEBUG_MSG("startSend is dropping tx packet because we are disabled\n");
packetPool.release(txp);
} else {

Wyświetl plik

@ -1,7 +1,7 @@
#include "configuration.h"
#include "ReliableRouter.h"
#include "MeshModule.h"
#include "MeshTypes.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
// ReliableRouter::ReliableRouter() {}
@ -14,11 +14,11 @@ ErrorCode ReliableRouter::send(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
// message will rebroadcast. But asking for hop_limit 0 in that context means the client app has no preference on hop counts
// and we want this message to get through the whole mesh, so use the default.
// message will rebroadcast. But asking for hop_limit 0 in that context means the client app has no preference on hop
// counts and we want this message to get through the whole mesh, so use the default.
if (p->to == NODENUM_BROADCAST && p->hop_limit == 0) {
if (radioConfig.preferences.hop_limit && radioConfig.preferences.hop_limit <= HOP_MAX) {
p->hop_limit = (radioConfig.preferences.hop_limit >= HOP_MAX) ? HOP_MAX : radioConfig.preferences.hop_limit;
if (config.payloadVariant.lora.hop_limit && config.payloadVariant.lora.hop_limit <= HOP_MAX) {
p->hop_limit = (config.payloadVariant.lora.hop_limit >= HOP_MAX) ? HOP_MAX : config.payloadVariant.lora.hop_limit;
} else {
p->hop_limit = HOP_RELIABLE;
}
@ -41,9 +41,9 @@ bool ReliableRouter::shouldFilterReceived(MeshPacket *p)
// If this is the first time we saw this, cancel any retransmissions we have queued up and generate an internal ack for
// the original sending process.
// FIXME - we might want to turn off this "optimization", it does save lots of airtime but it assumes that once we've heard one
// one adjacent node hear our packet that a) probably other adjacent nodes heard it and b) we can trust those nodes to reach
// our destination. Both of which might be incorrect.
// FIXME - we might want to turn off this "optimization", it does save lots of airtime but it assumes that once we've
// heard one one adjacent node hear our packet that a) probably other adjacent nodes heard it and b) we can trust those
// nodes to reach our destination. Both of which might be incorrect.
auto key = GlobalPacketId(getFrom(p), p->id);
auto old = findPendingPacket(key);
if (old) {
@ -53,8 +53,7 @@ bool ReliableRouter::shouldFilterReceived(MeshPacket *p)
sendAckNak(Routing_Error_NONE, getFrom(p), p->id, old->packet->channel);
stopRetransmission(key);
}
else {
} else {
DEBUG_MSG("didn't find pending packet\n");
}
}

Wyświetl plik

@ -118,8 +118,8 @@ MeshPacket *Router::allocForSending()
p->which_payloadVariant = MeshPacket_decoded_tag; // Assume payload is decoded at start.
p->from = nodeDB.getNodeNum();
p->to = NODENUM_BROADCAST;
if (radioConfig.preferences.hop_limit && radioConfig.preferences.hop_limit <= HOP_MAX) {
p->hop_limit = (radioConfig.preferences.hop_limit >= HOP_MAX) ? HOP_MAX : radioConfig.preferences.hop_limit;
if (config.payloadVariant.lora.hop_limit && config.payloadVariant.lora.hop_limit <= HOP_MAX) {
p->hop_limit = (config.payloadVariant.lora.hop_limit >= HOP_MAX) ? HOP_MAX : config.payloadVariant.lora.hop_limit;
} else {
p->hop_limit = HOP_RELIABLE;
}
@ -227,7 +227,7 @@ ErrorCode Router::send(MeshPacket *p)
*/
bool shouldActuallyEncrypt = true;
if (*radioConfig.preferences.mqtt_server && !radioConfig.preferences.mqtt_encryption_enabled) {
if (*moduleConfig.payloadVariant.mqtt.address && !moduleConfig.payloadVariant.mqtt.encryption_enabled) {
shouldActuallyEncrypt = false;
}
@ -304,13 +304,11 @@ bool perhapsDecode(MeshPacket *p)
p->which_payloadVariant = 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.which_payloadVariant == Data_payload_compressed_tag) {
// Decompress the file
}
printPacket("decoded message", p);
return true;
}
@ -361,10 +359,10 @@ Routing_Error perhapsEncode(MeshPacket *p)
} else {
DEBUG_MSG("Compressing message.\n");
// Copy the compressed data into the meshpacket
//p->decoded.payload_compressed.size = compressed_len;
//memcpy(p->decoded.payload_compressed.bytes, compressed_out, compressed_len);
// p->decoded.payload_compressed.size = compressed_len;
// memcpy(p->decoded.payload_compressed.bytes, compressed_out, compressed_len);
//p->decoded.which_payloadVariant = Data_payload_compressed_tag;
// p->decoded.which_payloadVariant = Data_payload_compressed_tag;
}
if (0) {
@ -437,8 +435,8 @@ void Router::handleReceived(MeshPacket *p, RxSource src)
void Router::perhapsHandleReceived(MeshPacket *p)
{
assert(radioConfig.has_preferences);
bool ignore = is_in_repeated(radioConfig.preferences.ignore_incoming, p->from);
// assert(radioConfig.has_preferences);
bool ignore = is_in_repeated(config.payloadVariant.lora.ignore_incoming, p->from);
if (ignore)
DEBUG_MSG("Ignoring incoming message, 0x%x is in our ignore list\n", p->from);

Wyświetl plik

@ -6,7 +6,7 @@
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(AdminMessage, AdminMessage, 2)
PB_BIND(AdminMessage, AdminMessage, AUTO)

Wyświetl plik

@ -8,7 +8,6 @@
#include "config.pb.h"
#include "mesh.pb.h"
#include "module_config.pb.h"
#include "radioconfig.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
@ -17,7 +16,7 @@
/* Enum definitions */
typedef enum _AdminMessage_ConfigType {
AdminMessage_ConfigType_DEVICE_CONFIG = 0,
AdminMessage_ConfigType_GPS_CONFIG = 1,
AdminMessage_ConfigType_POSITION_CONFIG = 1,
AdminMessage_ConfigType_POWER_CONFIG = 2,
AdminMessage_ConfigType_WIFI_CONFIG = 3,
AdminMessage_ConfigType_DISPLAY_CONFIG = 4,
@ -39,14 +38,11 @@ typedef enum _AdminMessage_ModuleConfigType {
This message is used to do settings operations to both remote AND local nodes.
(Prior to 1.2 these operations were done via special ToRadio operations) */
typedef struct _AdminMessage {
/* Set the radio provisioning for this node */
/* Set the owner for this node */
pb_size_t which_variant;
union {
RadioConfig set_radio;
User set_owner;
Channel set_channel;
bool get_radio_request;
RadioConfig get_radio_response;
uint32_t get_channel_request;
Channel get_channel_response;
bool get_owner_request;
@ -95,15 +91,12 @@ extern "C" {
#endif
/* Initializer values for message structs */
#define AdminMessage_init_default {0, {RadioConfig_init_default}}
#define AdminMessage_init_zero {0, {RadioConfig_init_zero}}
#define AdminMessage_init_default {0, {User_init_default}}
#define AdminMessage_init_zero {0, {User_init_zero}}
/* Field tags (for use in manual encoding/decoding) */
#define AdminMessage_set_radio_tag 1
#define AdminMessage_set_owner_tag 2
#define AdminMessage_set_channel_tag 3
#define AdminMessage_get_radio_request_tag 4
#define AdminMessage_get_radio_response_tag 5
#define AdminMessage_get_channel_request_tag 6
#define AdminMessage_get_channel_response_tag 7
#define AdminMessage_get_owner_request_tag 8
@ -136,11 +129,8 @@ extern "C" {
/* Struct field encoding specification for nanopb */
#define AdminMessage_FIELDLIST(X, a) \
X(a, STATIC, ONEOF, MESSAGE, (variant,set_radio,set_radio), 1) \
X(a, STATIC, ONEOF, MESSAGE, (variant,set_owner,set_owner), 2) \
X(a, STATIC, ONEOF, MESSAGE, (variant,set_channel,set_channel), 3) \
X(a, STATIC, ONEOF, BOOL, (variant,get_radio_request,get_radio_request), 4) \
X(a, STATIC, ONEOF, MESSAGE, (variant,get_radio_response,get_radio_response), 5) \
X(a, STATIC, ONEOF, UINT32, (variant,get_channel_request,get_channel_request), 6) \
X(a, STATIC, ONEOF, MESSAGE, (variant,get_channel_response,get_channel_response), 7) \
X(a, STATIC, ONEOF, BOOL, (variant,get_owner_request,get_owner_request), 8) \
@ -172,10 +162,8 @@ X(a, STATIC, ONEOF, STRING, (variant,set_canned_message_module_part4,set_
X(a, STATIC, ONEOF, INT32, (variant,shutdown_seconds,shutdown_seconds), 51)
#define AdminMessage_CALLBACK NULL
#define AdminMessage_DEFAULT NULL
#define AdminMessage_variant_set_radio_MSGTYPE RadioConfig
#define AdminMessage_variant_set_owner_MSGTYPE User
#define AdminMessage_variant_set_channel_MSGTYPE Channel
#define AdminMessage_variant_get_radio_response_MSGTYPE RadioConfig
#define AdminMessage_variant_get_channel_response_MSGTYPE Channel
#define AdminMessage_variant_get_owner_response_MSGTYPE User
#define AdminMessage_variant_get_config_response_MSGTYPE Config
@ -189,10 +177,7 @@ extern const pb_msgdesc_t AdminMessage_msg;
#define AdminMessage_fields &AdminMessage_msg
/* Maximum encoded size of messages (where known) */
#if defined(Config_size) && defined(Config_size)
#define AdminMessage_size (0 + sizeof(union AdminMessage_variant_size_union))
union AdminMessage_variant_size_union {char f0[551]; char f11[(6 + Config_size)]; char f12[(6 + Config_size)];};
#endif
#define AdminMessage_size 204
#ifdef __cplusplus
} /* extern "C" */

Wyświetl plik

@ -75,7 +75,7 @@ typedef struct _ChannelSettings {
is the special (minimally secure) "Default"channel.
In user interfaces it should be rendered as a local language translation of "X".
For channel_num hashing empty string will be treated as "X".
Where "X" is selected based on the English words listed above for ModemConfig */
Where "X" is selected based on the English words listed above for ModemPreset */
uint8_t channel_num;
/* Used to construct a globally unique channel ID.
The full globally unique ID will be: "name.id" where ID is shown as base36.

Wyświetl plik

@ -12,7 +12,7 @@ PB_BIND(Config, Config, AUTO)
PB_BIND(Config_DeviceConfig, Config_DeviceConfig, AUTO)
PB_BIND(Config_GpsConfig, Config_GpsConfig, AUTO)
PB_BIND(Config_PositionConfig, Config_PositionConfig, AUTO)
PB_BIND(Config_PowerConfig, Config_PowerConfig, AUTO)
@ -24,31 +24,12 @@ PB_BIND(Config_WiFiConfig, Config_WiFiConfig, AUTO)
PB_BIND(Config_DisplayConfig, Config_DisplayConfig, AUTO)
PB_BIND(Config_LoRaConfig, Config_LoRaConfig, AUTO)
PB_BIND(Config_ModuleConfig, Config_ModuleConfig, AUTO)
PB_BIND(Config_ModuleConfig_MQTTConfig, Config_ModuleConfig_MQTTConfig, AUTO)
PB_BIND(Config_ModuleConfig_SerialConfig, Config_ModuleConfig_SerialConfig, AUTO)
PB_BIND(Config_ModuleConfig_ExternalNotificationConfig, Config_ModuleConfig_ExternalNotificationConfig, AUTO)
PB_BIND(Config_ModuleConfig_StoreForwardConfig, Config_ModuleConfig_StoreForwardConfig, AUTO)
PB_BIND(Config_ModuleConfig_RangeTestConfig, Config_ModuleConfig_RangeTestConfig, AUTO)
PB_BIND(Config_ModuleConfig_TelemetryConfig, Config_ModuleConfig_TelemetryConfig, AUTO)
PB_BIND(Config_ModuleConfig_CannedMessageConfig, Config_ModuleConfig_CannedMessageConfig, AUTO)
PB_BIND(Config_LoRaConfig, Config_LoRaConfig, 2)

Wyświetl plik

@ -11,115 +11,181 @@
#endif
/* Enum definitions */
typedef enum _Config_LoRaConfig_ModemConfig {
Config_LoRaConfig_ModemConfig_VLongSlow = 0,
Config_LoRaConfig_ModemConfig_LongSlow = 1,
Config_LoRaConfig_ModemConfig_LongFast = 2,
Config_LoRaConfig_ModemConfig_MidSlow = 3,
Config_LoRaConfig_ModemConfig_MidFast = 4,
Config_LoRaConfig_ModemConfig_ShortSlow = 5,
Config_LoRaConfig_ModemConfig_ShortFast = 6
} Config_LoRaConfig_ModemConfig;
typedef enum _Config_DeviceConfig_Role {
Config_DeviceConfig_Role_Client = 0,
Config_DeviceConfig_Role_ClientMute = 1,
Config_DeviceConfig_Role_Router = 2,
Config_DeviceConfig_Role_RouterClient = 3
} Config_DeviceConfig_Role;
typedef enum _Config_PositionConfig_PositionFlags {
Config_PositionConfig_PositionFlags_POS_UNDEFINED = 0,
Config_PositionConfig_PositionFlags_POS_ALTITUDE = 1,
Config_PositionConfig_PositionFlags_POS_ALT_MSL = 2,
Config_PositionConfig_PositionFlags_POS_GEO_SEP = 4,
Config_PositionConfig_PositionFlags_POS_DOP = 8,
Config_PositionConfig_PositionFlags_POS_HVDOP = 16,
Config_PositionConfig_PositionFlags_POS_BATTERY = 32,
Config_PositionConfig_PositionFlags_POS_SATINVIEW = 64,
Config_PositionConfig_PositionFlags_POS_SEQ_NOS = 128,
Config_PositionConfig_PositionFlags_POS_TIMESTAMP = 256
} Config_PositionConfig_PositionFlags;
typedef enum _Config_PowerConfig_ChargeCurrent {
Config_PowerConfig_ChargeCurrent_MAUnset = 0,
Config_PowerConfig_ChargeCurrent_MA100 = 1,
Config_PowerConfig_ChargeCurrent_MA190 = 2,
Config_PowerConfig_ChargeCurrent_MA280 = 3,
Config_PowerConfig_ChargeCurrent_MA360 = 4,
Config_PowerConfig_ChargeCurrent_MA450 = 5,
Config_PowerConfig_ChargeCurrent_MA550 = 6,
Config_PowerConfig_ChargeCurrent_MA630 = 7,
Config_PowerConfig_ChargeCurrent_MA700 = 8,
Config_PowerConfig_ChargeCurrent_MA780 = 9,
Config_PowerConfig_ChargeCurrent_MA880 = 10,
Config_PowerConfig_ChargeCurrent_MA960 = 11,
Config_PowerConfig_ChargeCurrent_MA1000 = 12,
Config_PowerConfig_ChargeCurrent_MA1080 = 13,
Config_PowerConfig_ChargeCurrent_MA1160 = 14,
Config_PowerConfig_ChargeCurrent_MA1240 = 15,
Config_PowerConfig_ChargeCurrent_MA1320 = 16
} Config_PowerConfig_ChargeCurrent;
typedef enum _Config_DisplayConfig_GpsCoordinateFormat {
Config_DisplayConfig_GpsCoordinateFormat_GpsFormatDec = 0,
Config_DisplayConfig_GpsCoordinateFormat_GpsFormatDMS = 1,
Config_DisplayConfig_GpsCoordinateFormat_GpsFormatUTM = 2,
Config_DisplayConfig_GpsCoordinateFormat_GpsFormatMGRS = 3,
Config_DisplayConfig_GpsCoordinateFormat_GpsFormatOLC = 4,
Config_DisplayConfig_GpsCoordinateFormat_GpsFormatOSGR = 5
} Config_DisplayConfig_GpsCoordinateFormat;
typedef enum _Config_LoRaConfig_RegionCode {
Config_LoRaConfig_RegionCode_Unset = 0,
Config_LoRaConfig_RegionCode_US = 1,
Config_LoRaConfig_RegionCode_EU433 = 2,
Config_LoRaConfig_RegionCode_EU868 = 3,
Config_LoRaConfig_RegionCode_CN = 4,
Config_LoRaConfig_RegionCode_JP = 5,
Config_LoRaConfig_RegionCode_ANZ = 6,
Config_LoRaConfig_RegionCode_KR = 7,
Config_LoRaConfig_RegionCode_TW = 8,
Config_LoRaConfig_RegionCode_RU = 9,
Config_LoRaConfig_RegionCode_IN = 10,
Config_LoRaConfig_RegionCode_NZ865 = 11,
Config_LoRaConfig_RegionCode_TH = 12
} Config_LoRaConfig_RegionCode;
typedef enum _Config_LoRaConfig_ModemPreset {
Config_LoRaConfig_ModemPreset_VLongSlow = 0,
Config_LoRaConfig_ModemPreset_LongSlow = 1,
Config_LoRaConfig_ModemPreset_LongFast = 2,
Config_LoRaConfig_ModemPreset_MidSlow = 3,
Config_LoRaConfig_ModemPreset_MidFast = 4,
Config_LoRaConfig_ModemPreset_ShortSlow = 5,
Config_LoRaConfig_ModemPreset_ShortFast = 6
} Config_LoRaConfig_ModemPreset;
/* Struct definitions */
typedef struct _Config_DeviceConfig {
char dummy_field;
Config_DeviceConfig_Role role;
bool serial_disabled;
bool factory_reset;
bool debug_log_enabled;
} Config_DeviceConfig;
typedef struct _Config_DisplayConfig {
char dummy_field;
uint32_t screen_on_secs;
Config_DisplayConfig_GpsCoordinateFormat gps_format;
uint32_t auto_screen_carousel_secs;
} Config_DisplayConfig;
typedef struct _Config_GpsConfig {
char dummy_field;
} Config_GpsConfig;
typedef struct _Config_ModuleConfig_CannedMessageConfig {
char dummy_field;
} Config_ModuleConfig_CannedMessageConfig;
typedef struct _Config_ModuleConfig_ExternalNotificationConfig {
char dummy_field;
} Config_ModuleConfig_ExternalNotificationConfig;
typedef struct _Config_ModuleConfig_MQTTConfig {
char dummy_field;
} Config_ModuleConfig_MQTTConfig;
typedef struct _Config_ModuleConfig_RangeTestConfig {
char dummy_field;
} Config_ModuleConfig_RangeTestConfig;
typedef struct _Config_ModuleConfig_SerialConfig {
char dummy_field;
} Config_ModuleConfig_SerialConfig;
typedef struct _Config_ModuleConfig_StoreForwardConfig {
char dummy_field;
} Config_ModuleConfig_StoreForwardConfig;
typedef struct _Config_PowerConfig {
char dummy_field;
} Config_PowerConfig;
typedef struct _Config_LoRaConfig {
int32_t tx_power;
Config_LoRaConfig_ModemConfig modem_config;
Config_LoRaConfig_ModemPreset modem_preset;
uint32_t bandwidth;
uint32_t spread_factor;
uint32_t coding_rate;
float frequency_offset;
Config_LoRaConfig_RegionCode region;
uint32_t hop_limit;
bool tx_disabled;
pb_size_t ignore_incoming_count;
uint32_t ignore_incoming[3];
} Config_LoRaConfig;
typedef struct _Config_ModuleConfig_TelemetryConfig {
uint32_t device_update_interval;
uint32_t environment_update_interval;
bool environment_measurement_enabled;
bool environment_screen_enabled;
uint32_t environment_read_error_count_threshold;
uint32_t environment_recovery_interval;
bool environment_display_fahrenheit;
TelemetrySensorType environment_sensor_type;
uint32_t environment_sensor_pin;
} Config_ModuleConfig_TelemetryConfig;
typedef struct _Config_PositionConfig {
uint32_t position_broadcast_secs;
bool position_broadcast_smart_disabled;
bool fixed_position;
bool location_share_disabled;
bool gps_disabled;
uint32_t gps_update_interval;
uint32_t gps_attempt_time;
bool gps_accept_2d;
uint32_t gps_max_dop;
uint32_t position_flags;
} Config_PositionConfig;
typedef struct _Config_PowerConfig {
Config_PowerConfig_ChargeCurrent charge_current;
bool is_low_power;
bool is_always_powered;
uint32_t on_battery_shutdown_after_secs;
bool is_power_saving;
float adc_multiplier_override;
uint32_t wait_bluetooth_secs;
uint32_t phone_timeout_secs;
uint32_t mesh_sds_timeout_secs;
uint32_t sds_secs;
uint32_t ls_secs;
uint32_t min_wake_secs;
} Config_PowerConfig;
typedef struct _Config_WiFiConfig {
pb_callback_t wifi_ssid;
pb_callback_t wifi_password;
bool wifi_ap_mode;
char ssid[33];
char psk[64];
bool ap_mode;
} Config_WiFiConfig;
typedef struct _Config_ModuleConfig {
pb_size_t which_payloadVariant;
union {
Config_ModuleConfig_MQTTConfig mqtt_config;
Config_ModuleConfig_SerialConfig serial_config;
Config_ModuleConfig_ExternalNotificationConfig external_notification_config;
Config_ModuleConfig_StoreForwardConfig store_forward_config;
Config_ModuleConfig_RangeTestConfig range_test_config;
Config_ModuleConfig_TelemetryConfig telemetry_config;
Config_ModuleConfig_CannedMessageConfig canned_message_config;
} payloadVariant;
} Config_ModuleConfig;
typedef struct _Config {
/* TODO: REPLACE */
pb_size_t which_payloadVariant;
union {
Config_DeviceConfig device_config;
Config_GpsConfig gps_config;
Config_PowerConfig power_config;
Config_WiFiConfig wifi_config;
Config_DisplayConfig display_config;
Config_LoRaConfig lora_config;
Config_ModuleConfig module_config;
Config_DeviceConfig device;
Config_PositionConfig position;
Config_PowerConfig power;
Config_WiFiConfig wifi;
Config_DisplayConfig display;
Config_LoRaConfig lora;
} payloadVariant;
} Config;
/* Helper constants for enums */
#define _Config_LoRaConfig_ModemConfig_MIN Config_LoRaConfig_ModemConfig_VLongSlow
#define _Config_LoRaConfig_ModemConfig_MAX Config_LoRaConfig_ModemConfig_ShortFast
#define _Config_LoRaConfig_ModemConfig_ARRAYSIZE ((Config_LoRaConfig_ModemConfig)(Config_LoRaConfig_ModemConfig_ShortFast+1))
#define _Config_DeviceConfig_Role_MIN Config_DeviceConfig_Role_Client
#define _Config_DeviceConfig_Role_MAX Config_DeviceConfig_Role_RouterClient
#define _Config_DeviceConfig_Role_ARRAYSIZE ((Config_DeviceConfig_Role)(Config_DeviceConfig_Role_RouterClient+1))
#define _Config_PositionConfig_PositionFlags_MIN Config_PositionConfig_PositionFlags_POS_UNDEFINED
#define _Config_PositionConfig_PositionFlags_MAX Config_PositionConfig_PositionFlags_POS_TIMESTAMP
#define _Config_PositionConfig_PositionFlags_ARRAYSIZE ((Config_PositionConfig_PositionFlags)(Config_PositionConfig_PositionFlags_POS_TIMESTAMP+1))
#define _Config_PowerConfig_ChargeCurrent_MIN Config_PowerConfig_ChargeCurrent_MAUnset
#define _Config_PowerConfig_ChargeCurrent_MAX Config_PowerConfig_ChargeCurrent_MA1320
#define _Config_PowerConfig_ChargeCurrent_ARRAYSIZE ((Config_PowerConfig_ChargeCurrent)(Config_PowerConfig_ChargeCurrent_MA1320+1))
#define _Config_DisplayConfig_GpsCoordinateFormat_MIN Config_DisplayConfig_GpsCoordinateFormat_GpsFormatDec
#define _Config_DisplayConfig_GpsCoordinateFormat_MAX Config_DisplayConfig_GpsCoordinateFormat_GpsFormatOSGR
#define _Config_DisplayConfig_GpsCoordinateFormat_ARRAYSIZE ((Config_DisplayConfig_GpsCoordinateFormat)(Config_DisplayConfig_GpsCoordinateFormat_GpsFormatOSGR+1))
#define _Config_LoRaConfig_RegionCode_MIN Config_LoRaConfig_RegionCode_Unset
#define _Config_LoRaConfig_RegionCode_MAX Config_LoRaConfig_RegionCode_TH
#define _Config_LoRaConfig_RegionCode_ARRAYSIZE ((Config_LoRaConfig_RegionCode)(Config_LoRaConfig_RegionCode_TH+1))
#define _Config_LoRaConfig_ModemPreset_MIN Config_LoRaConfig_ModemPreset_VLongSlow
#define _Config_LoRaConfig_ModemPreset_MAX Config_LoRaConfig_ModemPreset_ShortFast
#define _Config_LoRaConfig_ModemPreset_ARRAYSIZE ((Config_LoRaConfig_ModemPreset)(Config_LoRaConfig_ModemPreset_ShortFast+1))
#ifdef __cplusplus
@ -128,234 +194,178 @@ extern "C" {
/* Initializer values for message structs */
#define Config_init_default {0, {Config_DeviceConfig_init_default}}
#define Config_DeviceConfig_init_default {0}
#define Config_GpsConfig_init_default {0}
#define Config_PowerConfig_init_default {0}
#define Config_WiFiConfig_init_default {{{NULL}, NULL}, {{NULL}, NULL}, 0}
#define Config_DisplayConfig_init_default {0}
#define Config_LoRaConfig_init_default {0, _Config_LoRaConfig_ModemConfig_MIN, 0, 0, 0}
#define Config_ModuleConfig_init_default {0, {Config_ModuleConfig_MQTTConfig_init_default}}
#define Config_ModuleConfig_MQTTConfig_init_default {0}
#define Config_ModuleConfig_SerialConfig_init_default {0}
#define Config_ModuleConfig_ExternalNotificationConfig_init_default {0}
#define Config_ModuleConfig_StoreForwardConfig_init_default {0}
#define Config_ModuleConfig_RangeTestConfig_init_default {0}
#define Config_ModuleConfig_TelemetryConfig_init_default {0, 0, 0, 0, 0, 0, 0, _TelemetrySensorType_MIN, 0}
#define Config_ModuleConfig_CannedMessageConfig_init_default {0}
#define Config_DeviceConfig_init_default {_Config_DeviceConfig_Role_MIN, 0, 0, 0}
#define Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define Config_PowerConfig_init_default {_Config_PowerConfig_ChargeCurrent_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define Config_WiFiConfig_init_default {"", "", 0}
#define Config_DisplayConfig_init_default {0, _Config_DisplayConfig_GpsCoordinateFormat_MIN, 0}
#define Config_LoRaConfig_init_default {0, _Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, {0, 0, 0}}
#define Config_init_zero {0, {Config_DeviceConfig_init_zero}}
#define Config_DeviceConfig_init_zero {0}
#define Config_GpsConfig_init_zero {0}
#define Config_PowerConfig_init_zero {0}
#define Config_WiFiConfig_init_zero {{{NULL}, NULL}, {{NULL}, NULL}, 0}
#define Config_DisplayConfig_init_zero {0}
#define Config_LoRaConfig_init_zero {0, _Config_LoRaConfig_ModemConfig_MIN, 0, 0, 0}
#define Config_ModuleConfig_init_zero {0, {Config_ModuleConfig_MQTTConfig_init_zero}}
#define Config_ModuleConfig_MQTTConfig_init_zero {0}
#define Config_ModuleConfig_SerialConfig_init_zero {0}
#define Config_ModuleConfig_ExternalNotificationConfig_init_zero {0}
#define Config_ModuleConfig_StoreForwardConfig_init_zero {0}
#define Config_ModuleConfig_RangeTestConfig_init_zero {0}
#define Config_ModuleConfig_TelemetryConfig_init_zero {0, 0, 0, 0, 0, 0, 0, _TelemetrySensorType_MIN, 0}
#define Config_ModuleConfig_CannedMessageConfig_init_zero {0}
#define Config_DeviceConfig_init_zero {_Config_DeviceConfig_Role_MIN, 0, 0, 0}
#define Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define Config_PowerConfig_init_zero {_Config_PowerConfig_ChargeCurrent_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define Config_WiFiConfig_init_zero {"", "", 0}
#define Config_DisplayConfig_init_zero {0, _Config_DisplayConfig_GpsCoordinateFormat_MIN, 0}
#define Config_LoRaConfig_init_zero {0, _Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, {0, 0, 0}}
/* Field tags (for use in manual encoding/decoding) */
#define Config_DeviceConfig_role_tag 1
#define Config_DeviceConfig_serial_disabled_tag 2
#define Config_DeviceConfig_factory_reset_tag 3
#define Config_DeviceConfig_debug_log_enabled_tag 4
#define Config_DisplayConfig_screen_on_secs_tag 1
#define Config_DisplayConfig_gps_format_tag 2
#define Config_DisplayConfig_auto_screen_carousel_secs_tag 3
#define Config_LoRaConfig_tx_power_tag 1
#define Config_LoRaConfig_modem_config_tag 3
#define Config_LoRaConfig_bandwidth_tag 6
#define Config_LoRaConfig_spread_factor_tag 7
#define Config_LoRaConfig_coding_rate_tag 8
#define Config_ModuleConfig_TelemetryConfig_device_update_interval_tag 1
#define Config_ModuleConfig_TelemetryConfig_environment_update_interval_tag 2
#define Config_ModuleConfig_TelemetryConfig_environment_measurement_enabled_tag 3
#define Config_ModuleConfig_TelemetryConfig_environment_screen_enabled_tag 4
#define Config_ModuleConfig_TelemetryConfig_environment_read_error_count_threshold_tag 5
#define Config_ModuleConfig_TelemetryConfig_environment_recovery_interval_tag 6
#define Config_ModuleConfig_TelemetryConfig_environment_display_fahrenheit_tag 7
#define Config_ModuleConfig_TelemetryConfig_environment_sensor_type_tag 8
#define Config_ModuleConfig_TelemetryConfig_environment_sensor_pin_tag 9
#define Config_WiFiConfig_wifi_ssid_tag 1
#define Config_WiFiConfig_wifi_password_tag 2
#define Config_WiFiConfig_wifi_ap_mode_tag 3
#define Config_ModuleConfig_mqtt_config_tag 1
#define Config_ModuleConfig_serial_config_tag 2
#define Config_ModuleConfig_external_notification_config_tag 3
#define Config_ModuleConfig_store_forward_config_tag 4
#define Config_ModuleConfig_range_test_config_tag 5
#define Config_ModuleConfig_telemetry_config_tag 6
#define Config_ModuleConfig_canned_message_config_tag 7
#define Config_device_config_tag 1
#define Config_gps_config_tag 2
#define Config_power_config_tag 3
#define Config_wifi_config_tag 4
#define Config_display_config_tag 5
#define Config_lora_config_tag 6
#define Config_module_config_tag 7
#define Config_LoRaConfig_modem_preset_tag 2
#define Config_LoRaConfig_bandwidth_tag 3
#define Config_LoRaConfig_spread_factor_tag 4
#define Config_LoRaConfig_coding_rate_tag 5
#define Config_LoRaConfig_frequency_offset_tag 6
#define Config_LoRaConfig_region_tag 7
#define Config_LoRaConfig_hop_limit_tag 8
#define Config_LoRaConfig_tx_disabled_tag 9
#define Config_LoRaConfig_ignore_incoming_tag 103
#define Config_PositionConfig_position_broadcast_secs_tag 1
#define Config_PositionConfig_position_broadcast_smart_disabled_tag 2
#define Config_PositionConfig_fixed_position_tag 3
#define Config_PositionConfig_location_share_disabled_tag 4
#define Config_PositionConfig_gps_disabled_tag 5
#define Config_PositionConfig_gps_update_interval_tag 6
#define Config_PositionConfig_gps_attempt_time_tag 7
#define Config_PositionConfig_gps_accept_2d_tag 8
#define Config_PositionConfig_gps_max_dop_tag 9
#define Config_PositionConfig_position_flags_tag 10
#define Config_PowerConfig_charge_current_tag 1
#define Config_PowerConfig_is_low_power_tag 2
#define Config_PowerConfig_is_always_powered_tag 3
#define Config_PowerConfig_on_battery_shutdown_after_secs_tag 4
#define Config_PowerConfig_is_power_saving_tag 5
#define Config_PowerConfig_adc_multiplier_override_tag 6
#define Config_PowerConfig_wait_bluetooth_secs_tag 7
#define Config_PowerConfig_phone_timeout_secs_tag 8
#define Config_PowerConfig_mesh_sds_timeout_secs_tag 9
#define Config_PowerConfig_sds_secs_tag 10
#define Config_PowerConfig_ls_secs_tag 11
#define Config_PowerConfig_min_wake_secs_tag 12
#define Config_WiFiConfig_ssid_tag 1
#define Config_WiFiConfig_psk_tag 2
#define Config_WiFiConfig_ap_mode_tag 3
#define Config_device_tag 1
#define Config_position_tag 2
#define Config_power_tag 3
#define Config_wifi_tag 4
#define Config_display_tag 5
#define Config_lora_tag 6
/* Struct field encoding specification for nanopb */
#define Config_FIELDLIST(X, a) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,device_config,payloadVariant.device_config), 1) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,gps_config,payloadVariant.gps_config), 2) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,power_config,payloadVariant.power_config), 3) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,wifi_config,payloadVariant.wifi_config), 4) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,display_config,payloadVariant.display_config), 5) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,lora_config,payloadVariant.lora_config), 6) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,module_config,payloadVariant.module_config), 7)
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,device,payloadVariant.device), 1) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,position,payloadVariant.position), 2) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,power,payloadVariant.power), 3) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,wifi,payloadVariant.wifi), 4) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,display,payloadVariant.display), 5) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,lora,payloadVariant.lora), 6)
#define Config_CALLBACK NULL
#define Config_DEFAULT NULL
#define Config_payloadVariant_device_config_MSGTYPE Config_DeviceConfig
#define Config_payloadVariant_gps_config_MSGTYPE Config_GpsConfig
#define Config_payloadVariant_power_config_MSGTYPE Config_PowerConfig
#define Config_payloadVariant_wifi_config_MSGTYPE Config_WiFiConfig
#define Config_payloadVariant_display_config_MSGTYPE Config_DisplayConfig
#define Config_payloadVariant_lora_config_MSGTYPE Config_LoRaConfig
#define Config_payloadVariant_module_config_MSGTYPE Config_ModuleConfig
#define Config_payloadVariant_device_MSGTYPE Config_DeviceConfig
#define Config_payloadVariant_position_MSGTYPE Config_PositionConfig
#define Config_payloadVariant_power_MSGTYPE Config_PowerConfig
#define Config_payloadVariant_wifi_MSGTYPE Config_WiFiConfig
#define Config_payloadVariant_display_MSGTYPE Config_DisplayConfig
#define Config_payloadVariant_lora_MSGTYPE Config_LoRaConfig
#define Config_DeviceConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UENUM, role, 1) \
X(a, STATIC, SINGULAR, BOOL, serial_disabled, 2) \
X(a, STATIC, SINGULAR, BOOL, factory_reset, 3) \
X(a, STATIC, SINGULAR, BOOL, debug_log_enabled, 4)
#define Config_DeviceConfig_CALLBACK NULL
#define Config_DeviceConfig_DEFAULT NULL
#define Config_GpsConfig_FIELDLIST(X, a) \
#define Config_GpsConfig_CALLBACK NULL
#define Config_GpsConfig_DEFAULT NULL
#define Config_PositionConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, position_broadcast_secs, 1) \
X(a, STATIC, SINGULAR, BOOL, position_broadcast_smart_disabled, 2) \
X(a, STATIC, SINGULAR, BOOL, fixed_position, 3) \
X(a, STATIC, SINGULAR, BOOL, location_share_disabled, 4) \
X(a, STATIC, SINGULAR, BOOL, gps_disabled, 5) \
X(a, STATIC, SINGULAR, UINT32, gps_update_interval, 6) \
X(a, STATIC, SINGULAR, UINT32, gps_attempt_time, 7) \
X(a, STATIC, SINGULAR, BOOL, gps_accept_2d, 8) \
X(a, STATIC, SINGULAR, UINT32, gps_max_dop, 9) \
X(a, STATIC, SINGULAR, UINT32, position_flags, 10)
#define Config_PositionConfig_CALLBACK NULL
#define Config_PositionConfig_DEFAULT NULL
#define Config_PowerConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UENUM, charge_current, 1) \
X(a, STATIC, SINGULAR, BOOL, is_low_power, 2) \
X(a, STATIC, SINGULAR, BOOL, is_always_powered, 3) \
X(a, STATIC, SINGULAR, UINT32, on_battery_shutdown_after_secs, 4) \
X(a, STATIC, SINGULAR, BOOL, is_power_saving, 5) \
X(a, STATIC, SINGULAR, FLOAT, adc_multiplier_override, 6) \
X(a, STATIC, SINGULAR, UINT32, wait_bluetooth_secs, 7) \
X(a, STATIC, SINGULAR, UINT32, phone_timeout_secs, 8) \
X(a, STATIC, SINGULAR, UINT32, mesh_sds_timeout_secs, 9) \
X(a, STATIC, SINGULAR, UINT32, sds_secs, 10) \
X(a, STATIC, SINGULAR, UINT32, ls_secs, 11) \
X(a, STATIC, SINGULAR, UINT32, min_wake_secs, 12)
#define Config_PowerConfig_CALLBACK NULL
#define Config_PowerConfig_DEFAULT NULL
#define Config_WiFiConfig_FIELDLIST(X, a) \
X(a, CALLBACK, SINGULAR, STRING, wifi_ssid, 1) \
X(a, CALLBACK, SINGULAR, STRING, wifi_password, 2) \
X(a, STATIC, SINGULAR, BOOL, wifi_ap_mode, 3)
#define Config_WiFiConfig_CALLBACK pb_default_field_callback
X(a, STATIC, SINGULAR, STRING, ssid, 1) \
X(a, STATIC, SINGULAR, STRING, psk, 2) \
X(a, STATIC, SINGULAR, BOOL, ap_mode, 3)
#define Config_WiFiConfig_CALLBACK NULL
#define Config_WiFiConfig_DEFAULT NULL
#define Config_DisplayConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, screen_on_secs, 1) \
X(a, STATIC, SINGULAR, UENUM, gps_format, 2) \
X(a, STATIC, SINGULAR, UINT32, auto_screen_carousel_secs, 3)
#define Config_DisplayConfig_CALLBACK NULL
#define Config_DisplayConfig_DEFAULT NULL
#define Config_LoRaConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, tx_power, 1) \
X(a, STATIC, SINGULAR, UENUM, modem_config, 3) \
X(a, STATIC, SINGULAR, UINT32, bandwidth, 6) \
X(a, STATIC, SINGULAR, UINT32, spread_factor, 7) \
X(a, STATIC, SINGULAR, UINT32, coding_rate, 8)
X(a, STATIC, SINGULAR, UENUM, modem_preset, 2) \
X(a, STATIC, SINGULAR, UINT32, bandwidth, 3) \
X(a, STATIC, SINGULAR, UINT32, spread_factor, 4) \
X(a, STATIC, SINGULAR, UINT32, coding_rate, 5) \
X(a, STATIC, SINGULAR, FLOAT, frequency_offset, 6) \
X(a, STATIC, SINGULAR, UENUM, region, 7) \
X(a, STATIC, SINGULAR, UINT32, hop_limit, 8) \
X(a, STATIC, SINGULAR, BOOL, tx_disabled, 9) \
X(a, STATIC, REPEATED, UINT32, ignore_incoming, 103)
#define Config_LoRaConfig_CALLBACK NULL
#define Config_LoRaConfig_DEFAULT NULL
#define Config_ModuleConfig_FIELDLIST(X, a) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,mqtt_config,payloadVariant.mqtt_config), 1) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,serial_config,payloadVariant.serial_config), 2) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,external_notification_config,payloadVariant.external_notification_config), 3) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,store_forward_config,payloadVariant.store_forward_config), 4) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,range_test_config,payloadVariant.range_test_config), 5) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,telemetry_config,payloadVariant.telemetry_config), 6) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,canned_message_config,payloadVariant.canned_message_config), 7)
#define Config_ModuleConfig_CALLBACK NULL
#define Config_ModuleConfig_DEFAULT NULL
#define Config_ModuleConfig_payloadVariant_mqtt_config_MSGTYPE Config_ModuleConfig_MQTTConfig
#define Config_ModuleConfig_payloadVariant_serial_config_MSGTYPE Config_ModuleConfig_SerialConfig
#define Config_ModuleConfig_payloadVariant_external_notification_config_MSGTYPE Config_ModuleConfig_ExternalNotificationConfig
#define Config_ModuleConfig_payloadVariant_store_forward_config_MSGTYPE Config_ModuleConfig_StoreForwardConfig
#define Config_ModuleConfig_payloadVariant_range_test_config_MSGTYPE Config_ModuleConfig_RangeTestConfig
#define Config_ModuleConfig_payloadVariant_telemetry_config_MSGTYPE Config_ModuleConfig_TelemetryConfig
#define Config_ModuleConfig_payloadVariant_canned_message_config_MSGTYPE Config_ModuleConfig_CannedMessageConfig
#define Config_ModuleConfig_MQTTConfig_FIELDLIST(X, a) \
#define Config_ModuleConfig_MQTTConfig_CALLBACK NULL
#define Config_ModuleConfig_MQTTConfig_DEFAULT NULL
#define Config_ModuleConfig_SerialConfig_FIELDLIST(X, a) \
#define Config_ModuleConfig_SerialConfig_CALLBACK NULL
#define Config_ModuleConfig_SerialConfig_DEFAULT NULL
#define Config_ModuleConfig_ExternalNotificationConfig_FIELDLIST(X, a) \
#define Config_ModuleConfig_ExternalNotificationConfig_CALLBACK NULL
#define Config_ModuleConfig_ExternalNotificationConfig_DEFAULT NULL
#define Config_ModuleConfig_StoreForwardConfig_FIELDLIST(X, a) \
#define Config_ModuleConfig_StoreForwardConfig_CALLBACK NULL
#define Config_ModuleConfig_StoreForwardConfig_DEFAULT NULL
#define Config_ModuleConfig_RangeTestConfig_FIELDLIST(X, a) \
#define Config_ModuleConfig_RangeTestConfig_CALLBACK NULL
#define Config_ModuleConfig_RangeTestConfig_DEFAULT NULL
#define Config_ModuleConfig_TelemetryConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, device_update_interval, 1) \
X(a, STATIC, SINGULAR, UINT32, environment_update_interval, 2) \
X(a, STATIC, SINGULAR, BOOL, environment_measurement_enabled, 3) \
X(a, STATIC, SINGULAR, BOOL, environment_screen_enabled, 4) \
X(a, STATIC, SINGULAR, UINT32, environment_read_error_count_threshold, 5) \
X(a, STATIC, SINGULAR, UINT32, environment_recovery_interval, 6) \
X(a, STATIC, SINGULAR, BOOL, environment_display_fahrenheit, 7) \
X(a, STATIC, SINGULAR, UENUM, environment_sensor_type, 8) \
X(a, STATIC, SINGULAR, UINT32, environment_sensor_pin, 9)
#define Config_ModuleConfig_TelemetryConfig_CALLBACK NULL
#define Config_ModuleConfig_TelemetryConfig_DEFAULT NULL
#define Config_ModuleConfig_CannedMessageConfig_FIELDLIST(X, a) \
#define Config_ModuleConfig_CannedMessageConfig_CALLBACK NULL
#define Config_ModuleConfig_CannedMessageConfig_DEFAULT NULL
extern const pb_msgdesc_t Config_msg;
extern const pb_msgdesc_t Config_DeviceConfig_msg;
extern const pb_msgdesc_t Config_GpsConfig_msg;
extern const pb_msgdesc_t Config_PositionConfig_msg;
extern const pb_msgdesc_t Config_PowerConfig_msg;
extern const pb_msgdesc_t Config_WiFiConfig_msg;
extern const pb_msgdesc_t Config_DisplayConfig_msg;
extern const pb_msgdesc_t Config_LoRaConfig_msg;
extern const pb_msgdesc_t Config_ModuleConfig_msg;
extern const pb_msgdesc_t Config_ModuleConfig_MQTTConfig_msg;
extern const pb_msgdesc_t Config_ModuleConfig_SerialConfig_msg;
extern const pb_msgdesc_t Config_ModuleConfig_ExternalNotificationConfig_msg;
extern const pb_msgdesc_t Config_ModuleConfig_StoreForwardConfig_msg;
extern const pb_msgdesc_t Config_ModuleConfig_RangeTestConfig_msg;
extern const pb_msgdesc_t Config_ModuleConfig_TelemetryConfig_msg;
extern const pb_msgdesc_t Config_ModuleConfig_CannedMessageConfig_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define Config_fields &Config_msg
#define Config_DeviceConfig_fields &Config_DeviceConfig_msg
#define Config_GpsConfig_fields &Config_GpsConfig_msg
#define Config_PositionConfig_fields &Config_PositionConfig_msg
#define Config_PowerConfig_fields &Config_PowerConfig_msg
#define Config_WiFiConfig_fields &Config_WiFiConfig_msg
#define Config_DisplayConfig_fields &Config_DisplayConfig_msg
#define Config_LoRaConfig_fields &Config_LoRaConfig_msg
#define Config_ModuleConfig_fields &Config_ModuleConfig_msg
#define Config_ModuleConfig_MQTTConfig_fields &Config_ModuleConfig_MQTTConfig_msg
#define Config_ModuleConfig_SerialConfig_fields &Config_ModuleConfig_SerialConfig_msg
#define Config_ModuleConfig_ExternalNotificationConfig_fields &Config_ModuleConfig_ExternalNotificationConfig_msg
#define Config_ModuleConfig_StoreForwardConfig_fields &Config_ModuleConfig_StoreForwardConfig_msg
#define Config_ModuleConfig_RangeTestConfig_fields &Config_ModuleConfig_RangeTestConfig_msg
#define Config_ModuleConfig_TelemetryConfig_fields &Config_ModuleConfig_TelemetryConfig_msg
#define Config_ModuleConfig_CannedMessageConfig_fields &Config_ModuleConfig_CannedMessageConfig_msg
/* Maximum encoded size of messages (where known) */
/* Config_size depends on runtime parameters */
/* Config_WiFiConfig_size depends on runtime parameters */
#define Config_DeviceConfig_size 0
#define Config_DisplayConfig_size 0
#define Config_GpsConfig_size 0
#define Config_LoRaConfig_size 31
#define Config_ModuleConfig_CannedMessageConfig_size 0
#define Config_ModuleConfig_ExternalNotificationConfig_size 0
#define Config_ModuleConfig_MQTTConfig_size 0
#define Config_ModuleConfig_RangeTestConfig_size 0
#define Config_ModuleConfig_SerialConfig_size 0
#define Config_ModuleConfig_StoreForwardConfig_size 0
#define Config_ModuleConfig_TelemetryConfig_size 38
#define Config_ModuleConfig_size 40
#define Config_PowerConfig_size 0
#define Config_DeviceConfig_size 8
#define Config_DisplayConfig_size 14
#define Config_LoRaConfig_size 67
#define Config_PositionConfig_size 40
#define Config_PowerConfig_size 55
#define Config_WiFiConfig_size 101
#define Config_size 103
#ifdef __cplusplus
} /* extern "C" */

Wyświetl plik

@ -31,3 +31,6 @@ PB_BIND(ModuleConfig_CannedMessageConfig, ModuleConfig_CannedMessageConfig, AUTO

Wyświetl plik

@ -10,29 +10,97 @@
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Enum definitions */
typedef enum _ModuleConfig_SerialConfig_Serial_Baud {
ModuleConfig_SerialConfig_Serial_Baud_BAUD_Default = 0,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_2400 = 1,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_4800 = 2,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_9600 = 3,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_19200 = 4,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_38400 = 5,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_57600 = 6,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_115200 = 7,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_230400 = 8,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_460800 = 9,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_576000 = 10,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_921600 = 11,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_110 = 12,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_300 = 13,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_600 = 14,
ModuleConfig_SerialConfig_Serial_Baud_BAUD_1200 = 15
} ModuleConfig_SerialConfig_Serial_Baud;
typedef enum _ModuleConfig_SerialConfig_Serial_Mode {
ModuleConfig_SerialConfig_Serial_Mode_MODE_Default = 0,
ModuleConfig_SerialConfig_Serial_Mode_MODE_SIMPLE = 1,
ModuleConfig_SerialConfig_Serial_Mode_MODE_PROTO = 2
} ModuleConfig_SerialConfig_Serial_Mode;
typedef enum _ModuleConfig_CannedMessageConfig_InputEventChar {
ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE = 0,
ModuleConfig_CannedMessageConfig_InputEventChar_KEY_UP = 17,
ModuleConfig_CannedMessageConfig_InputEventChar_KEY_DOWN = 18,
ModuleConfig_CannedMessageConfig_InputEventChar_KEY_LEFT = 19,
ModuleConfig_CannedMessageConfig_InputEventChar_KEY_RIGHT = 20,
ModuleConfig_CannedMessageConfig_InputEventChar_KEY_SELECT = 10,
ModuleConfig_CannedMessageConfig_InputEventChar_KEY_BACK = 27,
ModuleConfig_CannedMessageConfig_InputEventChar_KEY_CANCEL = 24
} ModuleConfig_CannedMessageConfig_InputEventChar;
/* Struct definitions */
typedef struct _ModuleConfig_CannedMessageConfig {
char dummy_field;
bool rotary1_enabled;
uint32_t inputbroker_pin_a;
uint32_t inputbroker_pin_b;
uint32_t inputbroker_pin_press;
ModuleConfig_CannedMessageConfig_InputEventChar inputbroker_event_cw;
ModuleConfig_CannedMessageConfig_InputEventChar inputbroker_event_ccw;
ModuleConfig_CannedMessageConfig_InputEventChar inputbroker_event_press;
bool updown1_enabled;
bool enabled;
char allow_input_source[16];
bool send_bell;
} ModuleConfig_CannedMessageConfig;
typedef struct _ModuleConfig_ExternalNotificationConfig {
char dummy_field;
bool enabled;
uint32_t output_ms;
uint32_t output;
bool active;
bool alert_message;
bool alert_bell;
} ModuleConfig_ExternalNotificationConfig;
typedef struct _ModuleConfig_MQTTConfig {
char dummy_field;
bool disabled;
char address[32];
char username[32];
char password[32];
bool encryption_enabled;
} ModuleConfig_MQTTConfig;
typedef struct _ModuleConfig_RangeTestConfig {
char dummy_field;
bool enabled;
uint32_t sender;
bool save;
} ModuleConfig_RangeTestConfig;
typedef struct _ModuleConfig_SerialConfig {
char dummy_field;
bool enabled;
bool echo;
uint32_t rxd;
uint32_t txd;
ModuleConfig_SerialConfig_Serial_Baud baud;
uint32_t timeout;
ModuleConfig_SerialConfig_Serial_Mode mode;
} ModuleConfig_SerialConfig;
typedef struct _ModuleConfig_StoreForwardConfig {
char dummy_field;
bool enabled;
bool heartbeat;
uint32_t records;
uint32_t history_return_max;
uint32_t history_return_window;
} ModuleConfig_StoreForwardConfig;
typedef struct _ModuleConfig_TelemetryConfig {
@ -52,40 +120,91 @@ typedef struct _ModuleConfig {
/* TODO: REPLACE */
pb_size_t which_payloadVariant;
union {
ModuleConfig_MQTTConfig mqtt_config;
ModuleConfig_SerialConfig serial_config;
ModuleConfig_ExternalNotificationConfig external_notification_config;
ModuleConfig_StoreForwardConfig store_forward_config;
ModuleConfig_RangeTestConfig range_test_config;
ModuleConfig_TelemetryConfig telemetry_config;
ModuleConfig_CannedMessageConfig canned_message_config;
ModuleConfig_MQTTConfig mqtt;
ModuleConfig_SerialConfig serial;
ModuleConfig_ExternalNotificationConfig external_notification;
ModuleConfig_StoreForwardConfig store_forward;
ModuleConfig_RangeTestConfig range_test;
ModuleConfig_TelemetryConfig telemetry;
ModuleConfig_CannedMessageConfig canned_message;
} payloadVariant;
} ModuleConfig;
/* Helper constants for enums */
#define _ModuleConfig_SerialConfig_Serial_Baud_MIN ModuleConfig_SerialConfig_Serial_Baud_BAUD_Default
#define _ModuleConfig_SerialConfig_Serial_Baud_MAX ModuleConfig_SerialConfig_Serial_Baud_BAUD_1200
#define _ModuleConfig_SerialConfig_Serial_Baud_ARRAYSIZE ((ModuleConfig_SerialConfig_Serial_Baud)(ModuleConfig_SerialConfig_Serial_Baud_BAUD_1200+1))
#define _ModuleConfig_SerialConfig_Serial_Mode_MIN ModuleConfig_SerialConfig_Serial_Mode_MODE_Default
#define _ModuleConfig_SerialConfig_Serial_Mode_MAX ModuleConfig_SerialConfig_Serial_Mode_MODE_PROTO
#define _ModuleConfig_SerialConfig_Serial_Mode_ARRAYSIZE ((ModuleConfig_SerialConfig_Serial_Mode)(ModuleConfig_SerialConfig_Serial_Mode_MODE_PROTO+1))
#define _ModuleConfig_CannedMessageConfig_InputEventChar_MIN ModuleConfig_CannedMessageConfig_InputEventChar_KEY_NONE
#define _ModuleConfig_CannedMessageConfig_InputEventChar_MAX ModuleConfig_CannedMessageConfig_InputEventChar_KEY_BACK
#define _ModuleConfig_CannedMessageConfig_InputEventChar_ARRAYSIZE ((ModuleConfig_CannedMessageConfig_InputEventChar)(ModuleConfig_CannedMessageConfig_InputEventChar_KEY_BACK+1))
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define ModuleConfig_init_default {0, {ModuleConfig_MQTTConfig_init_default}}
#define ModuleConfig_MQTTConfig_init_default {0}
#define ModuleConfig_SerialConfig_init_default {0}
#define ModuleConfig_ExternalNotificationConfig_init_default {0}
#define ModuleConfig_StoreForwardConfig_init_default {0}
#define ModuleConfig_RangeTestConfig_init_default {0}
#define ModuleConfig_MQTTConfig_init_default {0, "", "", "", 0}
#define ModuleConfig_SerialConfig_init_default {0, 0, 0, 0, _ModuleConfig_SerialConfig_Serial_Baud_MIN, 0, _ModuleConfig_SerialConfig_Serial_Mode_MIN}
#define ModuleConfig_ExternalNotificationConfig_init_default {0, 0, 0, 0, 0, 0}
#define ModuleConfig_StoreForwardConfig_init_default {0, 0, 0, 0, 0}
#define ModuleConfig_RangeTestConfig_init_default {0, 0, 0}
#define ModuleConfig_TelemetryConfig_init_default {0, 0, 0, 0, 0, 0, 0, _TelemetrySensorType_MIN, 0}
#define ModuleConfig_CannedMessageConfig_init_default {0}
#define ModuleConfig_CannedMessageConfig_init_default {0, 0, 0, 0, _ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _ModuleConfig_CannedMessageConfig_InputEventChar_MIN, 0, 0, "", 0}
#define ModuleConfig_init_zero {0, {ModuleConfig_MQTTConfig_init_zero}}
#define ModuleConfig_MQTTConfig_init_zero {0}
#define ModuleConfig_SerialConfig_init_zero {0}
#define ModuleConfig_ExternalNotificationConfig_init_zero {0}
#define ModuleConfig_StoreForwardConfig_init_zero {0}
#define ModuleConfig_RangeTestConfig_init_zero {0}
#define ModuleConfig_MQTTConfig_init_zero {0, "", "", "", 0}
#define ModuleConfig_SerialConfig_init_zero {0, 0, 0, 0, _ModuleConfig_SerialConfig_Serial_Baud_MIN, 0, _ModuleConfig_SerialConfig_Serial_Mode_MIN}
#define ModuleConfig_ExternalNotificationConfig_init_zero {0, 0, 0, 0, 0, 0}
#define ModuleConfig_StoreForwardConfig_init_zero {0, 0, 0, 0, 0}
#define ModuleConfig_RangeTestConfig_init_zero {0, 0, 0}
#define ModuleConfig_TelemetryConfig_init_zero {0, 0, 0, 0, 0, 0, 0, _TelemetrySensorType_MIN, 0}
#define ModuleConfig_CannedMessageConfig_init_zero {0}
#define ModuleConfig_CannedMessageConfig_init_zero {0, 0, 0, 0, _ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _ModuleConfig_CannedMessageConfig_InputEventChar_MIN, 0, 0, "", 0}
/* Field tags (for use in manual encoding/decoding) */
#define ModuleConfig_CannedMessageConfig_rotary1_enabled_tag 1
#define ModuleConfig_CannedMessageConfig_inputbroker_pin_a_tag 2
#define ModuleConfig_CannedMessageConfig_inputbroker_pin_b_tag 3
#define ModuleConfig_CannedMessageConfig_inputbroker_pin_press_tag 4
#define ModuleConfig_CannedMessageConfig_inputbroker_event_cw_tag 5
#define ModuleConfig_CannedMessageConfig_inputbroker_event_ccw_tag 6
#define ModuleConfig_CannedMessageConfig_inputbroker_event_press_tag 7
#define ModuleConfig_CannedMessageConfig_updown1_enabled_tag 8
#define ModuleConfig_CannedMessageConfig_enabled_tag 9
#define ModuleConfig_CannedMessageConfig_allow_input_source_tag 10
#define ModuleConfig_CannedMessageConfig_send_bell_tag 11
#define ModuleConfig_ExternalNotificationConfig_enabled_tag 1
#define ModuleConfig_ExternalNotificationConfig_output_ms_tag 2
#define ModuleConfig_ExternalNotificationConfig_output_tag 3
#define ModuleConfig_ExternalNotificationConfig_active_tag 4
#define ModuleConfig_ExternalNotificationConfig_alert_message_tag 5
#define ModuleConfig_ExternalNotificationConfig_alert_bell_tag 6
#define ModuleConfig_MQTTConfig_disabled_tag 1
#define ModuleConfig_MQTTConfig_address_tag 2
#define ModuleConfig_MQTTConfig_username_tag 3
#define ModuleConfig_MQTTConfig_password_tag 4
#define ModuleConfig_MQTTConfig_encryption_enabled_tag 5
#define ModuleConfig_RangeTestConfig_enabled_tag 1
#define ModuleConfig_RangeTestConfig_sender_tag 2
#define ModuleConfig_RangeTestConfig_save_tag 3
#define ModuleConfig_SerialConfig_enabled_tag 1
#define ModuleConfig_SerialConfig_echo_tag 2
#define ModuleConfig_SerialConfig_rxd_tag 3
#define ModuleConfig_SerialConfig_txd_tag 4
#define ModuleConfig_SerialConfig_baud_tag 5
#define ModuleConfig_SerialConfig_timeout_tag 6
#define ModuleConfig_SerialConfig_mode_tag 7
#define ModuleConfig_StoreForwardConfig_enabled_tag 1
#define ModuleConfig_StoreForwardConfig_heartbeat_tag 2
#define ModuleConfig_StoreForwardConfig_records_tag 3
#define ModuleConfig_StoreForwardConfig_history_return_max_tag 4
#define ModuleConfig_StoreForwardConfig_history_return_window_tag 5
#define ModuleConfig_TelemetryConfig_device_update_interval_tag 1
#define ModuleConfig_TelemetryConfig_environment_update_interval_tag 2
#define ModuleConfig_TelemetryConfig_environment_measurement_enabled_tag 3
@ -95,55 +214,76 @@ extern "C" {
#define ModuleConfig_TelemetryConfig_environment_display_fahrenheit_tag 7
#define ModuleConfig_TelemetryConfig_environment_sensor_type_tag 8
#define ModuleConfig_TelemetryConfig_environment_sensor_pin_tag 9
#define ModuleConfig_mqtt_config_tag 1
#define ModuleConfig_serial_config_tag 2
#define ModuleConfig_external_notification_config_tag 3
#define ModuleConfig_store_forward_config_tag 4
#define ModuleConfig_range_test_config_tag 5
#define ModuleConfig_telemetry_config_tag 6
#define ModuleConfig_canned_message_config_tag 7
#define ModuleConfig_mqtt_tag 1
#define ModuleConfig_serial_tag 2
#define ModuleConfig_external_notification_tag 3
#define ModuleConfig_store_forward_tag 4
#define ModuleConfig_range_test_tag 5
#define ModuleConfig_telemetry_tag 6
#define ModuleConfig_canned_message_tag 7
/* Struct field encoding specification for nanopb */
#define ModuleConfig_FIELDLIST(X, a) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,mqtt_config,payloadVariant.mqtt_config), 1) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,serial_config,payloadVariant.serial_config), 2) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,external_notification_config,payloadVariant.external_notification_config), 3) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,store_forward_config,payloadVariant.store_forward_config), 4) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,range_test_config,payloadVariant.range_test_config), 5) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,telemetry_config,payloadVariant.telemetry_config), 6) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,canned_message_config,payloadVariant.canned_message_config), 7)
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,mqtt,payloadVariant.mqtt), 1) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,serial,payloadVariant.serial), 2) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,external_notification,payloadVariant.external_notification), 3) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,store_forward,payloadVariant.store_forward), 4) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,range_test,payloadVariant.range_test), 5) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,telemetry,payloadVariant.telemetry), 6) \
X(a, STATIC, ONEOF, MESSAGE, (payloadVariant,canned_message,payloadVariant.canned_message), 7)
#define ModuleConfig_CALLBACK NULL
#define ModuleConfig_DEFAULT NULL
#define ModuleConfig_payloadVariant_mqtt_config_MSGTYPE ModuleConfig_MQTTConfig
#define ModuleConfig_payloadVariant_serial_config_MSGTYPE ModuleConfig_SerialConfig
#define ModuleConfig_payloadVariant_external_notification_config_MSGTYPE ModuleConfig_ExternalNotificationConfig
#define ModuleConfig_payloadVariant_store_forward_config_MSGTYPE ModuleConfig_StoreForwardConfig
#define ModuleConfig_payloadVariant_range_test_config_MSGTYPE ModuleConfig_RangeTestConfig
#define ModuleConfig_payloadVariant_telemetry_config_MSGTYPE ModuleConfig_TelemetryConfig
#define ModuleConfig_payloadVariant_canned_message_config_MSGTYPE ModuleConfig_CannedMessageConfig
#define ModuleConfig_payloadVariant_mqtt_MSGTYPE ModuleConfig_MQTTConfig
#define ModuleConfig_payloadVariant_serial_MSGTYPE ModuleConfig_SerialConfig
#define ModuleConfig_payloadVariant_external_notification_MSGTYPE ModuleConfig_ExternalNotificationConfig
#define ModuleConfig_payloadVariant_store_forward_MSGTYPE ModuleConfig_StoreForwardConfig
#define ModuleConfig_payloadVariant_range_test_MSGTYPE ModuleConfig_RangeTestConfig
#define ModuleConfig_payloadVariant_telemetry_MSGTYPE ModuleConfig_TelemetryConfig
#define ModuleConfig_payloadVariant_canned_message_MSGTYPE ModuleConfig_CannedMessageConfig
#define ModuleConfig_MQTTConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, BOOL, disabled, 1) \
X(a, STATIC, SINGULAR, STRING, address, 2) \
X(a, STATIC, SINGULAR, STRING, username, 3) \
X(a, STATIC, SINGULAR, STRING, password, 4) \
X(a, STATIC, SINGULAR, BOOL, encryption_enabled, 5)
#define ModuleConfig_MQTTConfig_CALLBACK NULL
#define ModuleConfig_MQTTConfig_DEFAULT NULL
#define ModuleConfig_SerialConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, BOOL, enabled, 1) \
X(a, STATIC, SINGULAR, BOOL, echo, 2) \
X(a, STATIC, SINGULAR, UINT32, rxd, 3) \
X(a, STATIC, SINGULAR, UINT32, txd, 4) \
X(a, STATIC, SINGULAR, UENUM, baud, 5) \
X(a, STATIC, SINGULAR, UINT32, timeout, 6) \
X(a, STATIC, SINGULAR, UENUM, mode, 7)
#define ModuleConfig_SerialConfig_CALLBACK NULL
#define ModuleConfig_SerialConfig_DEFAULT NULL
#define ModuleConfig_ExternalNotificationConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, BOOL, enabled, 1) \
X(a, STATIC, SINGULAR, UINT32, output_ms, 2) \
X(a, STATIC, SINGULAR, UINT32, output, 3) \
X(a, STATIC, SINGULAR, BOOL, active, 4) \
X(a, STATIC, SINGULAR, BOOL, alert_message, 5) \
X(a, STATIC, SINGULAR, BOOL, alert_bell, 6)
#define ModuleConfig_ExternalNotificationConfig_CALLBACK NULL
#define ModuleConfig_ExternalNotificationConfig_DEFAULT NULL
#define ModuleConfig_StoreForwardConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, BOOL, enabled, 1) \
X(a, STATIC, SINGULAR, BOOL, heartbeat, 2) \
X(a, STATIC, SINGULAR, UINT32, records, 3) \
X(a, STATIC, SINGULAR, UINT32, history_return_max, 4) \
X(a, STATIC, SINGULAR, UINT32, history_return_window, 5)
#define ModuleConfig_StoreForwardConfig_CALLBACK NULL
#define ModuleConfig_StoreForwardConfig_DEFAULT NULL
#define ModuleConfig_RangeTestConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, BOOL, enabled, 1) \
X(a, STATIC, SINGULAR, UINT32, sender, 2) \
X(a, STATIC, SINGULAR, BOOL, save, 3)
#define ModuleConfig_RangeTestConfig_CALLBACK NULL
#define ModuleConfig_RangeTestConfig_DEFAULT NULL
@ -161,7 +301,17 @@ X(a, STATIC, SINGULAR, UINT32, environment_sensor_pin, 9)
#define ModuleConfig_TelemetryConfig_DEFAULT NULL
#define ModuleConfig_CannedMessageConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, BOOL, rotary1_enabled, 1) \
X(a, STATIC, SINGULAR, UINT32, inputbroker_pin_a, 2) \
X(a, STATIC, SINGULAR, UINT32, inputbroker_pin_b, 3) \
X(a, STATIC, SINGULAR, UINT32, inputbroker_pin_press, 4) \
X(a, STATIC, SINGULAR, UENUM, inputbroker_event_cw, 5) \
X(a, STATIC, SINGULAR, UENUM, inputbroker_event_ccw, 6) \
X(a, STATIC, SINGULAR, UENUM, inputbroker_event_press, 7) \
X(a, STATIC, SINGULAR, BOOL, updown1_enabled, 8) \
X(a, STATIC, SINGULAR, BOOL, enabled, 9) \
X(a, STATIC, SINGULAR, STRING, allow_input_source, 10) \
X(a, STATIC, SINGULAR, BOOL, send_bell, 11)
#define ModuleConfig_CannedMessageConfig_CALLBACK NULL
#define ModuleConfig_CannedMessageConfig_DEFAULT NULL
@ -185,14 +335,14 @@ extern const pb_msgdesc_t ModuleConfig_CannedMessageConfig_msg;
#define ModuleConfig_CannedMessageConfig_fields &ModuleConfig_CannedMessageConfig_msg
/* Maximum encoded size of messages (where known) */
#define ModuleConfig_CannedMessageConfig_size 0
#define ModuleConfig_ExternalNotificationConfig_size 0
#define ModuleConfig_MQTTConfig_size 0
#define ModuleConfig_RangeTestConfig_size 0
#define ModuleConfig_SerialConfig_size 0
#define ModuleConfig_StoreForwardConfig_size 0
#define ModuleConfig_CannedMessageConfig_size 49
#define ModuleConfig_ExternalNotificationConfig_size 20
#define ModuleConfig_MQTTConfig_size 103
#define ModuleConfig_RangeTestConfig_size 10
#define ModuleConfig_SerialConfig_size 26
#define ModuleConfig_StoreForwardConfig_size 22
#define ModuleConfig_TelemetryConfig_size 38
#define ModuleConfig_size 40
#define ModuleConfig_size 105
#ifdef __cplusplus
} /* extern "C" */

Wyświetl plik

@ -1,23 +0,0 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.5 */
#include "radioconfig.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(RadioConfig, RadioConfig, 2)
PB_BIND(RadioConfig_UserPreferences, RadioConfig_UserPreferences, 2)

Wyświetl plik

@ -1,550 +0,0 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.5 */
#ifndef PB_RADIOCONFIG_PB_H_INCLUDED
#define PB_RADIOCONFIG_PB_H_INCLUDED
#include <pb.h>
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Enum definitions */
/* The frequency/regulatory region the user has selected.
Note: In 1.0 builds (which must still be supported by the android app for a
long time) this field will be unpopulated.
If firmware is ever upgraded from an old 1.0ish build, the old
MyNodeInfo.region string will be used to set UserPreferences.region and the
old value will be no longer set. */
typedef enum _RegionCode {
/* TODO: REPLACE */
RegionCode_Unset = 0,
/* TODO: REPLACE */
RegionCode_US = 1,
/* TODO: REPLACE */
RegionCode_EU433 = 2,
/* TODO: REPLACE */
RegionCode_EU868 = 3,
/* TODO: REPLACE */
RegionCode_CN = 4,
/* TODO: REPLACE */
RegionCode_JP = 5,
/* TODO: REPLACE */
RegionCode_ANZ = 6,
/* TODO: REPLACE */
RegionCode_KR = 7,
/* TODO: REPLACE */
RegionCode_TW = 8,
/* TODO: REPLACE */
RegionCode_RU = 9,
/* TODO: REPLACE */
RegionCode_IN = 10,
/* TODO: REPLACE */
RegionCode_NZ865 = 11,
/* TODO: REPLACE */
RegionCode_TH = 12
} RegionCode;
/* Defines the device's role on the Mesh network
unset
Behave normally.
Router
Functions as a router */
typedef enum _Role {
/* Client device role */
Role_Client = 0,
/* ClientMute device role
This is like the client but packets will not hop over this node. Would be
useful if you want to save power by not contributing to the mesh. */
Role_ClientMute = 1,
/* Router device role.
Uses an agressive algirithem for the flood networking so packets will
prefer to be routed over this node. Also assume that this will be generally
unattended and so will turn off the wifi/ble radio as well as the oled screen. */
Role_Router = 2,
/* RouterClient device role
Uses an agressive algirithem for the flood networking so packets will
prefer to be routed over this node. Similiar power management as a regular
client, so the RouterClient can be used as both a Router and a Client. Useful
as a well placed base station that you could also use to send messages. */
Role_RouterClient = 3
} Role;
/* Sets the charge control current of devices with a battery charger that can be
configured. This is passed into the axp power management chip like on the tbeam. */
typedef enum _ChargeCurrent {
/* TODO: REPLACE */
ChargeCurrent_MAUnset = 0,
/* TODO: REPLACE */
ChargeCurrent_MA100 = 1,
/* TODO: REPLACE */
ChargeCurrent_MA190 = 2,
/* TODO: REPLACE */
ChargeCurrent_MA280 = 3,
/* TODO: REPLACE */
ChargeCurrent_MA360 = 4,
/* TODO: REPLACE */
ChargeCurrent_MA450 = 5,
/* TODO: REPLACE */
ChargeCurrent_MA550 = 6,
/* TODO: REPLACE */
ChargeCurrent_MA630 = 7,
/* TODO: REPLACE */
ChargeCurrent_MA700 = 8,
/* TODO: REPLACE */
ChargeCurrent_MA780 = 9,
/* TODO: REPLACE */
ChargeCurrent_MA880 = 10,
/* TODO: REPLACE */
ChargeCurrent_MA960 = 11,
/* TODO: REPLACE */
ChargeCurrent_MA1000 = 12,
/* TODO: REPLACE */
ChargeCurrent_MA1080 = 13,
/* TODO: REPLACE */
ChargeCurrent_MA1160 = 14,
/* TODO: REPLACE */
ChargeCurrent_MA1240 = 15,
/* TODO: REPLACE */
ChargeCurrent_MA1320 = 16
} ChargeCurrent;
/* How the GPS coordinates are displayed on the OLED screen. */
typedef enum _GpsCoordinateFormat {
/* GPS coordinates are displayed in the normal decimal degrees format:
DD.DDDDDD DDD.DDDDDD */
GpsCoordinateFormat_GpsFormatDec = 0,
/* GPS coordinates are displayed in the degrees minutes seconds format:
DD°MM'SS"C DDD°MM'SS"C, where C is the compass point representing the locations quadrant */
GpsCoordinateFormat_GpsFormatDMS = 1,
/* GPS coordinates are displayed in Universal Transverse Mercator format:
ZZB EEEEEE NNNNNNN, where Z is zone, B is band, E is easting, N is northing */
GpsCoordinateFormat_GpsFormatUTM = 2,
/* GPS coordinates are displayed in Military Grid Reference System format:
ZZB CD EEEEE NNNNN, where Z is zone, B is band, C is the east 100k square, D is the north 100k square,
E is easting, N is northing */
GpsCoordinateFormat_GpsFormatMGRS = 3,
/* GPS coordinates are displayed in Open Location Code (aka Plus Codes). */
GpsCoordinateFormat_GpsFormatOLC = 4,
/* GPS coordinates are displayed in Ordnance Survey Grid Reference (the National Grid System of the UK).
Format: AB EEEEE NNNNN, where A is the east 100k square, B is the north 100k square, E is the easting,
N is the northing */
GpsCoordinateFormat_GpsFormatOSGR = 5
} GpsCoordinateFormat;
/* Bit field of boolean configuration options, indicating which optional
fields to include when assembling POSITION messages
Longitude and latitude are always included (also time if GPS-synced)
NOTE: the more fields are included, the larger the message will be -
leading to longer airtime and a higher risk of packet loss */
typedef enum _PositionFlags {
/* Required for compilation */
PositionFlags_POS_UNDEFINED = 0,
/* Include an altitude value (if available) */
PositionFlags_POS_ALTITUDE = 1,
/* Altitude value is MSL */
PositionFlags_POS_ALT_MSL = 2,
/* Include geoidal separation */
PositionFlags_POS_GEO_SEP = 4,
/* Include the DOP value ; PDOP used by default, see below */
PositionFlags_POS_DOP = 8,
/* If POS_DOP set, send separate HDOP / VDOP values instead of PDOP */
PositionFlags_POS_HVDOP = 16,
/* Include battery level */
PositionFlags_POS_BATTERY = 32,
/* Include number of "satellites in view" */
PositionFlags_POS_SATINVIEW = 64,
/* Include a sequence number incremented per packet */
PositionFlags_POS_SEQ_NOS = 128,
/* Include positional timestamp (from GPS solution) */
PositionFlags_POS_TIMESTAMP = 256
} PositionFlags;
/* TODO: REPLACE */
typedef enum _InputEventChar {
/* TODO: REPLACE */
InputEventChar_KEY_NONE = 0,
/* TODO: REPLACE */
InputEventChar_KEY_UP = 17,
/* TODO: REPLACE */
InputEventChar_KEY_DOWN = 18,
/* TODO: REPLACE */
InputEventChar_KEY_LEFT = 19,
/* TODO: REPLACE */
InputEventChar_KEY_RIGHT = 20,
/* '\n' */
InputEventChar_KEY_SELECT = 10,
/* TODO: REPLACE */
InputEventChar_KEY_BACK = 27,
/* TODO: REPLACE */
InputEventChar_KEY_CANCEL = 24
} InputEventChar;
/* The frequency/regulatory region the user has selected.
Note: In 1.0 builds (which must still be supported by the android app for a
long time) this field will be unpopulated.
If firmware is ever upgraded from an old 1.0ish build, the old
MyNodeInfo.region string will be used to set UserPreferences.region and the
old value will be no longer set. */
typedef enum _RadioConfig_UserPreferences_Serial_Baud {
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_Default = 0,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_2400 = 1,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_4800 = 2,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_9600 = 3,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_19200 = 4,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_38400 = 5,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_57600 = 6,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_115200 = 7,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_230400 = 8,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_460800 = 9,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_576000 = 10,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_921600 = 11,
/* TODO: REPLACE */
RadioConfig_UserPreferences_Serial_Baud_BAUD_110 = 12,
RadioConfig_UserPreferences_Serial_Baud_BAUD_300 = 13,
RadioConfig_UserPreferences_Serial_Baud_BAUD_600 = 14,
RadioConfig_UserPreferences_Serial_Baud_BAUD_1200 = 15
} RadioConfig_UserPreferences_Serial_Baud;
/* Defines the device's role on the Mesh network
unset
Behave normally.
Router
Functions as a router */
typedef enum _RadioConfig_UserPreferences_Serial_Mode {
/* Client device role */
RadioConfig_UserPreferences_Serial_Mode_MODE_Default = 0,
/* ClientMute device role
This is like the client but packets will not hop over this node. Would be
useful if you want to save power by not contributing to the mesh. */
RadioConfig_UserPreferences_Serial_Mode_MODE_SIMPLE = 1,
/* Router device role.
Uses an agressive algirithem for the flood networking so packets will
prefer to be routed over this node. Also assume that this will be generally
unattended and so will turn off the wifi/ble radio as well as the oled screen. */
RadioConfig_UserPreferences_Serial_Mode_MODE_PROTO = 2
} RadioConfig_UserPreferences_Serial_Mode;
/* Struct definitions */
typedef struct _RadioConfig_UserPreferences {
uint32_t position_broadcast_secs;
uint32_t wait_bluetooth_secs;
uint32_t screen_on_secs;
uint32_t phone_timeout_secs;
uint32_t mesh_sds_timeout_secs;
uint32_t sds_secs;
uint32_t ls_secs;
uint32_t min_wake_secs;
char wifi_ssid[33];
char wifi_password[64];
bool wifi_ap_mode;
RegionCode region;
ChargeCurrent charge_current;
bool position_broadcast_smart_disabled;
Role role;
bool location_share_disabled;
bool gps_disabled;
uint32_t gps_update_interval;
uint32_t gps_attempt_time;
bool is_low_power;
bool fixed_position;
bool serial_disabled;
float frequency_offset;
char mqtt_server[32];
bool mqtt_disabled;
GpsCoordinateFormat gps_format;
bool gps_accept_2d;
uint32_t gps_max_dop;
bool factory_reset;
bool debug_log_enabled;
pb_size_t ignore_incoming_count;
uint32_t ignore_incoming[3];
bool serial_module_enabled;
bool serial_module_echo;
uint32_t serial_module_rxd;
uint32_t serial_module_txd;
uint32_t serial_module_timeout;
RadioConfig_UserPreferences_Serial_Mode serial_module_mode;
bool ext_notification_module_enabled;
uint32_t ext_notification_module_output_ms;
uint32_t ext_notification_module_output;
bool ext_notification_module_active;
bool ext_notification_module_alert_message;
bool ext_notification_module_alert_bell;
bool range_test_module_enabled;
uint32_t range_test_module_sender;
bool range_test_module_save;
uint32_t store_forward_module_records;
uint32_t store_forward_module_history_return_max;
uint32_t store_forward_module_history_return_window;
bool store_forward_module_enabled;
bool store_forward_module_heartbeat;
uint32_t position_flags;
bool is_always_powered;
uint32_t auto_screen_carousel_secs;
uint32_t on_battery_shutdown_after_secs;
uint32_t hop_limit;
char mqtt_username[32];
char mqtt_password[32];
bool is_lora_tx_disabled;
bool is_power_saving;
bool rotary1_enabled;
uint32_t inputbroker_pin_a;
uint32_t inputbroker_pin_b;
uint32_t inputbroker_pin_press;
InputEventChar inputbroker_event_cw;
InputEventChar inputbroker_event_ccw;
InputEventChar inputbroker_event_press;
bool updown1_enabled;
bool canned_message_module_enabled;
char canned_message_module_allow_input_source[16];
bool canned_message_module_send_bell;
bool mqtt_encryption_enabled;
float adc_multiplier_override;
RadioConfig_UserPreferences_Serial_Baud serial_module_baud;
} RadioConfig_UserPreferences;
/* The entire set of user settable/readable settings for our radio device.
Includes both the current channel settings and any preferences the user has
set for behavior of their node */
typedef struct _RadioConfig {
/* TODO: REPLACE */
bool has_preferences;
RadioConfig_UserPreferences preferences;
} RadioConfig;
/* Helper constants for enums */
#define _RegionCode_MIN RegionCode_Unset
#define _RegionCode_MAX RegionCode_TH
#define _RegionCode_ARRAYSIZE ((RegionCode)(RegionCode_TH+1))
#define _Role_MIN Role_Client
#define _Role_MAX Role_RouterClient
#define _Role_ARRAYSIZE ((Role)(Role_RouterClient+1))
#define _ChargeCurrent_MIN ChargeCurrent_MAUnset
#define _ChargeCurrent_MAX ChargeCurrent_MA1320
#define _ChargeCurrent_ARRAYSIZE ((ChargeCurrent)(ChargeCurrent_MA1320+1))
#define _GpsCoordinateFormat_MIN GpsCoordinateFormat_GpsFormatDec
#define _GpsCoordinateFormat_MAX GpsCoordinateFormat_GpsFormatOSGR
#define _GpsCoordinateFormat_ARRAYSIZE ((GpsCoordinateFormat)(GpsCoordinateFormat_GpsFormatOSGR+1))
#define _PositionFlags_MIN PositionFlags_POS_UNDEFINED
#define _PositionFlags_MAX PositionFlags_POS_TIMESTAMP
#define _PositionFlags_ARRAYSIZE ((PositionFlags)(PositionFlags_POS_TIMESTAMP+1))
#define _InputEventChar_MIN InputEventChar_KEY_NONE
#define _InputEventChar_MAX InputEventChar_KEY_BACK
#define _InputEventChar_ARRAYSIZE ((InputEventChar)(InputEventChar_KEY_BACK+1))
#define _RadioConfig_UserPreferences_Serial_Baud_MIN RadioConfig_UserPreferences_Serial_Baud_BAUD_Default
#define _RadioConfig_UserPreferences_Serial_Baud_MAX RadioConfig_UserPreferences_Serial_Baud_BAUD_1200
#define _RadioConfig_UserPreferences_Serial_Baud_ARRAYSIZE ((RadioConfig_UserPreferences_Serial_Baud)(RadioConfig_UserPreferences_Serial_Baud_BAUD_1200+1))
#define _RadioConfig_UserPreferences_Serial_Mode_MIN RadioConfig_UserPreferences_Serial_Mode_MODE_Default
#define _RadioConfig_UserPreferences_Serial_Mode_MAX RadioConfig_UserPreferences_Serial_Mode_MODE_PROTO
#define _RadioConfig_UserPreferences_Serial_Mode_ARRAYSIZE ((RadioConfig_UserPreferences_Serial_Mode)(RadioConfig_UserPreferences_Serial_Mode_MODE_PROTO+1))
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define RadioConfig_init_default {false, RadioConfig_UserPreferences_init_default}
#define RadioConfig_UserPreferences_init_default {0, 0, 0, 0, 0, 0, 0, 0, "", "", 0, _RegionCode_MIN, _ChargeCurrent_MIN, 0, _Role_MIN, 0, 0, 0, 0, 0, 0, 0, 0, "", 0, _GpsCoordinateFormat_MIN, 0, 0, 0, 0, 0, {0, 0, 0}, 0, 0, 0, 0, 0, _RadioConfig_UserPreferences_Serial_Mode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, "", "", 0, 0, 0, 0, 0, 0, _InputEventChar_MIN, _InputEventChar_MIN, _InputEventChar_MIN, 0, 0, "", 0, 0, 0, _RadioConfig_UserPreferences_Serial_Baud_MIN}
#define RadioConfig_init_zero {false, RadioConfig_UserPreferences_init_zero}
#define RadioConfig_UserPreferences_init_zero {0, 0, 0, 0, 0, 0, 0, 0, "", "", 0, _RegionCode_MIN, _ChargeCurrent_MIN, 0, _Role_MIN, 0, 0, 0, 0, 0, 0, 0, 0, "", 0, _GpsCoordinateFormat_MIN, 0, 0, 0, 0, 0, {0, 0, 0}, 0, 0, 0, 0, 0, _RadioConfig_UserPreferences_Serial_Mode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, "", "", 0, 0, 0, 0, 0, 0, _InputEventChar_MIN, _InputEventChar_MIN, _InputEventChar_MIN, 0, 0, "", 0, 0, 0, _RadioConfig_UserPreferences_Serial_Baud_MIN}
/* Field tags (for use in manual encoding/decoding) */
#define RadioConfig_UserPreferences_position_broadcast_secs_tag 1
#define RadioConfig_UserPreferences_wait_bluetooth_secs_tag 4
#define RadioConfig_UserPreferences_screen_on_secs_tag 5
#define RadioConfig_UserPreferences_phone_timeout_secs_tag 6
#define RadioConfig_UserPreferences_mesh_sds_timeout_secs_tag 8
#define RadioConfig_UserPreferences_sds_secs_tag 9
#define RadioConfig_UserPreferences_ls_secs_tag 10
#define RadioConfig_UserPreferences_min_wake_secs_tag 11
#define RadioConfig_UserPreferences_wifi_ssid_tag 12
#define RadioConfig_UserPreferences_wifi_password_tag 13
#define RadioConfig_UserPreferences_wifi_ap_mode_tag 14
#define RadioConfig_UserPreferences_region_tag 15
#define RadioConfig_UserPreferences_charge_current_tag 16
#define RadioConfig_UserPreferences_position_broadcast_smart_disabled_tag 17
#define RadioConfig_UserPreferences_role_tag 18
#define RadioConfig_UserPreferences_location_share_disabled_tag 32
#define RadioConfig_UserPreferences_gps_disabled_tag 33
#define RadioConfig_UserPreferences_gps_update_interval_tag 34
#define RadioConfig_UserPreferences_gps_attempt_time_tag 36
#define RadioConfig_UserPreferences_is_low_power_tag 38
#define RadioConfig_UserPreferences_fixed_position_tag 39
#define RadioConfig_UserPreferences_serial_disabled_tag 40
#define RadioConfig_UserPreferences_frequency_offset_tag 41
#define RadioConfig_UserPreferences_mqtt_server_tag 42
#define RadioConfig_UserPreferences_mqtt_disabled_tag 43
#define RadioConfig_UserPreferences_gps_format_tag 44
#define RadioConfig_UserPreferences_gps_accept_2d_tag 45
#define RadioConfig_UserPreferences_gps_max_dop_tag 46
#define RadioConfig_UserPreferences_factory_reset_tag 100
#define RadioConfig_UserPreferences_debug_log_enabled_tag 101
#define RadioConfig_UserPreferences_ignore_incoming_tag 103
#define RadioConfig_UserPreferences_serial_module_enabled_tag 120
#define RadioConfig_UserPreferences_serial_module_echo_tag 121
#define RadioConfig_UserPreferences_serial_module_rxd_tag 122
#define RadioConfig_UserPreferences_serial_module_txd_tag 123
#define RadioConfig_UserPreferences_serial_module_timeout_tag 124
#define RadioConfig_UserPreferences_serial_module_mode_tag 125
#define RadioConfig_UserPreferences_ext_notification_module_enabled_tag 126
#define RadioConfig_UserPreferences_ext_notification_module_output_ms_tag 127
#define RadioConfig_UserPreferences_ext_notification_module_output_tag 128
#define RadioConfig_UserPreferences_ext_notification_module_active_tag 129
#define RadioConfig_UserPreferences_ext_notification_module_alert_message_tag 130
#define RadioConfig_UserPreferences_ext_notification_module_alert_bell_tag 131
#define RadioConfig_UserPreferences_range_test_module_enabled_tag 132
#define RadioConfig_UserPreferences_range_test_module_sender_tag 133
#define RadioConfig_UserPreferences_range_test_module_save_tag 134
#define RadioConfig_UserPreferences_store_forward_module_records_tag 137
#define RadioConfig_UserPreferences_store_forward_module_history_return_max_tag 138
#define RadioConfig_UserPreferences_store_forward_module_history_return_window_tag 139
#define RadioConfig_UserPreferences_store_forward_module_enabled_tag 148
#define RadioConfig_UserPreferences_store_forward_module_heartbeat_tag 149
#define RadioConfig_UserPreferences_position_flags_tag 150
#define RadioConfig_UserPreferences_is_always_powered_tag 151
#define RadioConfig_UserPreferences_auto_screen_carousel_secs_tag 152
#define RadioConfig_UserPreferences_on_battery_shutdown_after_secs_tag 153
#define RadioConfig_UserPreferences_hop_limit_tag 154
#define RadioConfig_UserPreferences_mqtt_username_tag 155
#define RadioConfig_UserPreferences_mqtt_password_tag 156
#define RadioConfig_UserPreferences_is_lora_tx_disabled_tag 157
#define RadioConfig_UserPreferences_is_power_saving_tag 158
#define RadioConfig_UserPreferences_rotary1_enabled_tag 160
#define RadioConfig_UserPreferences_inputbroker_pin_a_tag 161
#define RadioConfig_UserPreferences_inputbroker_pin_b_tag 162
#define RadioConfig_UserPreferences_inputbroker_pin_press_tag 163
#define RadioConfig_UserPreferences_inputbroker_event_cw_tag 164
#define RadioConfig_UserPreferences_inputbroker_event_ccw_tag 165
#define RadioConfig_UserPreferences_inputbroker_event_press_tag 166
#define RadioConfig_UserPreferences_updown1_enabled_tag 167
#define RadioConfig_UserPreferences_canned_message_module_enabled_tag 170
#define RadioConfig_UserPreferences_canned_message_module_allow_input_source_tag 171
#define RadioConfig_UserPreferences_canned_message_module_send_bell_tag 173
#define RadioConfig_UserPreferences_mqtt_encryption_enabled_tag 174
#define RadioConfig_UserPreferences_adc_multiplier_override_tag 175
#define RadioConfig_UserPreferences_serial_module_baud_tag 176
#define RadioConfig_preferences_tag 1
/* Struct field encoding specification for nanopb */
#define RadioConfig_FIELDLIST(X, a) \
X(a, STATIC, OPTIONAL, MESSAGE, preferences, 1)
#define RadioConfig_CALLBACK NULL
#define RadioConfig_DEFAULT NULL
#define RadioConfig_preferences_MSGTYPE RadioConfig_UserPreferences
#define RadioConfig_UserPreferences_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, position_broadcast_secs, 1) \
X(a, STATIC, SINGULAR, UINT32, wait_bluetooth_secs, 4) \
X(a, STATIC, SINGULAR, UINT32, screen_on_secs, 5) \
X(a, STATIC, SINGULAR, UINT32, phone_timeout_secs, 6) \
X(a, STATIC, SINGULAR, UINT32, mesh_sds_timeout_secs, 8) \
X(a, STATIC, SINGULAR, UINT32, sds_secs, 9) \
X(a, STATIC, SINGULAR, UINT32, ls_secs, 10) \
X(a, STATIC, SINGULAR, UINT32, min_wake_secs, 11) \
X(a, STATIC, SINGULAR, STRING, wifi_ssid, 12) \
X(a, STATIC, SINGULAR, STRING, wifi_password, 13) \
X(a, STATIC, SINGULAR, BOOL, wifi_ap_mode, 14) \
X(a, STATIC, SINGULAR, UENUM, region, 15) \
X(a, STATIC, SINGULAR, UENUM, charge_current, 16) \
X(a, STATIC, SINGULAR, BOOL, position_broadcast_smart_disabled, 17) \
X(a, STATIC, SINGULAR, UENUM, role, 18) \
X(a, STATIC, SINGULAR, BOOL, location_share_disabled, 32) \
X(a, STATIC, SINGULAR, BOOL, gps_disabled, 33) \
X(a, STATIC, SINGULAR, UINT32, gps_update_interval, 34) \
X(a, STATIC, SINGULAR, UINT32, gps_attempt_time, 36) \
X(a, STATIC, SINGULAR, BOOL, is_low_power, 38) \
X(a, STATIC, SINGULAR, BOOL, fixed_position, 39) \
X(a, STATIC, SINGULAR, BOOL, serial_disabled, 40) \
X(a, STATIC, SINGULAR, FLOAT, frequency_offset, 41) \
X(a, STATIC, SINGULAR, STRING, mqtt_server, 42) \
X(a, STATIC, SINGULAR, BOOL, mqtt_disabled, 43) \
X(a, STATIC, SINGULAR, UENUM, gps_format, 44) \
X(a, STATIC, SINGULAR, BOOL, gps_accept_2d, 45) \
X(a, STATIC, SINGULAR, UINT32, gps_max_dop, 46) \
X(a, STATIC, SINGULAR, BOOL, factory_reset, 100) \
X(a, STATIC, SINGULAR, BOOL, debug_log_enabled, 101) \
X(a, STATIC, REPEATED, UINT32, ignore_incoming, 103) \
X(a, STATIC, SINGULAR, BOOL, serial_module_enabled, 120) \
X(a, STATIC, SINGULAR, BOOL, serial_module_echo, 121) \
X(a, STATIC, SINGULAR, UINT32, serial_module_rxd, 122) \
X(a, STATIC, SINGULAR, UINT32, serial_module_txd, 123) \
X(a, STATIC, SINGULAR, UINT32, serial_module_timeout, 124) \
X(a, STATIC, SINGULAR, UENUM, serial_module_mode, 125) \
X(a, STATIC, SINGULAR, BOOL, ext_notification_module_enabled, 126) \
X(a, STATIC, SINGULAR, UINT32, ext_notification_module_output_ms, 127) \
X(a, STATIC, SINGULAR, UINT32, ext_notification_module_output, 128) \
X(a, STATIC, SINGULAR, BOOL, ext_notification_module_active, 129) \
X(a, STATIC, SINGULAR, BOOL, ext_notification_module_alert_message, 130) \
X(a, STATIC, SINGULAR, BOOL, ext_notification_module_alert_bell, 131) \
X(a, STATIC, SINGULAR, BOOL, range_test_module_enabled, 132) \
X(a, STATIC, SINGULAR, UINT32, range_test_module_sender, 133) \
X(a, STATIC, SINGULAR, BOOL, range_test_module_save, 134) \
X(a, STATIC, SINGULAR, UINT32, store_forward_module_records, 137) \
X(a, STATIC, SINGULAR, UINT32, store_forward_module_history_return_max, 138) \
X(a, STATIC, SINGULAR, UINT32, store_forward_module_history_return_window, 139) \
X(a, STATIC, SINGULAR, BOOL, store_forward_module_enabled, 148) \
X(a, STATIC, SINGULAR, BOOL, store_forward_module_heartbeat, 149) \
X(a, STATIC, SINGULAR, UINT32, position_flags, 150) \
X(a, STATIC, SINGULAR, BOOL, is_always_powered, 151) \
X(a, STATIC, SINGULAR, UINT32, auto_screen_carousel_secs, 152) \
X(a, STATIC, SINGULAR, UINT32, on_battery_shutdown_after_secs, 153) \
X(a, STATIC, SINGULAR, UINT32, hop_limit, 154) \
X(a, STATIC, SINGULAR, STRING, mqtt_username, 155) \
X(a, STATIC, SINGULAR, STRING, mqtt_password, 156) \
X(a, STATIC, SINGULAR, BOOL, is_lora_tx_disabled, 157) \
X(a, STATIC, SINGULAR, BOOL, is_power_saving, 158) \
X(a, STATIC, SINGULAR, BOOL, rotary1_enabled, 160) \
X(a, STATIC, SINGULAR, UINT32, inputbroker_pin_a, 161) \
X(a, STATIC, SINGULAR, UINT32, inputbroker_pin_b, 162) \
X(a, STATIC, SINGULAR, UINT32, inputbroker_pin_press, 163) \
X(a, STATIC, SINGULAR, UENUM, inputbroker_event_cw, 164) \
X(a, STATIC, SINGULAR, UENUM, inputbroker_event_ccw, 165) \
X(a, STATIC, SINGULAR, UENUM, inputbroker_event_press, 166) \
X(a, STATIC, SINGULAR, BOOL, updown1_enabled, 167) \
X(a, STATIC, SINGULAR, BOOL, canned_message_module_enabled, 170) \
X(a, STATIC, SINGULAR, STRING, canned_message_module_allow_input_source, 171) \
X(a, STATIC, SINGULAR, BOOL, canned_message_module_send_bell, 173) \
X(a, STATIC, SINGULAR, BOOL, mqtt_encryption_enabled, 174) \
X(a, STATIC, SINGULAR, FLOAT, adc_multiplier_override, 175) \
X(a, STATIC, SINGULAR, UENUM, serial_module_baud, 176)
#define RadioConfig_UserPreferences_CALLBACK NULL
#define RadioConfig_UserPreferences_DEFAULT NULL
extern const pb_msgdesc_t RadioConfig_msg;
extern const pb_msgdesc_t RadioConfig_UserPreferences_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define RadioConfig_fields &RadioConfig_msg
#define RadioConfig_UserPreferences_fields &RadioConfig_UserPreferences_msg
/* Maximum encoded size of messages (where known) */
#define RadioConfig_UserPreferences_size 545
#define RadioConfig_size 548
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

Wyświetl plik

@ -67,8 +67,6 @@ char contentTypes[][2][32] = {{".txt", "text/plain"}, {".html", "text/html"}
// Our API to handle messages to and from the radio.
HttpAPI webAPI;
void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
{
@ -85,9 +83,9 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
ResourceNode *nodeAdmin = new ResourceNode("/admin", "GET", &handleAdmin);
ResourceNode *nodeAdminSettings = new ResourceNode("/admin/settings", "GET", &handleAdminSettings);
ResourceNode *nodeAdminSettingsApply = new ResourceNode("/admin/settings/apply", "POST", &handleAdminSettingsApply);
// ResourceNode *nodeAdminFs = new ResourceNode("/admin/fs", "GET", &handleFs);
// ResourceNode *nodeUpdateFs = new ResourceNode("/admin/fs/update", "POST", &handleUpdateFs);
// ResourceNode *nodeDeleteFs = new ResourceNode("/admin/fs/delete", "GET", &handleDeleteFsContent);
// ResourceNode *nodeAdminFs = new ResourceNode("/admin/fs", "GET", &handleFs);
// ResourceNode *nodeUpdateFs = new ResourceNode("/admin/fs/update", "POST", &handleUpdateFs);
// ResourceNode *nodeDeleteFs = new ResourceNode("/admin/fs/delete", "GET", &handleDeleteFsContent);
ResourceNode *nodeRestart = new ResourceNode("/restart", "POST", &handleRestart);
ResourceNode *nodeFormUpload = new ResourceNode("/upload", "POST", &handleFormUpload);
@ -98,7 +96,6 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
ResourceNode *nodeJsonFsBrowseStatic = new ResourceNode("/json/fs/browse/static", "GET", &handleFsBrowseStatic);
ResourceNode *nodeJsonDelete = new ResourceNode("/json/fs/delete/static", "DELETE", &handleFsDeleteStatic);
ResourceNode *nodeRoot = new ResourceNode("/*", "GET", &handleStatic);
// Secure nodes
@ -114,10 +111,10 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
secureServer->registerNode(nodeJsonFsBrowseStatic);
secureServer->registerNode(nodeJsonDelete);
secureServer->registerNode(nodeJsonReport);
// secureServer->registerNode(nodeUpdateFs);
// secureServer->registerNode(nodeDeleteFs);
// secureServer->registerNode(nodeUpdateFs);
// secureServer->registerNode(nodeDeleteFs);
secureServer->registerNode(nodeAdmin);
// secureServer->registerNode(nodeAdminFs);
// secureServer->registerNode(nodeAdminFs);
secureServer->registerNode(nodeAdminSettings);
secureServer->registerNode(nodeAdminSettingsApply);
secureServer->registerNode(nodeRoot); // This has to be last
@ -135,10 +132,10 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
insecureServer->registerNode(nodeJsonFsBrowseStatic);
insecureServer->registerNode(nodeJsonDelete);
insecureServer->registerNode(nodeJsonReport);
// insecureServer->registerNode(nodeUpdateFs);
// insecureServer->registerNode(nodeDeleteFs);
// insecureServer->registerNode(nodeUpdateFs);
// insecureServer->registerNode(nodeDeleteFs);
insecureServer->registerNode(nodeAdmin);
// insecureServer->registerNode(nodeAdminFs);
// insecureServer->registerNode(nodeAdminFs);
insecureServer->registerNode(nodeAdminSettings);
insecureServer->registerNode(nodeAdminSettingsApply);
insecureServer->registerNode(nodeRoot); // This has to be last
@ -227,19 +224,19 @@ void handleAPIv1ToRadio(HTTPRequest *req, HTTPResponse *res)
DEBUG_MSG("webAPI handleAPIv1ToRadio\n");
}
void htmlDeleteDir(const char * dirname)
void htmlDeleteDir(const char *dirname)
{
File root = FSCom.open(dirname);
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(".")) {
while (file) {
if (file.isDirectory() && !String(file.name()).endsWith(".")) {
htmlDeleteDir(file.name());
file.close();
} else {
@ -247,32 +244,32 @@ void htmlDeleteDir(const char * dirname)
file.close();
DEBUG_MSG(" %s\n", fileName.c_str());
FSCom.remove(fileName);
}
file = root.openNextFile();
}
root.close();
}
std::vector<std::map<char *, char *>>* htmlListDir(std::vector<std::map<char *, char *>> *fileList, const char *dirname, uint8_t levels)
std::vector<std::map<char *, char *>> *htmlListDir(std::vector<std::map<char *, char *>> *fileList, const char *dirname,
uint8_t levels)
{
File root = FSCom.open(dirname);
if(!root){
if (!root) {
return NULL;
}
if(!root.isDirectory()){
if (!root.isDirectory()) {
return NULL;
}
// iterate over the file list
File file = root.openNextFile();
while(file){
if(file.isDirectory() && !String(file.name()).endsWith(".")) {
if(levels){
htmlListDir(fileList, file.name(), levels -1);
while (file) {
if (file.isDirectory() && !String(file.name()).endsWith(".")) {
if (levels) {
htmlListDir(fileList, file.name(), levels - 1);
}
} else {
std::map<char*, char*> thisFileMap;
} else {
std::map<char *, char *> thisFileMap;
thisFileMap[strdup("size")] = strdup(String(file.size()).c_str());
thisFileMap[strdup("name")] = strdup(String(file.name()).substring(1).c_str());
if (String(file.name()).substring(1).endsWith(".gz")) {
@ -305,9 +302,7 @@ void handleFsBrowseStatic(HTTPRequest *req, HTTPResponse *res)
{"free", String(FSCom.totalBytes() - FSCom.usedBytes()).c_str()},
};
Json jsonObjInner = Json::object{{"files", Json(*fileList)},
{"filesystem", filesystemObj}
};
Json jsonObjInner = Json::object{{"files", Json(*fileList)}, {"filesystem", filesystemObj}};
Json jsonObjOuter = Json::object{{"data", jsonObjInner}, {"status", "ok"}};
@ -365,7 +360,7 @@ void handleStatic(HTTPRequest *req, HTTPResponse *res)
filename = "/static/index.html";
filenameGzip = "/static/index.html.gz";
}
if (FSCom.exists(filename.c_str())) {
file = FSCom.open(filename.c_str());
if (!file.available()) {
@ -615,31 +610,28 @@ void handleReport(HTTPRequest *req, HTTPResponse *res)
// data->wifi
String ipStr;
if (radioConfig.preferences.wifi_ap_mode || isSoftAPForced()) {
if (config.payloadVariant.wifi.ap_mode || isSoftAPForced()) {
ipStr = String(WiFi.softAPIP().toString());
} else {
ipStr = String(WiFi.localIP().toString());
}
Json jsonObjWifi = Json::object{
{"rssi", String(WiFi.RSSI())},
{"ip", ipStr.c_str()}
};
Json jsonObjWifi = Json::object{{"rssi", String(WiFi.RSSI())}, {"ip", ipStr.c_str()}};
// data->memory
Json jsonObjMemory = Json::object{{"heap_total", Json(int(ESP.getHeapSize()))},
{"heap_free", Json(int(ESP.getFreeHeap()))},
{"psram_total", Json(int(ESP.getPsramSize()))},
{"psram_free", Json(int(ESP.getFreePsram()))},
{"fs_total", String(FSCom.totalBytes()).c_str()},
{"fs_used", String(FSCom.usedBytes()).c_str()},
{"fs_free", String(FSCom.totalBytes() - FSCom.usedBytes()).c_str()}};
{"heap_free", Json(int(ESP.getFreeHeap()))},
{"psram_total", Json(int(ESP.getPsramSize()))},
{"psram_free", Json(int(ESP.getFreePsram()))},
{"fs_total", String(FSCom.totalBytes()).c_str()},
{"fs_used", String(FSCom.usedBytes()).c_str()},
{"fs_free", String(FSCom.totalBytes() - FSCom.usedBytes()).c_str()}};
// data->power
Json jsonObjPower = Json::object{{"battery_percent", Json(powerStatus->getBatteryChargePercent())},
{"battery_voltage_mv", Json(powerStatus->getBatteryVoltageMv())},
{"has_battery", BoolToString(powerStatus->getHasBattery())},
{"has_usb", BoolToString(powerStatus->getHasUSB())},
{"is_charging", BoolToString(powerStatus->getIsCharging())}};
{"battery_voltage_mv", Json(powerStatus->getBatteryVoltageMv())},
{"has_battery", BoolToString(powerStatus->getHasBattery())},
{"has_usb", BoolToString(powerStatus->getHasUSB())},
{"is_charging", BoolToString(powerStatus->getIsCharging())}};
// data->device
Json jsonObjDevice = Json::object{{"reboot_counter", Json(int(myNodeInfo.reboot_count))}};
@ -681,7 +673,6 @@ void handleHotspot(HTTPRequest *req, HTTPResponse *res)
res->println("<meta http-equiv=\"refresh\" content=\"0;url=/\" />\n");
}
void handleDeleteFsContent(HTTPRequest *req, HTTPResponse *res)
{
res->setHeader("Content-Type", "text/html");
@ -723,7 +714,8 @@ void handleAdminSettings(HTTPRequest *req, HTTPResponse *res)
res->println("<tr><td>Set?</td><td>Setting</td><td>current value</td><td>new value</td></tr>\n");
res->println("<tr><td><input type=checkbox></td><td>WiFi SSID</td><td>false</td><td><input type=radio></td></tr>\n");
res->println("<tr><td><input type=checkbox></td><td>WiFi Password</td><td>false</td><td><input type=radio></td></tr>\n");
res->println("<tr><td><input type=checkbox></td><td>Smart Position Update</td><td>false</td><td><input type=radio></td></tr>\n");
res->println(
"<tr><td><input type=checkbox></td><td>Smart Position Update</td><td>false</td><td><input type=radio></td></tr>\n");
res->println("<tr><td><input type=checkbox></td><td>is_always_powered</td><td>false</td><td><input type=radio></td></tr>\n");
res->println("<tr><td><input type=checkbox></td><td>is_always_powered</td><td>false</td><td><input type=radio></td></tr>\n");
res->println("</table>\n");
@ -745,7 +737,6 @@ void handleAdminSettingsApply(HTTPRequest *req, HTTPResponse *res)
res->println("Settings Applied. Please wait.\n");
}
void handleFs(HTTPRequest *req, HTTPResponse *res)
{
res->setHeader("Content-Type", "text/html");
@ -798,9 +789,9 @@ void handleBlinkLED(HTTPRequest *req, HTTPResponse *res)
count = count - 1;
}
} else {
#ifndef NO_SCREEN
#ifndef NO_SCREEN
screen->blink();
#endif
#endif
}
Json jsonObjOuter = Json::object{{"status", "ok"}};

Wyświetl plik

@ -59,10 +59,11 @@ static WifiSleepObserver wifiSleepObserver;
static int32_t reconnectWiFi()
{
const char *wifiName = radioConfig.preferences.wifi_ssid;
const char *wifiPsw = radioConfig.preferences.wifi_password;
const char *wifiName = config.payloadVariant.wifi.ssid;
const char *wifiPsw = config.payloadVariant.wifi.psk;
if (radioConfig.has_preferences && needReconnect && !WiFi.isConnected()) {
if (needReconnect && !WiFi.isConnected()) {
// if (radioConfig.has_preferences && needReconnect && !WiFi.isConnected()) {
if (!*wifiPsw) // Treat empty password as no password
wifiPsw = NULL;
@ -114,7 +115,7 @@ bool isWifiAvailable()
return true;
}
const char *wifiName = radioConfig.preferences.wifi_ssid;
const char *wifiName = config.payloadVariant.wifi.ssid;
if (*wifiName) {
return true;
@ -184,16 +185,14 @@ bool initWifi(bool forceSoftAP)
{
forcedSoftAP = forceSoftAP;
// strcpy(radioConfig.preferences.wifi_ssid, "meshtastic");
// strcpy(radioConfig.preferences.wifi_password, "meshtastic!");
if ((radioConfig.has_preferences && radioConfig.preferences.wifi_ssid[0]) || forceSoftAP) {
const char *wifiName = radioConfig.preferences.wifi_ssid;
const char *wifiPsw = radioConfig.preferences.wifi_password;
if ((config.payloadVariant.wifi.ssid[0]) || forceSoftAP) {
// if ((radioConfig.has_preferences && config.payloadVariant.wifi.ssid[0]) || forceSoftAP) {
const char *wifiName = config.payloadVariant.wifi.ssid;
const char *wifiPsw = config.payloadVariant.wifi.psk;
if (forceSoftAP) {
DEBUG_MSG("WiFi ... Forced AP Mode\n");
} else if (radioConfig.preferences.wifi_ap_mode) {
} else if (config.payloadVariant.wifi.ap_mode) {
DEBUG_MSG("WiFi ... AP Mode\n");
} else {
DEBUG_MSG("WiFi ... Client Mode\n");
@ -205,7 +204,7 @@ bool initWifi(bool forceSoftAP)
wifiPsw = NULL;
if (*wifiName || forceSoftAP) {
if (radioConfig.preferences.wifi_ap_mode || forceSoftAP) {
if (config.payloadVariant.wifi.ap_mode || forceSoftAP) {
IPAddress apIP(192, 168, 42, 1);
WiFi.onEvent(WiFiEvent);
@ -364,7 +363,7 @@ static void WiFiEvent(WiFiEvent_t event)
void handleDNSResponse()
{
if (radioConfig.preferences.wifi_ap_mode || isSoftAPForced()) {
if (config.payloadVariant.wifi.ap_mode || isSoftAPForced()) {
dnsServer.processNextRequest();
}
}

Wyświetl plik

@ -56,11 +56,6 @@ bool AdminModule::handleReceivedProtobuf(const MeshPacket &mp, AdminMessage *r)
handleGetOwner(mp);
break;
case AdminMessage_get_radio_request_tag:
DEBUG_MSG("Client is getting radio\n");
handleGetRadio(mp);
break;
case AdminMessage_get_config_request_tag:
DEBUG_MSG("Client is getting config\n");
handleGetConfig(mp, r->get_channel_request);
@ -89,11 +84,6 @@ bool AdminModule::handleReceivedProtobuf(const MeshPacket &mp, AdminMessage *r)
handleSetOwner(r->set_owner);
break;
case AdminMessage_set_radio_tag:
DEBUG_MSG("Client is setting radio\n");
handleSetRadio(r->set_radio);
break;
case AdminMessage_set_config_tag:
DEBUG_MSG("Client is setting the config\n");
handleSetConfig(r->set_config);
@ -181,36 +171,40 @@ void AdminModule::handleSetOwner(const User &o)
service.reloadOwner();
}
void AdminModule::handleSetRadio(RadioConfig &r)
{
writeSecret(r.preferences.wifi_password, radioConfig.preferences.wifi_password);
radioConfig = r;
// void AdminModule::handleSetRadio(RadioConfig &r)
// {
// // writeSecret(r.preferences.wifi_password, radioConfig.preferences.wifi_password);
// radioConfig = r;
service.reloadConfig();
}
// service.reloadConfig();
// }
void AdminModule::handleSetConfig(const Config &c)
{
switch (c.which_payloadVariant) {
case Config_device_config_tag:
case Config_device_tag:
DEBUG_MSG("Setting config: Device\n");
config.payloadVariant.device = c.payloadVariant.device;
break;
case Config_gps_config_tag:
DEBUG_MSG("Setting config: GPS\n");
case Config_position_tag:
DEBUG_MSG("Setting config: Position\n");
config.payloadVariant.position = c.payloadVariant.position;
break;
case Config_power_config_tag:
case Config_power_tag:
DEBUG_MSG("Setting config: Power\n");
config.payloadVariant.power = c.payloadVariant.power;
break;
case Config_wifi_config_tag:
case Config_wifi_tag:
DEBUG_MSG("Setting config: WiFi\n");
config.payloadVariant.wifi = c.payloadVariant.wifi;
break;
case Config_display_config_tag:
case Config_display_tag:
DEBUG_MSG("Setting config: Display\n");
config.payloadVariant.display = c.payloadVariant.display;
break;
case Config_lora_config_tag:
case Config_lora_tag:
DEBUG_MSG("Setting config: LoRa\n");
config.payloadVariant.lora_config = c.payloadVariant.lora_config;
service.reloadConfig();
config.payloadVariant.lora = c.payloadVariant.lora;
break;
}
@ -220,27 +214,33 @@ void AdminModule::handleSetConfig(const Config &c)
void AdminModule::handleSetModuleConfig(const ModuleConfig &c)
{
switch (c.which_payloadVariant) {
case ModuleConfig_mqtt_config_tag:
case ModuleConfig_mqtt_tag:
DEBUG_MSG("Setting module config: MQTT\n");
moduleConfig.payloadVariant.mqtt = c.payloadVariant.mqtt;
break;
case ModuleConfig_serial_config_tag:
case ModuleConfig_serial_tag:
DEBUG_MSG("Setting module config: Serial\n");
moduleConfig.payloadVariant.serial = c.payloadVariant.serial;
break;
case ModuleConfig_external_notification_config_tag:
case ModuleConfig_external_notification_tag:
DEBUG_MSG("Setting module config: External Notification\n");
moduleConfig.payloadVariant.external_notification = c.payloadVariant.external_notification;
break;
case ModuleConfig_store_forward_config_tag:
case ModuleConfig_store_forward_tag:
DEBUG_MSG("Setting module config: Store & Forward\n");
moduleConfig.payloadVariant.store_forward = c.payloadVariant.store_forward;
break;
case ModuleConfig_range_test_config_tag:
case ModuleConfig_range_test_tag:
DEBUG_MSG("Setting module config: Range Test\n");
moduleConfig.payloadVariant.range_test = c.payloadVariant.range_test;
break;
case ModuleConfig_telemetry_config_tag:
case ModuleConfig_telemetry_tag:
DEBUG_MSG("Setting module config: Telemetry\n");
moduleConfig.payloadVariant.telemetry_config = c.payloadVariant.telemetry_config;
moduleConfig.payloadVariant.telemetry = c.payloadVariant.telemetry;
break;
case ModuleConfig_canned_message_config_tag:
case ModuleConfig_canned_message_tag:
DEBUG_MSG("Setting module config: Canned Message\n");
moduleConfig.payloadVariant.canned_message = c.payloadVariant.canned_message;
break;
}
@ -270,26 +270,28 @@ void AdminModule::handleGetOwner(const MeshPacket &req)
}
}
void AdminModule::handleGetRadio(const MeshPacket &req)
{
if (req.decoded.want_response) {
// We create the reply here
AdminMessage res = AdminMessage_init_default;
res.get_radio_response = radioConfig;
// void AdminModule::handleGetRadio(const MeshPacket &req)
// {
// if (req.decoded.want_response) {
// // We create the reply here
// AdminMessage res = AdminMessage_init_default;
// res.get_radio_response = radioConfig;
// NOTE: The phone app needs to know the ls_secs & phone_timeout value so it can properly expect sleep behavior.
// So even if we internally use 0 to represent 'use default' we still need to send the value we are
// using to the app (so that even old phone apps work with new device loads).
res.get_radio_response.preferences.ls_secs = getPref_ls_secs();
res.get_radio_response.preferences.phone_timeout_secs = getPref_phone_timeout_secs();
// hideSecret(r.get_radio_response.preferences.wifi_ssid); // hmm - leave public for now, because only minimally private
// and useful for users to know current provisioning)
hideSecret(res.get_radio_response.preferences.wifi_password);
// // NOTE: The phone app needs to know the ls_secs & phone_timeout value so it can properly expect sleep behavior.
// // So even if we internally use 0 to represent 'use default' we still need to send the value we are
// // using to the app (so that even old phone apps work with new device loads).
// // res.get_radio_response.preferences.ls_secs = getPref_ls_secs(); //TODO: Re-implement if necceasry
// // res.get_radio_response.preferences.phone_timeout_secs = getPref_phone_timeout_secs(); //TODO: Re-implement if
// necceasry
// // hideSecret(r.get_radio_response.preferences.wifi_ssid); // hmm - leave public for now, because only minimally
// private
// // and useful for users to know current provisioning)
// // hideSecret(res.get_radio_response.preferences.wifi_password);
res.which_variant = AdminMessage_get_radio_response_tag;
myReply = allocDataProtobuf(res);
}
}
// res.which_variant = AdminMessage_get_radio_response_tag;
// myReply = allocDataProtobuf(res);
// }
// }
void AdminModule::handleGetConfig(const MeshPacket &req, const uint32_t configType)
{
@ -299,28 +301,28 @@ void AdminModule::handleGetConfig(const MeshPacket &req, const uint32_t configTy
switch (configType) {
case AdminMessage_ConfigType_DEVICE_CONFIG:
DEBUG_MSG("Getting config: Device\n");
res.get_config_response.which_payloadVariant = Config_device_config_tag;
res.get_config_response.which_payloadVariant = Config_device_tag;
break;
case AdminMessage_ConfigType_GPS_CONFIG:
DEBUG_MSG("Getting config: GPS\n");
res.get_config_response.which_payloadVariant = Config_gps_config_tag;
case AdminMessage_ConfigType_POSITION_CONFIG:
DEBUG_MSG("Getting config: Position\n");
res.get_config_response.which_payloadVariant = Config_position_tag;
break;
case AdminMessage_ConfigType_POWER_CONFIG:
DEBUG_MSG("Getting config: Power\n");
res.get_config_response.which_payloadVariant = Config_power_config_tag;
res.get_config_response.which_payloadVariant = Config_power_tag;
break;
case AdminMessage_ConfigType_WIFI_CONFIG:
DEBUG_MSG("Getting config: WiFi\n");
res.get_config_response.which_payloadVariant = Config_wifi_config_tag;
res.get_config_response.which_payloadVariant = Config_wifi_tag;
break;
case AdminMessage_ConfigType_DISPLAY_CONFIG:
DEBUG_MSG("Getting config: Display\n");
res.get_config_response.which_payloadVariant = Config_display_config_tag;
res.get_config_response.which_payloadVariant = Config_display_tag;
break;
case AdminMessage_ConfigType_LORA_CONFIG:
DEBUG_MSG("Getting config: LoRa\n");
res.get_config_response.which_payloadVariant = Config_lora_config_tag;
res.get_config_response.payloadVariant.lora_config = config.payloadVariant.lora_config;
res.get_config_response.which_payloadVariant = Config_lora_tag;
res.get_config_response.payloadVariant.lora = config.payloadVariant.lora;
break;
}
@ -331,7 +333,7 @@ void AdminModule::handleGetConfig(const MeshPacket &req, const uint32_t configTy
// r.get_radio_response.preferences.phone_timeout_secs = getPref_phone_timeout_secs();
// hideSecret(r.get_radio_response.preferences.wifi_ssid); // hmm - leave public for now, because only minimally private
// and useful for users to know current provisioning) hideSecret(r.get_radio_response.preferences.wifi_password);
// r.get_config_response.which_payloadVariant = Config_ModuleConfig_telemetry_config_tag;
// r.get_config_response.which_payloadVariant = Config_ModuleConfig_telemetry_tag;
res.which_variant = AdminMessage_get_config_response_tag;
myReply = allocDataProtobuf(res);
}
@ -345,32 +347,39 @@ void AdminModule::handleGetModuleConfig(const MeshPacket &req, const uint32_t co
switch (configType) {
case AdminMessage_ModuleConfigType_MQTT_CONFIG:
DEBUG_MSG("Getting module config: MQTT\n");
res.get_module_config_response.which_payloadVariant = ModuleConfig_mqtt_config_tag;
res.get_module_config_response.which_payloadVariant = ModuleConfig_mqtt_tag;
res.get_module_config_response.payloadVariant.mqtt = moduleConfig.payloadVariant.mqtt;
break;
case AdminMessage_ModuleConfigType_SERIAL_CONFIG:
DEBUG_MSG("Getting module config: Serial\n");
res.get_module_config_response.which_payloadVariant = ModuleConfig_serial_config_tag;
res.get_module_config_response.which_payloadVariant = ModuleConfig_serial_tag;
res.get_module_config_response.payloadVariant.serial = moduleConfig.payloadVariant.serial;
break;
case AdminMessage_ModuleConfigType_EXTNOTIF_CONFIG:
DEBUG_MSG("Getting module config: External Notification\n");
res.get_module_config_response.which_payloadVariant = ModuleConfig_external_notification_config_tag;
res.get_module_config_response.which_payloadVariant = ModuleConfig_external_notification_tag;
res.get_module_config_response.payloadVariant.external_notification =
moduleConfig.payloadVariant.external_notification;
break;
case AdminMessage_ModuleConfigType_STOREFORWARD_CONFIG:
DEBUG_MSG("Getting module config: Store & Forward\n");
res.get_module_config_response.which_payloadVariant = ModuleConfig_store_forward_config_tag;
res.get_module_config_response.which_payloadVariant = ModuleConfig_store_forward_tag;
res.get_module_config_response.payloadVariant.store_forward = moduleConfig.payloadVariant.store_forward;
break;
case AdminMessage_ModuleConfigType_RANGETEST_CONFIG:
DEBUG_MSG("Getting module config: Range Test\n");
res.get_module_config_response.which_payloadVariant = ModuleConfig_range_test_config_tag;
res.get_module_config_response.which_payloadVariant = ModuleConfig_range_test_tag;
res.get_module_config_response.payloadVariant.range_test = moduleConfig.payloadVariant.range_test;
break;
case AdminMessage_ModuleConfigType_TELEMETRY_CONFIG:
DEBUG_MSG("Getting module config: Telemetry\n");
res.get_module_config_response.which_payloadVariant = ModuleConfig_telemetry_config_tag;
res.get_module_config_response.payloadVariant.telemetry_config = moduleConfig.payloadVariant.telemetry_config;
res.get_module_config_response.which_payloadVariant = ModuleConfig_telemetry_tag;
res.get_module_config_response.payloadVariant.telemetry = moduleConfig.payloadVariant.telemetry;
break;
case AdminMessage_ModuleConfigType_CANNEDMSG_CONFIG:
DEBUG_MSG("Getting module config: Canned Message\n");
res.get_module_config_response.which_payloadVariant = ModuleConfig_canned_message_config_tag;
res.get_module_config_response.which_payloadVariant = ModuleConfig_canned_message_tag;
res.get_module_config_response.payloadVariant.canned_message = moduleConfig.payloadVariant.canned_message;
break;
}
@ -381,7 +390,7 @@ void AdminModule::handleGetModuleConfig(const MeshPacket &req, const uint32_t co
// r.get_radio_response.preferences.phone_timeout_secs = getPref_phone_timeout_secs();
// hideSecret(r.get_radio_response.preferences.wifi_ssid); // hmm - leave public for now, because only minimally private
// and useful for users to know current provisioning) hideSecret(r.get_radio_response.preferences.wifi_password);
// r.get_config_response.which_payloadVariant = Config_ModuleConfig_telemetry_config_tag;
// r.get_config_response.which_payloadVariant = Config_ModuleConfig_telemetry_tag;
res.which_variant = AdminMessage_get_module_config_response_tag;
myReply = allocDataProtobuf(res);
}

Wyświetl plik

@ -24,7 +24,6 @@ class AdminModule : public ProtobufModule<AdminMessage>
* Getters
*/
void handleGetOwner(const MeshPacket &req);
void handleGetRadio(const MeshPacket &req);
void handleGetConfig(const MeshPacket &req, uint32_t configType);
void handleGetModuleConfig(const MeshPacket &req, uint32_t configType);
void handleGetChannel(const MeshPacket &req, uint32_t channelIndex);
@ -33,7 +32,6 @@ class AdminModule : public ProtobufModule<AdminMessage>
* Setters
*/
void handleSetOwner(const User &o);
void handleSetRadio(RadioConfig &r);
void handleSetChannel(const Channel &cc);
void handleSetConfig(const Config &c);
void handleSetModuleConfig(const ModuleConfig &c);

Wyświetl plik

@ -1,9 +1,9 @@
#include "configuration.h"
#ifndef NO_SCREEN
#include "CannedMessageModule.h"
#include "PowerFSM.h" // neede for button bypass
#include "MeshService.h"
#include "FSCommon.h"
#include "MeshService.h"
#include "PowerFSM.h" // neede for button bypass
#include "mesh/generated/cannedmessages.pb.h"
// TODO: reuse defined from Screen.cpp
@ -22,22 +22,18 @@ CannedMessageModule *cannedMessageModule;
// TODO: move it into NodeDB.h!
extern bool loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, void *dest_struct);
extern bool saveProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields, const void *dest_struct);
extern bool saveProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields,
const void *dest_struct);
CannedMessageModule::CannedMessageModule()
: SinglePortModule("canned", PortNum_TEXT_MESSAGE_APP),
concurrency::OSThread("CannedMessageModule")
: SinglePortModule("canned", PortNum_TEXT_MESSAGE_APP), concurrency::OSThread("CannedMessageModule")
{
if (radioConfig.preferences.canned_message_module_enabled)
{
if (moduleConfig.payloadVariant.canned_message.enabled) {
this->loadProtoForModule();
if(this->splitConfiguredMessages() <= 0)
{
if (this->splitConfiguredMessages() <= 0) {
DEBUG_MSG("CannedMessageModule: No messages are configured. Module is disabled\n");
this->runState = CANNED_MESSAGE_RUN_STATE_DISABLED;
}
else
{
} else {
DEBUG_MSG("CannedMessageModule is enabled\n");
this->inputObserver.observe(inputBroker);
}
@ -56,57 +52,38 @@ int CannedMessageModule::splitConfiguredMessages()
int i = 0;
// collect all the message parts
strcpy(
this->messageStore,
cannedMessageModuleConfig.messagesPart1);
strcat(
this->messageStore,
cannedMessageModuleConfig.messagesPart2);
strcat(
this->messageStore,
cannedMessageModuleConfig.messagesPart3);
strcat(
this->messageStore,
cannedMessageModuleConfig.messagesPart4);
strcpy(this->messageStore, cannedMessageModuleConfig.messagesPart1);
strcat(this->messageStore, cannedMessageModuleConfig.messagesPart2);
strcat(this->messageStore, cannedMessageModuleConfig.messagesPart3);
strcat(this->messageStore, cannedMessageModuleConfig.messagesPart4);
// The first message points to the beginning of the store.
this->messages[messageIndex++] =
this->messageStore;
int upTo =
strlen(this->messageStore) - 1;
this->messages[messageIndex++] = this->messageStore;
int upTo = strlen(this->messageStore) - 1;
while (i < upTo)
{
if (this->messageStore[i] == '|')
{
while (i < upTo) {
if (this->messageStore[i] == '|') {
// Message ending found, replace it with string-end character.
this->messageStore[i] = '\0';
DEBUG_MSG("CannedMessage %d is: '%s'\n",
messageIndex-1, this->messages[messageIndex-1]);
DEBUG_MSG("CannedMessage %d is: '%s'\n", messageIndex - 1, this->messages[messageIndex - 1]);
// hit our max messages, bail
if (messageIndex >= CANNED_MESSAGE_MODULE_MESSAGE_MAX_COUNT)
{
if (messageIndex >= CANNED_MESSAGE_MODULE_MESSAGE_MAX_COUNT) {
this->messagesCount = messageIndex;
return this->messagesCount;
}
// Next message starts after pipe (|) just found.
this->messages[messageIndex++] =
(this->messageStore + i + 1);
this->messages[messageIndex++] = (this->messageStore + i + 1);
}
i += 1;
}
if (strlen(this->messages[messageIndex-1]) > 0)
{
if (strlen(this->messages[messageIndex - 1]) > 0) {
// We have a last message.
DEBUG_MSG("CannedMessage %d is: '%s'\n",
messageIndex-1, this->messages[messageIndex-1]);
DEBUG_MSG("CannedMessage %d is: '%s'\n", messageIndex - 1, this->messages[messageIndex - 1]);
this->messagesCount = messageIndex;
}
else
{
this->messagesCount = messageIndex-1;
} else {
this->messagesCount = messageIndex - 1;
}
return this->messagesCount;
@ -114,11 +91,9 @@ int CannedMessageModule::splitConfiguredMessages()
int CannedMessageModule::handleInputEvent(const InputEvent *event)
{
if (
(strlen(radioConfig.preferences.canned_message_module_allow_input_source) > 0) &&
(strcmp(radioConfig.preferences.canned_message_module_allow_input_source, event->source) != 0) &&
(strcmp(radioConfig.preferences.canned_message_module_allow_input_source, "_any") != 0))
{
if ((strlen(moduleConfig.payloadVariant.canned_message.allow_input_source) > 0) &&
(strcmp(moduleConfig.payloadVariant.canned_message.allow_input_source, event->source) != 0) &&
(strcmp(moduleConfig.payloadVariant.canned_message.allow_input_source, "_any") != 0)) {
// Event source is not accepted.
// Event only accepted if source matches the configured one, or
// the configured one is "_any" (or if there is no configured
@ -127,32 +102,28 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event)
}
bool validEvent = false;
if (event->inputEvent == static_cast<char>(InputEventChar_KEY_UP))
{
if (event->inputEvent == static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_KEY_UP)) {
DEBUG_MSG("Canned message event UP\n");
this->runState = CANNED_MESSAGE_RUN_STATE_ACTION_UP;
validEvent = true;
}
if (event->inputEvent == static_cast<char>(InputEventChar_KEY_DOWN))
{
if (event->inputEvent == static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_KEY_DOWN)) {
DEBUG_MSG("Canned message event DOWN\n");
this->runState = CANNED_MESSAGE_RUN_STATE_ACTION_DOWN;
validEvent = true;
}
if (event->inputEvent == static_cast<char>(InputEventChar_KEY_SELECT))
{
if (event->inputEvent == static_cast<char>(ModuleConfig_CannedMessageConfig_InputEventChar_KEY_SELECT)) {
DEBUG_MSG("Canned message event Select\n");
// when inactive, call the onebutton shortpress instead. Activate Module only on up/down
if ((this->runState == CANNED_MESSAGE_RUN_STATE_INACTIVE) || (this->runState == CANNED_MESSAGE_RUN_STATE_DISABLED)) {
powerFSM.trigger(EVENT_PRESS);
}else{
} else {
this->runState = CANNED_MESSAGE_RUN_STATE_ACTION_SELECT;
validEvent = true;
}
}
if (validEvent)
{
if (validEvent) {
// Let runOnce to be called immediately.
setIntervalFromNow(0);
}
@ -160,90 +131,67 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event)
return 0;
}
void CannedMessageModule::sendText(NodeNum dest,
const char* message,
bool wantReplies)
void CannedMessageModule::sendText(NodeNum dest, const char *message, bool wantReplies)
{
MeshPacket *p = allocDataPacket();
p->to = dest;
p->want_ack = true;
p->decoded.payload.size = strlen(message);
memcpy(p->decoded.payload.bytes, message, p->decoded.payload.size);
if (radioConfig.preferences.canned_message_module_send_bell)
{
p->decoded.payload.bytes[p->decoded.payload.size-1] = 7; // Bell character
p->decoded.payload.bytes[p->decoded.payload.size] = '\0'; // Bell character
if (moduleConfig.payloadVariant.canned_message.send_bell) {
p->decoded.payload.bytes[p->decoded.payload.size - 1] = 7; // Bell character
p->decoded.payload.bytes[p->decoded.payload.size] = '\0'; // Bell character
p->decoded.payload.size++;
}
DEBUG_MSG("Sending message id=%d, msg=%.*s\n",
p->id, p->decoded.payload.size, p->decoded.payload.bytes);
DEBUG_MSG("Sending message id=%d, msg=%.*s\n", p->id, p->decoded.payload.size, p->decoded.payload.bytes);
service.sendToMesh(p);
}
int32_t CannedMessageModule::runOnce()
{
if ((!radioConfig.preferences.canned_message_module_enabled)
|| (this->runState == CANNED_MESSAGE_RUN_STATE_DISABLED)
|| (this->runState == CANNED_MESSAGE_RUN_STATE_INACTIVE))
{
if ((!moduleConfig.payloadVariant.canned_message.enabled) || (this->runState == CANNED_MESSAGE_RUN_STATE_DISABLED) ||
(this->runState == CANNED_MESSAGE_RUN_STATE_INACTIVE)) {
return 30000; // TODO: should return MAX_VAL
}
DEBUG_MSG("Check status\n");
UIFrameEvent e = {false, true};
if (this->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE)
{
if (this->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) {
// TODO: might have some feedback of sendig state
this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE;
e.frameChanged = true;
this->currentMessageIndex = -1;
this->notifyObservers(&e);
}
else if (
(this->runState == CANNED_MESSAGE_RUN_STATE_ACTIVE)
&& (millis() - this->lastTouchMillis) > INACTIVATE_AFTER_MS)
{
} else if ((this->runState == CANNED_MESSAGE_RUN_STATE_ACTIVE) && (millis() - this->lastTouchMillis) > INACTIVATE_AFTER_MS) {
// Reset module
DEBUG_MSG("Reset due the lack of activity.\n");
e.frameChanged = true;
this->currentMessageIndex = -1;
this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE;
this->notifyObservers(&e);
}
else if (this->currentMessageIndex == -1)
{
} else if (this->currentMessageIndex == -1) {
this->currentMessageIndex = 0;
DEBUG_MSG("First touch (%d):%s\n", this->currentMessageIndex, this->getCurrentMessage());
e.frameChanged = true;
this->runState = CANNED_MESSAGE_RUN_STATE_ACTIVE;
}
else if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTION_SELECT)
{
sendText(
NODENUM_BROADCAST,
this->messages[this->currentMessageIndex],
true);
} else if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTION_SELECT) {
sendText(NODENUM_BROADCAST, this->messages[this->currentMessageIndex], true);
this->runState = CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE;
this->currentMessageIndex = -1;
this->notifyObservers(&e);
return 2000;
}
else if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTION_UP)
{
} else if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTION_UP) {
this->currentMessageIndex = getPrevIndex();
this->runState = CANNED_MESSAGE_RUN_STATE_ACTIVE;
DEBUG_MSG("MOVE UP (%d):%s\n", this->currentMessageIndex, this->getCurrentMessage());
}
else if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTION_DOWN)
{
} else if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTION_DOWN) {
this->currentMessageIndex = this->getNextIndex();
this->runState = CANNED_MESSAGE_RUN_STATE_ACTIVE;
DEBUG_MSG("MOVE DOWN (%d):%s\n", this->currentMessageIndex, this->getCurrentMessage());
}
if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTIVE)
{
if (this->runState == CANNED_MESSAGE_RUN_STATE_ACTIVE) {
this->lastTouchMillis = millis();
this->notifyObservers(&e);
return INACTIVATE_AFTER_MS;
@ -252,22 +200,21 @@ int32_t CannedMessageModule::runOnce()
return 30000; // TODO: should return MAX_VAL
}
const char* CannedMessageModule::getCurrentMessage()
const char *CannedMessageModule::getCurrentMessage()
{
return this->messages[this->currentMessageIndex];
}
const char* CannedMessageModule::getPrevMessage()
const char *CannedMessageModule::getPrevMessage()
{
return this->messages[this->getPrevIndex()];
}
const char* CannedMessageModule::getNextMessage()
const char *CannedMessageModule::getNextMessage()
{
return this->messages[this->getNextIndex()];
}
bool CannedMessageModule::shouldDraw()
{
if (!radioConfig.preferences.canned_message_module_enabled)
{
if (!moduleConfig.payloadVariant.canned_message.enabled) {
return false;
}
return (currentMessageIndex != -1) || (this->runState != CANNED_MESSAGE_RUN_STATE_INACTIVE);
@ -275,47 +222,35 @@ bool CannedMessageModule::shouldDraw()
int CannedMessageModule::getNextIndex()
{
if (this->currentMessageIndex >= (this->messagesCount -1))
{
if (this->currentMessageIndex >= (this->messagesCount - 1)) {
return 0;
}
else
{
} else {
return this->currentMessageIndex + 1;
}
}
int CannedMessageModule::getPrevIndex()
{
if (this->currentMessageIndex <= 0)
{
if (this->currentMessageIndex <= 0) {
return this->messagesCount - 1;
}
else
{
} else {
return this->currentMessageIndex - 1;
}
}
void CannedMessageModule::drawFrame(
OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
displayedNodeNum = 0; // Not currently showing a node pane
if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE)
{
if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE) {
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->setFont(FONT_MEDIUM);
display->drawString(display->getWidth()/2 + x, 0 + y + 12, "Sending...");
}
else if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_DISABLED)
{
display->drawString(display->getWidth() / 2 + x, 0 + y + 12, "Sending...");
} else if (cannedMessageModule->runState == CANNED_MESSAGE_RUN_STATE_DISABLED) {
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
display->drawString(10 + x, 0 + y + 16, "Canned Message\nModule disabled.");
}
else
{
} else {
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_SMALL);
display->drawString(0 + x, 0 + y, cannedMessageModule->getPrevMessage());
@ -328,7 +263,8 @@ void CannedMessageModule::drawFrame(
void CannedMessageModule::loadProtoForModule()
{
if (!loadProto(cannedMessagesConfigFile, CannedMessageModuleConfig_size, sizeof(cannedMessagesConfigFile), CannedMessageModuleConfig_fields, &cannedMessageModuleConfig)) {
if (!loadProto(cannedMessagesConfigFile, CannedMessageModuleConfig_size, sizeof(cannedMessagesConfigFile),
CannedMessageModuleConfig_fields, &cannedMessageModuleConfig)) {
installDefaultCannedMessageModuleConfig();
}
}
@ -347,7 +283,8 @@ bool CannedMessageModule::saveProtoForModule()
FS.mkdir("/prefs");
#endif
okay &= saveProto(cannedMessagesConfigFile, CannedMessageModuleConfig_size, sizeof(CannedMessageModuleConfig), CannedMessageModuleConfig_fields, &cannedMessageModuleConfig);
okay &= saveProto(cannedMessagesConfigFile, CannedMessageModuleConfig_size, sizeof(CannedMessageModuleConfig),
CannedMessageModuleConfig_fields, &cannedMessageModuleConfig);
return okay;
}
@ -372,8 +309,8 @@ void CannedMessageModule::installDefaultCannedMessageModuleConfig()
* @return AdminMessageHandleResult HANDLED if message was handled
* HANDLED_WITH_RESULT if a result is also prepared.
*/
AdminMessageHandleResult CannedMessageModule::handleAdminMessageForModule(
const MeshPacket &mp, AdminMessage *request, AdminMessage *response)
AdminMessageHandleResult CannedMessageModule::handleAdminMessageForModule(const MeshPacket &mp, AdminMessage *request,
AdminMessage *response)
{
AdminMessageHandleResult result;
@ -404,29 +341,25 @@ AdminMessageHandleResult CannedMessageModule::handleAdminMessageForModule(
case AdminMessage_set_canned_message_module_part1_tag:
DEBUG_MSG("Client is setting radio canned message part 1\n");
this->handleSetCannedMessageModulePart1(
request->set_canned_message_module_part1);
this->handleSetCannedMessageModulePart1(request->set_canned_message_module_part1);
result = AdminMessageHandleResult::HANDLED;
break;
case AdminMessage_set_canned_message_module_part2_tag:
DEBUG_MSG("Client is setting radio canned message part 2\n");
this->handleSetCannedMessageModulePart2(
request->set_canned_message_module_part2);
this->handleSetCannedMessageModulePart2(request->set_canned_message_module_part2);
result = AdminMessageHandleResult::HANDLED;
break;
case AdminMessage_set_canned_message_module_part3_tag:
DEBUG_MSG("Client is setting radio canned message part 3\n");
this->handleSetCannedMessageModulePart3(
request->set_canned_message_module_part3);
this->handleSetCannedMessageModulePart3(request->set_canned_message_module_part3);
result = AdminMessageHandleResult::HANDLED;
break;
case AdminMessage_set_canned_message_module_part4_tag:
DEBUG_MSG("Client is setting radio canned message part 4\n");
this->handleSetCannedMessageModulePart4(
request->set_canned_message_module_part4);
this->handleSetCannedMessageModulePart4(request->set_canned_message_module_part4);
result = AdminMessageHandleResult::HANDLED;
break;
@ -437,67 +370,53 @@ AdminMessageHandleResult CannedMessageModule::handleAdminMessageForModule(
return result;
}
void CannedMessageModule::handleGetCannedMessageModulePart1(
const MeshPacket &req, AdminMessage *response)
void CannedMessageModule::handleGetCannedMessageModulePart1(const MeshPacket &req, AdminMessage *response)
{
DEBUG_MSG("*** handleGetCannedMessageModulePart1\n");
assert(req.decoded.want_response);
response->which_variant = AdminMessage_get_canned_message_module_part1_response_tag;
strcpy(
response->get_canned_message_module_part1_response,
cannedMessageModuleConfig.messagesPart1);
strcpy(response->get_canned_message_module_part1_response, cannedMessageModuleConfig.messagesPart1);
}
void CannedMessageModule::handleGetCannedMessageModulePart2(
const MeshPacket &req, AdminMessage *response)
void CannedMessageModule::handleGetCannedMessageModulePart2(const MeshPacket &req, AdminMessage *response)
{
DEBUG_MSG("*** handleGetCannedMessageModulePart2\n");
assert(req.decoded.want_response);
response->which_variant = AdminMessage_get_canned_message_module_part2_response_tag;
strcpy(
response->get_canned_message_module_part2_response,
cannedMessageModuleConfig.messagesPart2);
strcpy(response->get_canned_message_module_part2_response, cannedMessageModuleConfig.messagesPart2);
}
void CannedMessageModule::handleGetCannedMessageModulePart3(
const MeshPacket &req, AdminMessage *response)
void CannedMessageModule::handleGetCannedMessageModulePart3(const MeshPacket &req, AdminMessage *response)
{
DEBUG_MSG("*** handleGetCannedMessageModulePart3\n");
assert(req.decoded.want_response);
response->which_variant = AdminMessage_get_canned_message_module_part3_response_tag;
strcpy(
response->get_canned_message_module_part3_response,
cannedMessageModuleConfig.messagesPart3);
strcpy(response->get_canned_message_module_part3_response, cannedMessageModuleConfig.messagesPart3);
}
void CannedMessageModule::handleGetCannedMessageModulePart4(
const MeshPacket &req, AdminMessage *response)
void CannedMessageModule::handleGetCannedMessageModulePart4(const MeshPacket &req, AdminMessage *response)
{
DEBUG_MSG("*** handleGetCannedMessageModulePart4\n");
assert(req.decoded.want_response);
response->which_variant = AdminMessage_get_canned_message_module_part4_response_tag;
strcpy(
response->get_canned_message_module_part4_response,
cannedMessageModuleConfig.messagesPart4);
strcpy(response->get_canned_message_module_part4_response, cannedMessageModuleConfig.messagesPart4);
}
void CannedMessageModule::handleSetCannedMessageModulePart1(const char *from_msg)
{
int changed = 0;
if (*from_msg)
{
if (*from_msg) {
changed |= strcmp(cannedMessageModuleConfig.messagesPart1, from_msg);
strcpy(cannedMessageModuleConfig.messagesPart1, from_msg);
DEBUG_MSG("*** from_msg.text:%s\n", from_msg);
}
if (changed)
{
if (changed) {
this->saveProtoForModule();
}
}
@ -506,14 +425,12 @@ void CannedMessageModule::handleSetCannedMessageModulePart2(const char *from_msg
{
int changed = 0;
if (*from_msg)
{
if (*from_msg) {
changed |= strcmp(cannedMessageModuleConfig.messagesPart2, from_msg);
strcpy(cannedMessageModuleConfig.messagesPart2, from_msg);
}
if (changed)
{
if (changed) {
this->saveProtoForModule();
}
}
@ -522,14 +439,12 @@ void CannedMessageModule::handleSetCannedMessageModulePart3(const char *from_msg
{
int changed = 0;
if (*from_msg)
{
if (*from_msg) {
changed |= strcmp(cannedMessageModuleConfig.messagesPart3, from_msg);
strcpy(cannedMessageModuleConfig.messagesPart3, from_msg);
}
if (changed)
{
if (changed) {
this->saveProtoForModule();
}
}
@ -538,14 +453,12 @@ void CannedMessageModule::handleSetCannedMessageModulePart4(const char *from_msg
{
int changed = 0;
if (*from_msg)
{
if (*from_msg) {
changed |= strcmp(cannedMessageModuleConfig.messagesPart4, from_msg);
strcpy(cannedMessageModuleConfig.messagesPart4, from_msg);
}
if (changed)
{
if (changed) {
this->saveProtoForModule();
}
}

Wyświetl plik

@ -1,9 +1,9 @@
#include "configuration.h"
#include "ExternalNotificationModule.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
#include <Arduino.h>
//#include <assert.h>
@ -19,26 +19,26 @@
Quick reference:
radioConfig.preferences.ext_notification_module_enabled
moduleConfig.payloadVariant.external_notification.enabled
0 = Disabled (Default)
1 = Enabled
radioConfig.preferences.ext_notification_module_active
moduleConfig.payloadVariant.external_notification.active
0 = Active Low (Default)
1 = Active High
radioConfig.preferences.ext_notification_module_alert_message
moduleConfig.payloadVariant.external_notification.alert_message
0 = Disabled (Default)
1 = Alert when a text message comes
radioConfig.preferences.ext_notification_module_alert_bell
moduleConfig.payloadVariant.external_notification.alert_bell
0 = Disabled (Default)
1 = Alert when the bell character is received
radioConfig.preferences.ext_notification_module_output
moduleConfig.payloadVariant.external_notification.output
GPIO of the output. (Default = 13)
radioConfig.preferences.ext_notification_module_output_ms
moduleConfig.payloadVariant.external_notification.output_ms
Amount of time in ms for the alert. Default is 1000.
*/
@ -59,19 +59,19 @@ int32_t ExternalNotificationModule::runOnce()
without having to configure it from the PythonAPI or WebUI.
*/
// radioConfig.preferences.ext_notification_module_enabled = 1;
// radioConfig.preferences.ext_notification_module_alert_message = 1;
// moduleConfig.payloadVariant.external_notification.enabled = 1;
// moduleConfig.payloadVariant.external_notification.alert_message = 1;
// radioConfig.preferences.ext_notification_module_active = 1;
// radioConfig.preferences.ext_notification_module_alert_bell = 1;
// radioConfig.preferences.ext_notification_module_output_ms = 1000;
// radioConfig.preferences.ext_notification_module_output = 13;
// moduleConfig.payloadVariant.external_notification.active = 1;
// moduleConfig.payloadVariant.external_notification.alert_bell = 1;
// moduleConfig.payloadVariant.external_notification.output_ms = 1000;
// moduleConfig.payloadVariant.external_notification.output = 13;
if (externalCurrentState) {
// If the output is turned on, turn it back off after the given period of time.
if (externalTurnedOn + (radioConfig.preferences.ext_notification_module_output_ms
? radioConfig.preferences.ext_notification_module_output_ms
if (externalTurnedOn + (moduleConfig.payloadVariant.external_notification.output_ms
? moduleConfig.payloadVariant.external_notification.output_ms
: EXT_NOTIFICATION_MODULE_OUTPUT_MS) <
millis()) {
DEBUG_MSG("Turning off external notification\n");
@ -84,59 +84,62 @@ int32_t ExternalNotificationModule::runOnce()
void ExternalNotificationModule::setExternalOn()
{
#ifdef EXT_NOTIFY_OUT
#ifdef EXT_NOTIFY_OUT
externalCurrentState = 1;
externalTurnedOn = millis();
digitalWrite((radioConfig.preferences.ext_notification_module_output ? radioConfig.preferences.ext_notification_module_output
: EXT_NOTIFICATION_MODULE_OUTPUT),
(radioConfig.preferences.ext_notification_module_active ? true : false));
#endif
digitalWrite((moduleConfig.payloadVariant.external_notification.output
? moduleConfig.payloadVariant.external_notification.output
: EXT_NOTIFICATION_MODULE_OUTPUT),
(moduleConfig.payloadVariant.external_notification.active ? true : false));
#endif
}
void ExternalNotificationModule::setExternalOff()
{
#ifdef EXT_NOTIFY_OUT
#ifdef EXT_NOTIFY_OUT
externalCurrentState = 0;
digitalWrite((radioConfig.preferences.ext_notification_module_output ? radioConfig.preferences.ext_notification_module_output
: EXT_NOTIFICATION_MODULE_OUTPUT),
(radioConfig.preferences.ext_notification_module_active ? false : true));
#endif
digitalWrite((moduleConfig.payloadVariant.external_notification.output
? moduleConfig.payloadVariant.external_notification.output
: EXT_NOTIFICATION_MODULE_OUTPUT),
(moduleConfig.payloadVariant.external_notification.active ? false : true));
#endif
}
// --------
ExternalNotificationModule::ExternalNotificationModule()
: SinglePortModule("ExternalNotificationModule", PortNum_TEXT_MESSAGE_APP), concurrency::OSThread(
"ExternalNotificationModule")
"ExternalNotificationModule")
{
// restrict to the admin channel for rx
boundChannel = Channels::gpioChannel;
#ifndef NO_ESP32
#ifdef EXT_NOTIFY_OUT
#ifdef EXT_NOTIFY_OUT
/*
Uncomment the preferences below if you want to use the module
without having to configure it from the PythonAPI or WebUI.
*/
// radioConfig.preferences.ext_notification_module_enabled = 1;
// radioConfig.preferences.ext_notification_module_alert_message = 1;
// moduleConfig.payloadVariant.external_notification.enabled = 1;
// moduleConfig.payloadVariant.external_notification.alert_message = 1;
// radioConfig.preferences.ext_notification_module_active = 1;
// radioConfig.preferences.ext_notification_module_alert_bell = 1;
// radioConfig.preferences.ext_notification_module_output_ms = 1000;
// radioConfig.preferences.ext_notification_module_output = 13;
// moduleConfig.payloadVariant.external_notification.active = 1;
// moduleConfig.payloadVariant.external_notification.alert_bell = 1;
// moduleConfig.payloadVariant.external_notification.output_ms = 1000;
// moduleConfig.payloadVariant.external_notification.output = 13;
if (radioConfig.preferences.ext_notification_module_enabled) {
if (moduleConfig.payloadVariant.external_notification.enabled) {
DEBUG_MSG("Initializing External Notification Module\n");
// Set the direction of a pin
pinMode((radioConfig.preferences.ext_notification_module_output ? radioConfig.preferences.ext_notification_module_output
: EXT_NOTIFICATION_MODULE_OUTPUT),
pinMode((moduleConfig.payloadVariant.external_notification.output
? moduleConfig.payloadVariant.external_notification.output
: EXT_NOTIFICATION_MODULE_OUTPUT),
OUTPUT);
// Turn off the pin
@ -145,22 +148,22 @@ ExternalNotificationModule::ExternalNotificationModule()
DEBUG_MSG("External Notification Module Disabled\n");
enabled = false;
}
#endif
#endif
#endif
}
ProcessMessage ExternalNotificationModule::handleReceived(const MeshPacket &mp)
{
#ifndef NO_ESP32
#ifdef EXT_NOTIFY_OUT
#ifdef EXT_NOTIFY_OUT
if (radioConfig.preferences.ext_notification_module_enabled) {
if (moduleConfig.payloadVariant.external_notification.enabled) {
if (getFrom(&mp) != nodeDB.getNodeNum()) {
// TODO: This may be a problem if messages are sent in unicide, but I'm not sure if it will.
// Need to know if and how this could be a problem.
if (radioConfig.preferences.ext_notification_module_alert_bell) {
if (moduleConfig.payloadVariant.external_notification.alert_bell) {
auto &p = mp.decoded;
DEBUG_MSG("externalNotificationModule - Notification Bell\n");
for (int i = 0; i < p.payload.size; i++) {
@ -170,7 +173,7 @@ ProcessMessage ExternalNotificationModule::handleReceived(const MeshPacket &mp)
}
}
if (radioConfig.preferences.ext_notification_module_alert_message) {
if (moduleConfig.payloadVariant.external_notification.alert_message) {
DEBUG_MSG("externalNotificationModule - Notification Module\n");
setExternalOn();
}
@ -179,7 +182,7 @@ ProcessMessage ExternalNotificationModule::handleReceived(const MeshPacket &mp)
} else {
DEBUG_MSG("External Notification Module Disabled\n");
}
#endif
#endif
#endif

Wyświetl plik

@ -1,9 +1,9 @@
#include "configuration.h"
#include "NodeInfoModule.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
#include "main.h"
NodeInfoModule *nodeInfoModule;
@ -19,7 +19,7 @@ bool NodeInfoModule::handleReceivedProtobuf(const MeshPacket &mp, User *pptr)
// Show new nodes on LCD screen
if (wasBroadcast) {
String lcd = String("Joined: ") + p.long_name + "\n";
if(screen)
if (screen)
screen->print(lcd.c_str());
}
@ -69,6 +69,6 @@ int32_t NodeInfoModule::runOnce()
DEBUG_MSG("Sending our nodeinfo to mesh (wantReplies=%d)\n", requestReplies);
sendOurNodeInfo(NODENUM_BROADCAST, requestReplies); // Send our info (don't request replies)
return getPref_position_broadcast_secs() * 1000;
}
return config.payloadVariant.position.position_broadcast_secs ? config.payloadVariant.position.position_broadcast_secs
: default_broadcast_interval_secs * 1000;
}

Wyświetl plik

@ -60,7 +60,7 @@ MeshPacket *PositionModule::allocReply()
// configuration of POSITION packet
// consider making this a function argument?
uint32_t pos_flags = radioConfig.preferences.position_flags;
uint32_t pos_flags = config.payloadVariant.position.position_flags;
// Populate a Position struct with ONLY the requested fields
Position p = Position_init_default; // Start with an empty structure
@ -70,28 +70,28 @@ MeshPacket *PositionModule::allocReply()
p.longitude_i = node->position.longitude_i;
p.time = node->position.time;
if (pos_flags & PositionFlags_POS_ALTITUDE) {
if (pos_flags & PositionFlags_POS_ALT_MSL)
if (pos_flags & Config_PositionConfig_PositionFlags_POS_ALTITUDE) {
if (pos_flags & Config_PositionConfig_PositionFlags_POS_ALT_MSL)
p.altitude = node->position.altitude;
else
p.altitude_hae = node->position.altitude_hae;
if (pos_flags & PositionFlags_POS_GEO_SEP)
if (pos_flags & Config_PositionConfig_PositionFlags_POS_GEO_SEP)
p.alt_geoid_sep = node->position.alt_geoid_sep;
}
if (pos_flags & PositionFlags_POS_DOP) {
if (pos_flags & PositionFlags_POS_HVDOP) {
if (pos_flags & Config_PositionConfig_PositionFlags_POS_DOP) {
if (pos_flags & Config_PositionConfig_PositionFlags_POS_HVDOP) {
p.HDOP = node->position.HDOP;
p.VDOP = node->position.VDOP;
} else
p.PDOP = node->position.PDOP;
}
if (pos_flags & PositionFlags_POS_SATINVIEW)
if (pos_flags & Config_PositionConfig_PositionFlags_POS_SATINVIEW)
p.sats_in_view = node->position.sats_in_view;
if (pos_flags & PositionFlags_POS_TIMESTAMP)
if (pos_flags & Config_PositionConfig_PositionFlags_POS_TIMESTAMP)
p.pos_timestamp = node->position.pos_timestamp;
// Strip out any time information before sending packets to other nodes - to keep the wire size small (and because other
@ -127,7 +127,9 @@ int32_t PositionModule::runOnce()
// We limit our GPS broadcasts to a max rate
uint32_t now = millis();
if (lastGpsSend == 0 || now - lastGpsSend >= getPref_position_broadcast_secs() * 1000) {
if (lastGpsSend == 0 || now - lastGpsSend >= config.payloadVariant.position.position_broadcast_secs
? config.payloadVariant.position.position_broadcast_secs
: default_broadcast_interval_secs * 1000) {
// Only send packets if the channel is less than 40% utilized.
if (airTime->channelUtilizationPercent() < 40) {
@ -149,7 +151,7 @@ int32_t PositionModule::runOnce()
DEBUG_MSG("Channel utilization is >50 percent. Skipping this opportunity to send.\n");
}
} else if (!radioConfig.preferences.position_broadcast_smart_disabled) {
} else if (!config.payloadVariant.position.position_broadcast_smart_disabled) {
// Only send packets if the channel is less than 25% utilized.
if (airTime->channelUtilizationPercent() < 25) {

Wyświetl plik

@ -1,8 +1,8 @@
#include "DeviceTelemetry.h"
#include "../mesh/generated/telemetry.pb.h"
#include "PowerFSM.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
@ -20,8 +20,8 @@ int32_t DeviceTelemetryModule::runOnce()
}
sendOurTelemetry();
// OSThread library. Multiply the preference value by 1000 to convert seconds to miliseconds
return getIntervalOrDefaultMs(moduleConfig.device_update_interval);
return getIntervalOrDefaultMs(moduleConfig.payloadVariant.telemetry.device_update_interval);
#endif
}
@ -33,7 +33,7 @@ bool DeviceTelemetryModule::handleReceivedProtobuf(const MeshPacket &mp, Telemet
DEBUG_MSG("-----------------------------------------\n");
DEBUG_MSG("Device Telemetry: Received data from %s\n", sender);
DEBUG_MSG("Telemetry->time: %i\n", t->time);
DEBUG_MSG("Telemetry->air_util_tx: %f\n", t->variant.device_metrics.air_util_tx );
DEBUG_MSG("Telemetry->air_util_tx: %f\n", t->variant.device_metrics.air_util_tx);
DEBUG_MSG("Telemetry->battery_level: %i\n", t->variant.device_metrics.battery_level);
DEBUG_MSG("Telemetry->channel_utilization: %f\n", t->variant.device_metrics.channel_utilization);
DEBUG_MSG("Telemetry->voltage: %f\n", t->variant.device_metrics.voltage);

Wyświetl plik

@ -1,7 +1,7 @@
#pragma once
#include "../mesh/generated/telemetry.pb.h"
#include "ProtobufModule.h"
#include "NodeDB.h"
#include "ProtobufModule.h"
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
@ -9,8 +9,7 @@ class DeviceTelemetryModule : private concurrency::OSThread, public ProtobufModu
{
public:
DeviceTelemetryModule()
: concurrency::OSThread("DeviceTelemetryModule"),
ProtobufModule("DeviceTelemetry", PortNum_TELEMETRY_APP, &Telemetry_msg)
: concurrency::OSThread("DeviceTelemetryModule"), ProtobufModule("DeviceTelemetry", PortNum_TELEMETRY_APP, &Telemetry_msg)
{
lastMeasurementPacket = nullptr;
}
@ -28,7 +27,6 @@ class DeviceTelemetryModule : private concurrency::OSThread, public ProtobufModu
bool sendOurTelemetry(NodeNum dest = NODENUM_BROADCAST, bool wantReplies = false);
private:
Config_ModuleConfig_TelemetryConfig moduleConfig = config.payloadVariant.module_config.payloadVariant.telemetry_config;
bool firstTime = 1;
const MeshPacket *lastMeasurementPacket;
};

Wyświetl plik

@ -1,8 +1,8 @@
#include "EnvironmentTelemetry.h"
#include "../mesh/generated/telemetry.pb.h"
#include "PowerFSM.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
@ -50,17 +50,17 @@ int32_t EnvironmentTelemetryModule::runOnce()
without having to configure it from the PythonAPI or WebUI.
*/
/*
moduleConfig.environment_measurement_enabled = 1;
moduleConfig.environment_screen_enabled = 1;
moduleConfig.environment_read_error_count_threshold = 5;
moduleConfig.environment_update_interval = 600;
moduleConfig.environment_recovery_interval = 60;
moduleConfig.environment_sensor_pin = 13; // If one-wire
moduleConfig.environment_sensor_type = TelemetrySensorType::TelemetrySensorType_BME280;
moduleConfig.payloadVariant.telemetry.environment_measurement_enabled = 1;
moduleConfig.payloadVariant.telemetry.environment_screen_enabled = 1;
moduleConfig.payloadVariant.telemetry.environment_read_error_count_threshold = 5;
moduleConfig.payloadVariant.telemetry.environment_update_interval = 600;
moduleConfig.payloadVariant.telemetry.environment_recovery_interval = 60;
moduleConfig.payloadVariant.telemetry.environment_sensor_pin = 13; // If one-wire
moduleConfig.payloadVariant.telemetry.environment_sensor_type = TelemetrySensorType::TelemetrySensorType_BME280;
*/
if (!(moduleConfig.environment_measurement_enabled ||
moduleConfig.environment_screen_enabled)) {
if (!(moduleConfig.payloadVariant.telemetry.environment_measurement_enabled ||
moduleConfig.payloadVariant.telemetry.environment_screen_enabled)) {
// If this module is not enabled, and the user doesn't want the display screen don't waste any OSThread time on it
return (INT32_MAX);
}
@ -69,82 +69,81 @@ int32_t EnvironmentTelemetryModule::runOnce()
// This is the first time the OSThread library has called this function, so do some setup
firstTime = 0;
if (moduleConfig.environment_measurement_enabled) {
if (moduleConfig.payloadVariant.telemetry.environment_measurement_enabled) {
DEBUG_MSG("Environment Telemetry: Initializing\n");
// it's possible to have this module enabled, only for displaying values on the screen.
// therefore, we should only enable the sensor loop if measurement is also enabled
switch (moduleConfig.environment_sensor_type) {
switch (moduleConfig.payloadVariant.telemetry.environment_sensor_type) {
case TelemetrySensorType_DHT11:
case TelemetrySensorType_DHT12:
case TelemetrySensorType_DHT21:
case TelemetrySensorType_DHT22:
return dhtSensor.runOnce();
case TelemetrySensorType_DS18B20:
return dallasSensor.runOnce();
case TelemetrySensorType_BME280:
return bme280Sensor.runOnce();
case TelemetrySensorType_BME680:
return bme680Sensor.runOnce();
case TelemetrySensorType_MCP9808:
return mcp9808Sensor.runOnce();
default:
DEBUG_MSG("Environment Telemetry: Invalid sensor type selected; Disabling module");
return (INT32_MAX);
break;
case TelemetrySensorType_DHT11:
case TelemetrySensorType_DHT12:
case TelemetrySensorType_DHT21:
case TelemetrySensorType_DHT22:
return dhtSensor.runOnce();
case TelemetrySensorType_DS18B20:
return dallasSensor.runOnce();
case TelemetrySensorType_BME280:
return bme280Sensor.runOnce();
case TelemetrySensorType_BME680:
return bme680Sensor.runOnce();
case TelemetrySensorType_MCP9808:
return mcp9808Sensor.runOnce();
default:
DEBUG_MSG("Environment Telemetry: Invalid sensor type selected; Disabling module");
return (INT32_MAX);
break;
}
}
return (INT32_MAX);
} else {
// if we somehow got to a second run of this module with measurement disabled, then just wait forever
if (!moduleConfig.environment_measurement_enabled)
if (!moduleConfig.payloadVariant.telemetry.environment_measurement_enabled)
return (INT32_MAX);
// this is not the first time OSThread library has called this function
// so just do what we intend to do on the interval
if (sensor_read_error_count > moduleConfig.environment_read_error_count_threshold) {
if (moduleConfig.environment_recovery_interval > 0) {
if (sensor_read_error_count > moduleConfig.payloadVariant.telemetry.environment_read_error_count_threshold) {
if (moduleConfig.payloadVariant.telemetry.environment_recovery_interval > 0) {
DEBUG_MSG("Environment Telemetry: TEMPORARILY DISABLED; The "
"telemetry_module_environment_read_error_count_threshold has been exceed: %d. Will retry reads in "
"%d seconds\n",
moduleConfig.environment_read_error_count_threshold,
moduleConfig.environment_recovery_interval);
moduleConfig.payloadVariant.telemetry.environment_read_error_count_threshold,
moduleConfig.payloadVariant.telemetry.environment_recovery_interval);
sensor_read_error_count = 0;
return (moduleConfig.environment_recovery_interval * 1000);
return (moduleConfig.payloadVariant.telemetry.environment_recovery_interval * 1000);
}
DEBUG_MSG("Environment Telemetry: DISABLED; The telemetry_module_environment_read_error_count_threshold has "
"been exceed: %d. Reads will not be retried until after device reset\n",
moduleConfig.environment_read_error_count_threshold);
moduleConfig.payloadVariant.telemetry.environment_read_error_count_threshold);
return (INT32_MAX);
} else if (sensor_read_error_count > 0) {
DEBUG_MSG("Environment Telemetry: There have been %d sensor read failures. Will retry %d more times\n",
sensor_read_error_count, sensor_read_error_count, sensor_read_error_count,
moduleConfig.environment_read_error_count_threshold -
sensor_read_error_count);
moduleConfig.payloadVariant.telemetry.environment_read_error_count_threshold - sensor_read_error_count);
}
if (!sendOurTelemetry()) {
// if we failed to read the sensor, then try again
// as soon as we can according to the maximum polling frequency
switch (moduleConfig.environment_sensor_type) {
case TelemetrySensorType_DHT11:
case TelemetrySensorType_DHT12:
case TelemetrySensorType_DHT21:
case TelemetrySensorType_DHT22:
return (DHT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
case TelemetrySensorType_DS18B20:
return (DS18B20_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
case TelemetrySensorType_BME280:
case TelemetrySensorType_BME680:
return (BME_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
case TelemetrySensorType_MCP9808:
return (MCP_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
default:
return (DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
switch (moduleConfig.payloadVariant.telemetry.environment_sensor_type) {
case TelemetrySensorType_DHT11:
case TelemetrySensorType_DHT12:
case TelemetrySensorType_DHT21:
case TelemetrySensorType_DHT22:
return (DHT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
case TelemetrySensorType_DS18B20:
return (DS18B20_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
case TelemetrySensorType_BME280:
case TelemetrySensorType_BME680:
return (BME_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
case TelemetrySensorType_MCP9808:
return (MCP_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
default:
return (DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
}
}
}
return getIntervalOrDefaultMs(moduleConfig.environment_update_interval);
return getIntervalOrDefaultMs(moduleConfig.payloadVariant.telemetry.environment_update_interval);
#endif
}
@ -162,7 +161,7 @@ uint32_t GetTimeSinceMeshPacket(const MeshPacket *mp)
bool EnvironmentTelemetryModule::wantUIFrame()
{
return moduleConfig.environment_screen_enabled;
return moduleConfig.payloadVariant.telemetry.environment_screen_enabled;
}
float EnvironmentTelemetryModule::CelsiusToFahrenheit(float c)
@ -196,13 +195,16 @@ void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiSt
display->setFont(FONT_SMALL);
String last_temp = String(lastMeasurement.variant.environment_metrics.temperature, 0) + "°C";
if (moduleConfig.environment_display_fahrenheit) {
if (moduleConfig.payloadVariant.telemetry.environment_display_fahrenheit) {
last_temp = String(CelsiusToFahrenheit(lastMeasurement.variant.environment_metrics.temperature), 0) + "°F";
}
display->drawString(x, y += fontHeight(FONT_MEDIUM) - 2, "From: " + String(lastSender) + "(" + String(agoSecs) + "s)");
display->drawString(x, y += fontHeight(FONT_SMALL) - 2, "Temp/Hum: " + last_temp + " / " + String(lastMeasurement.variant.environment_metrics.relative_humidity, 0) + "%");
if (lastMeasurement.variant.environment_metrics.barometric_pressure != 0)
display->drawString(x, y += fontHeight(FONT_SMALL), "Press: " + String(lastMeasurement.variant.environment_metrics.barometric_pressure, 0) + "hPA");
display->drawString(x, y += fontHeight(FONT_SMALL) - 2,
"Temp/Hum: " + last_temp + " / " +
String(lastMeasurement.variant.environment_metrics.relative_humidity, 0) + "%");
if (lastMeasurement.variant.environment_metrics.barometric_pressure != 0)
display->drawString(x, y += fontHeight(FONT_SMALL),
"Press: " + String(lastMeasurement.variant.environment_metrics.barometric_pressure, 0) + "hPA");
}
bool EnvironmentTelemetryModule::handleReceivedProtobuf(const MeshPacket &mp, Telemetry *t)
@ -238,33 +240,33 @@ bool EnvironmentTelemetryModule::sendOurTelemetry(NodeNum dest, bool wantReplies
m.variant.environment_metrics.relative_humidity = 0;
m.variant.environment_metrics.temperature = 0;
m.variant.environment_metrics.voltage = 0;
DEBUG_MSG("-----------------------------------------\n");
DEBUG_MSG("Environment Telemetry: Read data\n");
switch (moduleConfig.environment_sensor_type) {
case TelemetrySensorType_DS18B20:
if (!dallasSensor.getMeasurement(&m))
sensor_read_error_count++;
break;
case TelemetrySensorType_DHT11:
case TelemetrySensorType_DHT12:
case TelemetrySensorType_DHT21:
case TelemetrySensorType_DHT22:
if (!dhtSensor.getMeasurement(&m))
sensor_read_error_count++;
break;
case TelemetrySensorType_BME280:
bme280Sensor.getMeasurement(&m);
break;
case TelemetrySensorType_BME680:
bme680Sensor.getMeasurement(&m);
break;
case TelemetrySensorType_MCP9808:
mcp9808Sensor.getMeasurement(&m);
break;
default:
DEBUG_MSG("Environment Telemetry: No external sensor type selected; Only sending internal metrics\n");
switch (moduleConfig.payloadVariant.telemetry.environment_sensor_type) {
case TelemetrySensorType_DS18B20:
if (!dallasSensor.getMeasurement(&m))
sensor_read_error_count++;
break;
case TelemetrySensorType_DHT11:
case TelemetrySensorType_DHT12:
case TelemetrySensorType_DHT21:
case TelemetrySensorType_DHT22:
if (!dhtSensor.getMeasurement(&m))
sensor_read_error_count++;
break;
case TelemetrySensorType_BME280:
bme280Sensor.getMeasurement(&m);
break;
case TelemetrySensorType_BME680:
bme680Sensor.getMeasurement(&m);
break;
case TelemetrySensorType_MCP9808:
mcp9808Sensor.getMeasurement(&m);
break;
default:
DEBUG_MSG("Environment Telemetry: No external sensor type selected; Only sending internal metrics\n");
}
DEBUG_MSG("Telemetry->time: %i\n", m.time);

Wyświetl plik

@ -1,7 +1,7 @@
#pragma once
#include "../mesh/generated/telemetry.pb.h"
#include "ProtobufModule.h"
#include "NodeDB.h"
#include "ProtobufModule.h"
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
@ -15,7 +15,7 @@ class EnvironmentTelemetryModule : private concurrency::OSThread, public Protobu
lastMeasurementPacket = nullptr;
}
virtual bool wantUIFrame() override;
#ifdef NO_SCREEN
#ifdef NO_SCREEN
void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
#else
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) override;
@ -33,7 +33,6 @@ class EnvironmentTelemetryModule : private concurrency::OSThread, public Protobu
bool sendOurTelemetry(NodeNum dest = NODENUM_BROADCAST, bool wantReplies = false);
private:
Config_ModuleConfig_TelemetryConfig moduleConfig = config.payloadVariant.module_config.payloadVariant.telemetry_config;
float CelsiusToFahrenheit(float c);
bool firstTime = 1;
const MeshPacket *lastMeasurementPacket;

Wyświetl plik

@ -1,31 +1,29 @@
#include "../mesh/generated/telemetry.pb.h"
#include "configuration.h"
#include "DHTSensor.h"
#include "./mesh/generated/telemetry.pb.h"
#include "MeshService.h"
#include "TelemetrySensor.h"
#include "DHTSensor.h"
#include "configuration.h"
#include <DHT.h>
DHTSensor::DHTSensor() : TelemetrySensor {} {
}
DHTSensor::DHTSensor() : TelemetrySensor{} {}
int32_t DHTSensor::runOnce() {
if (TelemetrySensorType_DHT11 ||
TelemetrySensorType_DHT12) {
dht = new DHT(moduleConfig.environment_sensor_pin, DHT11);
}
else {
dht = new DHT(moduleConfig.environment_sensor_pin, DHT22);
int32_t DHTSensor::runOnce()
{
if (TelemetrySensorType_DHT11 || TelemetrySensorType_DHT12) {
dht = new DHT(moduleConfig.payloadVariant.telemetry.environment_sensor_pin, DHT11);
} else {
dht = new DHT(moduleConfig.payloadVariant.telemetry.environment_sensor_pin, DHT22);
}
dht->begin();
dht->read();
DEBUG_MSG("Telemetry: Opened DHT11/DHT12 on pin: %d\n",
moduleConfig.environment_sensor_pin);
DEBUG_MSG("Telemetry: Opened DHT11/DHT12 on pin: %d\n", moduleConfig.payloadVariant.telemetry.environment_sensor_pin);
return (DHT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
}
bool DHTSensor::getMeasurement(Telemetry *measurement) {
bool DHTSensor::getMeasurement(Telemetry *measurement)
{
if (!dht->read(true)) {
DEBUG_MSG("Telemetry: FAILED TO READ DATA\n");
return false;
@ -33,4 +31,4 @@ bool DHTSensor::getMeasurement(Telemetry *measurement) {
measurement->variant.environment_metrics.relative_humidity = dht->readHumidity();
measurement->variant.environment_metrics.temperature = dht->readTemperature();
return true;
}
}

Wyświetl plik

@ -1,31 +1,31 @@
#include "DallasSensor.h"
#include "../mesh/generated/telemetry.pb.h"
#include "configuration.h"
#include "MeshService.h"
#include "TelemetrySensor.h"
#include "DallasSensor.h"
#include "configuration.h"
#include <DS18B20.h>
#include <OneWire.h>
DallasSensor::DallasSensor() : TelemetrySensor {} {
}
DallasSensor::DallasSensor() : TelemetrySensor{} {}
int32_t DallasSensor::runOnce() {
oneWire = new OneWire(moduleConfig.environment_sensor_pin);
int32_t DallasSensor::runOnce()
{
oneWire = new OneWire(moduleConfig.payloadVariant.telemetry.environment_sensor_pin);
ds18b20 = new DS18B20(oneWire);
ds18b20->begin();
ds18b20->setResolution(12);
ds18b20->requestTemperatures();
DEBUG_MSG("Telemetry: Opened DS18B20 on pin: %d\n",
moduleConfig.environment_sensor_pin);
DEBUG_MSG("Telemetry: Opened DS18B20 on pin: %d\n", moduleConfig.payloadVariant.telemetry.environment_sensor_pin);
return (DS18B20_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS);
}
bool DallasSensor::getMeasurement(Telemetry *measurement) {
bool DallasSensor::getMeasurement(Telemetry *measurement)
{
if (ds18b20->isConversionComplete()) {
measurement->variant.environment_metrics.temperature = ds18b20->getTempC();
measurement->variant.environment_metrics.relative_humidity = 0;
ds18b20->requestTemperatures();
return true;
}
}
return false;
}

Wyświetl plik

@ -3,11 +3,12 @@
#include "NodeDB.h"
#define DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS 1000
class TelemetrySensor {
protected:
TelemetrySensor() { }
Config_ModuleConfig_TelemetryConfig moduleConfig = config.payloadVariant.module_config.payloadVariant.telemetry_config;
public:
class TelemetrySensor
{
protected:
TelemetrySensor() {}
public:
virtual int32_t runOnce() = 0;
virtual bool getMeasurement(Telemetry *measurement) = 0;
virtual bool getMeasurement(Telemetry *measurement) = 0;
};

Wyświetl plik

@ -36,23 +36,23 @@ int32_t RangeTestModule::runOnce()
without having to configure it from the PythonAPI or WebUI.
*/
// radioConfig.preferences.range_test_module_enabled = 1;
// radioConfig.preferences.range_test_module_sender = 45;
// radioConfig.preferences.range_test_module_save = 1;
// moduleConfig.payloadVariant.range_test.enabled = 1;
// moduleConfig.payloadVariant.range_test.sender = 45;
// moduleConfig.payloadVariant.range_test.save = 1;
// Fixed position is useful when testing indoors.
// radioConfig.preferences.fixed_position = 1;
uint32_t senderHeartbeat = radioConfig.preferences.range_test_module_sender * 1000;
uint32_t senderHeartbeat = moduleConfig.payloadVariant.range_test.sender * 1000;
if (radioConfig.preferences.range_test_module_enabled) {
if (moduleConfig.payloadVariant.range_test.enabled) {
if (firstTime) {
rangeTestModuleRadio = new RangeTestModuleRadio();
firstTime = 0;
if (radioConfig.preferences.range_test_module_sender) {
if (moduleConfig.payloadVariant.range_test.sender) {
DEBUG_MSG("Initializing Range Test Module -- Sender\n");
return (5000); // Sending first message 5 seconds after initilization.
} else {
@ -62,7 +62,7 @@ int32_t RangeTestModule::runOnce()
} else {
if (radioConfig.preferences.range_test_module_sender) {
if (moduleConfig.payloadVariant.range_test.sender) {
// If sender
DEBUG_MSG("Range Test Module - Sending heartbeat every %d ms\n", (senderHeartbeat));
@ -71,7 +71,7 @@ int32_t RangeTestModule::runOnce()
DEBUG_MSG("gpsStatus->getHasLock() %d\n", gpsStatus->getHasLock());
DEBUG_MSG("gpsStatus->getDOP() %d\n", gpsStatus->getDOP());
DEBUG_MSG("gpsStatus->getHasLock() %d\n", gpsStatus->getHasLock());
DEBUG_MSG("pref.fixed_position() %d\n", radioConfig.preferences.fixed_position);
DEBUG_MSG("pref.fixed_position() %d\n", config.payloadVariant.position.fixed_position);
// Only send packets if the channel is less than 25% utilized.
if (airTime->channelUtilizationPercent() < 25) {
@ -131,7 +131,7 @@ ProcessMessage RangeTestModuleRadio::handleReceived(const MeshPacket &mp)
{
#ifndef NO_ESP32
if (radioConfig.preferences.range_test_module_enabled) {
if (moduleConfig.payloadVariant.range_test.enabled) {
/*
auto &p = mp.decoded;
@ -141,7 +141,7 @@ ProcessMessage RangeTestModuleRadio::handleReceived(const MeshPacket &mp)
if (getFrom(&mp) != nodeDB.getNodeNum()) {
if (radioConfig.preferences.range_test_module_save) {
if (moduleConfig.payloadVariant.range_test.save) {
appendFile(mp);
}

Wyświetl plik

@ -1,9 +1,9 @@
#include "configuration.h"
#include "SerialModule.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
#include <Arduino.h>
#include <assert.h>
@ -20,18 +20,18 @@
Basic Usage:
1) Enable the module by setting serial_module_enabled to 1.
2) Set the pins (serial_module_rxd / serial_module_rxd) for your preferred RX and TX GPIO pins.
1) Enable the module by setting enabled to 1.
2) Set the pins (rxd / rxd) for your preferred RX and TX GPIO pins.
On tbeam, recommend to use:
RXD 35
TXD 15
3) Set serial_module_timeout to the amount of time to wait before we consider
3) Set timeout to the amount of time to wait before we consider
your packet as "done".
4) (Optional) In SerialModule.h set the port to PortNum_TEXT_MESSAGE_APP if you want to
send messages to/from the general text message channel.
5) Connect to your device over the serial interface at 38400 8N1.
6) Send a packet up to 240 bytes in length. This will get relayed over the mesh network.
7) (Optional) Set serial_module_echo to 1 and any message you send out will be echoed back
7) (Optional) Set echo to 1 and any message you send out will be echoed back
to your device.
TODO (in this order):
@ -48,11 +48,11 @@
#define RXD2 16
#define TXD2 17
#define SERIAL_MODULE_RX_BUFFER 128
#define SERIAL_MODULE_STRING_MAX Constants_DATA_PAYLOAD_LEN
#define SERIAL_MODULE_TIMEOUT 250
#define SERIAL_MODULE_BAUD 38400
#define SERIAL_MODULE_ACK 1
#define RX_BUFFER 128
#define STRING_MAX Constants_DATA_PAYLOAD_LEN
#define TIMEOUT 250
#define BAUD 38400
#define ACK 1
SerialModule *serialModule;
SerialModuleRadio *serialModuleRadio;
@ -76,89 +76,86 @@ int32_t SerialModule::runOnce()
without having to configure it from the PythonAPI or WebUI.
*/
// radioConfig.preferences.serial_module_enabled = 1;
// radioConfig.preferences.serial_module_rxd = 35;
// radioConfig.preferences.serial_module_txd = 15;
// radioConfig.preferences.serial_module_timeout = 1000;
// radioConfig.preferences.serial_module_echo = 1;
// moduleConfig.payloadVariant.serial.enabled = 1;
// moduleConfig.payloadVariant.serial.rxd = 35;
// moduleConfig.payloadVariant.serial.txd = 15;
// moduleConfig.payloadVariant.serial.timeout = 1000;
// moduleConfig.payloadVariant.serial.echo = 1;
if (radioConfig.preferences.serial_module_enabled) {
if (moduleConfig.payloadVariant.serial.enabled) {
if (firstTime) {
// Interface with the serial peripheral from in here.
DEBUG_MSG("Initializing serial peripheral interface\n");
uint32_t baud = 0;
if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_Default) {
if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_Default) {
baud = 38400;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_110) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_110) {
baud = 110;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_300) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_300) {
baud = 300;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_600) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_600) {
baud = 600;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_1200) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_1200) {
baud = 1200;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_2400) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_2400) {
baud = 2400;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_4800) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_4800) {
baud = 4800;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_9600) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_9600) {
baud = 9600;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_19200) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_19200) {
baud = 19200;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_38400) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_38400) {
baud = 38400;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_57600) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_57600) {
baud = 57600;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_115200) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_115200) {
baud = 115200;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_230400) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_230400) {
baud = 230400;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_460800) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_460800) {
baud = 460800;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_576000) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_576000) {
baud = 576000;
} else if (radioConfig.preferences.serial_module_baud == RadioConfig_UserPreferences_Serial_Baud_BAUD_921600) {
} else if (moduleConfig.payloadVariant.serial.baud == ModuleConfig_SerialConfig_Serial_Baud_BAUD_921600) {
baud = 921600;
}
if (radioConfig.preferences.serial_module_rxd && radioConfig.preferences.serial_module_txd) {
Serial2.begin(baud, SERIAL_8N1, radioConfig.preferences.serial_module_rxd,
radioConfig.preferences.serial_module_txd);
if (moduleConfig.payloadVariant.serial.rxd && moduleConfig.payloadVariant.serial.txd) {
Serial2.begin(baud, SERIAL_8N1, moduleConfig.payloadVariant.serial.rxd, moduleConfig.payloadVariant.serial.txd);
} else {
Serial2.begin(baud, SERIAL_8N1, RXD2, TXD2);
}
if (radioConfig.preferences.serial_module_timeout) {
if (moduleConfig.payloadVariant.serial.timeout) {
Serial2.setTimeout(
radioConfig.preferences.serial_module_timeout); // Number of MS to wait to set the timeout for the string.
moduleConfig.payloadVariant.serial.timeout); // Number of MS to wait to set the timeout for the string.
} else {
Serial2.setTimeout(SERIAL_MODULE_TIMEOUT); // Number of MS to wait to set the timeout for the string.
Serial2.setTimeout(TIMEOUT); // Number of MS to wait to set the timeout for the string.
}
Serial2.setRxBufferSize(SERIAL_MODULE_RX_BUFFER);
Serial2.setRxBufferSize(RX_BUFFER);
serialModuleRadio = new SerialModuleRadio();
@ -202,7 +199,7 @@ void SerialModuleRadio::sendPayload(NodeNum dest, bool wantReplies)
p->to = dest;
p->decoded.want_response = wantReplies;
p->want_ack = SERIAL_MODULE_ACK;
p->want_ack = ACK;
p->decoded.payload.size = strlen(serialStringChar); // You must specify how many bytes are in the reply
memcpy(p->decoded.payload.bytes, serialStringChar, p->decoded.payload.size);
@ -214,7 +211,7 @@ ProcessMessage SerialModuleRadio::handleReceived(const MeshPacket &mp)
{
#ifndef NO_ESP32
if (radioConfig.preferences.serial_module_enabled) {
if (moduleConfig.payloadVariant.serial.enabled) {
auto &p = mp.decoded;
// DEBUG_MSG("Received text msg self=0x%0x, from=0x%0x, to=0x%0x, id=%d, msg=%.*s\n",
@ -223,10 +220,10 @@ ProcessMessage SerialModuleRadio::handleReceived(const MeshPacket &mp)
if (getFrom(&mp) == nodeDB.getNodeNum()) {
/*
* If radioConfig.preferences.serial_module_echo is true, then echo the packets that are sent out back to the TX
* of the serial interface.
* If moduleConfig.payloadVariant.serial.echo is true, then echo the packets that are sent out
* back to the TX of the serial interface.
*/
if (radioConfig.preferences.serial_module_echo) {
if (moduleConfig.payloadVariant.serial.echo) {
// For some reason, we get the packet back twice when we send out of the radio.
// TODO: need to find out why.
@ -240,13 +237,13 @@ ProcessMessage SerialModuleRadio::handleReceived(const MeshPacket &mp)
} else {
if (radioConfig.preferences.serial_module_mode == RadioConfig_UserPreferences_Serial_Mode_MODE_Default || radioConfig.preferences.serial_module_mode == RadioConfig_UserPreferences_Serial_Mode_MODE_SIMPLE) {
if (moduleConfig.payloadVariant.serial.mode == ModuleConfig_SerialConfig_Serial_Mode_MODE_Default ||
moduleConfig.payloadVariant.serial.mode == ModuleConfig_SerialConfig_Serial_Mode_MODE_SIMPLE) {
// DEBUG_MSG("* * Message came from the mesh\n");
// Serial2.println("* * Message came from the mesh");
Serial2.printf("%s", p.payload.bytes);
} else if (radioConfig.preferences.serial_module_mode == RadioConfig_UserPreferences_Serial_Mode_MODE_PROTO) {
} else if (moduleConfig.payloadVariant.serial.mode == ModuleConfig_SerialConfig_Serial_Mode_MODE_PROTO) {
}
}

Wyświetl plik

@ -19,13 +19,12 @@ int32_t StoreForwardModule::runOnce()
#ifndef NO_ESP32
if (radioConfig.preferences.store_forward_module_enabled) {
if (moduleConfig.payloadVariant.store_forward.enabled) {
if (radioConfig.preferences.role == Role_Router) {
if (config.payloadVariant.device.role == Config_DeviceConfig_Role_Router) {
// Send out the message queue.
if (this->busy) {
// Only send packets if the channel is less than 25% utilized.
if (airTime->channelUtilizationPercent() < 25) {
@ -43,7 +42,7 @@ int32_t StoreForwardModule::runOnce()
} else {
this->packetHistoryTXQueue_index++;
}
} else {
DEBUG_MSG("Channel utilization is too high. Skipping this opportunity to send and will retry later.\n");
}
@ -243,7 +242,7 @@ void StoreForwardModule::sendMessage(NodeNum dest, char *str)
ProcessMessage StoreForwardModule::handleReceived(const MeshPacket &mp)
{
#ifndef NO_ESP32
if (radioConfig.preferences.store_forward_module_enabled) {
if (moduleConfig.payloadVariant.store_forward.enabled) {
DEBUG_MSG("--- S&F Received something\n");
@ -267,10 +266,11 @@ ProcessMessage StoreForwardModule::handleReceived(const MeshPacket &mp)
}
} else if ((p.payload.bytes[0] == 'S') && (p.payload.bytes[1] == 'F') && (p.payload.bytes[2] == 'm') &&
(p.payload.bytes[3] == 0x00)) {
strlcpy(this->routerMessage, "01234567890123456789012345678901234567890123456789012345678901234567890123456789"
"01234567890123456789012345678901234567890123456789012345678901234567890123456789"
"01234567890123456789012345678901234567890123456789012345678901234567890123456",
sizeof(this->routerMessage));
strlcpy(this->routerMessage,
"01234567890123456789012345678901234567890123456789012345678901234567890123456789"
"01234567890123456789012345678901234567890123456789012345678901234567890123456789"
"01234567890123456789012345678901234567890123456789012345678901234567890123456",
sizeof(this->routerMessage));
storeForwardModule->sendMessage(getFrom(&mp), this->routerMessage);
} else {
@ -295,7 +295,7 @@ ProcessMessage StoreForwardModule::handleReceived(const MeshPacket &mp)
ProcessMessage StoreForwardModule::handleReceivedProtobuf(const MeshPacket &mp, StoreAndForward *p)
{
if (!radioConfig.preferences.store_forward_module_enabled) {
if (!moduleConfig.payloadVariant.store_forward.enabled) {
// If this module is not enabled in any capacity, don't handle the packet, and allow other modules to consume
return ProcessMessage::CONTINUE;
}
@ -391,14 +391,14 @@ StoreForwardModule::StoreForwardModule()
without having to configure it from the PythonAPI or WebUI.
*/
radioConfig.preferences.store_forward_module_enabled = 1;
radioConfig.preferences.is_always_powered = 1;
moduleConfig.payloadVariant.store_forward.enabled = 1;
config.payloadVariant.power.is_always_powered = 1;
}
if (radioConfig.preferences.store_forward_module_enabled) {
if (moduleConfig.payloadVariant.store_forward.enabled) {
// Router
if (radioConfig.preferences.role == Role_Router) {
if (config.payloadVariant.device.role == Config_DeviceConfig_Role_Router) {
DEBUG_MSG("Initializing Store & Forward Module - Enabled as Router\n");
if (ESP.getPsramSize()) {
if (ESP.getFreePsram() >= 1024 * 1024) {
@ -406,20 +406,20 @@ StoreForwardModule::StoreForwardModule()
// Do the startup here
// Maximum number of records to return.
if (radioConfig.preferences.store_forward_module_history_return_max)
this->historyReturnMax = radioConfig.preferences.store_forward_module_history_return_max;
if (moduleConfig.payloadVariant.store_forward.history_return_max)
this->historyReturnMax = moduleConfig.payloadVariant.store_forward.history_return_max;
// Maximum time window for records to return (in minutes)
if (radioConfig.preferences.store_forward_module_history_return_window)
this->historyReturnWindow = radioConfig.preferences.store_forward_module_history_return_window;
if (moduleConfig.payloadVariant.store_forward.history_return_window)
this->historyReturnWindow = moduleConfig.payloadVariant.store_forward.history_return_window;
// Maximum number of records to store in memory
if (radioConfig.preferences.store_forward_module_records)
this->records = radioConfig.preferences.store_forward_module_records;
if (moduleConfig.payloadVariant.store_forward.records)
this->records = moduleConfig.payloadVariant.store_forward.records;
// Maximum number of records to store in memory
if (radioConfig.preferences.store_forward_module_heartbeat)
this->heartbeat = radioConfig.preferences.store_forward_module_heartbeat;
if (moduleConfig.payloadVariant.store_forward.heartbeat)
this->heartbeat = moduleConfig.payloadVariant.store_forward.heartbeat;
// Popupate PSRAM with our data structures.
this->populatePSRAM();

Wyświetl plik

@ -111,17 +111,18 @@ void MQTT::reconnect()
const char *mqttUsername = "meshdev";
const char *mqttPassword = "large4cats";
if (*radioConfig.preferences.mqtt_server) {
serverAddr = radioConfig.preferences.mqtt_server; // Override the default
mqttUsername = radioConfig.preferences.mqtt_username; // do not use the hardcoded credentials for a custom mqtt server
mqttPassword = radioConfig.preferences.mqtt_password;
if (*moduleConfig.payloadVariant.mqtt.address) {
serverAddr = moduleConfig.payloadVariant.mqtt.address; // Override the default
mqttUsername =
moduleConfig.payloadVariant.mqtt.username; // do not use the hardcoded credentials for a custom mqtt server
mqttPassword = moduleConfig.payloadVariant.mqtt.password;
} else {
// we are using the default server. Use the hardcoded credentials by default, but allow overriding
if (*radioConfig.preferences.mqtt_username && radioConfig.preferences.mqtt_username[0] != '\0') {
mqttUsername = radioConfig.preferences.mqtt_username;
if (*moduleConfig.payloadVariant.mqtt.username && moduleConfig.payloadVariant.mqtt.username[0] != '\0') {
mqttUsername = moduleConfig.payloadVariant.mqtt.username;
}
if (*radioConfig.preferences.mqtt_password && radioConfig.preferences.mqtt_password[0] != '\0') {
mqttPassword = radioConfig.preferences.mqtt_password;
if (*moduleConfig.payloadVariant.mqtt.password && moduleConfig.payloadVariant.mqtt.password[0] != '\0') {
mqttPassword = moduleConfig.payloadVariant.mqtt.password;
}
}
@ -174,7 +175,7 @@ bool MQTT::wantsLink() const
{
bool hasChannel = false;
if (radioConfig.preferences.mqtt_disabled) {
if (moduleConfig.payloadVariant.mqtt.disabled) {
// DEBUG_MSG("MQTT disabled...\n");
} else {
// No need for link if no channel needed it
@ -254,7 +255,7 @@ String MQTT::downstreamPacketToJson(MeshPacket *mp)
{
using namespace json11;
// the created jsonObj is immutable after creation, so
// the created jsonObj is immutable after creation, so
// we need to do the heavy lifting before assembling it.
String msgType;
Json msgPayload;
@ -288,8 +289,7 @@ String MQTT::downstreamPacketToJson(MeshPacket *mp)
Telemetry *decoded = NULL;
if (mp->which_payloadVariant == MeshPacket_decoded_tag) {
memset(&scratch, 0, sizeof(scratch));
if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &Telemetry_msg,
&scratch)) {
if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &Telemetry_msg, &scratch)) {
decoded = &scratch;
if (decoded->which_variant == Telemetry_environment_metrics_tag) {
msgPayload = Json::object{

Wyświetl plik

@ -1,8 +1,8 @@
#include "buzz.h"
#include "configuration.h"
#include "graphics/Screen.h"
#include "power.h"
#include "buzz.h"
#include "main.h"
#include "power.h"
void powerCommandsCheck()
{
@ -30,7 +30,7 @@ void powerCommandsCheck()
DEBUG_MSG("Shutting down from admin command\n");
#ifdef TBEAM_V10
if (axp192_found == true) {
setLed(false);
// setLed(false); //TODO: FIXME: this is not working
power->shutdown();
}
#elif NRF52_SERIES