Merge branch 'master' into tft-gui-work

This commit is contained in:
Manuel 2024-11-05 13:18:07 +01:00 committed by GitHub
commit d5fb039719
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
121 changed files with 865 additions and 869 deletions

View File

@ -7,6 +7,7 @@ on:
permissions:
issues: write
pull-requests: write
actions: write
jobs:
stale_issues:

View File

@ -11,12 +11,12 @@ lint:
- trufflehog@3.83.2
- yamllint@1.35.1
- bandit@1.7.10
- checkov@3.2.276
- checkov@3.2.277
- terrascan@1.19.9
- trivy@0.56.2
#- trufflehog@3.63.2-rc0
- taplo@0.9.3
- ruff@0.7.1
- ruff@0.7.2
- isort@5.13.2
- markdownlint@0.42.0
- oxipng@9.1.2

View File

@ -81,17 +81,6 @@ I2C:
Display:
### Waveshare 2.8inch RPi LCD
# Panel: ST7789
# CS: 8
# DC: 22 # Data/Command pin
# Backlight: 18
# Width: 240
# Height: 320
# Reset: 27
# Rotate: true
# Invert: true
### Waveshare 1.44inch LCD HAT
# Panel: ST7735S
# CS: 8 #Chip Select
@ -148,10 +137,6 @@ Touchscreen:
# IRQ: 24
# I2CAddr: 0x38
# Module: XPT2046 # Waveshare 2.8inch
# CS: 7
# IRQ: 17
### You can also specify the spi device for the touchscreen to use
# spidev: spidev0.0

View File

@ -0,0 +1,9 @@
Lora:
Module: sx1262
CS: 21
IRQ: 16
Busy: 20
Reset: 18
TXen: 13
RXen: 12
DIO3_TCXO_VOLTAGE: true

View File

@ -88,12 +88,13 @@ Import("projenv")
prefsLoc = projenv["PROJECT_DIR"] + "/version.properties"
verObj = readProps(prefsLoc)
print("Using meshtastic platformio-custom.py, firmware version " + verObj["long"])
print("Using meshtastic platformio-custom.py, firmware version " + verObj["long"] + " on " + env.get("PIOENV"))
# General options that are passed to the C and C++ compilers
projenv.Append(
CCFLAGS=[
"-DAPP_VERSION=" + verObj["long"],
"-DAPP_VERSION_SHORT=" + verObj["short"],
"-DAPP_ENV=" + env.get("PIOENV"),
]
)

@ -1 +1 @@
Subproject commit 015202aead5f6807d63537c58f4cb6525f19e56f
Subproject commit 06cf134e2b3d035c3ca6cbbb90b4c017d4715398

View File

@ -21,7 +21,7 @@ namespace concurrency
class AmbientLightingThread : public concurrency::OSThread
{
public:
explicit AmbientLightingThread(ScanI2C::DeviceType type) : OSThread("AmbientLightingThread")
explicit AmbientLightingThread(ScanI2C::DeviceType type) : OSThread("AmbientLighting")
{
notifyDeepSleepObserver.observe(&notifyDeepSleep); // Let us know when shutdown() is issued.
@ -42,18 +42,18 @@ class AmbientLightingThread : public concurrency::OSThread
#ifdef HAS_NCP5623
_type = type;
if (_type == ScanI2C::DeviceType::NONE) {
LOG_DEBUG("AmbientLightingThread disabling due to no RGB leds found on I2C bus");
LOG_DEBUG("AmbientLighting Disable due to no RGB leds found on I2C bus");
disable();
return;
}
#endif
#if defined(HAS_NCP5623) || defined(RGBLED_RED) || defined(HAS_NEOPIXEL) || defined(UNPHONE)
if (!moduleConfig.ambient_lighting.led_state) {
LOG_DEBUG("AmbientLightingThread disabling due to moduleConfig.ambient_lighting.led_state OFF");
LOG_DEBUG("AmbientLighting Disable due to moduleConfig.ambient_lighting.led_state OFF");
disable();
return;
}
LOG_DEBUG("AmbientLightingThread initializing");
LOG_DEBUG("AmbientLighting init");
#ifdef HAS_NCP5623
if (_type == ScanI2C::NCP5623) {
rgb.begin();
@ -106,27 +106,27 @@ class AmbientLightingThread : public concurrency::OSThread
rgb.setRed(0);
rgb.setGreen(0);
rgb.setBlue(0);
LOG_INFO("Turn Off NCP5623 Ambient lighting.");
LOG_INFO("OFF: NCP5623 Ambient lighting");
#endif
#ifdef HAS_NEOPIXEL
pixels.clear();
pixels.show();
LOG_INFO("Turn Off NeoPixel Ambient lighting.");
LOG_INFO("OFF: NeoPixel Ambient lighting");
#endif
#ifdef RGBLED_CA
analogWrite(RGBLED_RED, 255 - 0);
analogWrite(RGBLED_GREEN, 255 - 0);
analogWrite(RGBLED_BLUE, 255 - 0);
LOG_INFO("Turn Off Ambient lighting RGB Common Anode.");
LOG_INFO("OFF: Ambient light RGB Common Anode");
#elif defined(RGBLED_RED)
analogWrite(RGBLED_RED, 0);
analogWrite(RGBLED_GREEN, 0);
analogWrite(RGBLED_BLUE, 0);
LOG_INFO("Turn Off Ambient lighting RGB Common Cathode.");
LOG_INFO("OFF: Ambient light RGB Common Cathode");
#endif
#ifdef UNPHONE
unphone.rgb(0, 0, 0);
LOG_INFO("Turn Off unPhone Ambient lighting.");
LOG_INFO("OFF: unPhone Ambient lighting");
#endif
return 0;
}
@ -138,9 +138,8 @@ class AmbientLightingThread : public concurrency::OSThread
rgb.setRed(moduleConfig.ambient_lighting.red);
rgb.setGreen(moduleConfig.ambient_lighting.green);
rgb.setBlue(moduleConfig.ambient_lighting.blue);
LOG_DEBUG("Initializing NCP5623 Ambient lighting w/ current=%d, red=%d, green=%d, blue=%d",
moduleConfig.ambient_lighting.current, moduleConfig.ambient_lighting.red, moduleConfig.ambient_lighting.green,
moduleConfig.ambient_lighting.blue);
LOG_DEBUG("Init NCP5623 Ambient light w/ current=%d, red=%d, green=%d, blue=%d", moduleConfig.ambient_lighting.current,
moduleConfig.ambient_lighting.red, moduleConfig.ambient_lighting.green, moduleConfig.ambient_lighting.blue);
#endif
#ifdef HAS_NEOPIXEL
pixels.fill(pixels.Color(moduleConfig.ambient_lighting.red, moduleConfig.ambient_lighting.green,
@ -158,7 +157,7 @@ class AmbientLightingThread : public concurrency::OSThread
#endif
#endif
pixels.show();
LOG_DEBUG("Initializing NeoPixel Ambient lighting w/ brightness(current)=%d, red=%d, green=%d, blue=%d",
LOG_DEBUG("Init NeoPixel Ambient light w/ brightness(current)=%d, red=%d, green=%d, blue=%d",
moduleConfig.ambient_lighting.current, moduleConfig.ambient_lighting.red, moduleConfig.ambient_lighting.green,
moduleConfig.ambient_lighting.blue);
#endif
@ -166,21 +165,21 @@ class AmbientLightingThread : public concurrency::OSThread
analogWrite(RGBLED_RED, 255 - moduleConfig.ambient_lighting.red);
analogWrite(RGBLED_GREEN, 255 - moduleConfig.ambient_lighting.green);
analogWrite(RGBLED_BLUE, 255 - moduleConfig.ambient_lighting.blue);
LOG_DEBUG("Initializing Ambient lighting RGB Common Anode w/ red=%d, green=%d, blue=%d",
moduleConfig.ambient_lighting.red, moduleConfig.ambient_lighting.green, moduleConfig.ambient_lighting.blue);
LOG_DEBUG("Init Ambient light RGB Common Anode w/ red=%d, green=%d, blue=%d", moduleConfig.ambient_lighting.red,
moduleConfig.ambient_lighting.green, moduleConfig.ambient_lighting.blue);
#elif defined(RGBLED_RED)
analogWrite(RGBLED_RED, moduleConfig.ambient_lighting.red);
analogWrite(RGBLED_GREEN, moduleConfig.ambient_lighting.green);
analogWrite(RGBLED_BLUE, moduleConfig.ambient_lighting.blue);
LOG_DEBUG("Initializing Ambient lighting RGB Common Cathode w/ red=%d, green=%d, blue=%d",
moduleConfig.ambient_lighting.red, moduleConfig.ambient_lighting.green, moduleConfig.ambient_lighting.blue);
LOG_DEBUG("Init Ambient light RGB Common Cathode w/ red=%d, green=%d, blue=%d", moduleConfig.ambient_lighting.red,
moduleConfig.ambient_lighting.green, moduleConfig.ambient_lighting.blue);
#endif
#ifdef UNPHONE
unphone.rgb(moduleConfig.ambient_lighting.red, moduleConfig.ambient_lighting.green, moduleConfig.ambient_lighting.blue);
LOG_DEBUG("Initializing unPhone Ambient lighting w/ red=%d, green=%d, blue=%d", moduleConfig.ambient_lighting.red,
LOG_DEBUG("Init unPhone Ambient light w/ red=%d, green=%d, blue=%d", moduleConfig.ambient_lighting.red,
moduleConfig.ambient_lighting.green, moduleConfig.ambient_lighting.blue);
#endif
}
};
} // namespace concurrency
} // namespace concurrency

View File

@ -16,7 +16,7 @@
class AudioThread : public concurrency::OSThread
{
public:
AudioThread() : OSThread("AudioThread") { initOutput(); }
AudioThread() : OSThread("Audio") { initOutput(); }
void beginRttl(const void *data, uint32_t len)
{

View File

@ -36,7 +36,7 @@ ButtonThread::ButtonThread() : OSThread("Button")
#if defined(ARCH_PORTDUINO)
if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) {
this->userButton = OneButton(settingsMap[user], true, true);
LOG_DEBUG("Using GPIO%02d for button", settingsMap[user]);
LOG_DEBUG("Use GPIO%02d for button", settingsMap[user]);
}
#elif defined(BUTTON_PIN)
int pin = config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN; // Resolved button pin
@ -47,7 +47,7 @@ ButtonThread::ButtonThread() : OSThread("Button")
#else
this->userButton = OneButton(pin, true, true);
#endif
LOG_DEBUG("Using GPIO%02d for button", pin);
LOG_DEBUG("Use GPIO%02d for button", pin);
#endif
#ifdef INPUT_PULLUP_SENSE

View File

@ -231,7 +231,7 @@ void listDir(const char *dirname, uint8_t levels, bool del)
#ifdef ARCH_ESP32
listDir(file.path(), levels - 1, del);
if (del) {
LOG_DEBUG("Removing %s", file.path());
LOG_DEBUG("Remove %s", file.path());
strncpy(buffer, file.path(), sizeof(buffer));
file.close();
FSCom.rmdir(buffer);
@ -241,7 +241,7 @@ void listDir(const char *dirname, uint8_t levels, bool del)
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
listDir(file.name(), levels - 1, del);
if (del) {
LOG_DEBUG("Removing %s", file.name());
LOG_DEBUG("Remove %s", file.name());
strncpy(buffer, file.name(), sizeof(buffer));
file.close();
FSCom.rmdir(buffer);
@ -257,7 +257,7 @@ void listDir(const char *dirname, uint8_t levels, bool del)
} else {
#ifdef ARCH_ESP32
if (del) {
LOG_DEBUG("Deleting %s", file.path());
LOG_DEBUG("Delete %s", file.path());
strncpy(buffer, file.path(), sizeof(buffer));
file.close();
FSCom.remove(buffer);
@ -267,7 +267,7 @@ void listDir(const char *dirname, uint8_t levels, bool del)
}
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
if (del) {
LOG_DEBUG("Deleting %s", file.name());
LOG_DEBUG("Delete %s", file.name());
strncpy(buffer, file.name(), sizeof(buffer));
file.close();
FSCom.remove(buffer);
@ -284,7 +284,7 @@ void listDir(const char *dirname, uint8_t levels, bool del)
}
#ifdef ARCH_ESP32
if (del) {
LOG_DEBUG("Removing %s", root.path());
LOG_DEBUG("Remove %s", root.path());
strncpy(buffer, root.path(), sizeof(buffer));
root.close();
FSCom.rmdir(buffer);
@ -293,7 +293,7 @@ void listDir(const char *dirname, uint8_t levels, bool del)
}
#elif (defined(ARCH_RP2040) || defined(ARCH_PORTDUINO))
if (del) {
LOG_DEBUG("Removing %s", root.name());
LOG_DEBUG("Remove %s", root.name());
strncpy(buffer, root.name(), sizeof(buffer));
root.close();
FSCom.rmdir(buffer);

View File

@ -50,9 +50,6 @@ class GPSStatus : public Status
int32_t getLatitude() const
{
if (config.position.fixed_position) {
#ifdef GPS_EXTRAVERBOSE
LOG_WARN("Using fixed latitude");
#endif
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum());
return node->position.latitude_i;
} else {
@ -63,9 +60,6 @@ class GPSStatus : public Status
int32_t getLongitude() const
{
if (config.position.fixed_position) {
#ifdef GPS_EXTRAVERBOSE
LOG_WARN("Using fixed longitude");
#endif
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum());
return node->position.longitude_i;
} else {
@ -76,9 +70,6 @@ class GPSStatus : public Status
int32_t getAltitude() const
{
if (config.position.fixed_position) {
#ifdef GPS_EXTRAVERBOSE
LOG_WARN("Using fixed altitude");
#endif
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum());
return node->position.altitude;
} else {
@ -94,7 +85,7 @@ class GPSStatus : public Status
bool matches(const GPSStatus *newStatus) const
{
#ifdef GPS_EXTRAVERBOSE
#ifdef GPS_DEBUG
LOG_DEBUG("GPSStatus.match() new pos@%x to old pos@%x", newStatus->p.timestamp, p.timestamp);
#endif
return (newStatus->hasLock != hasLock || newStatus->isConnected != isConnected ||

View File

@ -12,7 +12,6 @@ void GpioVirtPin::set(bool value)
void GpioHwPin::set(bool value)
{
// if (num == 3) LOG_DEBUG("Setting pin %d to %d", num, value);
pinMode(num, OUTPUT);
digitalWrite(num, value);
}
@ -88,7 +87,6 @@ void GpioBinaryTransformer::update()
newValue = (GpioVirtPin::PinState)(p1 && p2);
break;
case Or:
// LOG_DEBUG("Doing GPIO OR");
newValue = (GpioVirtPin::PinState)(p1 || p2);
break;
case Xor:
@ -101,4 +99,4 @@ void GpioBinaryTransformer::update()
set(newValue);
}
GpioSplitter::GpioSplitter(GpioPin *outPin1, GpioPin *outPin2) : outPin1(outPin1), outPin2(outPin2) {}
GpioSplitter::GpioSplitter(GpioPin *outPin1, GpioPin *outPin2) : outPin1(outPin1), outPin2(outPin2) {}

View File

@ -251,7 +251,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !defined(HAS_PMU) && \
!MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
if (hasINA()) {
LOG_DEBUG("Using INA on I2C addr 0x%x for device battery voltage", config.power.device_battery_ina_address);
LOG_DEBUG("Use INA on I2C addr 0x%x for device battery voltage", config.power.device_battery_ina_address);
return getINAVoltage();
}
#endif
@ -511,7 +511,7 @@ bool Power::analogInit()
#endif
#ifdef BATTERY_PIN
LOG_DEBUG("Using analog input %d for battery level", BATTERY_PIN);
LOG_DEBUG("Use analog input %d for battery level", BATTERY_PIN);
// disable any internal pullups
pinMode(BATTERY_PIN, INPUT);
@ -542,18 +542,18 @@ bool Power::analogInit()
esp_adc_cal_value_t val_type = esp_adc_cal_characterize(unit, atten, width, DEFAULT_VREF, adc_characs);
// show ADC characterization base
if (val_type == ESP_ADC_CAL_VAL_EFUSE_TP) {
LOG_INFO("ADCmod: ADC characterization based on Two Point values stored in eFuse");
LOG_INFO("ADC config based on Two Point values stored in eFuse");
} else if (val_type == ESP_ADC_CAL_VAL_EFUSE_VREF) {
LOG_INFO("ADCmod: ADC characterization based on reference voltage stored in eFuse");
LOG_INFO("ADC config based on reference voltage stored in eFuse");
}
#ifdef CONFIG_IDF_TARGET_ESP32S3
// ESP32S3
else if (val_type == ESP_ADC_CAL_VAL_EFUSE_TP_FIT) {
LOG_INFO("ADCmod: ADC Characterization based on Two Point values and fitting curve coefficients stored in eFuse");
LOG_INFO("ADC config based on Two Point values and fitting curve coefficients stored in eFuse");
}
#endif
else {
LOG_INFO("ADCmod: ADC characterization based on default reference voltage");
LOG_INFO("ADC config based on default reference voltage");
}
#endif // ARCH_ESP32
@ -722,9 +722,9 @@ void Power::readPowerStatus()
if (low_voltage_counter > 10) {
#ifdef ARCH_NRF52
// We can't trigger deep sleep on NRF52, it's freezing the board
LOG_DEBUG("Low voltage detected, but not triggering deep sleep");
LOG_DEBUG("Low voltage detected, but not trigger deep sleep");
#else
LOG_INFO("Low voltage detected, triggering deep sleep");
LOG_INFO("Low voltage detected, trigger deep sleep");
powerFSM.trigger(EVENT_LOW_BATTERY);
#endif
}
@ -816,22 +816,22 @@ bool Power::axpChipInit()
if (!PMU) {
PMU = new XPowersAXP2101(*w);
if (!PMU->init()) {
LOG_WARN("Failed to find AXP2101 power management");
LOG_WARN("No AXP2101 power management");
delete PMU;
PMU = NULL;
} else {
LOG_INFO("AXP2101 PMU init succeeded, using AXP2101 PMU");
LOG_INFO("AXP2101 PMU init succeeded");
}
}
if (!PMU) {
PMU = new XPowersAXP192(*w);
if (!PMU->init()) {
LOG_WARN("Failed to find AXP192 power management");
LOG_WARN("No AXP192 power management");
delete PMU;
PMU = NULL;
} else {
LOG_INFO("AXP192 PMU init succeeded, using AXP192 PMU");
LOG_INFO("AXP192 PMU init succeeded");
}
}

View File

@ -53,7 +53,7 @@ static bool isPowered()
static void sdsEnter()
{
LOG_DEBUG("Enter state: SDS");
LOG_DEBUG("State: SDS");
// FIXME - make sure GPS and LORA radio are off first - because we want close to zero current draw
doDeepSleep(Default::getConfiguredOrDefaultMs(config.power.sds_secs), false);
}
@ -62,7 +62,7 @@ extern Power *power;
static void shutdownEnter()
{
LOG_DEBUG("Enter state: SHUTDOWN");
LOG_DEBUG("State: SHUTDOWN");
power->shutdown();
}
@ -105,7 +105,7 @@ static void lsIdle()
wakeCause2 = doLightSleep(100); // leave led on for 1ms
secsSlept += sleepTime;
// LOG_INFO("sleeping, flash led!");
// LOG_INFO("Sleep, flash led!");
break;
case ESP_SLEEP_WAKEUP_UART:
@ -137,7 +137,7 @@ static void lsIdle()
} else {
// Time to stop sleeping!
ledBlink.set(false);
LOG_INFO("Reached ls_secs, servicing loop()");
LOG_INFO("Reached ls_secs, service loop()");
powerFSM.trigger(EVENT_WAKE_TIMER);
}
#endif
@ -150,7 +150,7 @@ static void lsExit()
static void nbEnter()
{
LOG_DEBUG("Enter state: NB");
LOG_DEBUG("State: NB");
screen->setOn(false);
#ifdef ARCH_ESP32
// Only ESP32 should turn off bluetooth
@ -168,7 +168,7 @@ static void darkEnter()
static void serialEnter()
{
LOG_DEBUG("Enter state: SERIAL");
LOG_DEBUG("State: SERIAL");
setBluetoothEnable(false);
screen->setOn(true);
screen->print("Serial connected\n");
@ -183,7 +183,7 @@ static void serialExit()
static void powerEnter()
{
// LOG_DEBUG("Enter state: POWER");
// LOG_DEBUG("State: POWER");
if (!isPowered()) {
// If we got here, we are in the wrong state - we should be in powered, let that state handle things
LOG_INFO("Loss of power in Powered");
@ -222,7 +222,7 @@ static void powerExit()
static void onEnter()
{
LOG_DEBUG("Enter state: ON");
LOG_DEBUG("State: ON");
screen->setOn(true);
setBluetoothEnable(true);
}
@ -242,7 +242,7 @@ static void screenPress()
static void bootEnter()
{
LOG_DEBUG("Enter state: BOOT");
LOG_DEBUG("State: BOOT");
}
State stateSHUTDOWN(shutdownEnter, NULL, NULL, "SHUTDOWN");

View File

@ -50,7 +50,7 @@ void AirTime::airtimeRotatePeriod()
{
if (this->airtimes.lastPeriodIndex != this->currentPeriodIndex()) {
LOG_DEBUG("Rotating airtimes to a new period = %u", this->currentPeriodIndex());
LOG_DEBUG("Rotate airtimes to a new period = %u", this->currentPeriodIndex());
for (int i = PERIODS_TO_LOG - 2; i >= 0; --i) {
this->airtimes.periodTX[i + 1] = this->airtimes.periodTX[i];
@ -105,7 +105,6 @@ float AirTime::channelUtilizationPercent()
uint32_t sum = 0;
for (uint32_t i = 0; i < CHANNEL_UTILIZATION_PERIODS; i++) {
sum += this->channelUtilization[i];
// LOG_DEBUG("ChanUtilArray %u %u", i, this->channelUtilization[i]);
}
return (float(sum) / float(CHANNEL_UTILIZATION_PERIODS * 10 * 1000)) * 100;
@ -127,7 +126,7 @@ bool AirTime::isTxAllowedChannelUtil(bool polite)
if (channelUtilizationPercent() < percentage) {
return true;
} else {
LOG_WARN("Channel utilization is >%d percent. Skipping this opportunity to send.", percentage);
LOG_WARN("Channel utilization is >%d percent. Skip opportunity to send.", percentage);
return false;
}
}
@ -138,7 +137,7 @@ bool AirTime::isTxAllowedAirUtil()
if (utilizationTXPercent() < myRegion->dutyCycle * polite_duty_cycle_percent / 100) {
return true;
} else {
LOG_WARN("Tx air utilization is >%f percent. Skipping this opportunity to send.",
LOG_WARN("Tx air utilization is >%f percent. Skip opportunity to send.",
myRegion->dutyCycle * polite_duty_cycle_percent / 100);
return false;
}
@ -208,14 +207,5 @@ int32_t AirTime::runOnce()
this->utilizationTX[utilPeriodTX] = 0;
}
}
/*
LOG_DEBUG("utilPeriodTX %d TX Airtime %3.2f%", utilPeriodTX, airTime->utilizationTXPercent());
for (uint32_t i = 0; i < MINUTES_IN_HOUR; i++) {
LOG_DEBUG(
"%d,", this->utilizationTX[i]
);
}
LOG_DEBUG("");
*/
return (1000 * 1);
}
}

View File

@ -32,12 +32,12 @@ IRAM_ATTR bool NotifiedWorkerThread::notifyCommon(uint32_t v, bool overwrite)
notification = v;
if (debugNotification) {
LOG_DEBUG("setting notification %d", v);
LOG_DEBUG("Set notification %d", v);
}
return true;
} else {
if (debugNotification) {
LOG_DEBUG("dropping notification %d", v);
LOG_DEBUG("Drop notification %d", v);
}
return false;
}
@ -67,7 +67,7 @@ bool NotifiedWorkerThread::notifyLater(uint32_t delay, uint32_t v, bool overwrit
if (didIt) { // If we didn't already have something queued, override the delay to be larger
setIntervalFromNow(delay); // a new version of setInterval relative to the current time
if (debugNotification) {
LOG_DEBUG("delaying notification %u", delay);
LOG_DEBUG("Delay notification %u", delay);
}
}

View File

@ -150,7 +150,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
{
concurrency::LockGuard guard((concurrency::Lock *)&lock);
LOG_DEBUG("Scanning for I2C devices on port %d", port);
LOG_DEBUG("Scan for I2C devices on port %d", port);
uint8_t err;
@ -186,7 +186,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
if (asize != 0) {
if (!in_array(address, asize, addr.address))
continue;
LOG_DEBUG("Scanning address 0x%x", addr.address);
LOG_DEBUG("Scan address 0x%x", addr.address);
}
i2cBus->beginTransmission(addr.address);
#ifdef ARCH_PORTDUINO

View File

@ -156,7 +156,7 @@ uint8_t GPS::makeCASPacket(uint8_t class_id, uint8_t msg_id, uint8_t payload_siz
CASChecksum(UBXscratch, (payload_size + 10));
#if defined(GPS_DEBUG) && defined(DEBUG_PORT)
LOG_DEBUG("Constructed CAS packet: ");
LOG_DEBUG("CAS packet: ");
DEBUG_PORT.hexDump(MESHTASTIC_LOG_LEVEL_DEBUG, UBXscratch, payload_size + 10);
#endif
return (payload_size + 10);
@ -237,7 +237,7 @@ GPS_RESPONSE GPS::getACKCas(uint8_t class_id, uint8_t msg_id, uint32_t waitMilli
// Check for an ACK-ACK for the specified class and message id
if ((msg_cls == 0x05) && (msg_msg_id == 0x01) && payload_cls == class_id && payload_msg == msg_id) {
#ifdef GPS_DEBUG
LOG_INFO("Got ACK for class %02X message %02X in %d millis.", class_id, msg_id, millis() - startTime);
LOG_INFO("Got ACK for class %02X message %02X in %dms", class_id, msg_id, millis() - startTime);
#endif
return GNSS_RESPONSE_OK;
}
@ -245,7 +245,7 @@ GPS_RESPONSE GPS::getACKCas(uint8_t class_id, uint8_t msg_id, uint32_t waitMilli
// Check for an ACK-NACK for the specified class and message id
if ((msg_cls == 0x05) && (msg_msg_id == 0x00) && payload_cls == class_id && payload_msg == msg_id) {
#ifdef GPS_DEBUG
LOG_WARN("Got NACK for class %02X message %02X in %d millis.", class_id, msg_id, millis() - startTime);
LOG_WARN("Got NACK for class %02X message %02X in %dms", class_id, msg_id, millis() - startTime);
#endif
return GNSS_RESPONSE_NAK;
}
@ -286,8 +286,7 @@ GPS_RESPONSE GPS::getACK(uint8_t class_id, uint8_t msg_id, uint32_t waitMillis)
while (Throttle::isWithinTimespanMs(startTime, waitMillis)) {
if (ack > 9) {
#ifdef GPS_DEBUG
LOG_DEBUG("");
LOG_INFO("Got ACK for class %02X message %02X in %d millis.", class_id, msg_id, millis() - startTime);
LOG_INFO("Got ACK for class %02X message %02X in %dms", class_id, msg_id, millis() - startTime);
#endif
return GNSS_RESPONSE_OK; // ACK received
}
@ -397,8 +396,7 @@ int GPS::getACK(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
} else {
// return payload length
#ifdef GPS_DEBUG
LOG_INFO("Got ACK for class %02X message %02X in %d millis.", requestedClass, requestedID,
millis() - startTime);
LOG_INFO("Got ACK for class %02X message %02X in %dms", requestedClass, requestedID, millis() - startTime);
#endif
return needRead;
}
@ -409,7 +407,6 @@ int GPS::getACK(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
}
}
}
// LOG_WARN("No response for class %02X message %02X", requestedClass, requestedID);
return 0;
}
@ -427,7 +424,7 @@ bool GPS::setup()
int msglen = 0;
if (tx_gpio && gnssModel == GNSS_MODEL_UNKNOWN) {
if (probeTries < 2) {
LOG_DEBUG("Probing for GPS at %d", serialSpeeds[speedSelect]);
LOG_DEBUG("Probe for GPS at %d", serialSpeeds[speedSelect]);
gnssModel = probe(serialSpeeds[speedSelect]);
if (gnssModel == GNSS_MODEL_UNKNOWN) {
if (++speedSelect == sizeof(serialSpeeds) / sizeof(int)) {
@ -438,11 +435,11 @@ bool GPS::setup()
}
// Rare Serial Speeds
if (probeTries == 2) {
LOG_DEBUG("Probing for GPS at %d", rareSerialSpeeds[speedSelect]);
LOG_DEBUG("Probe for GPS at %d", rareSerialSpeeds[speedSelect]);
gnssModel = probe(rareSerialSpeeds[speedSelect]);
if (gnssModel == GNSS_MODEL_UNKNOWN) {
if (++speedSelect == sizeof(rareSerialSpeeds) / sizeof(int)) {
LOG_WARN("Giving up on GPS probe and setting to %d", GPS_BAUDRATE);
LOG_WARN("Give up on GPS probe and set to %d", GPS_BAUDRATE);
return true;
}
}
@ -507,14 +504,14 @@ bool GPS::setup()
msglen = makeCASPacket(0x06, 0x07, sizeof(_message_CAS_CFG_NAVX_CONF), _message_CAS_CFG_NAVX_CONF);
_serial_gps->write(UBXscratch, msglen);
if (getACKCas(0x06, 0x07, 250) != GNSS_RESPONSE_OK) {
LOG_WARN("ATGM336H - Could not set Configuration");
LOG_WARN("ATGM336H: Could not set Config");
}
// Set the update frequence to 1Hz
msglen = makeCASPacket(0x06, 0x04, sizeof(_message_CAS_CFG_RATE_1HZ), _message_CAS_CFG_RATE_1HZ);
_serial_gps->write(UBXscratch, msglen);
if (getACKCas(0x06, 0x04, 250) != GNSS_RESPONSE_OK) {
LOG_WARN("ATGM336H - Could not set Update Frequency");
LOG_WARN("ATGM336H: Could not set Update Frequency");
}
// Set the NEMA output messages
@ -526,7 +523,7 @@ bool GPS::setup()
msglen = makeCASPacket(0x06, 0x01, sizeof(cas_cfg_msg_packet), cas_cfg_msg_packet);
_serial_gps->write(UBXscratch, msglen);
if (getACKCas(0x06, 0x01, 250) != GNSS_RESPONSE_OK) {
LOG_WARN("ATGM336H - Could not enable NMEA MSG: %d", fields[i]);
LOG_WARN("ATGM336H: Could not enable NMEA MSG: %d", fields[i]);
}
}
} else if (gnssModel == GNSS_MODEL_UC6580) {
@ -579,20 +576,20 @@ bool GPS::setup()
SEND_UBX_PACKET(0x06, 0x01, _message_GGA, "enable NMEA GGA", 500);
clearBuffer();
SEND_UBX_PACKET(0x06, 0x11, _message_CFG_RXM_ECO, "enable powersaving ECO mode for Neo-6", 500);
SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersaving details for GPS", 500);
SEND_UBX_PACKET(0x06, 0x11, _message_CFG_RXM_ECO, "enable powersave ECO mode for Neo-6", 500);
SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersave details for GPS", 500);
SEND_UBX_PACKET(0x06, 0x01, _message_AID, "disable UBX-AID", 500);
msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE);
_serial_gps->write(UBXscratch, msglen);
if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to save GNSS module configuration.");
LOG_WARN("Unable to save GNSS module config");
} else {
LOG_INFO("GNSS module configuration saved!");
LOG_INFO("GNSS module config saved!");
}
} else if (IS_ONE_OF(gnssModel, GNSS_MODEL_UBLOX7, GNSS_MODEL_UBLOX8, GNSS_MODEL_UBLOX9)) {
if (gnssModel == GNSS_MODEL_UBLOX7) {
LOG_DEBUG("Setting GPS+SBAS");
LOG_DEBUG("Set GPS+SBAS");
msglen = makeUBXPacket(0x06, 0x3e, sizeof(_message_GNSS_7), _message_GNSS_7);
_serial_gps->write(UBXscratch, msglen);
} else { // 8,9
@ -602,12 +599,12 @@ bool GPS::setup()
if (getACK(0x06, 0x3e, 800) == GNSS_RESPONSE_NAK) {
// It's not critical if the module doesn't acknowledge this configuration.
LOG_INFO("reconfigure GNSS - defaults maintained. Is this module GPS-only?");
LOG_DEBUG("reconfigure GNSS - defaults maintained. Is this module GPS-only?");
} else {
if (gnssModel == GNSS_MODEL_UBLOX7) {
LOG_INFO("GNSS configured for GPS+SBAS.");
LOG_INFO("GPS+SBAS configured");
} else { // 8,9
LOG_INFO("GNSS configured for GPS+SBAS+GLONASS+Galileo.");
LOG_INFO("GPS+SBAS+GLONASS+Galileo configured");
}
// Documentation say, we need wait atleast 0.5s after reconfiguration of GNSS module, before sending next
// commands for the M8 it tends to be more... 1 sec should be enough ;>)
@ -639,8 +636,8 @@ bool GPS::setup()
if (uBloxProtocolVersion >= 18) {
clearBuffer();
SEND_UBX_PACKET(0x06, 0x86, _message_PMS, "enable powersaving for GPS", 500);
SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersaving details for GPS", 500);
SEND_UBX_PACKET(0x06, 0x86, _message_PMS, "enable powersave for GPS", 500);
SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersave details for GPS", 500);
// For M8 we want to enable NMEA vserion 4.10 so we can see the additional sats.
if (gnssModel == GNSS_MODEL_UBLOX8) {
@ -648,14 +645,14 @@ bool GPS::setup()
SEND_UBX_PACKET(0x06, 0x17, _message_NMEA, "enable NMEA 4.10", 500);
}
} else {
SEND_UBX_PACKET(0x06, 0x11, _message_CFG_RXM_PSM, "enable powersaving mode for GPS", 500);
SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersaving details for GPS", 500);
SEND_UBX_PACKET(0x06, 0x11, _message_CFG_RXM_PSM, "enable powersave mode for GPS", 500);
SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersave details for GPS", 500);
}
msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE);
_serial_gps->write(UBXscratch, msglen);
if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to save GNSS module configuration.");
LOG_WARN("Unable to save GNSS module config");
} else {
LOG_INFO("GNSS module configuration saved!");
}
@ -675,13 +672,13 @@ bool GPS::setup()
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_TXT_INFO_BBR, "disable Info messages for M10 GPS BBR", 300);
delay(750);
// Do M10 configuration for Power Management.
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_PM_RAM, "enable powersaving for M10 GPS RAM", 300);
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_PM_RAM, "enable powersave for M10 GPS RAM", 300);
delay(750);
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_PM_BBR, "enable powersaving for M10 GPS BBR", 300);
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_PM_BBR, "enable powersave for M10 GPS BBR", 300);
delay(750);
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ITFM_RAM, "enable Jamming detection M10 GPS RAM", 300);
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ITFM_RAM, "enable jam detection M10 GPS RAM", 300);
delay(750);
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ITFM_BBR, "enable Jamming detection M10 GPS BBR", 300);
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ITFM_BBR, "enable jam detection M10 GPS BBR", 300);
delay(750);
// Here is where the init commands should go to do further M10 initialization.
SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_SBAS_RAM, "disable SBAS M10 GPS RAM", 300);
@ -703,7 +700,7 @@ bool GPS::setup()
msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE_10), _message_SAVE_10);
_serial_gps->write(UBXscratch, msglen);
if (getACK(0x06, 0x09, 2000) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to save GNSS module configuration.");
LOG_WARN("Unable to save GNSS module config");
} else {
LOG_INFO("GNSS module configuration saved!");
}
@ -727,7 +724,7 @@ void GPS::setPowerState(GPSPowerState newState, uint32_t sleepTime)
// Update the stored GPSPowerstate, and create local copies
GPSPowerState oldState = powerState;
powerState = newState;
LOG_INFO("GPS power state moving from %s to %s", getGPSPowerStateString(oldState), getGPSPowerStateString(newState));
LOG_INFO("GPS power state move from %s to %s", getGPSPowerStateString(oldState), getGPSPowerStateString(newState));
#ifdef HELTEC_MESH_NODE_T114
if ((oldState == GPS_OFF || oldState == GPS_HARDSLEEP) && (newState != GPS_OFF && newState != GPS_HARDSLEEP)) {
@ -796,8 +793,8 @@ void GPS::writePinEN(bool on)
// Write and log
enablePin->set(on);
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Pin EN %s", val == HIGH ? "HIGH" : "LOW");
#ifdef GPS_DEBUG
LOG_DEBUG("Pin EN %s", val == HIGH ? "HI" : "LOW");
#endif
}
@ -818,8 +815,8 @@ void GPS::writePinStandby(bool standby)
// Write and log
pinMode(PIN_GPS_STANDBY, OUTPUT);
digitalWrite(PIN_GPS_STANDBY, val);
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Pin STANDBY %s", val == HIGH ? "HIGH" : "LOW");
#ifdef GPS_DEBUG
LOG_DEBUG("Pin STANDBY %s", val == HIGH ? "HI" : "LOW");
#endif
#endif
}
@ -851,8 +848,7 @@ void GPS::setPowerPMU(bool on)
// t-beam v1.1 GNSS power channel
on ? PMU->enablePowerOutput(XPOWERS_LDO3) : PMU->disablePowerOutput(XPOWERS_LDO3);
}
#ifdef GPS_EXTRAVERBOSE
#ifdef GPS_DEBUG
LOG_DEBUG("PMU %s", on ? "on" : "off");
#endif
#endif
@ -869,9 +865,6 @@ void GPS::setPowerUBLOX(bool on, uint32_t sleepMs)
if (on) {
gps->_serial_gps->write(0xFF);
clearBuffer(); // This often returns old data, so drop it
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("UBLOX: wake");
#endif
}
// If putting to sleep
@ -903,8 +896,7 @@ void GPS::setPowerUBLOX(bool on, uint32_t sleepMs)
// Send the UBX packet
gps->_serial_gps->write(gps->UBXscratch, msglen);
#ifdef GPS_EXTRAVERBOSE
#ifdef GPS_DEBUG
LOG_DEBUG("UBLOX: sleep for %dmS", sleepMs);
#endif
}
@ -976,8 +968,7 @@ void GPS::publishUpdate()
shouldPublish = false;
// In debug logs, identify position by @timestamp:stage (stage 2 = publish)
LOG_DEBUG("publishing pos@%x:2, hasVal=%d, Sats=%d, GPSlock=%d", p.timestamp, hasValidLocation, p.sats_in_view,
hasLock());
LOG_DEBUG("Publish pos@%x:2, hasVal=%d, Sats=%d, GPSlock=%d", p.timestamp, hasValidLocation, p.sats_in_view, hasLock());
// Notify any status instances that are observing us
const meshtastic::GPSStatus status = meshtastic::GPSStatus(hasValidLocation, isConnected(), isPowerSaving(), p);
@ -992,7 +983,7 @@ int32_t GPS::runOnce()
{
if (!GPSInitFinished) {
if (!_serial_gps || config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT) {
LOG_INFO("GPS set to not-present. Skipping probe.");
LOG_INFO("GPS set to not-present. Skip probe");
return disable();
}
if (!setup())
@ -1028,7 +1019,7 @@ int32_t GPS::runOnce()
GNSS_MODEL_UBLOX10)) {
// reset the GPS on next bootup
if (devicestate.did_gps_reset && scheduling.elapsedSearchMs() > 60 * 1000UL && !hasFlow()) {
LOG_DEBUG("GPS is not communicating, trying factory reset on next bootup.");
LOG_DEBUG("GPS is not found, try factory reset on next boot");
devicestate.did_gps_reset = false;
nodeDB->saveToDisk(SEGMENT_DEVICESTATE);
return disable(); // Stop the GPS thread as it can do nothing useful until next reboot.
@ -1062,10 +1053,9 @@ int32_t GPS::runOnce()
bool tooLong = scheduling.searchedTooLong();
if (tooLong)
LOG_WARN("Couldn't publish a valid location: didn't get a GPS lock in time.");
LOG_WARN("Couldn't publish a valid location: didn't get a GPS lock in time");
// Once we get a location we no longer desperately want an update
// LOG_DEBUG("gotLoc %d, tooLong %d, gotTime %d", gotLoc, tooLong, gotTime);
if ((gotLoc && gotTime) || tooLong) {
if (tooLong) {
@ -1131,7 +1121,7 @@ GnssModel_t GPS::probe(int serialSpeed)
_serial_gps->begin(serialSpeed);
#else
if (_serial_gps->baudRate() != serialSpeed) {
LOG_DEBUG("Setting Baud to %i", serialSpeed);
LOG_DEBUG("Set Baud to %i", serialSpeed);
_serial_gps->updateBaudRate(serialSpeed);
}
#endif
@ -1181,7 +1171,7 @@ GnssModel_t GPS::probe(int serialSpeed)
// Check that the returned response class and message ID are correct
GPS_RESPONSE response = getACK(0x06, 0x08, 750);
if (response == GNSS_RESPONSE_NONE) {
LOG_WARN("Failed to find GNSS Module (baudrate %d)", serialSpeed);
LOG_WARN("No GNSS Module (baudrate %d)", serialSpeed);
return GNSS_MODEL_UNKNOWN;
} else if (response == GNSS_RESPONSE_FRAME_ERRORS) {
LOG_INFO("UBlox Frame Errors (baudrate %d)", serialSpeed);
@ -1201,7 +1191,6 @@ GnssModel_t GPS::probe(int serialSpeed)
uint16_t len = getACK(buffer, sizeof(buffer), 0x0A, 0x04, 1200);
if (len) {
// LOG_DEBUG("monver reply size = %d", len);
uint16_t position = 0;
for (int i = 0; i < 30; i++) {
info.swVersion[i] = buffer[position];
@ -1266,7 +1255,7 @@ GnssModel_t GPS::probe(int serialSpeed)
return GNSS_MODEL_UBLOX10;
}
}
LOG_WARN("Failed to find GNSS Module (baudrate %d)", serialSpeed);
LOG_WARN("No GNSS Module (baudrate %d)", serialSpeed);
return GNSS_MODEL_UNKNOWN;
}
@ -1329,7 +1318,7 @@ GPS *GPS::createGps()
// see NMEAGPS.h
gsafixtype.begin(reader, NMEA_MSG_GXGSA, 2);
gsapdop.begin(reader, NMEA_MSG_GXGSA, 15);
LOG_DEBUG("Using " NMEA_MSG_GXGSA " for 3DFIX and PDOP");
LOG_DEBUG("Use " NMEA_MSG_GXGSA " for 3DFIX and PDOP");
#endif
// Make sure the GPS is awake before performing any init.
@ -1350,8 +1339,8 @@ GPS *GPS::createGps()
// ESP32 has a special set of parameters vs other arduino ports
#if defined(ARCH_ESP32)
LOG_DEBUG("Using GPIO%d for GPS RX", new_gps->rx_gpio);
LOG_DEBUG("Using GPIO%d for GPS TX", new_gps->tx_gpio);
LOG_DEBUG("Use GPIO%d for GPS RX", new_gps->rx_gpio);
LOG_DEBUG("Use GPIO%d for GPS TX", new_gps->tx_gpio);
_serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, new_gps->rx_gpio, new_gps->tx_gpio);
#elif defined(ARCH_RP2040)
_serial_gps->setFIFOSize(256);
@ -1387,26 +1376,22 @@ bool GPS::factoryReset()
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x1C, 0xA2};
_serial_gps->write(_message_reset1, sizeof(_message_reset1));
if (getACK(0x05, 0x01, 10000)) {
LOG_INFO(ACK_SUCCESS_MESSAGE);
LOG_DEBUG(ACK_SUCCESS_MESSAGE);
}
delay(100);
byte _message_reset2[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x1B, 0xA1};
_serial_gps->write(_message_reset2, sizeof(_message_reset2));
if (getACK(0x05, 0x01, 10000)) {
LOG_INFO(ACK_SUCCESS_MESSAGE);
LOG_DEBUG(ACK_SUCCESS_MESSAGE);
}
delay(100);
byte _message_reset3[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x03, 0x1D, 0xB3};
_serial_gps->write(_message_reset3, sizeof(_message_reset3));
if (getACK(0x05, 0x01, 10000)) {
LOG_INFO(ACK_SUCCESS_MESSAGE);
LOG_DEBUG(ACK_SUCCESS_MESSAGE);
}
// Reset device ram to COLDSTART state
// byte _message_CFG_RST_COLDSTART[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0xB9, 0x00, 0x00, 0xC6, 0x8B};
// _serial_gps->write(_message_CFG_RST_COLDSTART, sizeof(_message_CFG_RST_COLDSTART));
// delay(1000);
} else if (gnssModel == GNSS_MODEL_MTK) {
// send the CAS10 to perform a factory restart of the device (and other device that support PCAS statements)
LOG_INFO("GNSS Factory Reset via PCAS10,3");
@ -1518,7 +1503,7 @@ bool GPS::lookForLocation()
#ifndef TINYGPS_OPTION_NO_STATISTICS
if (reader.failedChecksum() > lastChecksumFailCount) {
LOG_WARN("%u new GPS checksum failures, for a total of %u.", reader.failedChecksum() - lastChecksumFailCount,
LOG_WARN("%u new GPS checksum failures, for a total of %u", reader.failedChecksum() - lastChecksumFailCount,
reader.failedChecksum());
lastChecksumFailCount = reader.failedChecksum();
}
@ -1526,14 +1511,13 @@ bool GPS::lookForLocation()
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
fixType = atoi(gsafixtype.value()); // will set to zero if no data
// LOG_DEBUG("FIX QUAL=%d, TYPE=%d", fixQual, fixType);
#endif
// check if GPS has an acceptable lock
if (!hasLock())
return false;
#ifdef GPS_EXTRAVERBOSE
#ifdef GPS_DEBUG
LOG_DEBUG("AGE: LOC=%d FIX=%d DATE=%d TIME=%d", reader.location.age(),
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
gsafixtype.age(),
@ -1541,7 +1525,7 @@ bool GPS::lookForLocation()
0,
#endif
reader.date.age(), reader.time.age());
#endif // GPS_EXTRAVERBOSE
#endif // GPS_DEBUG
// Is this a new point or are we re-reading the previous one?
if (!reader.location.isUpdated() && !reader.altitude.isUpdated())
@ -1564,13 +1548,13 @@ bool GPS::lookForLocation()
// Bail out EARLY to avoid overwriting previous good data (like #857)
if (toDegInt(loc.lat) > 900000000) {
#ifdef GPS_EXTRAVERBOSE
#ifdef GPS_DEBUG
LOG_DEBUG("Bail out EARLY on LAT %i", toDegInt(loc.lat));
#endif
return false;
}
if (toDegInt(loc.lng) > 1800000000) {
#ifdef GPS_EXTRAVERBOSE
#ifdef GPS_DEBUG
LOG_DEBUG("Bail out EARLY on LNG %i", toDegInt(loc.lng));
#endif
return false;
@ -1582,7 +1566,6 @@ bool GPS::lookForLocation()
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
p.HDOP = reader.hdop.value();
p.PDOP = TinyGPSPlus::parseDecimal(gsapdop.value());
// LOG_DEBUG("PDOP=%d, HDOP=%d", p.PDOP, p.HDOP);
#else
// FIXME! naive PDOP emulation (assumes VDOP==HDOP)
// correct formula is PDOP = SQRT(HDOP^2 + VDOP^2)
@ -1672,12 +1655,10 @@ bool GPS::whileActive()
}
#ifdef SERIAL_BUFFER_SIZE
if (_serial_gps->available() >= SERIAL_BUFFER_SIZE - 1) {
LOG_WARN("GPS Buffer full with %u bytes waiting. Flushing to avoid corruption.", _serial_gps->available());
LOG_WARN("GPS Buffer full with %u bytes waiting. Flush to avoid corruption", _serial_gps->available());
clearBuffer();
}
#endif
// if (_serial_gps->available() > 0)
// LOG_DEBUG("GPS Bytes Waiting: %u", _serial_gps->available());
// First consume any chars that have piled up at the receiver
while (_serial_gps->available() > 0) {
int c = _serial_gps->read();
@ -1727,7 +1708,7 @@ void GPS::toggleGpsMode()
{
if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) {
config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_DISABLED;
LOG_INFO("User toggled GpsMode. Now DISABLED.");
LOG_INFO("User toggled GpsMode. Now DISABLED");
playGPSDisableBeep();
#ifdef GNSS_AIROHA
if (powerState == GPS_ACTIVE) {
@ -1743,4 +1724,4 @@ void GPS::toggleGpsMode()
enable();
}
}
#endif // Exclude GPS
#endif // Exclude GPS

View File

@ -108,7 +108,7 @@ void GPSUpdateScheduling::updateLockTimePrediction()
searchCount++; // Only tracked so we can disregard initial lock-times
LOG_DEBUG("Predicting %us to get next lock", predictedMsToGetLock / 1000);
LOG_DEBUG("Predict %us to get next lock", predictedMsToGetLock / 1000);
}
// How long do we expect to spend searching for a lock?

View File

@ -112,7 +112,7 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv, bool forceUpdate)
uint32_t printableEpoch = tv->tv_sec; // Print lib only supports 32 bit but time_t can be 64 bit on some platforms
#ifdef BUILD_EPOCH
if (tv->tv_sec < BUILD_EPOCH) {
LOG_WARN("Ignoring time (%ld) before build epoch (%ld)!", printableEpoch, BUILD_EPOCH);
LOG_WARN("Ignore time (%ld) before build epoch (%ld)!", printableEpoch, BUILD_EPOCH);
return false;
}
#endif
@ -120,21 +120,21 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv, bool forceUpdate)
bool shouldSet;
if (forceUpdate) {
shouldSet = true;
LOG_DEBUG("Overriding current RTC quality (%s) with incoming time of RTC quality of %s", RtcName(currentQuality),
LOG_DEBUG("Override current RTC quality (%s) with incoming time of RTC quality of %s", RtcName(currentQuality),
RtcName(q));
} else if (q > currentQuality) {
shouldSet = true;
LOG_DEBUG("Upgrading time to quality %s", RtcName(q));
LOG_DEBUG("Upgrade time to quality %s", RtcName(q));
} else if (q == RTCQualityGPS) {
shouldSet = true;
LOG_DEBUG("Reapplying GPS time: %ld secs", printableEpoch);
LOG_DEBUG("Reapply GPS time: %ld secs", printableEpoch);
} else if (q == RTCQualityNTP && !Throttle::isWithinTimespanMs(lastSetMsec, (12 * 60 * 60 * 1000UL))) {
// Every 12 hrs we will slam in a new NTP or Phone GPS / NTP time, to correct for local RTC clock drift
shouldSet = true;
LOG_DEBUG("Reapplying external time to correct clock drift %ld secs", printableEpoch);
LOG_DEBUG("Reapply external time to correct clock drift %ld secs", printableEpoch);
} else {
shouldSet = false;
LOG_DEBUG("Current RTC quality: %s. Ignoring time of RTC quality of %s", RtcName(currentQuality), RtcName(q));
LOG_DEBUG("Current RTC quality: %s. Ignore time of RTC quality of %s", RtcName(currentQuality), RtcName(q));
}
if (shouldSet) {
@ -230,7 +230,7 @@ bool perhapsSetRTC(RTCQuality q, struct tm &t)
// LOG_DEBUG("Got time from GPS month=%d, year=%d, unixtime=%ld", t.tm_mon, t.tm_year, tv.tv_sec);
if (t.tm_year < 0 || t.tm_year >= 300) {
// LOG_DEBUG("Ignoring invalid GPS month=%d, year=%d, unixtime=%ld", t.tm_mon, t.tm_year, tv.tv_sec);
// LOG_DEBUG("Ignore invalid GPS month=%d, year=%d, unixtime=%ld", t.tm_mon, t.tm_year, tv.tv_sec);
return false;
} else {
return perhapsSetRTC(q, &tv);

View File

@ -79,7 +79,7 @@ bool EInkDisplay::forceDisplay(uint32_t msecLimit)
}
// Trigger the refresh in GxEPD2
LOG_DEBUG("Updating E-Paper");
LOG_DEBUG("Update E-Paper");
adafruitDisplay->nextPage();
// End the update process
@ -123,7 +123,7 @@ void EInkDisplay::setDetected(uint8_t detected)
// Connect to the display - variant specific
bool EInkDisplay::connect()
{
LOG_INFO("Doing EInk init");
LOG_INFO("Do EInk init");
#ifdef PIN_EINK_EN
// backlight power, HIGH is backlight on, LOW is off

View File

@ -119,7 +119,7 @@ void EInkDynamicDisplay::endOrDetach()
awaitRefresh();
else {
// Async begins
LOG_DEBUG("Async full-refresh begins (dropping frames)");
LOG_DEBUG("Async full-refresh begins (drop frames)");
notifyLater(intervalPollAsyncRefresh, DUE_POLL_ASYNCREFRESH, true); // Hand-off to NotifiedWorkerThread
}
}
@ -469,7 +469,7 @@ void EInkDynamicDisplay::joinAsyncRefresh()
if (!asyncRefreshRunning)
return;
LOG_DEBUG("Joining an async refresh in progress");
LOG_DEBUG("Join an async refresh in progress");
// Continually poll the BUSY pin
while (adafruitDisplay->epd2.isBusy())

View File

@ -242,7 +242,7 @@ static void drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, i
// draw overlay in bottom right corner of screen to show when notifications are muted or modifier key is active
static void drawFunctionOverlay(OLEDDisplay *display, OLEDDisplayUiState *state)
{
// LOG_DEBUG("Drawing function overlay");
// LOG_DEBUG("Draw function overlay");
if (functionSymbals.begin() != functionSymbals.end()) {
char buf[64];
display->setFont(FONT_SMALL);
@ -260,7 +260,7 @@ static void drawDeepSleepScreen(OLEDDisplay *display, OLEDDisplayUiState *state,
EINK_ADD_FRAMEFLAG(display, COSMETIC);
EINK_ADD_FRAMEFLAG(display, BLOCKING);
LOG_DEBUG("Drawing deep sleep screen");
LOG_DEBUG("Draw deep sleep screen");
// Display displayStr on the screen
drawIconScreen("Sleeping", display, state, x, y);
@ -269,7 +269,7 @@ static void drawDeepSleepScreen(OLEDDisplay *display, OLEDDisplayUiState *state,
/// Used on eink displays when screen updates are paused
static void drawScreensaverOverlay(OLEDDisplay *display, OLEDDisplayUiState *state)
{
LOG_DEBUG("Drawing screensaver overlay");
LOG_DEBUG("Draw screensaver overlay");
EINK_ADD_FRAMEFLAG(display, COSMETIC); // Take the opportunity for a full-refresh
@ -337,7 +337,7 @@ static void drawModuleFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int
module_frame = state->currentFrame;
// LOG_DEBUG("Screen is not in transition. Frame: %d", module_frame);
}
// LOG_DEBUG("Drawing Module Frame %d", module_frame);
// LOG_DEBUG("Draw Module Frame %d", module_frame);
MeshModule &pi = *moduleFrames.at(module_frame);
pi.drawFrame(display, state, x, y);
}
@ -912,7 +912,7 @@ static void drawTextMessageFrame(OLEDDisplay *display, OLEDDisplayUiState *state
const meshtastic_MeshPacket &mp = devicestate.rx_text_message;
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(getFrom(&mp));
// LOG_DEBUG("drawing text message from 0x%x: %s", mp.from,
// LOG_DEBUG("Draw text message from 0x%x: %s", mp.from,
// mp.decoded.variant.data.decoded.bytes);
// Demo for drawStringMaxWidth:
@ -1499,7 +1499,7 @@ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_O
(address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE);
#elif ARCH_PORTDUINO
if (settingsMap[displayPanel] != no_screen) {
LOG_DEBUG("Making TFTDisplay!");
LOG_DEBUG("Make TFTDisplay!");
dispdev = new TFTDisplay(address.address, -1, -1, geometry,
(address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE);
} else {
@ -1546,7 +1546,7 @@ void Screen::handleSetOn(bool on, FrameCallback einkScreensaver)
if (on != screenOn) {
if (on) {
LOG_INFO("Turning on screen");
LOG_INFO("Turn on screen");
powerMon->setState(meshtastic_PowerMon_State_Screen_On);
#ifdef T_WATCH_S3
PMU->enablePowerOutput(XPOWERS_ALDO2);
@ -1581,7 +1581,7 @@ void Screen::handleSetOn(bool on, FrameCallback einkScreensaver)
// eInkScreensaver parameter is usually NULL (default argument), default frame used instead
setScreensaverFrames(einkScreensaver);
#endif
LOG_INFO("Turning off screen");
LOG_INFO("Turn off screen");
dispdev->displayOff();
#ifdef USE_ST7789
SPI1.end();
@ -1885,7 +1885,7 @@ int32_t Screen::runOnce()
EINK_ADD_FRAMEFLAG(dispdev, COSMETIC);
#endif
LOG_DEBUG("LastScreenTransition exceeded %ums transitioning to next frame", (millis() - lastScreenTransition));
LOG_DEBUG("LastScreenTransition exceeded %ums transition to next frame", (millis() - lastScreenTransition));
handleOnPress();
}
}
@ -1921,7 +1921,7 @@ void Screen::drawDebugInfoWiFiTrampoline(OLEDDisplay *display, OLEDDisplayUiStat
void Screen::setSSLFrames()
{
if (address_found.address) {
// LOG_DEBUG("showing SSL frames");
// LOG_DEBUG("Show SSL frames");
static FrameCallback sslFrames[] = {drawSSLScreen};
ui->setFrames(sslFrames, 1);
ui->update();
@ -1933,7 +1933,7 @@ void Screen::setSSLFrames()
void Screen::setWelcomeFrames()
{
if (address_found.address) {
// LOG_DEBUG("showing Welcome frames");
// LOG_DEBUG("Show Welcome frames");
static FrameCallback frames[] = {drawWelcomeScreen};
setFrameImmediateDraw(frames);
}
@ -1999,7 +1999,7 @@ void Screen::setFrames(FrameFocus focus)
uint8_t originalPosition = ui->getUiState()->currentFrame;
FramesetInfo fsi; // Location of specific frames, for applying focus parameter
LOG_DEBUG("showing standard frames");
LOG_DEBUG("Show standard frames");
showingNormalScreen = true;
#ifdef USE_EINK
@ -2012,7 +2012,7 @@ void Screen::setFrames(FrameFocus focus)
#endif
moduleFrames = MeshModule::GetMeshModulesWithUIFrames();
LOG_DEBUG("Showing %d module frames", moduleFrames.size());
LOG_DEBUG("Show %d module frames", moduleFrames.size());
#ifdef DEBUG_PORT
int totalFrameCount = MAX_NUM_NODES + NUM_EXTRA_FRAMES + moduleFrames.size();
LOG_DEBUG("Total frame count: %d", totalFrameCount);
@ -2094,7 +2094,7 @@ void Screen::setFrames(FrameFocus focus)
#endif
fsi.frameCount = numframes; // Total framecount is used to apply FOCUS_PRESERVE
LOG_DEBUG("Finished building frames. numframes: %d", numframes);
LOG_DEBUG("Finished build frames. numframes: %d", numframes);
ui->setFrames(normalFrames, numframes);
ui->enableAllIndicators();
@ -2175,13 +2175,13 @@ void Screen::dismissCurrentFrame()
bool dismissed = false;
if (currentFrame == framesetInfo.positions.textMessage && devicestate.has_rx_text_message) {
LOG_INFO("Dismissing Text Message");
LOG_INFO("Dismiss Text Message");
devicestate.has_rx_text_message = false;
dismissed = true;
}
else if (currentFrame == framesetInfo.positions.waypoint && devicestate.has_rx_waypoint) {
LOG_DEBUG("Dismissing Waypoint");
LOG_DEBUG("Dismiss Waypoint");
devicestate.has_rx_waypoint = false;
dismissed = true;
}
@ -2193,7 +2193,7 @@ void Screen::dismissCurrentFrame()
void Screen::handleStartFirmwareUpdateScreen()
{
LOG_DEBUG("showing firmware screen");
LOG_DEBUG("Show firmware screen");
showingNormalScreen = false;
EINK_ADD_FRAMEFLAG(dispdev, DEMAND_FAST); // E-Ink: Explicitly use fast-refresh for next frame
@ -2674,7 +2674,7 @@ int Screen::handleUIFrameEvent(const UIFrameEvent *event)
if (event->action == UIFrameEvent::Action::REGENERATE_FRAMESET)
setFrames(FOCUS_MODULE);
// Regenerate the frameset, while attempting to maintain focus on the current frame
// Regenerate the frameset, while Attempt to maintain focus on the current frame
else if (event->action == UIFrameEvent::Action::REGENERATE_FRAMESET_BACKGROUND)
setFrames(FOCUS_PRESERVE);

View File

@ -327,10 +327,15 @@ class Screen : public concurrency::OSThread
SKIPREST = false;
return (uint8_t)ch;
}
case 0xC3: {
SKIPREST = false;
return (uint8_t)(ch | 0xC0);
}
}
// We want to strip out prefix chars for two-byte char formats
if (ch == 0xC2)
if (ch == 0xC2 || ch == 0xC3)
return (uint8_t)0;
#if defined(OLED_PL)

View File

@ -834,7 +834,7 @@ void TFTDisplay::setDetected(uint8_t detected)
bool TFTDisplay::connect()
{
concurrency::LockGuard g(spiLock);
LOG_INFO("Doing TFT init");
LOG_INFO("Do TFT init");
#ifdef RAK14014
tft = new TFT_eSPI;
#else

View File

@ -116,7 +116,7 @@ void MPR121Keyboard::begin(i2c_com_fptr_t r, i2c_com_fptr_t w, uint8_t addr)
void MPR121Keyboard::reset()
{
LOG_DEBUG("MPR121 Resetting...");
LOG_DEBUG("MPR121 Reset...");
// Trigger a MPR121 Soft Reset
if (m_wire) {
m_wire->beginTransmission(m_addr);
@ -132,7 +132,7 @@ void MPR121Keyboard::reset()
writeRegister(_MPR121_REG_ELECTRODE_CONFIG, 0x00);
delay(100);
LOG_DEBUG("MPR121 Configuring");
LOG_DEBUG("MPR121 Configure");
// Set touch release thresholds
for (uint8_t i = 0; i < 12; i++) {
// Set touch threshold
@ -178,7 +178,7 @@ void MPR121Keyboard::reset()
writeRegister(_MPR121_REG_ELECTRODE_CONFIG,
ECR_CALIBRATION_TRACK_FROM_PARTIAL_FILTER | ECR_PROXIMITY_DETECTION_OFF | ECR_TOUCH_DETECTION_12CH);
delay(100);
LOG_DEBUG("MPR121 Running");
LOG_DEBUG("MPR121 Run");
state = Idle;
}

View File

@ -11,7 +11,7 @@ void CardKbI2cImpl::init()
{
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_PORTDUINO) && !defined(I2C_NO_RESCAN)
if (cardkb_found.address == 0x00) {
LOG_DEBUG("Rescanning for I2C keyboard");
LOG_DEBUG("Rescan for I2C keyboard");
uint8_t i2caddr_scan[] = {CARDKB_ADDR, TDECK_KB_ADDR, BBQ10_KB_ADDR, MPR121_KB_ADDR};
uint8_t i2caddr_asize = 4;
auto i2cScanner = std::unique_ptr<ScanI2CTwoWire>(new ScanI2CTwoWire());

View File

@ -34,7 +34,7 @@ int32_t KbI2cBase::runOnce()
switch (cardkb_found.port) {
case ScanI2C::WIRE1:
#if WIRE_INTERFACES_COUNT == 2
LOG_DEBUG("Using I2C Bus 1 (the second one)");
LOG_DEBUG("Use I2C Bus 1 (the second one)");
i2cBus = &Wire1;
if (cardkb_found.address == BBQ10_KB_ADDR) {
Q10keyboard.begin(BBQ10_KB_ADDR, &Wire1);
@ -46,7 +46,7 @@ int32_t KbI2cBase::runOnce()
break;
#endif
case ScanI2C::WIRE:
LOG_DEBUG("Using I2C Bus 0 (the first one)");
LOG_DEBUG("Use I2C Bus 0 (the first one)");
i2cBus = &Wire;
if (cardkb_found.address == BBQ10_KB_ADDR) {
Q10keyboard.begin(BBQ10_KB_ADDR, &Wire);

View File

@ -344,7 +344,7 @@ void setup()
#ifdef PERIPHERAL_WARMUP_MS
// Some peripherals may require additional time to stabilize after power is connected
// e.g. I2C on Heltec Vision Master
LOG_INFO("Waiting for peripherals to stabilize");
LOG_INFO("Wait for peripherals to stabilize");
delay(PERIPHERAL_WARMUP_MS);
#endif
@ -405,10 +405,10 @@ void setup()
Wire.begin(I2C_SDA, I2C_SCL);
#elif defined(ARCH_PORTDUINO)
if (settingsStrings[i2cdev] != "") {
LOG_INFO("Using %s as I2C device.", settingsStrings[i2cdev].c_str());
LOG_INFO("Use %s as I2C device", settingsStrings[i2cdev].c_str());
Wire.begin(settingsStrings[i2cdev].c_str());
} else {
LOG_INFO("No I2C device configured, skipping.");
LOG_INFO("No I2C device configured, Skip");
}
#elif HAS_WIRE
Wire.begin();
@ -451,7 +451,7 @@ void setup()
// accessories
auto i2cScanner = std::unique_ptr<ScanI2CTwoWire>(new ScanI2CTwoWire());
#if HAS_WIRE
LOG_INFO("Scanning for i2c devices...");
LOG_INFO("Scan for i2c devices...");
#endif
#if defined(I2C_SDA1) && defined(ARCH_RP2040)
@ -476,7 +476,7 @@ void setup()
i2cScanner->scanPort(ScanI2C::I2CPort::WIRE);
#elif defined(ARCH_PORTDUINO)
if (settingsStrings[i2cdev] != "") {
LOG_INFO("Scanning for i2c devices...");
LOG_INFO("Scan for i2c devices...");
i2cScanner->scanPort(ScanI2C::I2CPort::WIRE);
}
#elif HAS_WIRE
@ -686,7 +686,7 @@ void setup()
if (config.power.is_power_saving == true &&
IS_ONE_OF(config.device.role, meshtastic_Config_DeviceConfig_Role_TRACKER,
meshtastic_Config_DeviceConfig_Role_TAK_TRACKER, meshtastic_Config_DeviceConfig_Role_SENSOR))
LOG_DEBUG("Tracker/Sensor: Skipping start melody");
LOG_DEBUG("Tracker/Sensor: Skip start melody");
else
playStartMelody();
@ -836,7 +836,7 @@ void setup()
#endif
// setup TZ prior to time actions.
#if !MESHTASTIC_EXCLUDE_TZ
LOG_DEBUG("Using compiled/slipstreamed %s", slipstreamTZString); // important, removing this clobbers our magic string
LOG_DEBUG("Use compiled/slipstreamed %s", slipstreamTZString); // important, removing this clobbers our magic string
if (*config.device.tzdef && config.device.tzdef[0] != 0) {
LOG_DEBUG("Saved TZ: %s ", config.device.tzdef);
setenv("TZ", config.device.tzdef, 1);
@ -866,7 +866,7 @@ void setup()
if (gps) {
gpsStatus->observe(&gps->newStatus);
} else {
LOG_DEBUG("Running without GPS.");
LOG_DEBUG("Run without GPS");
}
}
}
@ -879,7 +879,7 @@ void setup()
nodeStatus->observe(&nodeDB->newStatus);
#ifdef HAS_I2S
LOG_DEBUG("Starting audio thread");
LOG_DEBUG("Start audio thread");
audioThread = new AudioThread();
#endif
service = new MeshService();
@ -926,63 +926,63 @@ void setup()
#ifdef ARCH_PORTDUINO
if (settingsMap[use_sx1262]) {
if (!rIf) {
LOG_DEBUG("Attempting to activate sx1262 radio on SPI port %s", settingsStrings[spidev].c_str());
LOG_DEBUG("Activate sx1262 radio on SPI port %s", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL =
new LockingArduinoHal(SPI, spiSettings, (settingsMap[ch341Quirk] ? settingsMap[busy] : RADIOLIB_NC));
rIf = new SX1262Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
LOG_ERROR("Failed to find SX1262 radio");
LOG_WARN("No SX1262 radio");
delete rIf;
exit(EXIT_FAILURE);
} else {
LOG_INFO("SX1262 Radio init succeeded, using SX1262 radio");
LOG_INFO("SX1262 init success");
}
}
} else if (settingsMap[use_rf95]) {
if (!rIf) {
LOG_DEBUG("Attempting to activate rf95 radio on SPI port %s", settingsStrings[spidev].c_str());
LOG_DEBUG("Activate rf95 radio on SPI port %s", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL =
new LockingArduinoHal(SPI, spiSettings, (settingsMap[ch341Quirk] ? settingsMap[busy] : RADIOLIB_NC));
rIf = new RF95Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
LOG_ERROR("Failed to find RF95 radio");
LOG_WARN("No RF95 radio");
delete rIf;
rIf = NULL;
exit(EXIT_FAILURE);
} else {
LOG_INFO("RF95 Radio init succeeded, using RF95 radio");
LOG_INFO("RF95 init success");
}
}
} else if (settingsMap[use_sx1280]) {
if (!rIf) {
LOG_DEBUG("Attempting to activate sx1280 radio on SPI port %s", settingsStrings[spidev].c_str());
LOG_DEBUG("Activate sx1280 radio on SPI port %s", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
rIf = new SX1280Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
LOG_ERROR("Failed to find SX1280 radio");
LOG_WARN("No SX1280 radio");
delete rIf;
rIf = NULL;
exit(EXIT_FAILURE);
} else {
LOG_INFO("SX1280 Radio init succeeded, using SX1280 radio");
LOG_INFO("SX1280 init success");
}
}
} else if (settingsMap[use_sx1268]) {
if (!rIf) {
LOG_DEBUG("Attempting to activate sx1268 radio on SPI port %s", settingsStrings[spidev].c_str());
LOG_DEBUG("Activate sx1268 radio on SPI port %s", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
rIf = new SX1268Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
LOG_ERROR("Failed to find SX1268 radio");
LOG_WARN("No SX1268 radio");
delete rIf;
rIf = NULL;
exit(EXIT_FAILURE);
} else {
LOG_INFO("SX1268 Radio init succeeded, using SX1268 radio");
LOG_INFO("SX1268 init success");
}
}
}
@ -998,11 +998,11 @@ void setup()
if (!rIf) {
rIf = new STM32WLE5JCInterface(RadioLibHAL, SX126X_CS, SX126X_DIO1, SX126X_RESET, SX126X_BUSY);
if (!rIf->init()) {
LOG_WARN("Failed to find STM32WL radio");
LOG_WARN("No STM32WL radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("STM32WL Radio init succeeded, using STM32WL radio");
LOG_INFO("STM32WL init success");
radioType = STM32WLx_RADIO;
}
}
@ -1012,11 +1012,11 @@ void setup()
if (!rIf) {
rIf = new SimRadio;
if (!rIf->init()) {
LOG_WARN("Failed to find simulated radio");
LOG_WARN("No simulated radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("Using SIMULATED radio!");
LOG_INFO("Use SIMULATED radio!");
radioType = SIM_RADIO;
}
}
@ -1026,11 +1026,11 @@ void setup()
if ((!rIf) && (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) {
rIf = new RF95Interface(RadioLibHAL, LORA_CS, RF95_IRQ, RF95_RESET, RF95_DIO1);
if (!rIf->init()) {
LOG_WARN("Failed to find RF95 radio");
LOG_WARN("No RF95 radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("RF95 Radio init succeeded, using RF95 radio");
LOG_INFO("RF95 init success");
radioType = RF95_RADIO;
}
}
@ -1040,11 +1040,11 @@ void setup()
if ((!rIf) && (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) {
rIf = new SX1262Interface(RadioLibHAL, SX126X_CS, SX126X_DIO1, SX126X_RESET, SX126X_BUSY);
if (!rIf->init()) {
LOG_WARN("Failed to find SX1262 radio");
LOG_WARN("No SX1262 radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("SX1262 Radio init succeeded, using SX1262 radio");
LOG_INFO("SX1262 init success");
radioType = SX1262_RADIO;
}
}
@ -1055,12 +1055,12 @@ void setup()
// Try using the specified TCXO voltage
rIf = new SX1262Interface(RadioLibHAL, SX126X_CS, SX126X_DIO1, SX126X_RESET, SX126X_BUSY);
if (!rIf->init()) {
LOG_WARN("Failed to find SX1262 radio with TCXO, Vref %f V", tcxoVoltage);
LOG_WARN("No SX1262 radio with TCXO, Vref %f V", tcxoVoltage);
delete rIf;
rIf = NULL;
tcxoVoltage = 0; // if it fails, set the TCXO voltage to zero for the next attempt
} else {
LOG_WARN("SX1262 Radio init succeeded, TCXO, Vref %f V", tcxoVoltage);
LOG_WARN("SX1262 init success, TCXO, Vref %f V", tcxoVoltage);
radioType = SX1262_RADIO;
}
}
@ -1069,12 +1069,12 @@ void setup()
// If specified TCXO voltage fails, attempt to use DIO3 as a reference instea
rIf = new SX1262Interface(RadioLibHAL, SX126X_CS, SX126X_DIO1, SX126X_RESET, SX126X_BUSY);
if (!rIf->init()) {
LOG_WARN("Failed to find SX1262 radio with XTAL, Vref %f V", tcxoVoltage);
LOG_WARN("No SX1262 radio with XTAL, Vref %f V", tcxoVoltage);
delete rIf;
rIf = NULL;
tcxoVoltage = SX126X_DIO3_TCXO_VOLTAGE; // if it fails, set the TCXO voltage back for the next radio search
} else {
LOG_INFO("SX1262 Radio init succeeded, XTAL, Vref %f V", tcxoVoltage);
LOG_INFO("SX1262 init success, XTAL, Vref %f V", tcxoVoltage);
radioType = SX1262_RADIO;
}
}
@ -1084,11 +1084,11 @@ void setup()
if ((!rIf) && (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) {
rIf = new SX1268Interface(RadioLibHAL, SX126X_CS, SX126X_DIO1, SX126X_RESET, SX126X_BUSY);
if (!rIf->init()) {
LOG_WARN("Failed to find SX1268 radio");
LOG_WARN("No SX1268 radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("SX1268 Radio init succeeded, using SX1268 radio");
LOG_INFO("SX1268 init success");
radioType = SX1268_RADIO;
}
}
@ -1098,11 +1098,11 @@ void setup()
if ((!rIf) && (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) {
rIf = new LLCC68Interface(RadioLibHAL, SX126X_CS, SX126X_DIO1, SX126X_RESET, SX126X_BUSY);
if (!rIf->init()) {
LOG_WARN("Failed to find LLCC68 radio");
LOG_WARN("No LLCC68 radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("LLCC68 Radio init succeeded, using LLCC68 radio");
LOG_INFO("LLCC68 init success");
radioType = LLCC68_RADIO;
}
}
@ -1112,11 +1112,11 @@ void setup()
if ((!rIf) && (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) {
rIf = new LR1110Interface(RadioLibHAL, LR1110_SPI_NSS_PIN, LR1110_IRQ_PIN, LR1110_NRESET_PIN, LR1110_BUSY_PIN);
if (!rIf->init()) {
LOG_WARN("Failed to find LR1110 radio");
LOG_WARN("No LR1110 radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("LR1110 Radio init succeeded, using LR1110 radio");
LOG_INFO("LR1110 init success");
radioType = LR1110_RADIO;
}
}
@ -1126,11 +1126,11 @@ void setup()
if (!rIf) {
rIf = new LR1120Interface(RadioLibHAL, LR1120_SPI_NSS_PIN, LR1120_IRQ_PIN, LR1120_NRESET_PIN, LR1120_BUSY_PIN);
if (!rIf->init()) {
LOG_WARN("Failed to find LR1120 radio");
LOG_WARN("No LR1120 radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("LR1120 Radio init succeeded, using LR1120 radio");
LOG_INFO("LR1120 init success");
radioType = LR1120_RADIO;
}
}
@ -1140,11 +1140,11 @@ void setup()
if (!rIf) {
rIf = new LR1121Interface(RadioLibHAL, LR1121_SPI_NSS_PIN, LR1121_IRQ_PIN, LR1121_NRESET_PIN, LR1121_BUSY_PIN);
if (!rIf->init()) {
LOG_WARN("Failed to find LR1121 radio");
LOG_WARN("No LR1121 radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("LR1121 Radio init succeeded, using LR1121 radio");
LOG_INFO("LR1121 init success");
radioType = LR1121_RADIO;
}
}
@ -1154,11 +1154,11 @@ void setup()
if (!rIf) {
rIf = new SX1280Interface(RadioLibHAL, SX128X_CS, SX128X_DIO1, SX128X_RESET, SX128X_BUSY);
if (!rIf->init()) {
LOG_WARN("Failed to find SX1280 radio");
LOG_WARN("No SX1280 radio");
delete rIf;
rIf = NULL;
} else {
LOG_INFO("SX1280 Radio init succeeded, using SX1280 radio");
LOG_INFO("SX1280 init success");
radioType = SX1280_RADIO;
}
}
@ -1166,7 +1166,7 @@ void setup()
// check if the radio chip matches the selected region
if ((config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_LORA_24) && (!rIf->wideLora())) {
LOG_WARN("Radio chip does not support 2.4GHz LoRa. Reverting to unset.");
LOG_WARN("LoRa chip does not support 2.4GHz. Revert to unset");
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET;
nodeDB->saveToDisk(SEGMENT_CONFIG);
if (!rIf->reconfigure()) {
@ -1268,6 +1268,7 @@ extern meshtastic_DeviceMetadata getDeviceMetadata()
deviceMetadata.position_flags = config.position.position_flags;
deviceMetadata.hw_model = HW_VENDOR;
deviceMetadata.hasRemoteHardware = moduleConfig.remote_hardware.enabled;
deviceMetadata.excluded_modules = meshtastic_ExcludedModules_EXCLUDED_NONE;
#if !(MESHTASTIC_EXCLUDE_PKI)
deviceMetadata.hasPKC = true;
#endif

View File

@ -190,7 +190,7 @@ CryptoKey Channels::getKey(ChannelIndex chIndex)
k.length = channelSettings.psk.size;
if (k.length == 0) {
if (ch.role == meshtastic_Channel_Role_SECONDARY) {
LOG_DEBUG("Unset PSK for secondary channel %s. using primary key", ch.settings.name);
LOG_DEBUG("Unset PSK for secondary channel %s. use primary key", ch.settings.name);
k = getKey(primaryIndex);
} else {
LOG_WARN("User disabled encryption");
@ -199,7 +199,7 @@ CryptoKey Channels::getKey(ChannelIndex chIndex)
// Convert the short single byte variants of psk into variant that can be used more generally
uint8_t pskIndex = k.bytes[0];
LOG_DEBUG("Expanding short PSK #%d", pskIndex);
LOG_DEBUG("Expand short PSK #%d", pskIndex);
if (pskIndex == 0)
k.length = 0; // Turn off encryption
else {
@ -384,11 +384,11 @@ bool Channels::hasDefaultChannel()
bool Channels::decryptForHash(ChannelIndex chIndex, ChannelHash channelHash)
{
if (chIndex > getNumChannels() || getHash(chIndex) != channelHash) {
// LOG_DEBUG("Skipping channel %d (hash %x) due to invalid hash/index, want=%x", chIndex, getHash(chIndex),
// LOG_DEBUG("Skip channel %d (hash %x) due to invalid hash/index, want=%x", chIndex, getHash(chIndex),
// channelHash);
return false;
} else {
LOG_DEBUG("Using channel %d (hash 0x%x)", chIndex, channelHash);
LOG_DEBUG("Use channel %d (hash 0x%x)", chIndex, channelHash);
setCrypto(chIndex);
return true;
}

View File

@ -18,7 +18,7 @@
*/
void CryptoEngine::generateKeyPair(uint8_t *pubKey, uint8_t *privKey)
{
LOG_DEBUG("Generating Curve25519 key pair...");
LOG_DEBUG("Generate Curve25519 keypair");
Curve25519::dh1(public_key, private_key);
memcpy(pubKey, public_key, sizeof(public_key));
memcpy(privKey, private_key, sizeof(private_key));
@ -80,8 +80,8 @@ bool CryptoEngine::encryptCurve25519(uint32_t toNode, uint32_t fromNode, meshtas
initNonce(fromNode, packetNum, extraNonceTmp);
// Calculate the shared secret with the destination node and encrypt
printBytes("Attempting encrypt using nonce: ", nonce, 13);
printBytes("Attempting encrypt using shared_key starting with: ", shared_key, 8);
printBytes("Attempt encrypt with nonce: ", nonce, 13);
printBytes("Attempt encrypt with shared_key starting with: ", shared_key, 8);
aes_ccm_ae(shared_key, 32, nonce, 8, bytes, numBytes, nullptr, 0, bytesOut,
auth); // this can write up to 15 bytes longer than numbytes past bytesOut
memcpy((uint8_t *)(auth + 8), &extraNonceTmp,
@ -117,8 +117,8 @@ bool CryptoEngine::decryptCurve25519(uint32_t fromNode, meshtastic_UserLite_publ
crypto->hash(shared_key, 32);
initNonce(fromNode, packetNum, extraNonce);
printBytes("Attempting decrypt using nonce: ", nonce, 13);
printBytes("Attempting decrypt using shared_key starting with: ", shared_key, 8);
printBytes("Attempt decrypt with nonce: ", nonce, 13);
printBytes("Attempt decrypt with shared_key starting with: ", shared_key, 8);
return aes_ccm_ad(shared_key, 32, nonce, 8, bytes, numBytes - 12, nullptr, 0, auth, bytesOut);
}
@ -185,7 +185,7 @@ concurrency::Lock *cryptLock;
void CryptoEngine::setKey(const CryptoKey &k)
{
LOG_DEBUG("Using AES%d key!", k.length * 8);
LOG_DEBUG("Use AES%d key!", k.length * 8);
key = k;
}
@ -249,4 +249,4 @@ void CryptoEngine::initNonce(uint32_t fromNode, uint64_t packetId, uint32_t extr
}
#ifndef HAS_CUSTOM_CRYPTO_ENGINE
CryptoEngine *crypto = new CryptoEngine;
#endif
#endif

View File

@ -21,7 +21,7 @@ ErrorCode FloodingRouter::send(meshtastic_MeshPacket *p)
bool FloodingRouter::shouldFilterReceived(const meshtastic_MeshPacket *p)
{
if (wasSeenRecently(p)) { // Note: this will also add a recent packet record
printPacket("Ignoring dupe incoming msg", p);
printPacket("Ignore dupe incoming msg", p);
rxDupe++;
if (config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER &&
config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) {
@ -46,7 +46,7 @@ void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas
bool isAckorReply = (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) && (p->decoded.request_id != 0);
if (isAckorReply && !isToUs(p) && !isBroadcast(p->to)) {
// do not flood direct message that is ACKed or replied to
LOG_DEBUG("Rxd an ACK/reply not for me, cancel rebroadcast.");
LOG_DEBUG("Rxd an ACK/reply not for me, cancel rebroadcast");
Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM
}
if (!isToUs(p) && (p->hop_limit > 0) && !isFromUs(p)) {
@ -63,17 +63,17 @@ void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas
}
#endif
LOG_INFO("Rebroadcasting received floodmsg");
LOG_INFO("Rebroadcast received floodmsg");
// Note: we are careful to resend using the original senders node id
// We are careful not to call our hooked version of send() - because we don't want to check this again
Router::send(tosend);
} else {
LOG_DEBUG("Not rebroadcasting: Role = CLIENT_MUTE or Rebroadcast Mode = NONE");
LOG_DEBUG("No rebroadcast: Role = CLIENT_MUTE or Rebroadcast Mode = NONE");
}
} else {
LOG_DEBUG("Ignoring 0 id broadcast");
LOG_DEBUG("Ignore 0 id broadcast");
}
}
// handle the packet as normal
Router::sniffReceived(p, c);
}
}

View File

@ -77,13 +77,13 @@ template <typename T> bool LR11x0Interface<T>::init()
#ifdef LR11X0_RF_SWITCH_SUBGHZ
pinMode(LR11X0_RF_SWITCH_SUBGHZ, OUTPUT);
digitalWrite(LR11X0_RF_SWITCH_SUBGHZ, getFreq() < 1e9 ? HIGH : LOW);
LOG_DEBUG("Setting RF0 switch to %s", getFreq() < 1e9 ? "SubGHz" : "2.4GHz");
LOG_DEBUG("Set RF0 switch to %s", getFreq() < 1e9 ? "SubGHz" : "2.4GHz");
#endif
#ifdef LR11X0_RF_SWITCH_2_4GHZ
pinMode(LR11X0_RF_SWITCH_2_4GHZ, OUTPUT);
digitalWrite(LR11X0_RF_SWITCH_2_4GHZ, getFreq() < 1e9 ? LOW : HIGH);
LOG_DEBUG("Setting RF1 switch to %s", getFreq() < 1e9 ? "SubGHz" : "2.4GHz");
LOG_DEBUG("Set RF1 switch to %s", getFreq() < 1e9 ? "SubGHz" : "2.4GHz");
#endif
int res = lora.begin(getFreq(), bw, sf, cr, syncWord, power, preambleLength, tcxoVoltage);
@ -122,7 +122,7 @@ template <typename T> bool LR11x0Interface<T>::init()
if (dioAsRfSwitch) {
lora.setRfSwitchTable(rfswitch_dio_pins, rfswitch_table);
LOG_DEBUG("Setting DIO RF switch", res);
LOG_DEBUG("Set DIO RF switch", res);
}
if (res == RADIOLIB_ERR_NONE) {

View File

@ -151,7 +151,7 @@ void MeshModule::callModules(meshtastic_MeshPacket &mp, RxSource src)
// If the requester didn't ask for a response we might need to discard unused replies to prevent memory leaks
if (pi.myReply) {
LOG_DEBUG("Discarding an unneeded response");
LOG_DEBUG("Discard an unneeded response");
packetPool.release(pi.myReply);
pi.myReply = NULL;
}
@ -168,7 +168,7 @@ void MeshModule::callModules(meshtastic_MeshPacket &mp, RxSource src)
if (isDecoded && mp.decoded.want_response && toUs) {
if (currentReply) {
printPacket("Sending response", currentReply);
printPacket("Send response", currentReply);
service->sendToMesh(currentReply);
currentReply = NULL;
} else if (mp.from != ourNodeNum && !ignoreRequest) {

View File

@ -40,7 +40,7 @@ struct UIFrameEvent {
enum Action {
REDRAW_ONLY, // Don't change which frames are show, just redraw, asap
REGENERATE_FRAMESET, // Regenerate (change? add? remove?) screen frames, honoring requestFocus()
REGENERATE_FRAMESET_BACKGROUND, // Regenerate screen frames, attempting to remain on the same frame throughout
REGENERATE_FRAMESET_BACKGROUND, // Regenerate screen frames, Attempt to remain on the same frame throughout
} action = REDRAW_ONLY;
// We might want to pass additional data inside this struct at some point

View File

@ -13,6 +13,7 @@
#include "TypeConversions.h"
#include "main.h"
#include "mesh-pb-constants.h"
#include "meshUtils.h"
#include "modules/NodeInfoModule.h"
#include "modules/PositionModule.h"
#include "power.h"
@ -78,17 +79,19 @@ int MeshService::handleFromRadio(const meshtastic_MeshPacket *mp)
powerFSM.trigger(EVENT_PACKET_FOR_PHONE); // Possibly keep the node from sleeping
nodeDB->updateFrom(*mp); // update our DB state based off sniffing every RX packet from the radio
bool isPreferredRebroadcaster =
IS_ONE_OF(config.device.role, meshtastic_Config_DeviceConfig_Role_ROUTER, meshtastic_Config_DeviceConfig_Role_REPEATER);
if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag &&
mp->decoded.portnum == meshtastic_PortNum_TELEMETRY_APP && mp->decoded.request_id > 0) {
LOG_DEBUG("Received telemetry response. Skip sending our NodeInfo."); // because this potentially a Repeater which will
// ignore our request for its NodeInfo
LOG_DEBUG("Received telemetry response. Skip sending our NodeInfo"); // because this potentially a Repeater which will
// ignore our request for its NodeInfo
} else if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag && !nodeDB->getMeshNode(mp->from)->has_user &&
nodeInfoModule) {
LOG_INFO("Heard new node on channel %d, sending NodeInfo and asking for a response.", mp->channel);
nodeInfoModule && !isPreferredRebroadcaster && !nodeDB->isFull()) {
if (airTime->isTxAllowedChannelUtil(true)) {
LOG_INFO("Heard new node on ch. %d, send NodeInfo and ask for response", mp->channel);
nodeInfoModule->sendOurNodeInfo(mp->from, true, mp->channel);
} else {
LOG_DEBUG("Skip sending NodeInfo due to > 25 percent channel util.");
LOG_DEBUG("Skip sending NodeInfo > 25%% ch. util");
}
}
@ -164,7 +167,7 @@ NodeNum MeshService::getNodenumFromRequestId(uint32_t request_id)
void MeshService::handleToRadio(meshtastic_MeshPacket &p)
{
#if defined(ARCH_PORTDUINO) && !HAS_RADIO
// Simulates device is receiving a packet via the LoRa chip
// Simulates device received a packet via the LoRa chip
if (p.decoded.portnum == meshtastic_PortNum_SIMULATOR_APP) {
// Simulator packet (=Compressed packet) is encapsulated in a MeshPacket, so need to unwrap first
meshtastic_Compressed scratch;
@ -180,7 +183,7 @@ void MeshService::handleToRadio(meshtastic_MeshPacket &p)
// Switch the port from PortNum_SIMULATOR_APP back to the original PortNum
p.decoded.portnum = decoded->portnum;
} else
LOG_ERROR("Error decoding protobuf for simulator message!");
LOG_ERROR("Error decoding proto for simulator message!");
}
// Let SimRadio receive as if it did via its LoRa chip
SimRadio::instance->startReceive(&p);
@ -222,7 +225,7 @@ ErrorCode MeshService::sendQueueStatusToPhone(const meshtastic_QueueStatus &qs,
copied->mesh_packet_id = mesh_packet_id;
if (toPhoneQueueStatusQueue.numFree() == 0) {
LOG_INFO("tophone queue status queue is full, discarding oldest");
LOG_INFO("tophone queue status queue is full, discard oldest");
meshtastic_QueueStatus *d = toPhoneQueueStatusQueue.dequeuePtr(0);
if (d)
releaseQueueStatusToPool(d);
@ -252,9 +255,14 @@ void MeshService::sendToMesh(meshtastic_MeshPacket *p, RxSource src, bool ccToPh
LOG_DEBUG("Can't send status to phone");
}
if (res == ERRNO_OK && ccToPhone) { // Check if p is not released in case it couldn't be sent
if ((res == ERRNO_OK || res == ERRNO_SHOULD_RELEASE) && ccToPhone) { // Check if p is not released in case it couldn't be sent
sendToPhone(packetPool.allocCopy(*p));
}
// Router may ask us to release the packet if it wasn't sent
if (res == ERRNO_SHOULD_RELEASE) {
releaseToPool(p);
}
}
bool MeshService::trySendPosition(NodeNum dest, bool wantReplies)
@ -266,14 +274,14 @@ bool MeshService::trySendPosition(NodeNum dest, bool wantReplies)
if (hasValidPosition(node)) {
#if HAS_GPS && !MESHTASTIC_EXCLUDE_GPS
if (positionModule) {
LOG_INFO("Sending position ping to 0x%x, wantReplies=%d, channel=%d", dest, wantReplies, node->channel);
LOG_INFO("Send position ping to 0x%x, wantReplies=%d, channel=%d", dest, wantReplies, node->channel);
positionModule->sendOurPosition(dest, wantReplies, node->channel);
return true;
}
} else {
#endif
if (nodeInfoModule) {
LOG_INFO("Sending nodeinfo ping to 0x%x, wantReplies=%d, channel=%d", dest, wantReplies, node->channel);
LOG_INFO("Send nodeinfo ping to 0x%x, wantReplies=%d, channel=%d", dest, wantReplies, node->channel);
nodeInfoModule->sendOurNodeInfo(dest, wantReplies, node->channel);
}
}
@ -298,12 +306,12 @@ void MeshService::sendToPhone(meshtastic_MeshPacket *p)
if (toPhoneQueue.numFree() == 0) {
if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP ||
p->decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP) {
LOG_WARN("ToPhone queue is full, discarding oldest");
LOG_WARN("ToPhone queue is full, discard oldest");
meshtastic_MeshPacket *d = toPhoneQueue.dequeuePtr(0);
if (d)
releaseToPool(d);
} else {
LOG_WARN("ToPhone queue is full, dropping packet.");
LOG_WARN("ToPhone queue is full, drop packet");
releaseToPool(p);
fromNum++; // Make sure to notify observers in case they are reconnected so they can get the packets
return;
@ -316,9 +324,9 @@ void MeshService::sendToPhone(meshtastic_MeshPacket *p)
void MeshService::sendMqttMessageToClientProxy(meshtastic_MqttClientProxyMessage *m)
{
LOG_DEBUG("Sending mqtt message on topic '%s' to client for proxy", m->topic);
LOG_DEBUG("Send mqtt message on topic '%s' to client for proxy", m->topic);
if (toPhoneMqttProxyQueue.numFree() == 0) {
LOG_WARN("MqttClientProxyMessagePool queue is full, discarding oldest");
LOG_WARN("MqttClientProxyMessagePool queue is full, discard oldest");
meshtastic_MqttClientProxyMessage *d = toPhoneMqttProxyQueue.dequeuePtr(0);
if (d)
releaseMqttClientProxyMessageToPool(d);
@ -330,9 +338,9 @@ void MeshService::sendMqttMessageToClientProxy(meshtastic_MqttClientProxyMessage
void MeshService::sendClientNotification(meshtastic_ClientNotification *n)
{
LOG_DEBUG("Sending client notification to phone");
LOG_DEBUG("Send client notification to phone");
if (toPhoneClientNotificationQueue.numFree() == 0) {
LOG_WARN("ClientNotification queue is full, discarding oldest");
LOG_WARN("ClientNotification queue is full, discard oldest");
meshtastic_ClientNotification *d = toPhoneClientNotificationQueue.dequeuePtr(0);
if (d)
releaseClientNotificationToPool(d);
@ -380,13 +388,13 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
pos = gps->p;
} else {
// The GPS has lost lock
#ifdef GPS_EXTRAVERBOSE
#ifdef GPS_DEBUG
LOG_DEBUG("onGPSchanged() - lost validLocation");
#endif
}
// Used fixed position if configured regardless of GPS lock
if (config.position.fixed_position) {
LOG_WARN("Using fixed position");
LOG_WARN("Use fixed position");
pos = TypeConversions::ConvertToPosition(node->position);
}
@ -418,4 +426,4 @@ uint32_t MeshService::GetTimeSinceMeshPacket(const meshtastic_MeshPacket *mp)
delta = 0;
return delta;
}
}

View File

@ -16,6 +16,7 @@ typedef uint32_t PacketId; // A packet sequence number
#define ERRNO_NO_INTERFACES 33
#define ERRNO_UNKNOWN 32 // pick something that doesn't conflict with RH_ROUTER_ERROR_UNABLE_TO_DELIVER
#define ERRNO_DISABLED 34 // the interface is disabled
#define ERRNO_SHOULD_RELEASE 35 // no error, but the packet should still be released
#define ID_COUNTER_MASK (UINT32_MAX >> 22) // mask to select the counter portion of the ID
/*

View File

@ -106,7 +106,7 @@ static uint8_t ourMacAddr[6];
NodeDB::NodeDB()
{
LOG_INFO("Initializing NodeDB");
LOG_INFO("Init NodeDB");
loadFromDisk();
cleanupMeshDB();
@ -183,7 +183,7 @@ NodeDB::NodeDB()
keygenSuccess = true;
}
} else {
LOG_INFO("Generating new PKI keys");
LOG_INFO("Generate new PKI keys");
crypto->generateKeyPair(config.security.public_key.bytes, config.security.private_key.bytes);
keygenSuccess = true;
}
@ -220,7 +220,7 @@ NodeDB::NodeDB()
// If we are setup to broadcast on the default channel, ensure that the telemetry intervals are coerced to the minimum value
// of 30 minutes or more
if (channels.isDefaultChannel(channels.getPrimaryIndex())) {
LOG_DEBUG("Coercing telemetry to min of 30 minutes on defaults");
LOG_DEBUG("Coerce telemetry to min of 30 minutes on defaults");
moduleConfig.telemetry.device_update_interval = Default::getConfiguredOrMinimumValue(
moduleConfig.telemetry.device_update_interval, min_default_telemetry_interval_secs);
moduleConfig.telemetry.environment_update_interval = Default::getConfiguredOrMinimumValue(
@ -284,7 +284,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
}
if (channelFile.channels_count != MAX_NUM_CHANNELS) {
LOG_INFO("Setting default channel and radio preferences!");
LOG_INFO("Set default channel and radio preferences!");
channels.initDefaults();
}
@ -295,7 +295,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
initRegion();
if (didFactoryReset) {
LOG_INFO("Rebooting due to factory reset");
LOG_INFO("Reboot due to factory reset");
screen->startAlert("Rebooting...");
rebootAtMsec = millis() + (5 * 1000);
}
@ -312,7 +312,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
bool NodeDB::factoryReset(bool eraseBleBonds)
{
LOG_INFO("Performing factory reset!");
LOG_INFO("Perform factory reset!");
// first, remove the "/prefs" (this removes most prefs)
rmDir("/prefs");
#ifdef FSCom
@ -328,14 +328,14 @@ bool NodeDB::factoryReset(bool eraseBleBonds)
// third, write everything to disk
saveToDisk();
if (eraseBleBonds) {
LOG_INFO("Erasing BLE bonds");
LOG_INFO("Erase BLE bonds");
#ifdef ARCH_ESP32
// This will erase what's in NVS including ssl keys, persistent variables and ble pairing
nvs_flash_erase();
#endif
#ifdef ARCH_NRF52
Bluefruit.begin();
LOG_INFO("Clearing bluetooth bonds!");
LOG_INFO("Clear bluetooth bonds!");
bond_print_list(BLE_GAP_ROLE_PERIPH);
bond_print_list(BLE_GAP_ROLE_CENTRAL);
Bluefruit.Periph.clearBonds();
@ -352,7 +352,7 @@ void NodeDB::installDefaultConfig(bool preserveKey = false)
if (shouldPreserveKey) {
memcpy(private_key_temp, config.security.private_key.bytes, config.security.private_key.size);
}
LOG_INFO("Installing default LocalConfig");
LOG_INFO("Install default LocalConfig");
memset(&config, 0, sizeof(meshtastic_LocalConfig));
config.version = DEVICESTATE_CUR_VER;
config.has_device = true;
@ -490,7 +490,7 @@ void NodeDB::initConfigIntervals()
void NodeDB::installDefaultModuleConfig()
{
LOG_INFO("Installing default ModuleConfig");
LOG_INFO("Install default ModuleConfig");
memset(&moduleConfig, 0, sizeof(meshtastic_ModuleConfig));
moduleConfig.version = DEVICESTATE_CUR_VER;
@ -625,7 +625,7 @@ void NodeDB::initModuleConfigIntervals()
void NodeDB::installDefaultChannels()
{
LOG_INFO("Installing default ChannelFile");
LOG_INFO("Install default ChannelFile");
memset(&channelFile, 0, sizeof(meshtastic_ChannelFile));
channelFile.version = DEVICESTATE_CUR_VER;
}
@ -655,7 +655,7 @@ void NodeDB::removeNodeByNum(NodeNum nodeNum)
numMeshNodes -= removed;
std::fill(devicestate.node_db_lite.begin() + numMeshNodes, devicestate.node_db_lite.begin() + numMeshNodes + 1,
meshtastic_NodeInfoLite());
LOG_DEBUG("NodeDB::removeNodeByNum purged %d entries. Saving changes...", removed);
LOG_DEBUG("NodeDB::removeNodeByNum purged %d entries. Save changes...", removed);
saveDeviceStateToDisk();
}
@ -692,7 +692,7 @@ void NodeDB::cleanupMeshDB()
void NodeDB::installDefaultDeviceState()
{
LOG_INFO("Installing default DeviceState");
LOG_INFO("Install default DeviceState");
// memset(&devicestate, 0, sizeof(meshtastic_DeviceState));
numMeshNodes = 0;
@ -750,7 +750,7 @@ void NodeDB::pickNewNodeNum()
nodeNum, found->user.macaddr[4], found->user.macaddr[5], ourMacAddr[4], ourMacAddr[5], candidate);
nodeNum = candidate;
}
LOG_DEBUG("Using nodenum 0x%x ", nodeNum);
LOG_DEBUG("Use nodenum 0x%x ", nodeNum);
myNodeInfo.my_node_num = nodeNum;
}
@ -771,7 +771,7 @@ LoadFileResult NodeDB::loadProto(const char *filename, size_t protoSize, size_t
auto f = FSCom.open(filename, FILE_O_READ);
if (f) {
LOG_INFO("Loading %s", filename);
LOG_INFO("Load %s", filename);
pb_istream_t stream = {&readcb, &f, protoSize};
memset(dest_struct, 0, objSize);
@ -812,7 +812,7 @@ void NodeDB::loadFromDisk()
// installDefaultDeviceState(); // Our in RAM copy might now be corrupt
//} else {
if (devicestate.version < DEVICESTATE_MIN_VER) {
LOG_WARN("Devicestate %d is old, discarding", devicestate.version);
LOG_WARN("Devicestate %d is old, discard", devicestate.version);
installDefaultDeviceState();
} else {
LOG_INFO("Loaded saved devicestate version %d, with nodecount: %d", devicestate.version, devicestate.node_db_lite.size());
@ -827,7 +827,7 @@ void NodeDB::loadFromDisk()
installDefaultConfig(); // Our in RAM copy might now be corrupt
} else {
if (config.version < DEVICESTATE_MIN_VER) {
LOG_WARN("config %d is old, discarding", config.version);
LOG_WARN("config %d is old, discard", config.version);
installDefaultConfig(true);
} else {
LOG_INFO("Loaded saved config version %d", config.version);
@ -840,7 +840,7 @@ void NodeDB::loadFromDisk()
installDefaultModuleConfig(); // Our in RAM copy might now be corrupt
} else {
if (moduleConfig.version < DEVICESTATE_MIN_VER) {
LOG_WARN("moduleConfig %d is old, discarding", moduleConfig.version);
LOG_WARN("moduleConfig %d is old, discard", moduleConfig.version);
installDefaultModuleConfig();
} else {
LOG_INFO("Loaded saved moduleConfig version %d", moduleConfig.version);
@ -853,7 +853,7 @@ void NodeDB::loadFromDisk()
installDefaultChannels(); // Our in RAM copy might now be corrupt
} else {
if (channelFile.version < DEVICESTATE_MIN_VER) {
LOG_WARN("channelFile %d is old, discarding", channelFile.version);
LOG_WARN("channelFile %d is old, discard", channelFile.version);
installDefaultChannels();
} else {
LOG_INFO("Loaded saved channelFile version %d", channelFile.version);
@ -898,7 +898,7 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_
#ifdef FSCom
auto f = SafeFile(filename, fullAtomic);
LOG_INFO("Saving %s", filename);
LOG_INFO("Save %s", filename);
pb_ostream_t stream = {&writecb, static_cast<Print *>(&f), protoSize};
if (!pb_encode(&stream, fields, dest_struct)) {
@ -1141,7 +1141,7 @@ bool NodeDB::updateUser(uint32_t nodeId, meshtastic_User &p, uint8_t channelInde
// we copy the key into the incoming packet, to prevent overwrite
memcpy(p.public_key.bytes, info->user.public_key.bytes, 32);
} else {
LOG_INFO("Updating Node Pubkey!");
LOG_INFO("Update Node Pubkey!");
}
}
#endif
@ -1156,7 +1156,7 @@ bool NodeDB::updateUser(uint32_t nodeId, meshtastic_User &p, uint8_t channelInde
}
if (nodeId != getNodeNum())
info->channel = channelIndex; // Set channel we need to use to reach this node (but don't set our own channel)
LOG_DEBUG("updating changed=%d user %s/%s, channel=%d", changed, info->user.long_name, info->user.short_name, info->channel);
LOG_DEBUG("Update changed=%d user %s/%s, channel=%d", changed, info->user.long_name, info->user.short_name, info->channel);
info->has_user = true;
if (changed) {
@ -1221,13 +1221,19 @@ meshtastic_NodeInfoLite *NodeDB::getMeshNode(NodeNum n)
return NULL;
}
// returns true if the maximum number of nodes is reached or we are running low on memory
bool NodeDB::isFull()
{
return (numMeshNodes >= MAX_NUM_NODES) || (memGet.getFreeHeap() < MINIMUM_SAFE_FREE_HEAP);
}
/// Find a node in our DB, create an empty NodeInfo if missing
meshtastic_NodeInfoLite *NodeDB::getOrCreateMeshNode(NodeNum n)
{
meshtastic_NodeInfoLite *lite = getMeshNode(n);
if (!lite) {
if ((numMeshNodes >= MAX_NUM_NODES) || (memGet.getFreeHeap() < MINIMUM_SAFE_FREE_HEAP)) {
if (isFull()) {
if (screen)
screen->print("Warn: node database full!\nErasing oldest entry\n");
LOG_WARN("Node database full with %i nodes and %i bytes free! Erasing oldest entry", numMeshNodes,
@ -1280,9 +1286,9 @@ void recordCriticalError(meshtastic_CriticalErrorCode code, uint32_t address, co
if (screen)
screen->print(lcd.c_str());
if (filename) {
LOG_ERROR("NOTE! Recording critical error %d at %s:%lu", code, filename, address);
LOG_ERROR("NOTE! Record critical error %d at %s:%lu", code, filename, address);
} else {
LOG_ERROR("NOTE! Recording critical error %d, address=0x%lx", code, address);
LOG_ERROR("NOTE! Record critical error %d, address=0x%lx", code, address);
}
// Record error to DB

View File

@ -148,17 +148,20 @@ class NodeDB
meshtastic_NodeInfoLite *getMeshNode(NodeNum n);
size_t getNumMeshNodes() { return numMeshNodes; }
// returns true if the maximum number of nodes is reached or we are running low on memory
bool isFull();
void clearLocalPosition();
void setLocalPosition(meshtastic_Position position, bool timeOnly = false)
{
if (timeOnly) {
LOG_DEBUG("Setting local position time only: time=%u timestamp=%u", position.time, position.timestamp);
LOG_DEBUG("Set local position time only: time=%u timestamp=%u", position.time, position.timestamp);
localPosition.time = position.time;
localPosition.timestamp = position.timestamp > 0 ? position.timestamp : position.time;
return;
}
LOG_DEBUG("Setting local position: lat=%i lon=%i time=%u timestamp=%u", position.latitude_i, position.longitude_i,
LOG_DEBUG("Set local position: lat=%i lon=%i time=%u timestamp=%u", position.latitude_i, position.longitude_i,
position.time, position.timestamp);
localPosition = position;
}

View File

@ -19,7 +19,7 @@ PacketHistory::PacketHistory()
bool PacketHistory::wasSeenRecently(const meshtastic_MeshPacket *p, bool withUpdate)
{
if (p->id == 0) {
LOG_DEBUG("Ignoring message with zero id");
LOG_DEBUG("Ignore message with zero id");
return false; // Not a floodable message ID, so we don't care
}

View File

@ -57,14 +57,14 @@ void PhoneAPI::handleStartConfig()
filesManifest = getFiles("/", 10);
LOG_DEBUG("Got %d files in manifest", filesManifest.size());
LOG_INFO("Starting API client config");
LOG_INFO("Start API client config");
nodeInfoForPhone.num = 0; // Don't keep returning old nodeinfos
resetReadIndex();
}
void PhoneAPI::close()
{
LOG_INFO("PhoneAPI::close()");
LOG_DEBUG("PhoneAPI::close()");
if (state != STATE_SEND_NOTHING) {
state = STATE_SEND_NOTHING;
@ -122,7 +122,7 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength)
handleStartConfig();
break;
case meshtastic_ToRadio_disconnect_tag:
LOG_INFO("Disconnecting from phone");
LOG_INFO("Disconnect from phone");
close();
break;
case meshtastic_ToRadio_xmodemPacket_tag:
@ -133,7 +133,7 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength)
break;
#if !MESHTASTIC_EXCLUDE_MQTT
case meshtastic_ToRadio_mqttClientProxyMessage_tag:
LOG_INFO("Got MqttClientProxy message");
LOG_DEBUG("Got MqttClientProxy message");
if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled && moduleConfig.mqtt.enabled &&
(channels.anyMqttEnabled() || moduleConfig.mqtt.map_reporting_enabled)) {
mqtt->onClientProxyReceive(toRadioScratch.mqttClientProxyMessage);
@ -148,11 +148,10 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength)
break;
default:
// Ignore nop messages
// LOG_DEBUG("Error: unexpected ToRadio variant");
break;
}
} else {
LOG_ERROR("Error: ignoring malformed toradio");
LOG_ERROR("Error: ignore malformed toradio");
}
return false;
@ -180,7 +179,6 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength)
size_t PhoneAPI::getFromRadio(uint8_t *buf)
{
if (!available()) {
// LOG_DEBUG("getFromRadio=not available");
return 0;
}
// In case we send a FromRadio packet
@ -189,13 +187,14 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// Advance states as needed
switch (state) {
case STATE_SEND_NOTHING:
LOG_INFO("getFromRadio=STATE_SEND_NOTHING");
LOG_DEBUG("FromRadio=STATE_SEND_NOTHING");
break;
case STATE_SEND_MY_INFO:
LOG_INFO("getFromRadio=STATE_SEND_MY_INFO");
LOG_DEBUG("FromRadio=STATE_SEND_MY_INFO");
// If the user has specified they don't want our node to share its location, make sure to tell the phone
// app not to send locations on our behalf.
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_my_info_tag;
strncpy(myNodeInfo.pio_env, optstr(APP_ENV), sizeof(myNodeInfo.pio_env));
fromRadioScratch.my_info = myNodeInfo;
state = STATE_SEND_UIDATA;
@ -210,7 +209,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
break;
case STATE_SEND_OWN_NODEINFO: {
LOG_INFO("getFromRadio=STATE_SEND_OWN_NODEINFO");
LOG_DEBUG("Send My NodeInfo");
auto us = nodeDB->readNextMeshNode(readIndex);
if (us) {
nodeInfoForPhone = TypeConversions::ConvertToNodeInfo(us);
@ -226,14 +225,14 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
}
case STATE_SEND_METADATA:
LOG_INFO("getFromRadio=STATE_SEND_METADATA");
LOG_DEBUG("Send Metadata");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_metadata_tag;
fromRadioScratch.metadata = getDeviceMetadata();
state = STATE_SEND_CHANNELS;
break;
case STATE_SEND_CHANNELS:
LOG_INFO("getFromRadio=STATE_SEND_CHANNELS");
LOG_DEBUG("Send Channels");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_channel_tag;
fromRadioScratch.channel = channels.getByIndex(config_state);
config_state++;
@ -245,7 +244,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
break;
case STATE_SEND_CONFIG:
LOG_INFO("getFromRadio=STATE_SEND_CONFIG");
LOG_DEBUG("Send Radio config");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_tag;
switch (config_state) {
case meshtastic_Config_device_tag:
@ -303,7 +302,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
break;
case STATE_SEND_MODULECONFIG:
LOG_INFO("getFromRadio=STATE_SEND_MODULECONFIG");
LOG_DEBUG("Send Module Config");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_moduleConfig_tag;
switch (config_state) {
case meshtastic_ModuleConfig_mqtt_tag:
@ -372,7 +371,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
break;
case STATE_SEND_OTHER_NODEINFOS: {
LOG_INFO("getFromRadio=STATE_SEND_OTHER_NODEINFOS");
LOG_DEBUG("Send known nodes");
if (nodeInfoForPhone.num != 0) {
LOG_INFO("nodeinfo: num=0x%x, lastseen=%u, id=%s, name=%s", nodeInfoForPhone.num, nodeInfoForPhone.last_heard,
nodeInfoForPhone.user.id, nodeInfoForPhone.user.long_name);
@ -381,7 +380,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// Stay in current state until done sending nodeinfos
nodeInfoForPhone.num = 0; // We just consumed a nodeinfo, will need a new one next time
} else {
LOG_INFO("Done sending nodeinfos");
LOG_DEBUG("Done sending nodeinfo");
state = STATE_SEND_FILEMANIFEST;
// Go ahead and send that ID right now
return getFromRadio(buf);
@ -390,7 +389,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
}
case STATE_SEND_FILEMANIFEST: {
LOG_INFO("getFromRadio=STATE_SEND_FILEMANIFEST");
LOG_DEBUG("FromRadio=STATE_SEND_FILEMANIFEST");
// last element
if (config_state == filesManifest.size()) { // also handles an empty filesManifest
config_state = 0;
@ -413,7 +412,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
case STATE_SEND_PACKETS:
pauseBluetoothLogging = false;
// Do we have a message from the mesh or packet from the local device?
LOG_INFO("getFromRadio=STATE_SEND_PACKETS");
LOG_DEBUG("FromRadio=STATE_SEND_PACKETS");
if (queueStatusPacketForPhone) {
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_queueStatus_tag;
fromRadioScratch.queueStatus = *queueStatusPacketForPhone;
@ -451,7 +450,6 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// VERY IMPORTANT to not print debug messages while writing to fromRadioScratch - because we use that same buffer
// for logging (when we are encapsulating with protobufs)
// LOG_DEBUG("encoding toPhone packet to phone variant=%d, %d bytes", fromRadioScratch.which_payload_variant, numbytes);
return numbytes;
}
@ -461,7 +459,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
void PhoneAPI::sendConfigComplete()
{
LOG_INFO("getFromRadio=STATE_SEND_COMPLETE_ID");
LOG_INFO("Config Send Complete");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_complete_id_tag;
fromRadioScratch.config_complete_id = config_nonce;
config_nonce = 0;
@ -562,7 +560,6 @@ bool PhoneAPI::available()
if (!packetForPhone)
packetForPhone = service->getForPhone();
hasPacket = !!packetForPhone;
// LOG_DEBUG("available hasPacket=%d", hasPacket);
return hasPacket;
}
default:
@ -610,21 +607,21 @@ bool PhoneAPI::handleToRadioPacket(meshtastic_MeshPacket &p)
// For use with the simulator, we should not ignore duplicate packets
#if !(defined(ARCH_PORTDUINO) && !HAS_RADIO)
if (p.id > 0 && wasSeenRecently(p.id)) {
LOG_DEBUG("Ignoring packet from phone, already seen recently");
LOG_DEBUG("Ignore packet from phone, already seen recently");
return false;
}
#endif
if (p.decoded.portnum == meshtastic_PortNum_TRACEROUTE_APP && lastPortNumToRadio[p.decoded.portnum] &&
Throttle::isWithinTimespanMs(lastPortNumToRadio[p.decoded.portnum], THIRTY_SECONDS_MS)) {
LOG_WARN("Rate limiting portnum %d", p.decoded.portnum);
LOG_WARN("Rate limit portnum %d", p.decoded.portnum);
sendNotification(meshtastic_LogRecord_Level_WARNING, p.id, "TraceRoute can only be sent once every 30 seconds");
meshtastic_QueueStatus qs = router->getQueueStatus();
service->sendQueueStatusToPhone(qs, 0, p.id);
return false;
} else if (p.decoded.portnum == meshtastic_PortNum_POSITION_APP && lastPortNumToRadio[p.decoded.portnum] &&
Throttle::isWithinTimespanMs(lastPortNumToRadio[p.decoded.portnum], FIVE_SECONDS_MS)) {
LOG_WARN("Rate limiting portnum %d", p.decoded.portnum);
LOG_WARN("Rate limit portnum %d", p.decoded.portnum);
meshtastic_QueueStatus qs = router->getQueueStatus();
service->sendQueueStatusToPhone(qs, 0, p.id);
// FIXME: Figure out why this continues to happen
@ -643,11 +640,11 @@ int PhoneAPI::onNotify(uint32_t newValue)
// doesn't call this from idle)
if (state == STATE_SEND_PACKETS) {
LOG_INFO("Telling client we have new packets %u", newValue);
LOG_INFO("Tell client we have new packets %u", newValue);
onNowHasData(newValue);
} else {
LOG_DEBUG("(Client not yet interested in packets)");
}
return timeout ? -1 : 0; // If we timed out, MeshService should stop iterating through observers as we just removed one
}
}

View File

@ -91,7 +91,7 @@ template <class T> class ProtobufModule : protected SinglePortModule
if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, fields, &scratch)) {
decoded = &scratch;
} else {
LOG_ERROR("Error decoding protobuf module!");
LOG_ERROR("Error decoding proto module!");
// if we can't decode it, nobody can process it!
return ProcessMessage::STOP;
}
@ -112,7 +112,7 @@ template <class T> class ProtobufModule : protected SinglePortModule
if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, fields, &scratch)) {
decoded = &scratch;
} else {
LOG_ERROR("Error decoding protobuf module!");
LOG_ERROR("Error decoding proto module!");
// if we can't decode it, nobody can process it!
return;
}

View File

@ -346,7 +346,7 @@ bool RadioInterface::reconfigure()
bool RadioInterface::init()
{
LOG_INFO("Starting meshradio init...");
LOG_INFO("Start meshradio init");
configChangedObserver.observe(&service->configChanged);
preflightSleepObserver.observe(&preflightSleep);
@ -494,7 +494,7 @@ void RadioInterface::applyModemConfig()
}
if ((myRegion->freqEnd - myRegion->freqStart) < bw / 1000) {
static const char *err_string = "Regional frequency range is smaller than bandwidth. Falling back to default preset.";
static const char *err_string = "Regional frequency range is smaller than bandwidth. Fall back to default preset";
LOG_ERROR(err_string);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
@ -578,7 +578,7 @@ void RadioInterface::limitPower()
maxPower = myRegion->powerLimit;
if ((power > maxPower) && !devicestate.owner.is_licensed) {
LOG_INFO("Lowering transmit power because of regulatory limits");
LOG_INFO("Lower transmit power because of regulatory limits");
power = maxPower;
}
@ -598,7 +598,7 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p)
{
assert(!sendingPacket);
// LOG_DEBUG("sending queued packet on mesh (txGood=%d,rxGood=%d,rxBad=%d)", rf95.txGood(), rf95.rxGood(), rf95.rxBad());
// LOG_DEBUG("Send queued packet on mesh (txGood=%d,rxGood=%d,rxBad=%d)", rf95.txGood(), rf95.rxGood(), rf95.rxBad());
assert(p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag); // It should have already been encoded by now
lastTxStart = millis();

View File

@ -143,12 +143,12 @@ bool RadioLibInterface::receiveDetected(uint16_t irq, ulong syncWordHeaderValidF
} else if (!Throttle::isWithinTimespanMs(activeReceiveStart, 2 * preambleTimeMsec) && !(irq & syncWordHeaderValidFlag)) {
// The HEADER_VALID flag should be set by now if it was really a packet, so ignore PREAMBLE_DETECTED flag
activeReceiveStart = 0;
LOG_DEBUG("Ignore false preamble detection.");
LOG_DEBUG("Ignore false preamble detection");
return false;
} else if (!Throttle::isWithinTimespanMs(activeReceiveStart, maxPacketTimeMsec)) {
// We should have gotten an RX_DONE IRQ by now if it was really a packet, so ignore HEADER_VALID flag
activeReceiveStart = 0;
LOG_DEBUG("Ignore false header detection.");
LOG_DEBUG("Ignore false header detection");
return false;
}
}
@ -171,7 +171,7 @@ ErrorCode RadioLibInterface::send(meshtastic_MeshPacket *p)
}
} else {
LOG_WARN("send - lora tx disabled because RegionCode_Unset");
LOG_WARN("send - lora tx disabled: Region unset");
packetPool.release(p);
return ERRNO_DISABLED;
}
@ -186,9 +186,14 @@ ErrorCode RadioLibInterface::send(meshtastic_MeshPacket *p)
#endif
if (p->to == NODENUM_BROADCAST_NO_LORA) {
LOG_DEBUG("Drop no-LoRa pkt");
return ERRNO_SHOULD_RELEASE;
}
// Sometimes when testing it is useful to be able to never turn on the xmitter
#ifndef LORA_DISABLE_SENDING
printPacket("enqueuing for send", p);
printPacket("enqueue for send", p);
LOG_DEBUG("txGood=%d,txRelay=%d,rxGood=%d,rxBad=%d", txGood, txRelay, rxGood, rxBad);
ErrorCode res = txQueue.enqueue(p) ? ERRNO_OK : ERRNO_UNKNOWN;
@ -200,7 +205,6 @@ ErrorCode RadioLibInterface::send(meshtastic_MeshPacket *p)
// set (random) transmit delay to let others reconfigure their radio,
// to avoid collisions and implement timing-based flooding
// LOG_DEBUG("Set random delay before transmitting.");
setTransmitDelay();
return res;
@ -225,7 +229,7 @@ bool RadioLibInterface::canSleep()
{
bool res = txQueue.empty();
if (!res) { // only print debug messages if we are vetoing sleep
LOG_DEBUG("radio wait to sleep, txEmpty=%d", res);
LOG_DEBUG("Radio wait to sleep, txEmpty=%d", res);
}
return res;
}
@ -255,37 +259,30 @@ void RadioLibInterface::onNotify(uint32_t notification)
case ISR_TX:
handleTransmitInterrupt();
startReceive();
// LOG_DEBUG("tx complete - starting timer");
startTransmitTimer();
break;
case ISR_RX:
handleReceiveInterrupt();
startReceive();
// LOG_DEBUG("rx complete - starting timer");
startTransmitTimer();
break;
case TRANSMIT_DELAY_COMPLETED:
// LOG_DEBUG("delay done");
// If we are not currently in receive mode, then restart the random delay (this can happen if the main thread
// has placed the unit into standby) FIXME, how will this work if the chipset is in sleep mode?
if (!txQueue.empty()) {
if (!canSendImmediately()) {
// LOG_DEBUG("Currently Rx/Tx-ing: set random delay");
setTransmitDelay(); // currently Rx/Tx-ing: reset random delay
} else {
if (isChannelActive()) { // check if there is currently a LoRa packet on the channel
// LOG_DEBUG("Channel is active, try receiving first.");
startReceive(); // try receiving this packet, afterwards we'll be trying to transmit again
startReceive(); // try receiving this packet, afterwards we'll be trying to transmit again
setTransmitDelay();
} else {
// Send any outgoing packets we have ready
meshtastic_MeshPacket *txp = txQueue.dequeue();
assert(txp);
bool isLoraTx = txp->to != NODENUM_BROADCAST_NO_LORA;
startSend(txp);
if (isLoraTx) {
bool sent = startSend(txp);
if (sent) {
// Packet has been sent, count it toward our TX airtime utilization.
uint32_t xmitMsec = getPacketTime(txp);
airTime->logAirtime(TX_LOG, xmitMsec);
@ -293,7 +290,6 @@ void RadioLibInterface::onNotify(uint32_t notification)
}
}
} else {
// LOG_DEBUG("done with txqueue");
}
break;
default:
@ -326,7 +322,6 @@ void RadioLibInterface::startTransmitTimer(bool withDelay)
// If we have work to do and the timer wasn't already scheduled, schedule it now
if (!txQueue.empty()) {
uint32_t delay = !withDelay ? 1 : getTxDelayMsec();
// LOG_DEBUG("xmit timer %d", delay);
notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
}
}
@ -336,14 +331,12 @@ void RadioLibInterface::startTransmitTimerSNR(float snr)
// If we have work to do and the timer wasn't already scheduled, schedule it now
if (!txQueue.empty()) {
uint32_t delay = getTxDelayMsecWeighted(snr);
// LOG_DEBUG("xmit timer %d", delay);
notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
}
}
void RadioLibInterface::handleTransmitInterrupt()
{
// LOG_DEBUG("handling lora TX interrupt");
// This can be null if we forced the device to enter standby mode. In that case
// ignore the transmit interrupt
if (sendingPacket)
@ -366,7 +359,6 @@ void RadioLibInterface::completeSending()
// We are done sending that packet, release it
packetPool.release(p);
// LOG_DEBUG("Done with send");
}
}
@ -377,7 +369,7 @@ void RadioLibInterface::handleReceiveInterrupt()
// when this is called, we should be in receive mode - if we are not, just jump out instead of bombing. Possible Race
// Condition?
if (!isReceiving) {
LOG_ERROR("handleReceiveInterrupt called when not in receive mode, which shouldn't happen.");
LOG_ERROR("handleReceiveInterrupt called when not in rx mode, which shouldn't happen");
return;
}
@ -390,7 +382,7 @@ void RadioLibInterface::handleReceiveInterrupt()
#ifndef DISABLE_WELCOME_UNSET
if (config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_UNSET) {
LOG_WARN("recv - lora rx disabled because RegionCode_Unset");
LOG_WARN("lora rx disabled: Region unset");
airTime->logAirtime(RX_ALL_LOG, xmitMsec);
return;
}
@ -403,7 +395,7 @@ void RadioLibInterface::handleReceiveInterrupt()
}
#endif
if (state != RADIOLIB_ERR_NONE) {
LOG_ERROR("ignoring received packet due to error=%d", state);
LOG_ERROR("Ignore received packet due to error=%d", state);
rxBad++;
airTime->logAirtime(RX_ALL_LOG, xmitMsec);
@ -414,14 +406,14 @@ void RadioLibInterface::handleReceiveInterrupt()
// check for short packets
if (payloadLen < 0) {
LOG_WARN("ignoring received packet too short");
LOG_WARN("Ignore received packet too short");
rxBad++;
airTime->logAirtime(RX_ALL_LOG, xmitMsec);
} else {
rxGood++;
// altered packet with "from == 0" can do Remote Node Administration without permission
if (radioBuffer.header.from == 0) {
LOG_WARN("ignoring received packet without sender");
LOG_WARN("Ignore received packet without sender");
return;
}
@ -476,15 +468,13 @@ void RadioLibInterface::setStandby()
}
/** start an immediate transmit */
void RadioLibInterface::startSend(meshtastic_MeshPacket *txp)
bool RadioLibInterface::startSend(meshtastic_MeshPacket *txp)
{
printPacket("Starting low level send", txp);
if (txp->to == NODENUM_BROADCAST_NO_LORA) {
LOG_DEBUG("Drop Tx packet because dest is broadcast no-lora");
packetPool.release(txp);
} else if (disabled || !config.lora.tx_enabled) {
printPacket("Start low level send", txp);
if (disabled || !config.lora.tx_enabled) {
LOG_WARN("Drop Tx packet because LoRa Tx disabled");
packetPool.release(txp);
return false;
} else {
configHardwareForSend(); // must be after setStandby
@ -504,5 +494,7 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp)
// Must be done AFTER, starting transmit, because startTransmit clears (possibly stale) interrupt pending register
// bits
enableInterrupt(isrTxLevel0);
return res == RADIOLIB_ERR_NONE;
}
}

View File

@ -162,8 +162,9 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
/** start an immediate transmit
* This method is virtual so subclasses can hook as needed, subclasses should not call directly
* @return true if packet was sent
*/
virtual void startSend(meshtastic_MeshPacket *txp);
virtual bool startSend(meshtastic_MeshPacket *txp);
meshtastic_QueueStatus getQueueStatus();

View File

@ -53,14 +53,14 @@ bool ReliableRouter::shouldFilterReceived(const meshtastic_MeshPacket *p)
auto key = GlobalPacketId(getFrom(p), p->id);
auto old = findPendingPacket(key);
if (old) {
LOG_DEBUG("generating implicit ack");
LOG_DEBUG("Generate implicit ack");
// NOTE: we do NOT check p->wantAck here because p is the INCOMING rebroadcast and that packet is not expected to be
// marked as wantAck
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, old->packet->channel);
stopRetransmission(key);
} else {
LOG_DEBUG("didn't find pending packet");
LOG_DEBUG("Didn't find pending packet");
}
}
@ -221,14 +221,14 @@ int32_t ReliableRouter::doRetransmissions()
// FIXME, handle 51 day rollover here!!!
if (p.nextTxMsec <= now) {
if (p.numRetransmissions == 0) {
LOG_DEBUG("Reliable send failed, returning a nak for fr=0x%x,to=0x%x,id=0x%x", p.packet->from, p.packet->to,
LOG_DEBUG("Reliable send failed, return a nak for fr=0x%x,to=0x%x,id=0x%x", p.packet->from, p.packet->to,
p.packet->id);
sendAckNak(meshtastic_Routing_Error_MAX_RETRANSMIT, getFrom(p.packet), p.packet->id, p.packet->channel);
// Note: we don't stop retransmission here, instead the Nak packet gets processed in sniffReceived
stopRetransmission(it->first);
stillValid = false; // just deleted it
} else {
LOG_DEBUG("Sending reliable retransmission fr=0x%x,to=0x%x,id=0x%x, tries left=%d", p.packet->from, p.packet->to,
LOG_DEBUG("Send reliable retransmission fr=0x%x,to=0x%x,id=0x%x, tries left=%d", p.packet->from, p.packet->to,
p.packet->id, p.numRetransmissions);
// Note: we call the superclass version because we don't want to have our version of send() add a new
@ -257,7 +257,7 @@ void ReliableRouter::setNextTx(PendingPacket *pending)
assert(iface);
auto d = iface->getRetransmissionMsec(pending->packet);
pending->nextTxMsec = millis() + d;
LOG_DEBUG("Setting next retransmission in %u msecs: ", d);
LOG_DEBUG("Set next retransmission in %u msecs: ", d);
printPacket("", pending->packet);
setReceivedMessage(); // Run ASAP, so we can figure out our correct sleep time
}

View File

@ -71,7 +71,7 @@ int32_t Router::runOnce()
perhapsHandleReceived(mp);
}
// LOG_DEBUG("sleeping forever!");
// LOG_DEBUG("Sleep forever!");
return INT32_MAX; // Wait a long time - until we get woken for the message queue
}
@ -143,7 +143,7 @@ void Router::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFro
void Router::abortSendAndNak(meshtastic_Routing_Error err, meshtastic_MeshPacket *p)
{
LOG_ERROR("Error=%d, returning NAK and dropping packet.", err);
LOG_ERROR("Error=%d, return NAK and drop packet", err);
sendAckNak(err, getFrom(p), p->id, p->channel);
packetPool.release(p);
}
@ -218,13 +218,13 @@ ErrorCode Router::send(meshtastic_MeshPacket *p)
if (hourlyTxPercent > myRegion->dutyCycle) {
#ifdef DEBUG_PORT
uint8_t silentMinutes = airTime->getSilentMinutes(hourlyTxPercent, myRegion->dutyCycle);
LOG_WARN("Duty cycle limit exceeded. Aborting send for now, you can send again in %d minutes.", silentMinutes);
LOG_WARN("Duty cycle limit exceeded. Aborting send for now, you can send again in %d mins", silentMinutes);
meshtastic_ClientNotification *cn = clientNotificationPool.allocZeroed();
cn->has_reply_id = true;
cn->reply_id = p->id;
cn->level = meshtastic_LogRecord_Level_WARNING;
cn->time = getValidTime(RTCQualityFromNet);
sprintf(cn->message, "Duty cycle limit exceeded. You can send again in %d minutes.", silentMinutes);
sprintf(cn->message, "Duty cycle limit exceeded. You can send again in %d mins", silentMinutes);
service->sendClientNotification(cn);
#endif
meshtastic_Routing_Error err = meshtastic_Routing_Error_DUTY_CYCLE_LIMIT;
@ -333,7 +333,7 @@ bool perhapsDecode(meshtastic_MeshPacket *p)
if (p->channel == 0 && isToUs(p) && p->to > 0 && !isBroadcast(p->to) && nodeDB->getMeshNode(p->from) != nullptr &&
nodeDB->getMeshNode(p->from)->user.public_key.size > 0 && nodeDB->getMeshNode(p->to)->user.public_key.size > 0 &&
rawSize > MESHTASTIC_PKC_OVERHEAD) {
LOG_DEBUG("Attempting PKI decryption");
LOG_DEBUG("Attempt PKI decryption");
if (crypto->decryptCurve25519(p->from, nodeDB->getMeshNode(p->from)->user.public_key, p->id, rawSize, ScratchEncrypted,
bytes)) {
@ -462,13 +462,13 @@ meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p)
// If the compressed length is greater than or equal to the original size, don't use the compressed form
if (compressed_len >= p->decoded.payload.size) {
LOG_DEBUG("Not using compressing message.");
LOG_DEBUG("Not using compressing message");
// Set the uncompressed payload variant anyway. Shouldn't hurt?
// p->decoded.which_payloadVariant = Data_payload_tag;
// Otherwise we use the compressor
} else {
LOG_DEBUG("Using compressed message.");
LOG_DEBUG("Use compressed message");
// Copy the compressed data into the meshpacket
p->decoded.payload.size = compressed_len;
@ -501,7 +501,7 @@ meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p)
// Some portnums either make no sense to send with PKC
p->decoded.portnum != meshtastic_PortNum_TRACEROUTE_APP && p->decoded.portnum != meshtastic_PortNum_NODEINFO_APP &&
p->decoded.portnum != meshtastic_PortNum_ROUTING_APP && p->decoded.portnum != meshtastic_PortNum_POSITION_APP) {
LOG_DEBUG("Using PKI!");
LOG_DEBUG("Use PKI!");
if (numbytes + MESHTASTIC_HEADER_LENGTH + MESHTASTIC_PKC_OVERHEAD > MAX_LORA_PAYLOAD_LEN)
return meshtastic_Routing_Error_TOO_LARGE;
if (p->pki_encrypted && !memfll(p->public_key.bytes, 0, 32) &&
@ -588,7 +588,7 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src)
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag &&
p->decoded.portnum == meshtastic_PortNum_NEIGHBORINFO_APP &&
(!moduleConfig.has_neighbor_info || !moduleConfig.neighbor_info.enabled)) {
LOG_DEBUG("Neighbor info module is disabled, ignoring neighbor packet");
LOG_DEBUG("Neighbor info module is disabled, ignore neighbor packet");
cancelSending(p->from, p->id);
skipHandle = true;
}
@ -603,7 +603,7 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src)
meshtastic_PortNum_PAXCOUNTER_APP, meshtastic_PortNum_IP_TUNNEL_APP, meshtastic_PortNum_AUDIO_APP,
meshtastic_PortNum_PRIVATE_APP, meshtastic_PortNum_DETECTION_SENSOR_APP, meshtastic_PortNum_RANGE_TEST_APP,
meshtastic_PortNum_REMOTE_HARDWARE_APP)) {
LOG_DEBUG("Ignoring packet on blacklisted portnum for CORE_PORTNUMS_ONLY");
LOG_DEBUG("Ignore packet on blacklisted portnum for CORE_PORTNUMS_ONLY");
cancelSending(p->from, p->id);
skipHandle = true;
}
@ -644,13 +644,13 @@ void Router::perhapsHandleReceived(meshtastic_MeshPacket *p)
#endif
// assert(radioConfig.has_preferences);
if (is_in_repeated(config.lora.ignore_incoming, p->from)) {
LOG_DEBUG("Ignoring msg, 0x%x is in our ignore list", p->from);
LOG_DEBUG("Ignore msg, 0x%x is in our ignore list", p->from);
packetPool.release(p);
return;
}
if (p->from == NODENUM_BROADCAST) {
LOG_DEBUG("Ignoring msg from broadcast address");
LOG_DEBUG("Ignore msg from broadcast address");
packetPool.release(p);
return;
}
@ -671,4 +671,4 @@ void Router::perhapsHandleReceived(meshtastic_MeshPacket *p)
// cache/learn of the existence of nodes (i.e. FloodRouter) that they should not
handleReceived(p);
packetPool.release(p);
}
}

View File

@ -123,7 +123,7 @@ template <typename T> bool SX126xInterface<T>::init()
// no effect
#if ARCH_PORTDUINO
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("Using MCU pin %i as RXEN and pin %i as TXEN to control RF switching", settingsMap[rxen], settingsMap[txen]);
LOG_DEBUG("Use MCU pin %i as RXEN and pin %i as TXEN to control RF switching", settingsMap[rxen], settingsMap[txen]);
lora.setRfSwitchPins(settingsMap[rxen], settingsMap[txen]);
}
#else
@ -136,7 +136,7 @@ template <typename T> bool SX126xInterface<T>::init()
LOG_DEBUG("SX126X_TXEN not defined, defaulting to RADIOLIB_NC");
#endif
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("Using MCU pin %i as RXEN and pin %i as TXEN to control RF switching", SX126X_RXEN, SX126X_TXEN);
LOG_DEBUG("Use MCU pin %i as RXEN and pin %i as TXEN to control RF switching", SX126X_RXEN, SX126X_TXEN);
lora.setRfSwitchPins(SX126X_RXEN, SX126X_TXEN);
}
#endif

View File

@ -80,7 +80,7 @@ template <typename T> bool SX128xInterface<T>::init()
#elif defined(ARCH_NRF52)
NVIC_SystemReset();
#else
LOG_ERROR("FIXME implement reboot for this platform. Skipping for now.");
LOG_ERROR("FIXME implement reboot for this platform. Skip for now.");
#endif
}

View File

@ -30,7 +30,7 @@ template <class T> int32_t ServerAPI<T>::runOnce()
if (client.connected()) {
return StreamAPI::runOncePart();
} else {
LOG_INFO("Client dropped connection, suspending API service");
LOG_INFO("Client dropped connection, suspend API service");
enabled = false; // we no longer need to run
return 0;
}
@ -63,11 +63,11 @@ template <class T, class U> int32_t APIServerPort<T, U>::runOnce()
// Reconnections are delayed by full wait time
if (waitTime < 400) {
waitTime *= 2;
LOG_INFO("Previous TCP connection still open, trying again in %dms", waitTime);
LOG_INFO("Previous TCP connection still open, try again in %dms", waitTime);
return waitTime;
}
#endif
LOG_INFO("Force closing previous TCP connection");
LOG_INFO("Force close previous TCP connection");
delete openAPI;
}

View File

@ -11,7 +11,7 @@ void initApiServer(int port)
// Start API server on port 4403
if (!apiPort) {
apiPort = new WiFiServerPort(port);
LOG_INFO("API server listening on TCP port %d", port);
LOG_INFO("API server listen on TCP port %d", port);
apiPort->init();
}
}

View File

@ -38,16 +38,16 @@ static int32_t reconnectETH()
Ethernet.maintain();
if (!ethStartupComplete) {
// Start web server
LOG_INFO("Starting Ethernet network services");
LOG_INFO("Start Ethernet network services");
#ifndef DISABLE_NTP
LOG_INFO("Starting NTP time client");
LOG_INFO("Start NTP time client");
timeClient.begin();
timeClient.setUpdateInterval(60 * 60); // Update once an hour
#endif
if (config.network.rsyslog_server[0]) {
LOG_INFO("Starting Syslog client");
LOG_INFO("Start Syslog client");
// Defaults
int serverPort = 514;
const char *serverAddr = config.network.rsyslog_server;
@ -82,9 +82,9 @@ static int32_t reconnectETH()
#ifndef DISABLE_NTP
if (isEthernetAvailable() && (ntp_renew < millis())) {
LOG_INFO("Updating NTP time from %s", config.network.ntp_server);
LOG_INFO("Update NTP time from %s", config.network.ntp_server);
if (timeClient.update()) {
LOG_DEBUG("NTP Request Success - Setting RTCQualityNTP if needed");
LOG_DEBUG("NTP Request Success - Set RTCQualityNTP if needed");
struct timeval tv;
tv.tv_sec = timeClient.getEpochTime();
@ -127,10 +127,10 @@ bool initEthernet()
mac[0] &= 0xfe; // Make sure this is not a multicast MAC
if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_DHCP) {
LOG_INFO("starting Ethernet DHCP");
LOG_INFO("Start Ethernet DHCP");
status = Ethernet.begin(mac);
} else if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_STATIC) {
LOG_INFO("starting Ethernet Static");
LOG_INFO("Start Ethernet Static");
Ethernet.begin(mac, config.network.ipv4_config.ip, config.network.ipv4_config.dns, config.network.ipv4_config.gateway,
config.network.ipv4_config.subnet);
status = 1;

View File

@ -97,6 +97,8 @@ PB_BIND(meshtastic_ChunkedPayloadResponse, meshtastic_ChunkedPayloadResponse, AU

View File

@ -270,6 +270,40 @@ typedef enum _meshtastic_CriticalErrorCode {
meshtastic_CriticalErrorCode_FLASH_CORRUPTION_UNRECOVERABLE = 13
} meshtastic_CriticalErrorCode;
/* Enum for modules excluded from a device's configuration.
Each value represents a ModuleConfigType that can be toggled as excluded
by setting its corresponding bit in the `excluded_modules` bitmask field. */
typedef enum _meshtastic_ExcludedModules {
/* Default value of 0 indicates no modules are excluded. */
meshtastic_ExcludedModules_EXCLUDED_NONE = 0,
/* MQTT module */
meshtastic_ExcludedModules_MQTT_CONFIG = 1,
/* Serial module */
meshtastic_ExcludedModules_SERIAL_CONFIG = 2,
/* External Notification module */
meshtastic_ExcludedModules_EXTNOTIF_CONFIG = 4,
/* Store and Forward module */
meshtastic_ExcludedModules_STOREFORWARD_CONFIG = 8,
/* Range Test module */
meshtastic_ExcludedModules_RANGETEST_CONFIG = 16,
/* Telemetry module */
meshtastic_ExcludedModules_TELEMETRY_CONFIG = 32,
/* Canned Message module */
meshtastic_ExcludedModules_CANNEDMSG_CONFIG = 64,
/* Audio module */
meshtastic_ExcludedModules_AUDIO_CONFIG = 128,
/* Remote Hardware module */
meshtastic_ExcludedModules_REMOTEHARDWARE_CONFIG = 256,
/* Neighbor Info module */
meshtastic_ExcludedModules_NEIGHBORINFO_CONFIG = 512,
/* Ambient Lighting module */
meshtastic_ExcludedModules_AMBIENTLIGHTING_CONFIG = 1024,
/* Detection Sensor module */
meshtastic_ExcludedModules_DETECTIONSENSOR_CONFIG = 2048,
/* Paxcounter module */
meshtastic_ExcludedModules_PAXCOUNTER_CONFIG = 4096
} meshtastic_ExcludedModules;
/* How the location was acquired: manual, onboard GPS, external (EUD) GPS */
typedef enum _meshtastic_Position_LocSource {
/* TODO: REPLACE */
@ -781,6 +815,8 @@ typedef struct _meshtastic_MyNodeInfo {
uint32_t min_app_version;
/* Unique hardware identifier for this device */
meshtastic_MyNodeInfo_device_id_t device_id;
/* The PlatformIO environment used to build this firmware */
char pio_env[40];
} meshtastic_MyNodeInfo;
/* Debug output from the device.
@ -894,6 +930,9 @@ typedef struct _meshtastic_DeviceMetadata {
bool hasRemoteHardware;
/* Has PKC capabilities */
bool hasPKC;
/* Bit field of boolean for excluded modules
(bitwise OR of ExcludedModules) */
uint32_t excluded_modules;
} meshtastic_DeviceMetadata;
/* Packets from the radio to the phone will appear on the fromRadio characteristic.
@ -1042,6 +1081,10 @@ extern "C" {
#define _meshtastic_CriticalErrorCode_MAX meshtastic_CriticalErrorCode_FLASH_CORRUPTION_UNRECOVERABLE
#define _meshtastic_CriticalErrorCode_ARRAYSIZE ((meshtastic_CriticalErrorCode)(meshtastic_CriticalErrorCode_FLASH_CORRUPTION_UNRECOVERABLE+1))
#define _meshtastic_ExcludedModules_MIN meshtastic_ExcludedModules_EXCLUDED_NONE
#define _meshtastic_ExcludedModules_MAX meshtastic_ExcludedModules_PAXCOUNTER_CONFIG
#define _meshtastic_ExcludedModules_ARRAYSIZE ((meshtastic_ExcludedModules)(meshtastic_ExcludedModules_PAXCOUNTER_CONFIG+1))
#define _meshtastic_Position_LocSource_MIN meshtastic_Position_LocSource_LOC_UNSET
#define _meshtastic_Position_LocSource_MAX meshtastic_Position_LocSource_LOC_EXTERNAL
#define _meshtastic_Position_LocSource_ARRAYSIZE ((meshtastic_Position_LocSource)(meshtastic_Position_LocSource_LOC_EXTERNAL+1))
@ -1115,7 +1158,7 @@ extern "C" {
#define meshtastic_MqttClientProxyMessage_init_default {"", 0, {{0, {0}}}, 0}
#define meshtastic_MeshPacket_init_default {0, 0, 0, 0, {meshtastic_Data_init_default}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0, 0, {0, {0}}, 0}
#define meshtastic_NodeInfo_init_default {0, false, meshtastic_User_init_default, false, meshtastic_Position_init_default, 0, 0, false, meshtastic_DeviceMetrics_init_default, 0, 0, false, 0, 0}
#define meshtastic_MyNodeInfo_init_default {0, 0, 0, {0, {0}}}
#define meshtastic_MyNodeInfo_init_default {0, 0, 0, {0, {0}}, ""}
#define meshtastic_LogRecord_init_default {"", 0, "", _meshtastic_LogRecord_Level_MIN}
#define meshtastic_QueueStatus_init_default {0, 0, 0, 0}
#define meshtastic_FromRadio_init_default {0, 0, {meshtastic_MeshPacket_init_default}}
@ -1125,7 +1168,7 @@ extern "C" {
#define meshtastic_Compressed_init_default {_meshtastic_PortNum_MIN, {0, {0}}}
#define meshtastic_NeighborInfo_init_default {0, 0, 0, 0, {meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default}}
#define meshtastic_Neighbor_init_default {0, 0, 0, 0}
#define meshtastic_DeviceMetadata_init_default {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0, 0}
#define meshtastic_DeviceMetadata_init_default {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0, 0, 0}
#define meshtastic_Heartbeat_init_default {0}
#define meshtastic_NodeRemoteHardwarePin_init_default {0, false, meshtastic_RemoteHardwarePin_init_default}
#define meshtastic_ChunkedPayload_init_default {0, 0, 0, {0, {0}}}
@ -1140,7 +1183,7 @@ extern "C" {
#define meshtastic_MqttClientProxyMessage_init_zero {"", 0, {{0, {0}}}, 0}
#define meshtastic_MeshPacket_init_zero {0, 0, 0, 0, {meshtastic_Data_init_zero}, 0, 0, 0, 0, 0, _meshtastic_MeshPacket_Priority_MIN, 0, _meshtastic_MeshPacket_Delayed_MIN, 0, 0, {0, {0}}, 0}
#define meshtastic_NodeInfo_init_zero {0, false, meshtastic_User_init_zero, false, meshtastic_Position_init_zero, 0, 0, false, meshtastic_DeviceMetrics_init_zero, 0, 0, false, 0, 0}
#define meshtastic_MyNodeInfo_init_zero {0, 0, 0, {0, {0}}}
#define meshtastic_MyNodeInfo_init_zero {0, 0, 0, {0, {0}}, ""}
#define meshtastic_LogRecord_init_zero {"", 0, "", _meshtastic_LogRecord_Level_MIN}
#define meshtastic_QueueStatus_init_zero {0, 0, 0, 0}
#define meshtastic_FromRadio_init_zero {0, 0, {meshtastic_MeshPacket_init_zero}}
@ -1150,7 +1193,7 @@ extern "C" {
#define meshtastic_Compressed_init_zero {_meshtastic_PortNum_MIN, {0, {0}}}
#define meshtastic_NeighborInfo_init_zero {0, 0, 0, 0, {meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero}}
#define meshtastic_Neighbor_init_zero {0, 0, 0, 0}
#define meshtastic_DeviceMetadata_init_zero {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0, 0}
#define meshtastic_DeviceMetadata_init_zero {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0, 0, 0}
#define meshtastic_Heartbeat_init_zero {0}
#define meshtastic_NodeRemoteHardwarePin_init_zero {0, false, meshtastic_RemoteHardwarePin_init_zero}
#define meshtastic_ChunkedPayload_init_zero {0, 0, 0, {0, {0}}}
@ -1248,6 +1291,7 @@ extern "C" {
#define meshtastic_MyNodeInfo_reboot_count_tag 8
#define meshtastic_MyNodeInfo_min_app_version_tag 11
#define meshtastic_MyNodeInfo_device_id_tag 12
#define meshtastic_MyNodeInfo_pio_env_tag 13
#define meshtastic_LogRecord_message_tag 1
#define meshtastic_LogRecord_time_tag 2
#define meshtastic_LogRecord_source_tag 3
@ -1283,6 +1327,7 @@ extern "C" {
#define meshtastic_DeviceMetadata_hw_model_tag 9
#define meshtastic_DeviceMetadata_hasRemoteHardware_tag 10
#define meshtastic_DeviceMetadata_hasPKC_tag 11
#define meshtastic_DeviceMetadata_excluded_modules_tag 12
#define meshtastic_FromRadio_id_tag 1
#define meshtastic_FromRadio_packet_tag 2
#define meshtastic_FromRadio_my_info_tag 3
@ -1451,7 +1496,8 @@ X(a, STATIC, SINGULAR, BOOL, is_favorite, 10)
X(a, STATIC, SINGULAR, UINT32, my_node_num, 1) \
X(a, STATIC, SINGULAR, UINT32, reboot_count, 8) \
X(a, STATIC, SINGULAR, UINT32, min_app_version, 11) \
X(a, STATIC, SINGULAR, BYTES, device_id, 12)
X(a, STATIC, SINGULAR, BYTES, device_id, 12) \
X(a, STATIC, SINGULAR, STRING, pio_env, 13)
#define meshtastic_MyNodeInfo_CALLBACK NULL
#define meshtastic_MyNodeInfo_DEFAULT NULL
@ -1568,7 +1614,8 @@ X(a, STATIC, SINGULAR, UENUM, role, 7) \
X(a, STATIC, SINGULAR, UINT32, position_flags, 8) \
X(a, STATIC, SINGULAR, UENUM, hw_model, 9) \
X(a, STATIC, SINGULAR, BOOL, hasRemoteHardware, 10) \
X(a, STATIC, SINGULAR, BOOL, hasPKC, 11)
X(a, STATIC, SINGULAR, BOOL, hasPKC, 11) \
X(a, STATIC, SINGULAR, UINT32, excluded_modules, 12)
#define meshtastic_DeviceMetadata_CALLBACK NULL
#define meshtastic_DeviceMetadata_DEFAULT NULL
@ -1667,14 +1714,14 @@ extern const pb_msgdesc_t meshtastic_ChunkedPayloadResponse_msg;
#define meshtastic_ClientNotification_size 415
#define meshtastic_Compressed_size 243
#define meshtastic_Data_size 273
#define meshtastic_DeviceMetadata_size 48
#define meshtastic_DeviceMetadata_size 54
#define meshtastic_FileInfo_size 236
#define meshtastic_FromRadio_size 510
#define meshtastic_Heartbeat_size 0
#define meshtastic_LogRecord_size 426
#define meshtastic_MeshPacket_size 367
#define meshtastic_MqttClientProxyMessage_size 501
#define meshtastic_MyNodeInfo_size 36
#define meshtastic_MyNodeInfo_size 77
#define meshtastic_NeighborInfo_size 258
#define meshtastic_Neighbor_size 22
#define meshtastic_NodeInfo_size 317

View File

@ -449,7 +449,7 @@ void handleStatic(HTTPRequest *req, HTTPResponse *res)
void handleFormUpload(HTTPRequest *req, HTTPResponse *res)
{
LOG_DEBUG("Form Upload - Disabling keep-alive");
LOG_DEBUG("Form Upload - Disable keep-alive");
res->setHeader("Connection", "close");
// First, we need to check the encoding of the form that we have received.
@ -508,14 +508,14 @@ void handleFormUpload(HTTPRequest *req, HTTPResponse *res)
// Double check that it is what we expect
if (name != "file") {
LOG_DEBUG("Skipping unexpected field");
LOG_DEBUG("Skip unexpected field");
res->println("<p>No file found.</p>");
return;
}
// Double check that it is what we expect
if (filename == "") {
LOG_DEBUG("Skipping unexpected field");
LOG_DEBUG("Skip unexpected field");
res->println("<p>No file found.</p>");
return;
}
@ -700,9 +700,9 @@ void handleDeleteFsContent(HTTPRequest *req, HTTPResponse *res)
res->setHeader("Access-Control-Allow-Methods", "GET");
res->println("<h1>Meshtastic</h1>");
res->println("Deleting Content in /static/*");
res->println("Delete Content in /static/*");
LOG_INFO("Deleting files from /static/* : ");
LOG_INFO("Delete files from /static/* : ");
htmlDeleteDir("/static");

View File

@ -69,13 +69,13 @@ static void taskCreateCert(void *parameter)
#if 0
// Delete the saved certs (used in debugging)
LOG_DEBUG("Deleting any saved SSL keys ...");
LOG_DEBUG("Delete any saved SSL keys");
// prefs.clear();
prefs.remove("PK");
prefs.remove("cert");
#endif
LOG_INFO("Checking if we have a previously saved SSL Certificate.");
LOG_INFO("Checking if we have a saved SSL Certificate");
size_t pkLen = prefs.getBytesLength("PK");
size_t certLen = prefs.getBytesLength("cert");
@ -139,7 +139,7 @@ void createSSLCert()
16, /* Priority of the task. */
NULL); /* Task handle. */
LOG_DEBUG("Waiting for SSL Cert to be generated.");
LOG_DEBUG("Waiting for SSL Cert to be generated");
while (!isCertReady) {
if ((millis() / 500) % 2) {
if (runLoop) {
@ -164,7 +164,7 @@ void createSSLCert()
WebServerThread *webServerThread;
WebServerThread::WebServerThread() : concurrency::OSThread("WebServerThread")
WebServerThread::WebServerThread() : concurrency::OSThread("WebServer")
{
if (!config.network.wifi_enabled) {
disable();
@ -189,7 +189,7 @@ int32_t WebServerThread::runOnce()
void initWebServer()
{
LOG_DEBUG("Initializing Web Server ...");
LOG_DEBUG("Init Web Server...");
// We can now use the new certificate to setup our server as usual.
secureServer = new HTTPSServer(cert);
@ -198,10 +198,10 @@ void initWebServer()
registerHandlers(insecureServer, secureServer);
if (secureServer) {
LOG_INFO("Starting Secure Web Server...");
LOG_INFO("Start Secure Web Server...");
secureServer->start();
}
LOG_INFO("Starting Insecure Web Server...");
LOG_INFO("Start Insecure Web Server...");
insecureServer->start();
if (insecureServer->isRunning()) {
LOG_INFO("Web Servers Ready! :-) ");
@ -210,4 +210,4 @@ void initWebServer()
LOG_ERROR("Web Servers Failed! ;-( ");
}
}
#endif
#endif

View File

@ -403,19 +403,19 @@ int PiWebServerThread::CreateSSLCertificate()
X509 *x509 = NULL;
if (generate_rsa_key(&pkey) != 0) {
LOG_ERROR("Error generating RSA-Key.");
LOG_ERROR("Error generating RSA-Key");
return 1;
}
if (generate_self_signed_x509(pkey, &x509) != 0) {
LOG_ERROR("Error generating of X509-Certificat.");
LOG_ERROR("Error generating X509-Cert");
return 2;
}
// Ope file to write private key file
FILE *pkey_file = fopen("private_key.pem", "wb");
if (!pkey_file) {
LOG_ERROR("Error opening private key file.");
LOG_ERROR("Error opening private key file");
return 3;
}
// write private key file
@ -425,7 +425,7 @@ int PiWebServerThread::CreateSSLCertificate()
// open Certificate file
FILE *x509_file = fopen("certificate.pem", "wb");
if (!x509_file) {
LOG_ERROR("Error opening certificate.");
LOG_ERROR("Error opening cert");
return 4;
}
// write cirtificate
@ -434,7 +434,7 @@ int PiWebServerThread::CreateSSLCertificate()
EVP_PKEY_free(pkey);
X509_free(x509);
LOG_INFO("Create SSL Certifictate -certificate.pem- succesfull ");
LOG_INFO("Create SSL Cert -certificate.pem- succesfull ");
return 0;
}
@ -453,9 +453,9 @@ PiWebServerThread::PiWebServerThread()
if (settingsMap[webserverport] != 0) {
webservport = settingsMap[webserverport];
LOG_INFO("Using webserver port from yaml config. %i ", webservport);
LOG_INFO("Use webserver port from yaml config %i ", webservport);
} else {
LOG_INFO("Webserver port in yaml config set to 0, so defaulting to port 443.");
LOG_INFO("Webserver port in yaml config set to 0, defaulting to port 443");
webservport = 443;
}
@ -464,7 +464,7 @@ PiWebServerThread::PiWebServerThread()
LOG_ERROR("Webserver couldn't be started, abort execution");
} else {
LOG_INFO("Webserver started ....");
LOG_INFO("Webserver started");
u_map_init(&configWeb.mime_types);
u_map_put(&configWeb.mime_types, "*", "application/octet-stream");
u_map_put(&configWeb.mime_types, ".html", "text/html");
@ -527,4 +527,4 @@ PiWebServerThread::~PiWebServerThread()
}
#endif
#endif
#endif

View File

@ -57,7 +57,7 @@ static void onNetworkConnected()
{
if (!APStartupComplete) {
// Start web server
LOG_INFO("Starting WiFi network services");
LOG_INFO("Start WiFi network services");
#ifdef ARCH_ESP32
// start mdns
@ -74,13 +74,13 @@ static void onNetworkConnected()
#endif
#ifndef DISABLE_NTP
LOG_INFO("Starting NTP time client");
LOG_INFO("Start NTP time client");
timeClient.begin();
timeClient.setUpdateInterval(60 * 60); // Update once an hour
#endif
if (config.network.rsyslog_server[0]) {
LOG_INFO("Starting Syslog client");
LOG_INFO("Start Syslog client");
// Defaults
int serverPort = 514;
const char *serverAddr = config.network.rsyslog_server;
@ -144,7 +144,7 @@ static int32_t reconnectWiFi()
#ifndef DISABLE_NTP
if (WiFi.isConnected() && (!Throttle::isWithinTimespanMs(lastrun_ntp, 43200000) || (lastrun_ntp == 0))) { // every 12 hours
LOG_DEBUG("Updating NTP time from %s", config.network.ntp_server);
LOG_DEBUG("Update NTP time from %s", config.network.ntp_server);
if (timeClient.update()) {
LOG_DEBUG("NTP Request Success - Setting RTCQualityNTP if needed");
@ -396,25 +396,25 @@ static void WiFiEvent(WiFiEvent_t event)
LOG_INFO("SmartConfig: Send ACK done");
break;
case ARDUINO_EVENT_PROV_INIT:
LOG_INFO("Provisioning: Init");
LOG_INFO("Provision Init");
break;
case ARDUINO_EVENT_PROV_DEINIT:
LOG_INFO("Provisioning: Stopped");
LOG_INFO("Provision Stopped");
break;
case ARDUINO_EVENT_PROV_START:
LOG_INFO("Provisioning: Started");
LOG_INFO("Provision Started");
break;
case ARDUINO_EVENT_PROV_END:
LOG_INFO("Provisioning: End");
LOG_INFO("Provision End");
break;
case ARDUINO_EVENT_PROV_CRED_RECV:
LOG_INFO("Provisioning: Credentials received");
LOG_INFO("Provision Credentials received");
break;
case ARDUINO_EVENT_PROV_CRED_FAIL:
LOG_INFO("Provisioning: Credentials failed");
LOG_INFO("Provision Credentials failed");
break;
case ARDUINO_EVENT_PROV_CRED_SUCCESS:
LOG_INFO("Provisioning: Credentials success");
LOG_INFO("Provision Credentials success");
break;
default:
break;

View File

@ -74,15 +74,15 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
// Could tighten this up further by tracking the last public_key we went an AdminMessage request to
// and only allowing responses from that remote.
if (messageIsResponse(r)) {
LOG_DEBUG("Allowing admin response message");
LOG_DEBUG("Allow admin response message");
} else if (mp.from == 0) {
if (config.security.is_managed) {
LOG_INFO("Ignoring local admin payload because is_managed.");
LOG_INFO("Ignore local admin payload because is_managed");
return handled;
}
} else if (strcasecmp(ch->settings.name, Channels::adminChannel) == 0) {
if (!config.security.admin_channel_enabled) {
LOG_INFO("Ignoring admin channel, as legacy admin is disabled.");
LOG_INFO("Ignore admin channel, legacy admin is disabled");
myReply = allocErrorResponse(meshtastic_Routing_Error_NOT_AUTHORIZED, &mp);
return handled;
}
@ -93,19 +93,19 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
memcmp(mp.public_key.bytes, config.security.admin_key[1].bytes, 32) == 0) ||
(config.security.admin_key[2].size == 32 &&
memcmp(mp.public_key.bytes, config.security.admin_key[2].bytes, 32) == 0)) {
LOG_INFO("PKC admin payload with authorized sender key.");
LOG_INFO("PKC admin payload with authorized sender key");
} else {
myReply = allocErrorResponse(meshtastic_Routing_Error_ADMIN_PUBLIC_KEY_UNAUTHORIZED, &mp);
LOG_INFO("Received PKC admin payload, but the sender public key does not match the admin authorized key!");
return handled;
}
} else {
LOG_INFO("Ignoring unauthorized admin payload %i", r->which_payload_variant);
LOG_INFO("Ignore unauthorized admin payload %i", r->which_payload_variant);
myReply = allocErrorResponse(meshtastic_Routing_Error_NOT_AUTHORIZED, &mp);
return handled;
}
LOG_INFO("Handling admin payload %i", r->which_payload_variant);
LOG_INFO("Handle admin payload %i", r->which_payload_variant);
// all of the get and set messages, including those for other modules, flow through here first.
// any message that changes state, we want to check the passkey for
@ -122,23 +122,23 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
* Getters
*/
case meshtastic_AdminMessage_get_owner_request_tag:
LOG_INFO("Client is getting owner");
LOG_INFO("Client got owner");
handleGetOwner(mp);
break;
case meshtastic_AdminMessage_get_config_request_tag:
LOG_INFO("Client is getting config");
LOG_INFO("Client got config");
handleGetConfig(mp, r->get_config_request);
break;
case meshtastic_AdminMessage_get_module_config_request_tag:
LOG_INFO("Client is getting module config");
LOG_INFO("Client got module config");
handleGetModuleConfig(mp, r->get_module_config_request);
break;
case meshtastic_AdminMessage_get_channel_request_tag: {
uint32_t i = r->get_channel_request - 1;
LOG_INFO("Client is getting channel %u", i);
LOG_INFO("Client got channel %u", i);
if (i >= MAX_NUM_CHANNELS)
myReply = allocErrorResponse(meshtastic_Routing_Error_BAD_REQUEST, &mp);
else
@ -150,29 +150,29 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
* Setters
*/
case meshtastic_AdminMessage_set_owner_tag:
LOG_INFO("Client is setting owner");
LOG_INFO("Client set owner");
handleSetOwner(r->set_owner);
break;
case meshtastic_AdminMessage_set_config_tag:
LOG_INFO("Client is setting the config");
LOG_INFO("Client set config");
handleSetConfig(r->set_config);
break;
case meshtastic_AdminMessage_set_module_config_tag:
LOG_INFO("Client is setting the module config");
LOG_INFO("Client set module config");
handleSetModuleConfig(r->set_module_config);
break;
case meshtastic_AdminMessage_set_channel_tag:
LOG_INFO("Client is setting channel %d", r->set_channel.index);
LOG_INFO("Client set channel %d", r->set_channel.index);
if (r->set_channel.index < 0 || r->set_channel.index >= (int)MAX_NUM_CHANNELS)
myReply = allocErrorResponse(meshtastic_Routing_Error_BAD_REQUEST, &mp);
else
handleSetChannel(r->set_channel);
break;
case meshtastic_AdminMessage_set_ham_mode_tag:
LOG_INFO("Client is setting ham mode");
LOG_INFO("Client set ham mode");
handleSetHamMode(r->set_ham_mode);
break;
case meshtastic_AdminMessage_get_ui_config_request_tag: {
@ -198,7 +198,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
} else {
screen->startFirmwareUpdateScreen();
BleOta::switchToOtaApp();
LOG_INFO("Rebooting to OTA in %d seconds", s);
LOG_INFO("Reboot to OTA in %d seconds", s);
}
#else
LOG_INFO("Not on ESP32, scheduling regular reboot in %d seconds", s);
@ -214,28 +214,28 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
break;
}
case meshtastic_AdminMessage_get_device_metadata_request_tag: {
LOG_INFO("Client is getting device metadata");
LOG_INFO("Client got device metadata");
handleGetDeviceMetadata(mp);
break;
}
case meshtastic_AdminMessage_factory_reset_config_tag: {
disableBluetooth();
LOG_INFO("Initiating factory config reset");
LOG_INFO("Initiate factory config reset");
nodeDB->factoryReset();
LOG_INFO("Factory config reset finished, rebooting soon.");
LOG_INFO("Factory config reset finished, rebooting soon");
reboot(DEFAULT_REBOOT_SECONDS);
break;
}
case meshtastic_AdminMessage_factory_reset_device_tag: {
disableBluetooth();
LOG_INFO("Initiating full factory reset");
LOG_INFO("Initiate full factory reset");
nodeDB->factoryReset(true);
reboot(DEFAULT_REBOOT_SECONDS);
break;
}
case meshtastic_AdminMessage_nodedb_reset_tag: {
disableBluetooth();
LOG_INFO("Initiating node-db reset");
LOG_INFO("Initiate node-db reset");
nodeDB->resetNodes();
reboot(DEFAULT_REBOOT_SECONDS);
break;
@ -247,24 +247,24 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
break;
}
case meshtastic_AdminMessage_begin_edit_settings_tag: {
LOG_INFO("Beginning transaction for editing settings");
LOG_INFO("Begin transaction for editing settings");
hasOpenEditTransaction = true;
break;
}
case meshtastic_AdminMessage_commit_edit_settings_tag: {
disableBluetooth();
LOG_INFO("Committing transaction for edited settings");
LOG_INFO("Commit transaction for edited settings");
hasOpenEditTransaction = false;
saveChanges(SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS);
break;
}
case meshtastic_AdminMessage_get_device_connection_status_request_tag: {
LOG_INFO("Client is getting device connection status");
LOG_INFO("Client got device connection status");
handleGetDeviceConnectionStatus(mp);
break;
}
case meshtastic_AdminMessage_get_module_config_response_tag: {
LOG_INFO("Client is receiving a get_module_config response.");
LOG_INFO("Client received a get_module_config response");
if (fromOthers && r->get_module_config_response.which_payload_variant ==
meshtastic_AdminMessage_ModuleConfigType_REMOTEHARDWARE_CONFIG) {
handleGetModuleConfigResponse(mp, r);
@ -272,13 +272,13 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
break;
}
case meshtastic_AdminMessage_remove_by_nodenum_tag: {
LOG_INFO("Client is receiving a remove_nodenum command.");
LOG_INFO("Client received remove_nodenum command");
nodeDB->removeNodeByNum(r->remove_by_nodenum);
this->notifyObservers(r); // Observed by screen
break;
}
case meshtastic_AdminMessage_set_favorite_node_tag: {
LOG_INFO("Client is receiving a set_favorite_node command.");
LOG_INFO("Client received set_favorite_node command");
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(r->set_favorite_node);
if (node != NULL) {
node->is_favorite = true;
@ -287,7 +287,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
break;
}
case meshtastic_AdminMessage_remove_favorite_node_tag: {
LOG_INFO("Client is receiving a remove_favorite_node command.");
LOG_INFO("Client received remove_favorite_node command");
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(r->remove_favorite_node);
if (node != NULL) {
node->is_favorite = false;
@ -296,7 +296,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
break;
}
case meshtastic_AdminMessage_set_fixed_position_tag: {
LOG_INFO("Client is receiving a set_fixed_position command.");
LOG_INFO("Client received set_fixed_position command");
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum());
node->has_position = true;
node->position = TypeConversions::ConvertToPositionLite(r->set_fixed_position);
@ -312,14 +312,14 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
break;
}
case meshtastic_AdminMessage_remove_fixed_position_tag: {
LOG_INFO("Client is receiving a remove_fixed_position command.");
LOG_INFO("Client received remove_fixed_position command");
nodeDB->clearLocalPosition();
config.position.fixed_position = false;
saveChanges(SEGMENT_DEVICESTATE | SEGMENT_CONFIG, false);
break;
}
case meshtastic_AdminMessage_set_time_only_tag: {
LOG_INFO("Client is receiving a set_time_only command.");
LOG_INFO("Client received set_time_only command");
struct timeval tv;
tv.tv_sec = r->set_time_only;
tv.tv_usec = 0;
@ -328,14 +328,14 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
break;
}
case meshtastic_AdminMessage_enter_dfu_mode_request_tag: {
LOG_INFO("Client is requesting to enter DFU mode.");
LOG_INFO("Client requesting to enter DFU mode");
#if defined(ARCH_NRF52) || defined(ARCH_RP2040)
enterDfuMode();
#endif
break;
}
case meshtastic_AdminMessage_delete_file_request_tag: {
LOG_DEBUG("Client is requesting to delete file: %s", r->delete_file_request);
LOG_DEBUG("Client requesting to delete file: %s", r->delete_file_request);
#ifdef FSCom
if (FSCom.remove(r->delete_file_request)) {
LOG_DEBUG("Successfully deleted file");
@ -360,10 +360,10 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
setPassKey(&res);
myReply = allocDataProtobuf(res);
} else if (mp.decoded.want_response) {
LOG_DEBUG("We did not responded to a request that wanted a respond. req.variant=%d", r->which_payload_variant);
LOG_DEBUG("Did not responded to a request that wanted a respond. req.variant=%d", r->which_payload_variant);
} else if (handleResult != AdminMessageHandleResult::HANDLED) {
// Probably a message sent by us or sent to our local node. FIXME, we should avoid scanning these messages
LOG_INFO("Ignoring nonrelevant admin %d", r->which_payload_variant);
LOG_INFO("Ignore irrelevant admin %d", r->which_payload_variant);
}
break;
}
@ -381,7 +381,7 @@ void AdminModule::handleGetModuleConfigResponse(const meshtastic_MeshPacket &mp,
// Skip if it's disabled or no pins are exposed
if (!r->get_module_config_response.payload_variant.remote_hardware.enabled ||
r->get_module_config_response.payload_variant.remote_hardware.available_pins_count == 0) {
LOG_DEBUG("Remote hardware module disabled or no available_pins. Skipping...");
LOG_DEBUG("Remote hardware module disabled or no available_pins. Skip...");
return;
}
for (uint8_t i = 0; i < devicestate.node_remote_hardware_pins_count; i++) {
@ -439,7 +439,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c)
switch (c.which_payload_variant) {
case meshtastic_Config_device_tag:
LOG_INFO("Setting config: Device");
LOG_INFO("Set config: Device");
config.has_device = true;
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
if (config.device.double_tap_as_button_press == false && c.payload_variant.device.double_tap_as_button_press == true &&
@ -496,14 +496,14 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c)
#endif
break;
case meshtastic_Config_position_tag:
LOG_INFO("Setting config: Position");
LOG_INFO("Set config: Position");
config.has_position = true;
config.position = c.payload_variant.position;
// Save nodedb as well in case we got a fixed position packet
saveChanges(SEGMENT_DEVICESTATE, false);
break;
case meshtastic_Config_power_tag:
LOG_INFO("Setting config: Power");
LOG_INFO("Set config: Power");
config.has_power = true;
// Really just the adc override is the only thing that can change without a reboot
if (config.power.device_battery_ina_address == c.payload_variant.power.device_battery_ina_address &&
@ -518,12 +518,12 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c)
config.power = c.payload_variant.power;
break;
case meshtastic_Config_network_tag:
LOG_INFO("Setting config: WiFi");
LOG_INFO("Set config: WiFi");
config.has_network = true;
config.network = c.payload_variant.network;
break;
case meshtastic_Config_display_tag:
LOG_INFO("Setting config: Display");
LOG_INFO("Set config: Display");
config.has_display = true;
if (config.display.screen_on_secs == c.payload_variant.display.screen_on_secs &&
config.display.flip_screen == c.payload_variant.display.flip_screen &&
@ -541,7 +541,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c)
config.display = c.payload_variant.display;
break;
case meshtastic_Config_lora_tag:
LOG_INFO("Setting config: LoRa");
LOG_INFO("Set config: LoRa");
config.has_lora = true;
// If no lora radio parameters change, don't need to reboot
if (config.lora.use_preset == c.payload_variant.lora.use_preset && config.lora.region == c.payload_variant.lora.region &&
@ -580,12 +580,12 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c)
}
break;
case meshtastic_Config_bluetooth_tag:
LOG_INFO("Setting config: Bluetooth");
LOG_INFO("Set config: Bluetooth");
config.has_bluetooth = true;
config.bluetooth = c.payload_variant.bluetooth;
break;
case meshtastic_Config_security_tag:
LOG_INFO("Setting config: Security");
LOG_INFO("Set config: Security");
config.security = c.payload_variant.security;
#if !(MESHTASTIC_EXCLUDE_PKI_KEYGEN) && !(MESHTASTIC_EXCLUDE_PKI)
// We check for a potentially valid private key, and a blank public key, and regen the public key if needed.
@ -623,52 +623,52 @@ void AdminModule::handleSetModuleConfig(const meshtastic_ModuleConfig &c)
disableBluetooth();
switch (c.which_payload_variant) {
case meshtastic_ModuleConfig_mqtt_tag:
LOG_INFO("Setting module config: MQTT");
LOG_INFO("Set module config: MQTT");
moduleConfig.has_mqtt = true;
moduleConfig.mqtt = c.payload_variant.mqtt;
break;
case meshtastic_ModuleConfig_serial_tag:
LOG_INFO("Setting module config: Serial");
LOG_INFO("Set module config: Serial");
moduleConfig.has_serial = true;
moduleConfig.serial = c.payload_variant.serial;
break;
case meshtastic_ModuleConfig_external_notification_tag:
LOG_INFO("Setting module config: External Notification");
LOG_INFO("Set module config: External Notification");
moduleConfig.has_external_notification = true;
moduleConfig.external_notification = c.payload_variant.external_notification;
break;
case meshtastic_ModuleConfig_store_forward_tag:
LOG_INFO("Setting module config: Store & Forward");
LOG_INFO("Set module config: Store & Forward");
moduleConfig.has_store_forward = true;
moduleConfig.store_forward = c.payload_variant.store_forward;
break;
case meshtastic_ModuleConfig_range_test_tag:
LOG_INFO("Setting module config: Range Test");
LOG_INFO("Set module config: Range Test");
moduleConfig.has_range_test = true;
moduleConfig.range_test = c.payload_variant.range_test;
break;
case meshtastic_ModuleConfig_telemetry_tag:
LOG_INFO("Setting module config: Telemetry");
LOG_INFO("Set module config: Telemetry");
moduleConfig.has_telemetry = true;
moduleConfig.telemetry = c.payload_variant.telemetry;
break;
case meshtastic_ModuleConfig_canned_message_tag:
LOG_INFO("Setting module config: Canned Message");
LOG_INFO("Set module config: Canned Message");
moduleConfig.has_canned_message = true;
moduleConfig.canned_message = c.payload_variant.canned_message;
break;
case meshtastic_ModuleConfig_audio_tag:
LOG_INFO("Setting module config: Audio");
LOG_INFO("Set module config: Audio");
moduleConfig.has_audio = true;
moduleConfig.audio = c.payload_variant.audio;
break;
case meshtastic_ModuleConfig_remote_hardware_tag:
LOG_INFO("Setting module config: Remote Hardware");
LOG_INFO("Set module config: Remote Hardware");
moduleConfig.has_remote_hardware = true;
moduleConfig.remote_hardware = c.payload_variant.remote_hardware;
break;
case meshtastic_ModuleConfig_neighbor_info_tag:
LOG_INFO("Setting module config: Neighbor Info");
LOG_INFO("Set module config: Neighbor Info");
moduleConfig.has_neighbor_info = true;
if (moduleConfig.neighbor_info.update_interval < min_neighbor_info_broadcast_secs) {
LOG_DEBUG("Tried to set update_interval too low, setting to %d", default_neighbor_info_broadcast_secs);
@ -677,17 +677,17 @@ void AdminModule::handleSetModuleConfig(const meshtastic_ModuleConfig &c)
moduleConfig.neighbor_info = c.payload_variant.neighbor_info;
break;
case meshtastic_ModuleConfig_detection_sensor_tag:
LOG_INFO("Setting module config: Detection Sensor");
LOG_INFO("Set module config: Detection Sensor");
moduleConfig.has_detection_sensor = true;
moduleConfig.detection_sensor = c.payload_variant.detection_sensor;
break;
case meshtastic_ModuleConfig_ambient_lighting_tag:
LOG_INFO("Setting module config: Ambient Lighting");
LOG_INFO("Set module config: Ambient Lighting");
moduleConfig.has_ambient_lighting = true;
moduleConfig.ambient_lighting = c.payload_variant.ambient_lighting;
break;
case meshtastic_ModuleConfig_paxcounter_tag:
LOG_INFO("Setting module config: Paxcounter");
LOG_INFO("Set module config: Paxcounter");
moduleConfig.has_paxcounter = true;
moduleConfig.paxcounter = c.payload_variant.paxcounter;
break;
@ -726,49 +726,49 @@ void AdminModule::handleGetConfig(const meshtastic_MeshPacket &req, const uint32
if (req.decoded.want_response) {
switch (configType) {
case meshtastic_AdminMessage_ConfigType_DEVICE_CONFIG:
LOG_INFO("Getting config: Device");
LOG_INFO("Get config: Device");
res.get_config_response.which_payload_variant = meshtastic_Config_device_tag;
res.get_config_response.payload_variant.device = config.device;
break;
case meshtastic_AdminMessage_ConfigType_POSITION_CONFIG:
LOG_INFO("Getting config: Position");
LOG_INFO("Get config: Position");
res.get_config_response.which_payload_variant = meshtastic_Config_position_tag;
res.get_config_response.payload_variant.position = config.position;
break;
case meshtastic_AdminMessage_ConfigType_POWER_CONFIG:
LOG_INFO("Getting config: Power");
LOG_INFO("Get config: Power");
res.get_config_response.which_payload_variant = meshtastic_Config_power_tag;
res.get_config_response.payload_variant.power = config.power;
break;
case meshtastic_AdminMessage_ConfigType_NETWORK_CONFIG:
LOG_INFO("Getting config: Network");
LOG_INFO("Get config: Network");
res.get_config_response.which_payload_variant = meshtastic_Config_network_tag;
res.get_config_response.payload_variant.network = config.network;
writeSecret(res.get_config_response.payload_variant.network.wifi_psk,
sizeof(res.get_config_response.payload_variant.network.wifi_psk), config.network.wifi_psk);
break;
case meshtastic_AdminMessage_ConfigType_DISPLAY_CONFIG:
LOG_INFO("Getting config: Display");
LOG_INFO("Get config: Display");
res.get_config_response.which_payload_variant = meshtastic_Config_display_tag;
res.get_config_response.payload_variant.display = config.display;
break;
case meshtastic_AdminMessage_ConfigType_LORA_CONFIG:
LOG_INFO("Getting config: LoRa");
LOG_INFO("Get config: LoRa");
res.get_config_response.which_payload_variant = meshtastic_Config_lora_tag;
res.get_config_response.payload_variant.lora = config.lora;
break;
case meshtastic_AdminMessage_ConfigType_BLUETOOTH_CONFIG:
LOG_INFO("Getting config: Bluetooth");
LOG_INFO("Get config: Bluetooth");
res.get_config_response.which_payload_variant = meshtastic_Config_bluetooth_tag;
res.get_config_response.payload_variant.bluetooth = config.bluetooth;
break;
case meshtastic_AdminMessage_ConfigType_SECURITY_CONFIG:
LOG_INFO("Getting config: Security");
LOG_INFO("Get config: Security");
res.get_config_response.which_payload_variant = meshtastic_Config_security_tag;
res.get_config_response.payload_variant.security = config.security;
break;
case meshtastic_AdminMessage_ConfigType_SESSIONKEY_CONFIG:
LOG_INFO("Getting config: Sessionkey");
LOG_INFO("Get config: Sessionkey");
res.get_config_response.which_payload_variant = meshtastic_Config_sessionkey_tag;
break;
case meshtastic_AdminMessage_ConfigType_DEVICEUI_CONFIG:
@ -796,67 +796,67 @@ void AdminModule::handleGetModuleConfig(const meshtastic_MeshPacket &req, const
if (req.decoded.want_response) {
switch (configType) {
case meshtastic_AdminMessage_ModuleConfigType_MQTT_CONFIG:
LOG_INFO("Getting module config: MQTT");
LOG_INFO("Get module config: MQTT");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_mqtt_tag;
res.get_module_config_response.payload_variant.mqtt = moduleConfig.mqtt;
break;
case meshtastic_AdminMessage_ModuleConfigType_SERIAL_CONFIG:
LOG_INFO("Getting module config: Serial");
LOG_INFO("Get module config: Serial");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_serial_tag;
res.get_module_config_response.payload_variant.serial = moduleConfig.serial;
break;
case meshtastic_AdminMessage_ModuleConfigType_EXTNOTIF_CONFIG:
LOG_INFO("Getting module config: External Notification");
LOG_INFO("Get module config: External Notification");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_external_notification_tag;
res.get_module_config_response.payload_variant.external_notification = moduleConfig.external_notification;
break;
case meshtastic_AdminMessage_ModuleConfigType_STOREFORWARD_CONFIG:
LOG_INFO("Getting module config: Store & Forward");
LOG_INFO("Get module config: Store & Forward");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_store_forward_tag;
res.get_module_config_response.payload_variant.store_forward = moduleConfig.store_forward;
break;
case meshtastic_AdminMessage_ModuleConfigType_RANGETEST_CONFIG:
LOG_INFO("Getting module config: Range Test");
LOG_INFO("Get module config: Range Test");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_range_test_tag;
res.get_module_config_response.payload_variant.range_test = moduleConfig.range_test;
break;
case meshtastic_AdminMessage_ModuleConfigType_TELEMETRY_CONFIG:
LOG_INFO("Getting module config: Telemetry");
LOG_INFO("Get module config: Telemetry");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_telemetry_tag;
res.get_module_config_response.payload_variant.telemetry = moduleConfig.telemetry;
break;
case meshtastic_AdminMessage_ModuleConfigType_CANNEDMSG_CONFIG:
LOG_INFO("Getting module config: Canned Message");
LOG_INFO("Get module config: Canned Message");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_canned_message_tag;
res.get_module_config_response.payload_variant.canned_message = moduleConfig.canned_message;
break;
case meshtastic_AdminMessage_ModuleConfigType_AUDIO_CONFIG:
LOG_INFO("Getting module config: Audio");
LOG_INFO("Get module config: Audio");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_audio_tag;
res.get_module_config_response.payload_variant.audio = moduleConfig.audio;
break;
case meshtastic_AdminMessage_ModuleConfigType_REMOTEHARDWARE_CONFIG:
LOG_INFO("Getting module config: Remote Hardware");
LOG_INFO("Get module config: Remote Hardware");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_remote_hardware_tag;
res.get_module_config_response.payload_variant.remote_hardware = moduleConfig.remote_hardware;
break;
case meshtastic_AdminMessage_ModuleConfigType_NEIGHBORINFO_CONFIG:
LOG_INFO("Getting module config: Neighbor Info");
LOG_INFO("Get module config: Neighbor Info");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_neighbor_info_tag;
res.get_module_config_response.payload_variant.neighbor_info = moduleConfig.neighbor_info;
break;
case meshtastic_AdminMessage_ModuleConfigType_DETECTIONSENSOR_CONFIG:
LOG_INFO("Getting module config: Detection Sensor");
LOG_INFO("Get module config: Detection Sensor");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_detection_sensor_tag;
res.get_module_config_response.payload_variant.detection_sensor = moduleConfig.detection_sensor;
break;
case meshtastic_AdminMessage_ModuleConfigType_AMBIENTLIGHTING_CONFIG:
LOG_INFO("Getting module config: Ambient Lighting");
LOG_INFO("Get module config: Ambient Lighting");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_ambient_lighting_tag;
res.get_module_config_response.payload_variant.ambient_lighting = moduleConfig.ambient_lighting;
break;
case meshtastic_AdminMessage_ModuleConfigType_PAXCOUNTER_CONFIG:
LOG_INFO("Getting module config: Paxcounter");
LOG_INFO("Get module config: Paxcounter");
res.get_module_config_response.which_payload_variant = meshtastic_ModuleConfig_paxcounter_tag;
res.get_module_config_response.payload_variant.paxcounter = moduleConfig.paxcounter;
break;
@ -997,7 +997,7 @@ void AdminModule::handleGetDeviceUIConfig(const meshtastic_MeshPacket &req)
void AdminModule::reboot(int32_t seconds)
{
LOG_INFO("Rebooting in %d seconds", seconds);
LOG_INFO("Reboot in %d seconds", seconds);
screen->startAlert("Rebooting...");
rebootAtMsec = (seconds < 0) ? 0 : (millis() + seconds * 1000);
}
@ -1005,10 +1005,10 @@ void AdminModule::reboot(int32_t seconds)
void AdminModule::saveChanges(int saveWhat, bool shouldReboot)
{
if (!hasOpenEditTransaction) {
LOG_INFO("Saving changes to disk");
LOG_INFO("Save changes to disk");
service->reloadConfig(saveWhat); // Calls saveToDisk among other things
} else {
LOG_INFO("Delaying save of changes to disk until the open transaction is committed");
LOG_INFO("Delay save of changes to disk until the open transaction is committed");
}
if (shouldReboot && !hasOpenEditTransaction) {
reboot(DEFAULT_REBOOT_SECONDS);
@ -1062,7 +1062,7 @@ void AdminModule::setPassKey(meshtastic_AdminMessage *res)
}
memcpy(res->session_passkey.bytes, session_passkey, 8);
res->session_passkey.size = 8;
printBytes("Setting admin key to ", res->session_passkey.bytes, 8);
printBytes("Set admin key to ", res->session_passkey.bytes, 8);
// if halfway to session_expire, regenerate session_passkey, reset the timeout
// set the key in the packet
}
@ -1130,4 +1130,4 @@ void disableBluetooth()
nrf52Bluetooth->shutdown();
#endif
#endif
}
}

View File

@ -11,7 +11,7 @@
AtakPluginModule *atakPluginModule;
AtakPluginModule::AtakPluginModule()
: ProtobufModule("atak", meshtastic_PortNum_ATAK_PLUGIN, &meshtastic_TAKPacket_msg), concurrency::OSThread("AtakPluginModule")
: ProtobufModule("atak", meshtastic_PortNum_ATAK_PLUGIN, &meshtastic_TAKPacket_msg), concurrency::OSThread("AtakPlugin")
{
ourPortNum = meshtastic_PortNum_ATAK_PLUGIN;
}
@ -73,7 +73,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
auto length = unishox2_compress_lines(t->contact.callsign, strlen(t->contact.callsign), compressed.contact.callsign,
sizeof(compressed.contact.callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compression overflowed contact.callsign. Reverting to uncompressed packet");
LOG_WARN("Compress overflow contact.callsign. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed callsign: %d bytes", length);
@ -81,7 +81,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
compressed.contact.device_callsign, sizeof(compressed.contact.device_callsign) - 1,
USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compression overflowed contact.device_callsign. Reverting to uncompressed packet");
LOG_WARN("Compress overflow contact.device_callsign. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed device_callsign: %d bytes", length);
@ -91,7 +91,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
compressed.payload_variant.chat.message,
sizeof(compressed.payload_variant.chat.message) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compression overflowed chat.message. Reverting to uncompressed packet");
LOG_WARN("Compress overflow chat.message. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed chat message: %d bytes", length);
@ -102,7 +102,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
compressed.payload_variant.chat.to,
sizeof(compressed.payload_variant.chat.to) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compression overflowed chat.to. Reverting to uncompressed packet");
LOG_WARN("Compress overflow chat.to. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed chat to: %d bytes", length);
@ -114,7 +114,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
compressed.payload_variant.chat.to_callsign,
sizeof(compressed.payload_variant.chat.to_callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compression overflowed chat.to_callsign. Reverting to uncompressed packet");
LOG_WARN("Compress overflow chat.to_callsign. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed chat to_callsign: %d bytes", length);
@ -126,7 +126,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
} else {
if (!t->is_compressed) {
// Not compressed. Something is wrong
LOG_WARN("Received uncompressed TAKPacket over radio! Skipping");
LOG_WARN("Received uncompressed TAKPacket over radio! Skip");
return;
}
@ -139,7 +139,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
unishox2_decompress_lines(t->contact.callsign, strlen(t->contact.callsign), uncompressed.contact.callsign,
sizeof(uncompressed.contact.callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompression overflowed contact.callsign. Bailing out");
LOG_WARN("Decompress overflow contact.callsign. Bailing out");
return;
}
LOG_DEBUG("Decompressed callsign: %d bytes", length);
@ -148,7 +148,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
uncompressed.contact.device_callsign,
sizeof(uncompressed.contact.device_callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompression overflowed contact.device_callsign. Bailing out");
LOG_WARN("Decompress overflow contact.device_callsign. Bailing out");
return;
}
LOG_DEBUG("Decompressed device_callsign: %d bytes", length);
@ -158,7 +158,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
uncompressed.payload_variant.chat.message,
sizeof(uncompressed.payload_variant.chat.message) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompression overflowed chat.message. Bailing out");
LOG_WARN("Decompress overflow chat.message. Bailing out");
return;
}
LOG_DEBUG("Decompressed chat message: %d bytes", length);
@ -169,7 +169,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
uncompressed.payload_variant.chat.to,
sizeof(uncompressed.payload_variant.chat.to) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompression overflowed chat.to. Bailing out");
LOG_WARN("Decompress overflow chat.to. Bailing out");
return;
}
LOG_DEBUG("Decompressed chat to: %d bytes", length);
@ -182,7 +182,7 @@ void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtast
uncompressed.payload_variant.chat.to_callsign,
sizeof(uncompressed.payload_variant.chat.to_callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompression overflowed chat.to_callsign. Bailing out");
LOG_WARN("Decompress overflow chat.to_callsign. Bailing out");
return;
}
LOG_DEBUG("Decompressed chat to_callsign: %d bytes", length);

View File

@ -42,7 +42,7 @@ meshtastic_CannedMessageModuleConfig cannedMessageModuleConfig;
CannedMessageModule *cannedMessageModule;
CannedMessageModule::CannedMessageModule()
: SinglePortModule("canned", meshtastic_PortNum_TEXT_MESSAGE_APP), concurrency::OSThread("CannedMessageModule")
: SinglePortModule("canned", meshtastic_PortNum_TEXT_MESSAGE_APP), concurrency::OSThread("CannedMessage")
{
if (moduleConfig.canned_message.enabled || CANNED_MESSAGE_MODULE_ENABLE) {
this->loadProtoForModule();
@ -227,12 +227,12 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event)
case INPUT_BROKER_MSG_BRIGHTNESS_UP: // make screen brighter
if (screen)
screen->increaseBrightness();
LOG_DEBUG("increasing Screen Brightness");
LOG_DEBUG("Increase Screen Brightness");
break;
case INPUT_BROKER_MSG_BRIGHTNESS_DOWN: // make screen dimmer
if (screen)
screen->decreaseBrightness();
LOG_DEBUG("Decreasing Screen Brightness");
LOG_DEBUG("Decrease Screen Brightness");
break;
case INPUT_BROKER_MSG_FN_SYMBOL_ON: // draw modifier (function) symbal
if (screen)
@ -414,7 +414,7 @@ void CannedMessageModule::sendText(NodeNum dest, ChannelIndex channel, const cha
// or raising a UIFrameEvent before another module has the chance
this->waitingForAck = true;
LOG_INFO("Sending message id=%d, dest=%x, msg=%.*s", p->id, p->to, p->decoded.payload.size, p->decoded.payload.bytes);
LOG_INFO("Send message id=%d, dest=%x, msg=%.*s", p->id, p->to, p->decoded.payload.size, p->decoded.payload.bytes);
service->sendToMesh(
p, RX_SRC_LOCAL,
@ -481,7 +481,7 @@ int32_t CannedMessageModule::runOnce()
}
this->runState = CANNED_MESSAGE_RUN_STATE_SENDING_ACTIVE;
} else {
// LOG_DEBUG("Reset message is empty.");
// LOG_DEBUG("Reset message is empty");
this->runState = CANNED_MESSAGE_RUN_STATE_INACTIVE;
}
}
@ -978,7 +978,7 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st
if (temporaryMessage.length() != 0) {
requestFocus(); // Tell Screen::setFrames to move to our module's frame
LOG_DEBUG("Drawing temporary message: %s", temporaryMessage.c_str());
LOG_DEBUG("Draw temporary message: %s", temporaryMessage.c_str());
display->setTextAlignment(TEXT_ALIGN_CENTER);
display->setFont(FONT_MEDIUM);
display->drawString(display->getWidth() / 2 + x, 0 + y + 12, temporaryMessage);
@ -1208,13 +1208,13 @@ AdminMessageHandleResult CannedMessageModule::handleAdminMessageForModule(const
switch (request->which_payload_variant) {
case meshtastic_AdminMessage_get_canned_message_module_messages_request_tag:
LOG_DEBUG("Client is getting radio canned messages");
LOG_DEBUG("Client getting radio canned messages");
this->handleGetCannedMessageModuleMessages(mp, response);
result = AdminMessageHandleResult::HANDLED_WITH_RESPONSE;
break;
case meshtastic_AdminMessage_set_canned_message_module_messages_tag:
LOG_DEBUG("Client is setting radio canned messages");
LOG_DEBUG("Client getting radio canned messages");
this->handleSetCannedMessageModuleMessages(request->set_canned_message_module_messages);
result = AdminMessageHandleResult::HANDLED;
break;
@ -1258,4 +1258,4 @@ String CannedMessageModule::drawWithCursor(String text, int cursor)
return result;
}
#endif
#endif

View File

@ -76,10 +76,10 @@ int32_t DetectionSensorModule::runOnce()
if (moduleConfig.detection_sensor.monitor_pin > 0) {
pinMode(moduleConfig.detection_sensor.monitor_pin, moduleConfig.detection_sensor.use_pullup ? INPUT_PULLUP : INPUT);
} else {
LOG_WARN("Detection Sensor Module: Set to enabled but no monitor pin is set. Disabling module...");
LOG_WARN("Detection Sensor Module: Set to enabled but no monitor pin is set. Disable module...");
return disable();
}
LOG_INFO("Detection Sensor Module: Initializing");
LOG_INFO("Detection Sensor Module: init");
return DELAYED_INTERVAL;
}
@ -118,7 +118,7 @@ int32_t DetectionSensorModule::runOnce()
void DetectionSensorModule::sendDetectionMessage()
{
LOG_DEBUG("Detected event observed. Sending message");
LOG_DEBUG("Detected event observed. Send message");
char *message = new char[40];
sprintf(message, "%s detected", moduleConfig.detection_sensor.name);
meshtastic_MeshPacket *p = allocDataPacket();
@ -130,7 +130,7 @@ void DetectionSensorModule::sendDetectionMessage()
p->decoded.payload.bytes[p->decoded.payload.size + 1] = '\0'; // Bell character
p->decoded.payload.size++;
}
LOG_INFO("Sending message id=%d, dest=%x, msg=%.*s", p->id, p->to, p->decoded.payload.size, p->decoded.payload.bytes);
LOG_INFO("Send message id=%d, dest=%x, msg=%.*s", p->id, p->to, p->decoded.payload.size, p->decoded.payload.bytes);
lastSentToMesh = millis();
service->sendToMesh(p);
delete[] message;
@ -145,7 +145,7 @@ void DetectionSensorModule::sendCurrentStateMessage(bool state)
p->want_ack = false;
p->decoded.payload.size = strlen(message);
memcpy(p->decoded.payload.bytes, message, p->decoded.payload.size);
LOG_INFO("Sending message id=%d, dest=%x, msg=%.*s", p->id, p->to, p->decoded.payload.size, p->decoded.payload.bytes);
LOG_INFO("Send message id=%d, dest=%x, msg=%.*s", p->id, p->to, p->decoded.payload.size, p->decoded.payload.bytes);
lastSentToMesh = millis();
service->sendToMesh(p);
delete[] message;

View File

@ -4,8 +4,7 @@
class DetectionSensorModule : public SinglePortModule, private concurrency::OSThread
{
public:
DetectionSensorModule()
: SinglePortModule("detection", meshtastic_PortNum_DETECTION_SENSOR_APP), OSThread("DetectionSensorModule")
DetectionSensorModule() : SinglePortModule("detection", meshtastic_PortNum_DETECTION_SENSOR_APP), OSThread("DetectionSensor")
{
}

View File

@ -15,7 +15,7 @@ class DropzoneModule : public SinglePortModule, private concurrency::OSThread
/** Constructor
* name is for debugging output
*/
DropzoneModule() : SinglePortModule("dropzone", meshtastic_PortNum_TEXT_MESSAGE_APP), concurrency::OSThread("DropzoneModule")
DropzoneModule() : SinglePortModule("dropzone", meshtastic_PortNum_TEXT_MESSAGE_APP), concurrency::OSThread("Dropzone")
{
// Set up the analog pin for reading the dropzone status
pinMode(PIN_A1, INPUT);

View File

@ -291,7 +291,7 @@ void ExternalNotificationModule::stopNow()
ExternalNotificationModule::ExternalNotificationModule()
: SinglePortModule("ExternalNotificationModule", meshtastic_PortNum_TEXT_MESSAGE_APP),
concurrency::OSThread("ExternalNotificationModule")
concurrency::OSThread("ExternalNotification")
{
/*
Uncomment the preferences below if you want to use the module
@ -327,34 +327,34 @@ ExternalNotificationModule::ExternalNotificationModule()
sizeof(rtttlConfig.ringtone));
}
LOG_INFO("Initializing External Notification Module");
LOG_INFO("Init External Notification Module");
output = moduleConfig.external_notification.output ? moduleConfig.external_notification.output
: EXT_NOTIFICATION_MODULE_OUTPUT;
// Set the direction of a pin
if (output > 0) {
LOG_INFO("Using Pin %i in digital mode", output);
LOG_INFO("Use Pin %i in digital mode", output);
pinMode(output, OUTPUT);
}
setExternalState(0, false);
externalTurnedOn[0] = 0;
if (moduleConfig.external_notification.output_vibra) {
LOG_INFO("Using Pin %i for vibra motor", moduleConfig.external_notification.output_vibra);
LOG_INFO("Use Pin %i for vibra motor", moduleConfig.external_notification.output_vibra);
pinMode(moduleConfig.external_notification.output_vibra, OUTPUT);
setExternalState(1, false);
externalTurnedOn[1] = 0;
}
if (moduleConfig.external_notification.output_buzzer) {
if (!moduleConfig.external_notification.use_pwm) {
LOG_INFO("Using Pin %i for buzzer", moduleConfig.external_notification.output_buzzer);
LOG_INFO("Use Pin %i for buzzer", moduleConfig.external_notification.output_buzzer);
pinMode(moduleConfig.external_notification.output_buzzer, OUTPUT);
setExternalState(2, false);
externalTurnedOn[2] = 0;
} else {
config.device.buzzer_gpio = config.device.buzzer_gpio ? config.device.buzzer_gpio : PIN_BUZZER;
// in PWM Mode we force the buzzer pin if it is set
LOG_INFO("Using Pin %i in PWM mode", config.device.buzzer_gpio);
LOG_INFO("Use Pin %i in PWM mode", config.device.buzzer_gpio);
}
}
#ifdef HAS_NCP5623
@ -518,13 +518,13 @@ AdminMessageHandleResult ExternalNotificationModule::handleAdminMessageForModule
switch (request->which_payload_variant) {
case meshtastic_AdminMessage_get_ringtone_request_tag:
LOG_INFO("Client is getting ringtone");
LOG_INFO("Client getting ringtone");
this->handleGetRingtone(mp, response);
result = AdminMessageHandleResult::HANDLED_WITH_RESPONSE;
break;
case meshtastic_AdminMessage_set_ringtone_message_tag:
LOG_INFO("Client is setting ringtone");
LOG_INFO("Client setting ringtone");
this->handleSetRingtone(request->set_canned_message_module_messages);
result = AdminMessageHandleResult::HANDLED;
break;

View File

@ -37,7 +37,7 @@ void NeighborInfoModule::printNodeDBNeighbors()
/* Send our initial owner announcement 35 seconds after we start (to give network time to setup) */
NeighborInfoModule::NeighborInfoModule()
: ProtobufModule("neighborinfo", meshtastic_PortNum_NEIGHBORINFO_APP, &meshtastic_NeighborInfo_msg),
concurrency::OSThread("NeighborInfoModule")
concurrency::OSThread("NeighborInfo")
{
ourPortNum = meshtastic_PortNum_NEIGHBORINFO_APP;
nodeStatusObserver.observe(&nodeStatus->onNewStatus);
@ -91,7 +91,7 @@ void NeighborInfoModule::cleanUpNeighbors()
// We will remove a neighbor if we haven't heard from them in twice the broadcast interval
// cannot use isWithinTimespanMs() as it->last_rx_time is seconds since 1970
if ((now - it->last_rx_time > it->node_broadcast_interval_secs * 2) && (it->node_id != my_node_id)) {
LOG_DEBUG("Removing neighbor with node ID 0x%x", it->node_id);
LOG_DEBUG("Remove neighbor with node ID 0x%x", it->node_id);
it = std::vector<meshtastic_Neighbor>::reverse_iterator(
neighbors.erase(std::next(it).base())); // Erase the element and update the iterator
} else {
@ -203,7 +203,7 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen
neighbors.push_back(new_nbr);
} else {
// If we have too many neighbors, replace the oldest one
LOG_WARN("Neighbor DB is full, replacing oldest neighbor");
LOG_WARN("Neighbor DB is full, replace oldest neighbor");
neighbors.erase(neighbors.begin());
neighbors.push_back(new_nbr);
}

View File

@ -50,7 +50,7 @@ void NodeInfoModule::sendOurNodeInfo(NodeNum dest, bool wantReplies, uint8_t cha
else
p->priority = meshtastic_MeshPacket_Priority_BACKGROUND;
if (channel > 0) {
LOG_DEBUG("sending ourNodeInfo to channel %d", channel);
LOG_DEBUG("Send ourNodeInfo to channel %d", channel);
p->channel = channel;
}
@ -65,16 +65,16 @@ meshtastic_MeshPacket *NodeInfoModule::allocReply()
{
if (!airTime->isTxAllowedChannelUtil(false)) {
ignoreRequest = true; // Mark it as ignored for MeshModule
LOG_DEBUG("Skip sending NodeInfo due to > 40 percent channel util.");
LOG_DEBUG("Skip send NodeInfo > 40%% ch. util");
return NULL;
}
// If we sent our NodeInfo less than 5 min. ago, don't send it again as it may be still underway.
if (!shorterTimeout && lastSentToMesh && Throttle::isWithinTimespanMs(lastSentToMesh, 5 * 60 * 1000)) {
LOG_DEBUG("Skip sending NodeInfo since we just sent it less than 5 minutes ago.");
LOG_DEBUG("Skip send NodeInfo since we sent it <5 mins ago.");
ignoreRequest = true; // Mark it as ignored for MeshModule
return NULL;
} else if (shorterTimeout && lastSentToMesh && Throttle::isWithinTimespanMs(lastSentToMesh, 60 * 1000)) {
LOG_DEBUG("Skip sending actively requested NodeInfo since we just sent it less than 60 seconds ago.");
LOG_DEBUG("Skip send requested NodeInfo since we sent it <60s ago.");
ignoreRequest = true; // Mark it as ignored for MeshModule
return NULL;
} else {
@ -87,14 +87,14 @@ meshtastic_MeshPacket *NodeInfoModule::allocReply()
u.public_key.size = 0;
}
LOG_INFO("sending owner %s/%s/%s", u.id, u.long_name, u.short_name);
LOG_INFO("Send owner %s/%s/%s", u.id, u.long_name, u.short_name);
lastSentToMesh = millis();
return allocDataProtobuf(u);
}
}
NodeInfoModule::NodeInfoModule()
: ProtobufModule("nodeinfo", meshtastic_PortNum_NODEINFO_APP, &meshtastic_User_msg), concurrency::OSThread("NodeInfoModule")
: ProtobufModule("nodeinfo", meshtastic_PortNum_NODEINFO_APP, &meshtastic_User_msg), concurrency::OSThread("NodeInfo")
{
isPromiscuous = true; // We always want to update our nodedb, even if we are sniffing on others
setIntervalFromNow(30 *
@ -108,8 +108,8 @@ int32_t NodeInfoModule::runOnce()
currentGeneration = radioGeneration;
if (airTime->isTxAllowedAirUtil() && config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) {
LOG_INFO("Sending our nodeinfo to mesh (wantReplies=%d)", requestReplies);
LOG_INFO("Send our nodeinfo to mesh (wantReplies=%d)", requestReplies);
sendOurNodeInfo(NODENUM_BROADCAST, requestReplies); // Send our info (don't request replies)
}
return Default::getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_node_info_broadcast_secs);
}
}

View File

@ -24,8 +24,7 @@ extern "C" {
PositionModule *positionModule;
PositionModule::PositionModule()
: ProtobufModule("position", meshtastic_PortNum_POSITION_APP, &meshtastic_Position_msg),
concurrency::OSThread("PositionModule")
: ProtobufModule("position", meshtastic_PortNum_POSITION_APP, &meshtastic_Position_msg), concurrency::OSThread("Position")
{
precision = 0; // safe starting value
isPromiscuous = true; // We always want to update our nodedb, even if we are sniffing on others
@ -39,7 +38,7 @@ PositionModule::PositionModule()
if ((config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER ||
config.device.role == meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) &&
config.power.is_power_saving) {
LOG_DEBUG("Clearing position on startup for sleepy tracker (ー。ー) zzz");
LOG_DEBUG("Clear position on startup for sleepy tracker (ー。ー) zzz");
nodeDB->clearLocalPosition();
}
}
@ -111,7 +110,7 @@ void PositionModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtastic
{
// Phone position packets need to be truncated to the channel precision
if (isFromUs(&mp) && (precision < 32 && precision > 0)) {
LOG_DEBUG("Truncating phone position to channel precision %i", precision);
LOG_DEBUG("Truncate phone position to channel precision %i", precision);
p->latitude_i = p->latitude_i & (UINT32_MAX << (32 - precision));
p->longitude_i = p->longitude_i & (UINT32_MAX << (32 - precision));
@ -127,11 +126,11 @@ void PositionModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtastic
void PositionModule::trySetRtc(meshtastic_Position p, bool isLocal, bool forceUpdate)
{
if (hasQualityTimesource() && !isLocal) {
LOG_DEBUG("Ignoring time from mesh because we have a GPS, RTC, or Phone/NTP time source in the past day");
LOG_DEBUG("Ignore time from mesh because we have a GPS, RTC, or Phone/NTP time source in the past day");
return;
}
if (!isLocal && p.location_source < meshtastic_Position_LocSource_LOC_INTERNAL) {
LOG_DEBUG("Ignoring time from mesh because it has a unknown or manual source");
LOG_DEBUG("Ignore time from mesh because it has a unknown or manual source");
return;
}
struct timeval tv;
@ -158,7 +157,7 @@ bool PositionModule::hasQualityTimesource()
meshtastic_MeshPacket *PositionModule::allocReply()
{
if (precision == 0) {
LOG_DEBUG("Skipping location send because precision is set to 0!");
LOG_DEBUG("Skip location send because precision is set to 0!");
return nullptr;
}
@ -178,12 +177,12 @@ meshtastic_MeshPacket *PositionModule::allocReply()
localPosition.seq_number++;
if (localPosition.latitude_i == 0 && localPosition.longitude_i == 0) {
LOG_WARN("Skipping position send because lat/lon are zero!");
LOG_WARN("Skip position send because lat/lon are zero!");
return nullptr;
}
// lat/lon are unconditionally included - IF AVAILABLE!
LOG_DEBUG("Sending location with precision %i", precision);
LOG_DEBUG("Send location with precision %i", precision);
if (precision < 32 && precision > 0) {
p.latitude_i = localPosition.latitude_i & (UINT32_MAX << (32 - precision));
p.longitude_i = localPosition.longitude_i & (UINT32_MAX << (32 - precision));
@ -250,11 +249,11 @@ meshtastic_MeshPacket *PositionModule::allocReply()
// nodes shouldn't trust it anyways) Note: we allow a device with a local GPS or NTP to include the time, so that devices
// without can get time.
if (getRTCQuality() < RTCQualityNTP) {
LOG_INFO("Stripping time %u from position send", p.time);
LOG_INFO("Strip time %u from position send", p.time);
p.time = 0;
} else {
p.time = getValidTime(RTCQualityNTP);
LOG_INFO("Providing time to mesh %u", p.time);
LOG_INFO("Provide time to mesh %u", p.time);
}
LOG_INFO("Position reply: time=%i lat=%i lon=%i", p.time, p.latitude_i, p.longitude_i);
@ -268,7 +267,7 @@ meshtastic_MeshPacket *PositionModule::allocReply()
meshtastic_MeshPacket *PositionModule::allocAtakPli()
{
LOG_INFO("Sending TAK PLI packet");
LOG_INFO("Send TAK PLI packet");
meshtastic_MeshPacket *mp = allocDataPacket();
mp->decoded.portnum = meshtastic_PortNum_ATAK_PLUGIN;
@ -308,7 +307,7 @@ void PositionModule::sendOurPosition()
currentGeneration = radioGeneration;
// If we changed channels, ask everyone else for their latest info
LOG_INFO("Sending pos@%x:6 to mesh (wantReplies=%d)", localPosition.timestamp, requestReplies);
LOG_INFO("Send pos@%x:6 to mesh (wantReplies=%d)", localPosition.timestamp, requestReplies);
sendOurPosition(NODENUM_BROADCAST, requestReplies);
}
@ -351,7 +350,7 @@ void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t cha
if (IS_ONE_OF(config.device.role, meshtastic_Config_DeviceConfig_Role_TRACKER,
meshtastic_Config_DeviceConfig_Role_TAK_TRACKER) &&
config.power.is_power_saving) {
LOG_DEBUG("Starting next execution in 5 seconds and then going to sleep.");
LOG_DEBUG("Start next execution in 5s, then sleep");
sleepOnNextExecution = true;
setIntervalFromNow(5000);
}
@ -364,7 +363,7 @@ int32_t PositionModule::runOnce()
if (sleepOnNextExecution == true) {
sleepOnNextExecution = false;
uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(config.position.position_broadcast_secs);
LOG_DEBUG("Sleeping for %ims, then awaking to send position again.", nightyNightMs);
LOG_DEBUG("Sleep for %ims, then awaking to send position again", nightyNightMs);
doDeepSleep(nightyNightMs, false);
}
@ -407,7 +406,7 @@ int32_t PositionModule::runOnce()
if (smartPosition.hasTraveledOverThreshold &&
Throttle::execute(
&lastGpsSend, minimumTimeThreshold, []() { positionModule->sendOurPosition(); },
[]() { LOG_DEBUG("Skipping send smart broadcast due to time throttling"); })) {
[]() { LOG_DEBUG("Skip send smart broadcast due to time throttling"); })) {
LOG_DEBUG("Sent smart pos@%x:6 to mesh (distanceTraveled=%fm, minDistanceThreshold=%im, timeElapsed=%ims, "
"minTimeInterval=%ims)",
@ -449,23 +448,6 @@ struct SmartPosition PositionModule::getDistanceTraveledSinceLastSend(meshtastic
float distanceTraveledSinceLastSend = GeoCoord::latLongToMeter(
lastGpsLatitude * 1e-7, lastGpsLongitude * 1e-7, currentPosition.latitude_i * 1e-7, currentPosition.longitude_i * 1e-7);
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("--------LAST POSITION------------------------------------");
LOG_DEBUG("lastGpsLatitude=%i, lastGpsLatitude=%i", lastGpsLatitude, lastGpsLongitude);
LOG_DEBUG("--------CURRENT POSITION---------------------------------");
LOG_DEBUG("currentPosition.latitude_i=%i, currentPosition.longitude_i=%i", lastGpsLatitude, lastGpsLongitude);
LOG_DEBUG("--------SMART POSITION-----------------------------------");
LOG_DEBUG("hasTraveledOverThreshold=%i, distanceTraveled=%f, distanceThreshold=%f",
abs(distanceTraveledSinceLastSend) >= distanceTravelThreshold, abs(distanceTraveledSinceLastSend),
distanceTravelThreshold);
if (abs(distanceTraveledSinceLastSend) >= distanceTravelThreshold) {
LOG_DEBUG("SMART SEEEEEEEEENDING");
}
#endif
return SmartPosition{.distanceTraveled = abs(distanceTraveledSinceLastSend),
.distanceThreshold = distanceTravelThreshold,
.hasTraveledOverThreshold = abs(distanceTraveledSinceLastSend) >= distanceTravelThreshold};
@ -482,7 +464,7 @@ void PositionModule::handleNewPosition()
if (smartPosition.hasTraveledOverThreshold &&
Throttle::execute(
&lastGpsSend, minimumTimeThreshold, []() { positionModule->sendOurPosition(); },
[]() { LOG_DEBUG("Skipping send smart broadcast due to time throttling"); })) {
[]() { LOG_DEBUG("Skip send smart broadcast due to time throttling"); })) {
LOG_DEBUG("Sent smart pos@%x:6 to mesh (distanceTraveled=%fm, minDistanceThreshold=%im, timeElapsed=%ims, "
"minTimeInterval=%ims)",
localPosition.timestamp, smartPosition.distanceTraveled, smartPosition.distanceThreshold, msSinceLastSend,
@ -495,4 +477,4 @@ void PositionModule::handleNewPosition()
}
}
#endif
#endif

View File

@ -15,7 +15,7 @@ extern void printInfo();
PowerStressModule::PowerStressModule()
: ProtobufModule("powerstress", meshtastic_PortNum_POWERSTRESS_APP, &meshtastic_PowerStressMessage_msg),
concurrency::OSThread("PowerStressModule")
concurrency::OSThread("PowerStress")
{
}

View File

@ -24,7 +24,7 @@
RangeTestModule *rangeTestModule;
RangeTestModuleRadio *rangeTestModuleRadio;
RangeTestModule::RangeTestModule() : concurrency::OSThread("RangeTestModule") {}
RangeTestModule::RangeTestModule() : concurrency::OSThread("RangeTest") {}
uint32_t packetSequence = 0;
@ -54,11 +54,11 @@ int32_t RangeTestModule::runOnce()
firstTime = 0;
if (moduleConfig.range_test.sender) {
LOG_INFO("Initializing Range Test Module -- Sender");
LOG_INFO("Init Range Test Module -- Sender");
started = millis(); // make a note of when we started
return (5000); // Sending first message 5 seconds after initialization.
} else {
LOG_INFO("Initializing Range Test Module -- Receiver");
LOG_INFO("Init Range Test Module -- Receiver");
return disable();
// This thread does not need to run as a receiver
}
@ -81,7 +81,7 @@ int32_t RangeTestModule::runOnce()
// If we have been running for more than 8 hours, turn module back off
if (!Throttle::isWithinTimespanMs(started, 28800000)) {
LOG_INFO("Range Test Module - Disabling after 8 hours");
LOG_INFO("Range Test Module - Disable after 8 hours");
return disable();
} else {
return (senderHeartbeat);
@ -215,7 +215,7 @@ bool RangeTestModuleRadio::appendFile(const meshtastic_MeshPacket &mp)
}
if (FSCom.totalBytes() - FSCom.usedBytes() < 51200) {
LOG_DEBUG("Filesystem doesn't have enough free space. Aborting write.");
LOG_DEBUG("Filesystem doesn't have enough free space. Aborting write");
return 0;
}
@ -292,4 +292,4 @@ bool RangeTestModuleRadio::appendFile(const meshtastic_MeshPacket &mp)
#endif
return 1;
}
}

View File

@ -64,7 +64,7 @@ static uint64_t digitalReads(uint64_t mask, uint64_t maskAvailable)
RemoteHardwareModule::RemoteHardwareModule()
: ProtobufModule("remotehardware", meshtastic_PortNum_REMOTE_HARDWARE_APP, &meshtastic_HardwareMessage_msg),
concurrency::OSThread("RemoteHardwareModule")
concurrency::OSThread("RemoteHardware")
{
// restrict to the gpio channel for rx
boundChannel = Channels::gpioChannel;
@ -149,7 +149,7 @@ int32_t RemoteHardwareModule::runOnce()
if (curVal != previousWatch) {
previousWatch = curVal;
LOG_INFO("Broadcasting GPIOS 0x%llx changed!", curVal);
LOG_INFO("Broadcast GPIOS 0x%llx changed!", curVal);
// Something changed! Tell the world with a broadcast message
meshtastic_HardwareMessage r = meshtastic_HardwareMessage_init_default;

View File

@ -15,7 +15,7 @@ meshtastic_MeshPacket *ReplyModule::allocReply()
LOG_INFO("Received message from=0x%0x, id=%d, msg=%.*s", req.from, req.id, p.payload.size, p.payload.bytes);
#endif
screen->print("Sending reply\n");
screen->print("Send reply\n");
const char *replyStr = "Message Received";
auto reply = allocDataPacket(); // Allocate a packet for sending

View File

@ -61,13 +61,13 @@ SerialModule *serialModule;
SerialModuleRadio *serialModuleRadio;
#if defined(TTGO_T_ECHO) || defined(CANARYONE)
SerialModule::SerialModule() : StreamAPI(&Serial), concurrency::OSThread("SerialModule") {}
SerialModule::SerialModule() : StreamAPI(&Serial), concurrency::OSThread("Serial") {}
static Print *serialPrint = &Serial;
#elif defined(CONFIG_IDF_TARGET_ESP32C6)
SerialModule::SerialModule() : StreamAPI(&Serial1), concurrency::OSThread("SerialModule") {}
SerialModule::SerialModule() : StreamAPI(&Serial1), concurrency::OSThread("Serial") {}
static Print *serialPrint = &Serial1;
#else
SerialModule::SerialModule() : StreamAPI(&Serial2), concurrency::OSThread("SerialModule") {}
SerialModule::SerialModule() : StreamAPI(&Serial2), concurrency::OSThread("Serial") {}
static Print *serialPrint = &Serial2;
#endif
@ -125,7 +125,7 @@ int32_t SerialModule::runOnce()
if (moduleConfig.serial.override_console_serial_port || (moduleConfig.serial.rxd && moduleConfig.serial.txd)) {
if (firstTime) {
// Interface with the serial peripheral from in here.
LOG_INFO("Initializing serial peripheral interface");
LOG_INFO("Init serial peripheral interface");
uint32_t baud = getBaudRate();

View File

@ -46,7 +46,7 @@ int32_t StoreForwardModule::runOnce()
} else if (this->heartbeat && (!Throttle::isWithinTimespanMs(lastHeartbeat, heartbeatInterval * 1000)) &&
airTime->isTxAllowedChannelUtil(true)) {
lastHeartbeat = millis();
LOG_INFO("Sending heartbeat");
LOG_INFO("Send heartbeat");
meshtastic_StoreAndForward sf = meshtastic_StoreAndForward_init_zero;
sf.rr = meshtastic_StoreAndForward_RequestResponse_ROUTER_HEARTBEAT;
sf.which_variant = meshtastic_StoreAndForward_heartbeat_tag;
@ -105,7 +105,7 @@ void StoreForwardModule::historySend(uint32_t secAgo, uint32_t to)
queueSize = this->historyReturnMax;
if (queueSize) {
LOG_INFO("S&F - Sending %u message(s)", queueSize);
LOG_INFO("S&F - Send %u message(s)", queueSize);
this->busy = true; // runOnce() will pickup the next steps once busy = true.
this->busyTo = to;
} else {
@ -187,7 +187,7 @@ void StoreForwardModule::historyAdd(const meshtastic_MeshPacket &mp)
const auto &p = mp.decoded;
if (this->packetHistoryTotalCount == this->records) {
LOG_WARN("S&F - PSRAM Full. Starting overwrite.");
LOG_WARN("S&F - PSRAM Full. Starting overwrite");
this->packetHistoryTotalCount = 0;
for (auto &i : lastRequest) {
i.second = 0; // Clear the last request index for each client device
@ -215,7 +215,7 @@ bool StoreForwardModule::sendPayload(NodeNum dest, uint32_t last_time)
{
meshtastic_MeshPacket *p = preparePayload(dest, last_time);
if (p) {
LOG_INFO("Sending S&F Payload");
LOG_INFO("Send S&F Payload");
service->sendToMesh(p);
this->requestCount++;
return true;
@ -365,7 +365,7 @@ void StoreForwardModule::statsSend(uint32_t to)
sf.variant.stats.return_max = this->historyReturnMax;
sf.variant.stats.return_window = this->historyReturnWindow;
LOG_DEBUG("Sending S&F Stats");
LOG_DEBUG("Send S&F Stats");
storeForwardModule->sendMessage(to, sf);
}
@ -393,7 +393,7 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m
}
} else {
storeForwardModule->historyAdd(mp);
LOG_INFO("S&F stored. Message history contains %u records now.", this->packetHistoryTotalCount);
LOG_INFO("S&F stored. Message history contains %u records now", this->packetHistoryTotalCount);
}
} else if (!isFromUs(&mp) && mp.decoded.portnum == meshtastic_PortNum_STORE_FORWARD_APP) {
auto &p = mp.decoded;
@ -403,7 +403,7 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m
if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, &meshtastic_StoreAndForward_msg, &scratch)) {
decoded = &scratch;
} else {
LOG_ERROR("Error decoding protobuf module!");
LOG_ERROR("Error decoding proto module!");
// if we can't decode it, nobody can process it!
return ProcessMessage::STOP;
}
@ -482,7 +482,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp,
LOG_INFO("Client Request to send STATS");
if (this->busy) {
storeForwardModule->sendMessage(getFrom(&mp), meshtastic_StoreAndForward_RequestResponse_ROUTER_BUSY);
LOG_INFO("S&F - Busy. Try again shortly.");
LOG_INFO("S&F - Busy. Try again shortly");
} else {
storeForwardModule->statsSend(getFrom(&mp));
}
@ -552,7 +552,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp,
}
StoreForwardModule::StoreForwardModule()
: concurrency::OSThread("StoreForwardModule"),
: concurrency::OSThread("StoreForward"),
ProtobufModule("StoreForward", meshtastic_PortNum_STORE_FORWARD_APP, &meshtastic_StoreAndForward_msg)
{
@ -573,7 +573,7 @@ StoreForwardModule::StoreForwardModule()
// Router
if ((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER || moduleConfig.store_forward.is_server)) {
LOG_INFO("Initializing Store & Forward Module in Server mode");
LOG_INFO("Init Store & Forward Module in Server mode");
if (memGet.getPsramSize() > 0) {
if (memGet.getFreePsram() >= 1024 * 1024) {
@ -602,19 +602,19 @@ StoreForwardModule::StoreForwardModule()
is_server = true;
} else {
LOG_INFO(".");
LOG_INFO("S&F: not enough PSRAM free, disabling.");
LOG_INFO("S&F: not enough PSRAM free, Disable");
}
} else {
LOG_INFO("S&F: device doesn't have PSRAM, disabling.");
LOG_INFO("S&F: device doesn't have PSRAM, Disable");
}
// Client
} else {
is_client = true;
LOG_INFO("Initializing Store & Forward Module in Client mode");
LOG_INFO("Init Store & Forward Module in Client mode");
}
} else {
disable();
}
#endif
}
}

View File

@ -33,10 +33,10 @@ int32_t AirQualityTelemetryModule::runOnce()
firstTime = false;
if (moduleConfig.telemetry.air_quality_enabled) {
LOG_INFO("Air quality Telemetry: Initializing");
LOG_INFO("Air quality Telemetry: init");
if (!aqi.begin_I2C()) {
#ifndef I2C_NO_RESCAN
LOG_WARN("Could not establish i2c connection to AQI sensor. Rescanning...");
LOG_WARN("Could not establish i2c connection to AQI sensor. Rescan");
// rescan for late arriving sensors. AQI Module starts about 10 seconds into the boot so this is plenty.
uint8_t i2caddr_scan[] = {PMSA0031_ADDR};
uint8_t i2caddr_asize = 1;
@ -107,7 +107,7 @@ bool AirQualityTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPack
bool AirQualityTelemetryModule::getAirQualityTelemetry(meshtastic_Telemetry *m)
{
if (!aqi.read(&data)) {
LOG_WARN("Skipping send measurements. Could not read AQIn");
LOG_WARN("Skip send measurements. Could not read AQIn");
return false;
}
@ -121,9 +121,8 @@ bool AirQualityTelemetryModule::getAirQualityTelemetry(meshtastic_Telemetry *m)
m->variant.air_quality_metrics.pm25_environmental = data.pm25_env;
m->variant.air_quality_metrics.pm100_environmental = data.pm100_env;
LOG_INFO("(Sending): PM1.0(Standard)=%i, PM2.5(Standard)=%i, PM10.0(Standard)=%i",
m->variant.air_quality_metrics.pm10_standard, m->variant.air_quality_metrics.pm25_standard,
m->variant.air_quality_metrics.pm100_standard);
LOG_INFO("Send: PM1.0(Standard)=%i, PM2.5(Standard)=%i, PM10.0(Standard)=%i", m->variant.air_quality_metrics.pm10_standard,
m->variant.air_quality_metrics.pm25_standard, m->variant.air_quality_metrics.pm100_standard);
LOG_INFO(" | PM1.0(Environmental)=%i, PM2.5(Environmental)=%i, PM10.0(Environmental)=%i",
m->variant.air_quality_metrics.pm10_environmental, m->variant.air_quality_metrics.pm25_environmental,
@ -150,7 +149,7 @@ meshtastic_MeshPacket *AirQualityTelemetryModule::allocReply()
if (decoded->which_variant == meshtastic_Telemetry_air_quality_metrics_tag) {
meshtastic_Telemetry m = meshtastic_Telemetry_init_zero;
if (getAirQualityTelemetry(&m)) {
LOG_INFO("Air quality telemetry replying to request");
LOG_INFO("Air quality telemetry reply to request");
return allocDataProtobuf(m);
} else {
return NULL;
@ -178,10 +177,10 @@ bool AirQualityTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
lastMeasurementPacket = packetPool.allocCopy(*p);
if (phoneOnly) {
LOG_INFO("Sending packet to phone");
LOG_INFO("Send packet to phone");
service->sendToPhone(p);
} else {
LOG_INFO("Sending packet to mesh");
LOG_INFO("Send packet to mesh");
service->sendToMesh(p, RX_SRC_LOCAL, true);
}
return true;

View File

@ -16,7 +16,7 @@ class AirQualityTelemetryModule : private concurrency::OSThread, public Protobuf
public:
AirQualityTelemetryModule()
: concurrency::OSThread("AirQualityTelemetryModule"),
: concurrency::OSThread("AirQualityTelemetry"),
ProtobufModule("AirQualityTelemetry", meshtastic_PortNum_TELEMETRY_APP, &meshtastic_Telemetry_msg)
{
lastMeasurementPacket = nullptr;

View File

@ -76,7 +76,7 @@ meshtastic_MeshPacket *DeviceTelemetryModule::allocReply()
}
// Check for a request for device metrics
if (decoded->which_variant == meshtastic_Telemetry_device_metrics_tag) {
LOG_INFO("Device telemetry replying to request");
LOG_INFO("Device telemetry reply to request");
meshtastic_Telemetry telemetry = getDeviceTelemetry();
return allocDataProtobuf(telemetry);
@ -134,7 +134,7 @@ void DeviceTelemetryModule::sendLocalStatsToPhone()
telemetry.variant.local_stats.num_tx_relay_canceled = router->txRelayCanceled;
}
LOG_INFO("(Sending local stats): uptime=%i, channel_utilization=%f, air_util_tx=%f, num_online_nodes=%i, num_total_nodes=%i",
LOG_INFO("Sending local stats: uptime=%i, channel_utilization=%f, air_util_tx=%f, num_online_nodes=%i, num_total_nodes=%i",
telemetry.variant.local_stats.uptime_seconds, telemetry.variant.local_stats.channel_utilization,
telemetry.variant.local_stats.air_util_tx, telemetry.variant.local_stats.num_online_nodes,
telemetry.variant.local_stats.num_total_nodes);
@ -153,7 +153,7 @@ void DeviceTelemetryModule::sendLocalStatsToPhone()
bool DeviceTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
{
meshtastic_Telemetry telemetry = getDeviceTelemetry();
LOG_INFO("(Sending): air_util_tx=%f, channel_utilization=%f, battery_level=%i, voltage=%f, uptime=%i",
LOG_INFO("Send: air_util_tx=%f, channel_utilization=%f, battery_level=%i, voltage=%f, uptime=%i",
telemetry.variant.device_metrics.air_util_tx, telemetry.variant.device_metrics.channel_utilization,
telemetry.variant.device_metrics.battery_level, telemetry.variant.device_metrics.voltage,
telemetry.variant.device_metrics.uptime_seconds);
@ -165,10 +165,10 @@ bool DeviceTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
nodeDB->updateTelemetry(nodeDB->getNodeNum(), telemetry, RX_SRC_LOCAL);
if (phoneOnly) {
LOG_INFO("Sending packet to phone");
LOG_INFO("Send packet to phone");
service->sendToPhone(p);
} else {
LOG_INFO("Sending packet to mesh");
LOG_INFO("Send packet to mesh");
service->sendToMesh(p, RX_SRC_LOCAL, true);
}
return true;

View File

@ -12,7 +12,7 @@ class DeviceTelemetryModule : private concurrency::OSThread, public ProtobufModu
public:
DeviceTelemetryModule()
: concurrency::OSThread("DeviceTelemetryModule"),
: concurrency::OSThread("DeviceTelemetry"),
ProtobufModule("DeviceTelemetry", meshtastic_PortNum_TELEMETRY_APP, &meshtastic_Telemetry_msg)
{
uptimeWrapCount = 0;

View File

@ -73,7 +73,7 @@ int32_t EnvironmentTelemetryModule::runOnce()
sleepOnNextExecution = false;
uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval,
default_telemetry_broadcast_interval_secs);
LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.", nightyNightMs);
LOG_DEBUG("Sleep for %ims, then awake to send metrics again", nightyNightMs);
doDeepSleep(nightyNightMs, true);
}
@ -97,7 +97,7 @@ int32_t EnvironmentTelemetryModule::runOnce()
firstTime = 0;
if (moduleConfig.telemetry.environment_measurement_enabled) {
LOG_INFO("Environment Telemetry: Initializing");
LOG_INFO("Environment Telemetry: init");
// 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
#ifdef T1000X_SENSOR_EN
@ -411,7 +411,7 @@ meshtastic_MeshPacket *EnvironmentTelemetryModule::allocReply()
if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) {
meshtastic_Telemetry m = meshtastic_Telemetry_init_zero;
if (getEnvironmentTelemetry(&m)) {
LOG_INFO("Environment telemetry replying to request");
LOG_INFO("Environment telemetry reply to request");
return allocDataProtobuf(m);
} else {
return NULL;
@ -431,14 +431,14 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
#else
if (getEnvironmentTelemetry(&m)) {
#endif
LOG_INFO("(Sending): barometric_pressure=%f, current=%f, gas_resistance=%f, relative_humidity=%f, temperature=%f",
LOG_INFO("Send: barometric_pressure=%f, current=%f, gas_resistance=%f, relative_humidity=%f, temperature=%f",
m.variant.environment_metrics.barometric_pressure, m.variant.environment_metrics.current,
m.variant.environment_metrics.gas_resistance, m.variant.environment_metrics.relative_humidity,
m.variant.environment_metrics.temperature);
LOG_INFO("(Sending): voltage=%f, IAQ=%d, distance=%f, lux=%f", m.variant.environment_metrics.voltage,
LOG_INFO("Send: voltage=%f, IAQ=%d, distance=%f, lux=%f", m.variant.environment_metrics.voltage,
m.variant.environment_metrics.iaq, m.variant.environment_metrics.distance, m.variant.environment_metrics.lux);
LOG_INFO("(Sending): wind speed=%fm/s, direction=%d degrees, weight=%fkg", m.variant.environment_metrics.wind_speed,
LOG_INFO("Send: wind speed=%fm/s, direction=%d degrees, weight=%fkg", m.variant.environment_metrics.wind_speed,
m.variant.environment_metrics.wind_direction, m.variant.environment_metrics.weight);
sensor_read_error_count = 0;
@ -456,14 +456,14 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
lastMeasurementPacket = packetPool.allocCopy(*p);
if (phoneOnly) {
LOG_INFO("Sending packet to phone");
LOG_INFO("Send packet to phone");
service->sendToPhone(p);
} else {
LOG_INFO("Sending packet to mesh");
LOG_INFO("Send packet to mesh");
service->sendToMesh(p, RX_SRC_LOCAL, true);
if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR && config.power.is_power_saving) {
LOG_DEBUG("Starting next execution in 5 seconds and then going to sleep.");
LOG_DEBUG("Start next execution in 5s, then sleep");
sleepOnNextExecution = true;
setIntervalFromNow(5000);
}
@ -586,4 +586,4 @@ AdminMessageHandleResult EnvironmentTelemetryModule::handleAdminMessageForModule
return result;
}
#endif
#endif

View File

@ -17,7 +17,7 @@ class EnvironmentTelemetryModule : private concurrency::OSThread, public Protobu
public:
EnvironmentTelemetryModule()
: concurrency::OSThread("EnvironmentTelemetryModule"),
: concurrency::OSThread("EnvironmentTelemetry"),
ProtobufModule("EnvironmentTelemetry", meshtastic_PortNum_TELEMETRY_APP, &meshtastic_Telemetry_msg)
{
lastMeasurementPacket = nullptr;

View File

@ -39,7 +39,7 @@ int32_t HealthTelemetryModule::runOnce()
sleepOnNextExecution = false;
uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.health_update_interval,
default_telemetry_broadcast_interval_secs);
LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.", nightyNightMs);
LOG_DEBUG("Sleep for %ims, then awake to send metrics again", nightyNightMs);
doDeepSleep(nightyNightMs, true);
}
@ -55,7 +55,7 @@ int32_t HealthTelemetryModule::runOnce()
firstTime = false;
if (moduleConfig.telemetry.health_measurement_enabled) {
LOG_INFO("Health Telemetry: Initializing");
LOG_INFO("Health Telemetry: init");
// Initialize sensors
if (mlx90614Sensor.hasSensor())
result = mlx90614Sensor.runOnce();
@ -195,7 +195,7 @@ meshtastic_MeshPacket *HealthTelemetryModule::allocReply()
if (decoded->which_variant == meshtastic_Telemetry_health_metrics_tag) {
meshtastic_Telemetry m = meshtastic_Telemetry_init_zero;
if (getHealthTelemetry(&m)) {
LOG_INFO("Health telemetry replying to request");
LOG_INFO("Health telemetry reply to request");
return allocDataProtobuf(m);
} else {
return NULL;
@ -211,7 +211,7 @@ bool HealthTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
m.which_variant = meshtastic_Telemetry_health_metrics_tag;
m.time = getTime();
if (getHealthTelemetry(&m)) {
LOG_INFO("(Sending): temperature=%f, heart_bpm=%d, spO2=%d", m.variant.health_metrics.temperature,
LOG_INFO("Send: temperature=%f, heart_bpm=%d, spO2=%d", m.variant.health_metrics.temperature,
m.variant.health_metrics.heart_bpm, m.variant.health_metrics.spO2);
sensor_read_error_count = 0;
@ -229,14 +229,14 @@ bool HealthTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
lastMeasurementPacket = packetPool.allocCopy(*p);
if (phoneOnly) {
LOG_INFO("Sending packet to phone");
LOG_INFO("Send packet to phone");
service->sendToPhone(p);
} else {
LOG_INFO("Sending packet to mesh");
LOG_INFO("Send packet to mesh");
service->sendToMesh(p, RX_SRC_LOCAL, true);
if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR && config.power.is_power_saving) {
LOG_DEBUG("Starting next execution in 5 seconds and then going to sleep.");
LOG_DEBUG("Start next execution in 5s, then sleep");
sleepOnNextExecution = true;
setIntervalFromNow(5000);
}

View File

@ -16,7 +16,7 @@ class HealthTelemetryModule : private concurrency::OSThread, public ProtobufModu
public:
HealthTelemetryModule()
: concurrency::OSThread("HealthTelemetryModule"),
: concurrency::OSThread("HealthTelemetry"),
ProtobufModule("HealthTelemetry", meshtastic_PortNum_TELEMETRY_APP, &meshtastic_Telemetry_msg)
{
lastMeasurementPacket = nullptr;

View File

@ -27,7 +27,7 @@ int32_t PowerTelemetryModule::runOnce()
sleepOnNextExecution = false;
uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval,
default_telemetry_broadcast_interval_secs);
LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.", nightyNightMs);
LOG_DEBUG("Sleep for %ims, then awake to send metrics again", nightyNightMs);
doDeepSleep(nightyNightMs, true);
}
@ -51,7 +51,7 @@ int32_t PowerTelemetryModule::runOnce()
firstTime = 0;
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
if (moduleConfig.telemetry.power_measurement_enabled) {
LOG_INFO("Power Telemetry: Initializing");
LOG_INFO("Power Telemetry: init");
// 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
if (ina219Sensor.hasSensor() && !ina219Sensor.isInitialized())
@ -199,7 +199,7 @@ meshtastic_MeshPacket *PowerTelemetryModule::allocReply()
if (decoded->which_variant == meshtastic_Telemetry_power_metrics_tag) {
meshtastic_Telemetry m = meshtastic_Telemetry_init_zero;
if (getPowerTelemetry(&m)) {
LOG_INFO("Power telemetry replying to request");
LOG_INFO("Power telemetry reply to request");
return allocDataProtobuf(m);
} else {
return NULL;
@ -216,7 +216,7 @@ bool PowerTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
m.which_variant = meshtastic_Telemetry_power_metrics_tag;
m.time = getTime();
if (getPowerTelemetry(&m)) {
LOG_INFO("(Sending): ch1_voltage=%f, ch1_current=%f, ch2_voltage=%f, ch2_current=%f, "
LOG_INFO("Send: ch1_voltage=%f, ch1_current=%f, ch2_voltage=%f, ch2_current=%f, "
"ch3_voltage=%f, ch3_current=%f",
m.variant.power_metrics.ch1_voltage, m.variant.power_metrics.ch1_current, m.variant.power_metrics.ch2_voltage,
m.variant.power_metrics.ch2_current, m.variant.power_metrics.ch3_voltage, m.variant.power_metrics.ch3_current);
@ -236,14 +236,14 @@ bool PowerTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
lastMeasurementPacket = packetPool.allocCopy(*p);
if (phoneOnly) {
LOG_INFO("Sending packet to phone");
LOG_INFO("Send packet to phone");
service->sendToPhone(p);
} else {
LOG_INFO("Sending packet to mesh");
LOG_INFO("Send packet to mesh");
service->sendToMesh(p, RX_SRC_LOCAL, true);
if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR && config.power.is_power_saving) {
LOG_DEBUG("Starting next execution in 5s then going to sleep.");
LOG_DEBUG("Start next execution in 5s then sleep");
sleepOnNextExecution = true;
setIntervalFromNow(5000);
}

View File

@ -17,7 +17,7 @@ class PowerTelemetryModule : private concurrency::OSThread, public ProtobufModul
public:
PowerTelemetryModule()
: concurrency::OSThread("PowerTelemetryModule"),
: concurrency::OSThread("PowerTelemetry"),
ProtobufModule("PowerTelemetry", meshtastic_PortNum_TELEMETRY_APP, &meshtastic_Telemetry_msg)
{
lastMeasurementPacket = nullptr;

View File

@ -27,7 +27,7 @@ void AHT10Sensor::setup() {}
bool AHT10Sensor::getMetrics(meshtastic_Telemetry *measurement)
{
LOG_DEBUG("AHT10Sensor::getMetrics");
LOG_DEBUG("AHT10 getMetrics");
sensors_event_t humidity, temp;
aht10.getEvent(&humidity, &temp);

View File

@ -35,7 +35,7 @@ bool BME280Sensor::getMetrics(meshtastic_Telemetry *measurement)
measurement->variant.environment_metrics.has_relative_humidity = true;
measurement->variant.environment_metrics.has_barometric_pressure = true;
LOG_DEBUG("BME280Sensor::getMetrics");
LOG_DEBUG("BME280 getMetrics");
bme280.takeForcedMeasurement();
measurement->variant.environment_metrics.temperature = bme280.readTemperature();
measurement->variant.environment_metrics.relative_humidity = bme280.readHumidity();

View File

@ -80,9 +80,9 @@ void BME680Sensor::loadState()
file.read((uint8_t *)&bsecState, BSEC_MAX_STATE_BLOB_SIZE);
file.close();
bme680.setState(bsecState);
LOG_INFO("%s state read from %s.", sensorName, bsecConfigFileName);
LOG_INFO("%s state read from %s", sensorName, bsecConfigFileName);
} else {
LOG_INFO("No %s state found (File: %s).", sensorName, bsecConfigFileName);
LOG_INFO("No %s state found (File: %s)", sensorName, bsecConfigFileName);
}
#else
LOG_ERROR("ERROR: Filesystem not implemented");
@ -119,12 +119,12 @@ void BME680Sensor::updateState()
}
auto file = FSCom.open(bsecConfigFileName, FILE_O_WRITE);
if (file) {
LOG_INFO("%s state write to %s.", sensorName, bsecConfigFileName);
LOG_INFO("%s state write to %s", sensorName, bsecConfigFileName);
file.write((uint8_t *)&bsecState, BSEC_MAX_STATE_BLOB_SIZE);
file.flush();
file.close();
} else {
LOG_INFO("Can't write %s state (File: %s).", sensorName, bsecConfigFileName);
LOG_INFO("Can't write %s state (File: %s)", sensorName, bsecConfigFileName);
}
}
#else
@ -145,4 +145,4 @@ void BME680Sensor::checkStatus(String functionName)
LOG_WARN("%s BME68X code: %s", functionName.c_str(), String(bme680.sensor.status).c_str());
}
#endif
#endif

View File

@ -29,7 +29,7 @@ bool BMP085Sensor::getMetrics(meshtastic_Telemetry *measurement)
measurement->variant.environment_metrics.has_temperature = true;
measurement->variant.environment_metrics.has_barometric_pressure = true;
LOG_DEBUG("BMP085Sensor::getMetrics");
LOG_DEBUG("BMP085 getMetrics");
measurement->variant.environment_metrics.temperature = bmp085.readTemperature();
measurement->variant.environment_metrics.barometric_pressure = bmp085.readPressure() / 100.0F;

View File

@ -34,7 +34,7 @@ bool BMP280Sensor::getMetrics(meshtastic_Telemetry *measurement)
measurement->variant.environment_metrics.has_temperature = true;
measurement->variant.environment_metrics.has_barometric_pressure = true;
LOG_DEBUG("BMP280Sensor::getMetrics");
LOG_DEBUG("BMP280 getMetrics");
bmp280.takeForcedMeasurement();
measurement->variant.environment_metrics.temperature = bmp280.readTemperature();
measurement->variant.environment_metrics.barometric_pressure = bmp280.readPressure() / 100.0F;

View File

@ -50,11 +50,11 @@ bool BMP3XXSensor::getMetrics(meshtastic_Telemetry *measurement)
measurement->variant.environment_metrics.barometric_pressure = static_cast<float>(bmp3xx->pressure) / 100.0F;
measurement->variant.environment_metrics.relative_humidity = 0.0f;
LOG_DEBUG("BMP3XXSensor::getMetrics id: %i temp: %.1f press %.1f", measurement->which_variant,
LOG_DEBUG("BMP3XX getMetrics id: %i temp: %.1f press %.1f", measurement->which_variant,
measurement->variant.environment_metrics.temperature,
measurement->variant.environment_metrics.barometric_pressure);
} else {
LOG_DEBUG("BMP3XXSensor::getMetrics id: %i", measurement->which_variant);
LOG_DEBUG("BMP3XX getMetrics id: %i", measurement->which_variant);
}
return true;
}

View File

@ -27,7 +27,7 @@ bool MAX17048Singleton::isBatteryCharging()
{
float volts = cellVoltage();
if (isnan(volts)) {
LOG_DEBUG("%s::isBatteryCharging is not connected", sensorStr);
LOG_DEBUG("%s::isBatteryCharging not connected", sensorStr);
return 0;
}
@ -140,11 +140,11 @@ void MAX17048Sensor::setup() {}
bool MAX17048Sensor::getMetrics(meshtastic_Telemetry *measurement)
{
LOG_DEBUG("MAX17048Sensor::getMetrics id: %i", measurement->which_variant);
LOG_DEBUG("MAX17048 getMetrics id: %i", measurement->which_variant);
float volts = max17048->cellVoltage();
if (isnan(volts)) {
LOG_DEBUG("MAX17048Sensor::getMetrics battery is not connected");
LOG_DEBUG("MAX17048 getMetrics battery is not connected");
return false;
}
@ -153,7 +153,7 @@ bool MAX17048Sensor::getMetrics(meshtastic_Telemetry *measurement)
soc = clamp(soc, 0.0f, 100.0f); // clamp soc between 0 and 100%
float ttg = (100.0f - soc) / rate; // calculate hours to charge/discharge
LOG_DEBUG("MAX17048Sensor::getMetrics volts: %.3fV soc: %.1f%% ttg: %.1f hours", volts, soc, ttg);
LOG_DEBUG("MAX17048 getMetrics volts: %.3fV soc: %.1f%% ttg: %.1f hours", volts, soc, ttg);
if ((int)measurement->which_variant == meshtastic_Telemetry_power_metrics_tag) {
measurement->variant.power_metrics.has_ch1_voltage = true;
measurement->variant.power_metrics.ch1_voltage = volts;

View File

@ -28,7 +28,7 @@ bool MCP9808Sensor::getMetrics(meshtastic_Telemetry *measurement)
{
measurement->variant.environment_metrics.has_temperature = true;
LOG_DEBUG("MCP9808Sensor::getMetrics");
LOG_DEBUG("MCP9808 getMetrics");
measurement->variant.environment_metrics.temperature = mcp9808.readTempC();
return true;
}

View File

@ -19,7 +19,7 @@ int32_t MLX90614Sensor::runOnce()
LOG_DEBUG("MLX90614 emissivity: %f", mlx.readEmissivity());
if (fabs(MLX90614_EMISSIVITY - mlx.readEmissivity()) > 0.001) {
mlx.writeEmissivity(MLX90614_EMISSIVITY);
LOG_INFO("MLX90614 emissivity updated. In case of weird data, power cycle.");
LOG_INFO("MLX90614 emissivity updated. In case of weird data, power cycle");
}
LOG_DEBUG("MLX90614 Init Succeed");
status = true;

View File

@ -35,7 +35,7 @@ void NAU7802Sensor::setup() {}
bool NAU7802Sensor::getMetrics(meshtastic_Telemetry *measurement)
{
LOG_DEBUG("NAU7802Sensor::getMetrics");
LOG_DEBUG("NAU7802 getMetrics");
nau7802.powerUp();
// Wait for the sensor to become ready for one second max
uint32_t start = millis();
@ -103,7 +103,7 @@ bool NAU7802Sensor::saveCalibrationData()
nau7802config.calibrationFactor = nau7802.getCalibrationFactor();
bool okay = false;
LOG_INFO("%s state write to %s.", sensorName, nau7802ConfigFileName);
LOG_INFO("%s state write to %s", sensorName, nau7802ConfigFileName);
pb_ostream_t stream = {&writecb, static_cast<Print *>(&file), meshtastic_Nau7802Config_size};
if (!pb_encode(&stream, &meshtastic_Nau7802Config_msg, &nau7802config)) {
@ -121,7 +121,7 @@ bool NAU7802Sensor::loadCalibrationData()
auto file = FSCom.open(nau7802ConfigFileName, FILE_O_READ);
bool okay = false;
if (file) {
LOG_INFO("%s state read from %s.", sensorName, nau7802ConfigFileName);
LOG_INFO("%s state read from %s", sensorName, nau7802ConfigFileName);
pb_istream_t stream = {&readcb, &file, meshtastic_Nau7802Config_size};
if (!pb_decode(&stream, &meshtastic_Nau7802Config_msg, &nau7802config)) {
LOG_ERROR("Error: can't decode protobuf %s", PB_GET_ERROR(&stream));
@ -132,9 +132,9 @@ bool NAU7802Sensor::loadCalibrationData()
}
file.close();
} else {
LOG_INFO("No %s state found (File: %s).", sensorName, nau7802ConfigFileName);
LOG_INFO("No %s state found (File: %s)", sensorName, nau7802ConfigFileName);
}
return okay;
}
#endif
#endif

View File

@ -24,7 +24,7 @@ void RCWL9620Sensor::setup() {}
bool RCWL9620Sensor::getMetrics(meshtastic_Telemetry *measurement)
{
measurement->variant.environment_metrics.has_distance = true;
LOG_DEBUG("RCWL9620Sensor::getMetrics");
LOG_DEBUG("RCWL9620 getMetrics");
measurement->variant.environment_metrics.distance = getDistance();
return true;
}

View File

@ -31,7 +31,7 @@ class TelemetrySensor
int32_t initI2CSensor()
{
if (!status) {
LOG_WARN("Could not connect to detected %s sensor. Removing from nodeTelemetrySensorsMap.", sensorName);
LOG_WARN("Could not connect to detected %s sensor. Remove from nodeTelemetrySensorsMap.", sensorName);
nodeTelemetrySensorsMap[sensorType].first = 0;
} else {
LOG_INFO("Opened %s sensor on i2c bus", sensorName);

View File

@ -46,7 +46,7 @@ void run_codec2(void *parameter)
// 4 bytes of header in each frame hex c0 de c2 plus the bitrate
memcpy(audioModule->tx_encode_frame, &audioModule->tx_header, sizeof(audioModule->tx_header));
LOG_INFO("Starting codec2 task");
LOG_INFO("Start codec2 task");
while (true) {
uint32_t tcount = ulTaskNotifyTake(pdFALSE, pdMS_TO_TICKS(10000));
@ -61,7 +61,7 @@ void run_codec2(void *parameter)
audioModule->tx_encode_frame_index += audioModule->encode_codec_size;
if (audioModule->tx_encode_frame_index == (audioModule->encode_frame_size + sizeof(audioModule->tx_header))) {
LOG_INFO("Sending %d codec2 bytes", audioModule->encode_frame_size);
LOG_INFO("Send %d codec2 bytes", audioModule->encode_frame_size);
audioModule->sendPayload();
audioModule->tx_encode_frame_index = sizeof(audioModule->tx_header);
}
@ -91,7 +91,7 @@ void run_codec2(void *parameter)
}
}
AudioModule::AudioModule() : SinglePortModule("AudioModule", meshtastic_PortNum_AUDIO_APP), concurrency::OSThread("AudioModule")
AudioModule::AudioModule() : SinglePortModule("Audio", meshtastic_PortNum_AUDIO_APP), concurrency::OSThread("Audio")
{
// moduleConfig.audio.codec2_enabled = true;
// moduleConfig.audio.i2s_ws = 13;
@ -101,8 +101,7 @@ AudioModule::AudioModule() : SinglePortModule("AudioModule", meshtastic_PortNum_
// moduleConfig.audio.ptt_pin = 39;
if ((moduleConfig.audio.codec2_enabled) && (myRegion->audioPermitted)) {
LOG_INFO("Setting up codec2 in mode %u",
(moduleConfig.audio.bitrate ? moduleConfig.audio.bitrate : AUDIO_MODULE_MODE) - 1);
LOG_INFO("Set up codec2 in mode %u", (moduleConfig.audio.bitrate ? moduleConfig.audio.bitrate : AUDIO_MODULE_MODE) - 1);
codec2 = codec2_create((moduleConfig.audio.bitrate ? moduleConfig.audio.bitrate : AUDIO_MODULE_MODE) - 1);
memcpy(tx_header.magic, c2_magic, sizeof(c2_magic));
tx_header.mode = (moduleConfig.audio.bitrate ? moduleConfig.audio.bitrate : AUDIO_MODULE_MODE) - 1;
@ -111,7 +110,7 @@ AudioModule::AudioModule() : SinglePortModule("AudioModule", meshtastic_PortNum_
encode_frame_num = (meshtastic_Constants_DATA_PAYLOAD_LEN - sizeof(tx_header)) / encode_codec_size;
encode_frame_size = encode_frame_num * encode_codec_size; // max 233 bytes + 4 header bytes
adc_buffer_size = codec2_samples_per_frame(codec2);
LOG_INFO("using %d frames of %d bytes for a total payload length of %d bytes", encode_frame_num, encode_codec_size,
LOG_INFO("Use %d frames of %d bytes for a total payload length of %d bytes", encode_frame_num, encode_codec_size,
encode_frame_size);
xTaskCreate(&run_codec2, "codec2_task", 30000, NULL, 5, &codec2HandlerTask);
} else {
@ -148,7 +147,7 @@ int32_t AudioModule::runOnce()
esp_err_t res;
if (firstTime) {
// Set up I2S Processor configuration. This will produce 16bit samples at 8 kHz instead of 12 from the ADC
LOG_INFO("Initializing I2S SD: %d DIN: %d WS: %d SCK: %d", moduleConfig.audio.i2s_sd, moduleConfig.audio.i2s_din,
LOG_INFO("Init I2S SD: %d DIN: %d WS: %d SCK: %d", moduleConfig.audio.i2s_sd, moduleConfig.audio.i2s_din,
moduleConfig.audio.i2s_ws, moduleConfig.audio.i2s_sck);
i2s_config_t i2s_config = {.mode = (i2s_mode_t)(I2S_MODE_MASTER | (moduleConfig.audio.i2s_sd ? I2S_MODE_RX : 0) |
(moduleConfig.audio.i2s_din ? I2S_MODE_TX : 0)),
@ -185,7 +184,7 @@ int32_t AudioModule::runOnce()
radio_state = RadioState::rx;
// Configure PTT input
LOG_INFO("Initializing PTT on Pin %u", moduleConfig.audio.ptt_pin ? moduleConfig.audio.ptt_pin : PTT_PIN);
LOG_INFO("Init PTT on Pin %u", moduleConfig.audio.ptt_pin ? moduleConfig.audio.ptt_pin : PTT_PIN);
pinMode(moduleConfig.audio.ptt_pin ? moduleConfig.audio.ptt_pin : PTT_PIN, INPUT);
firstTime = false;
@ -204,7 +203,7 @@ int32_t AudioModule::runOnce()
LOG_INFO("PTT released, switching to RX");
if (tx_encode_frame_index > sizeof(tx_header)) {
// Send the incomplete frame
LOG_INFO("Sending %d codec2 bytes (incomplete)", tx_encode_frame_index);
LOG_INFO("Send %d codec2 bytes (incomplete)", tx_encode_frame_index);
sendPayload();
}
tx_encode_frame_index = sizeof(tx_header);

View File

@ -22,7 +22,7 @@ void PaxcounterModule::handlePaxCounterReportRequest()
}
PaxcounterModule::PaxcounterModule()
: concurrency::OSThread("PaxcounterModule"),
: concurrency::OSThread("Paxcounter"),
ProtobufModule("paxcounter", meshtastic_PortNum_PAXCOUNTER_APP, &meshtastic_Paxcount_msg)
{
}
@ -39,7 +39,7 @@ bool PaxcounterModule::sendInfo(NodeNum dest)
if (paxcounterModule->reportedDataSent)
return false;
LOG_INFO("PaxcounterModule: sending pax info wifi=%d; ble=%d; uptime=%lu", count_from_libpax.wifi_count,
LOG_INFO("PaxcounterModule: send pax info wifi=%d; ble=%d; uptime=%lu", count_from_libpax.wifi_count,
count_from_libpax.ble_count, millis() / 1000);
meshtastic_Paxcount pl = meshtastic_Paxcount_init_default;

View File

@ -28,7 +28,7 @@ class AccelerometerThread : public concurrency::OSThread
bool isInitialised = false;
public:
explicit AccelerometerThread(ScanI2C::FoundDevice foundDevice) : OSThread("AccelerometerThread")
explicit AccelerometerThread(ScanI2C::FoundDevice foundDevice) : OSThread("Accelerometer")
{
device = foundDevice;
init();
@ -65,14 +65,14 @@ class AccelerometerThread : public concurrency::OSThread
return;
if (device.address.port == ScanI2C::I2CPort::NO_I2C || device.address.address == 0 || device.type == ScanI2C::NONE) {
LOG_DEBUG("AccelerometerThread disabling due to no sensors found");
LOG_DEBUG("AccelerometerThread Disable due to no sensors found");
disable();
return;
}
#ifndef RAK_4631
if (!config.display.wake_on_tap_or_motion && !config.device.double_tap_as_button_press) {
LOG_DEBUG("AccelerometerThread disabling due to no interested configurations");
LOG_DEBUG("AccelerometerThread Disable due to no interested configurations");
disable();
return;
}
@ -118,7 +118,7 @@ class AccelerometerThread : public concurrency::OSThread
}
// Copy constructor (not implemented / included to avoid cppcheck warnings)
AccelerometerThread(const AccelerometerThread &other) : OSThread::OSThread("AccelerometerThread") { this->copy(other); }
AccelerometerThread(const AccelerometerThread &other) : OSThread::OSThread("Accelerometer") { this->copy(other); }
// Destructor (included to avoid cppcheck warnings)
virtual ~AccelerometerThread() { clean(); }

View File

@ -41,10 +41,10 @@ bool BMA423Sensor::init()
// It corresponds to isDoubleClick interrupt
sensor.enableWakeupIRQ();
LOG_DEBUG("BMA423Sensor::init ok");
LOG_DEBUG("BMA423 init ok");
return true;
}
LOG_DEBUG("BMA423Sensor::init failed");
LOG_DEBUG("BMA423 init failed");
return false;
}

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