Pass#2: Lots more savings in logs and string reduction surgery (#5251)

* Pass#2: Lots more savings in logs and string reduction surgery

* Don't need Thread suffix either

* Warn
This commit is contained in:
Ben Meadors
2024-11-04 12:16:25 -06:00
committed by GitHub
parent bf944e78d8
commit 50dac38a1b
70 changed files with 320 additions and 324 deletions

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 disabling 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 disabling 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();
@@ -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 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);
#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 lighting 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,18 +165,18 @@ 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 lighting 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 lighting 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 lighting w/ red=%d, green=%d, blue=%d", moduleConfig.ambient_lighting.red,
moduleConfig.ambient_lighting.green, moduleConfig.ambient_lighting.blue);
#endif
}

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

@@ -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
@@ -816,7 +816,7 @@ 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 {
@@ -827,7 +827,7 @@ bool Power::axpChipInit()
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 {

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();
}
@@ -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

@@ -32,7 +32,7 @@ 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 {

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

@@ -589,7 +589,7 @@ bool GPS::setup()
}
} 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
@@ -1122,7 +1122,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
@@ -1172,7 +1172,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);
@@ -1256,7 +1256,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;
}
@@ -1319,7 +1319,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.
@@ -1340,8 +1340,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);

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,18 +120,18 @@ 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));
@@ -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

@@ -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;
}
@@ -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

@@ -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

@@ -328,7 +328,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
@@ -389,7 +389,7 @@ 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");
@@ -435,7 +435,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)
@@ -460,7 +460,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
@@ -740,7 +740,7 @@ void setup()
// 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);
@@ -783,7 +783,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();
@@ -830,63 +830,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, using SX1262 radio");
}
}
} 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, using RF95 radio");
}
}
} 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, using SX1280 radio");
}
}
} 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, using SX1268 radio");
}
}
}
@@ -902,11 +902,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, using STM32WL radio");
radioType = STM32WLx_RADIO;
}
}
@@ -916,11 +916,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;
}
}
@@ -930,11 +930,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, using RF95 radio");
radioType = RF95_RADIO;
}
}
@@ -944,11 +944,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, using SX1262 radio");
radioType = SX1262_RADIO;
}
}
@@ -959,12 +959,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;
}
}
@@ -973,12 +973,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;
}
}
@@ -988,11 +988,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, using SX1268 radio");
radioType = SX1268_RADIO;
}
}
@@ -1002,11 +1002,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, using LLCC68 radio");
radioType = LLCC68_RADIO;
}
}
@@ -1016,11 +1016,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, using LR1110 radio");
radioType = LR1110_RADIO;
}
}
@@ -1030,11 +1030,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, using LR1120 radio");
radioType = LR1120_RADIO;
}
}
@@ -1044,11 +1044,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, using LR1121 radio");
radioType = LR1121_RADIO;
}
}
@@ -1058,11 +1058,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, using SX1280 radio");
radioType = SX1280_RADIO;
}
}
@@ -1070,7 +1070,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("LoRa chip does not support 2.4GHz. 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()) {

View File

@@ -388,7 +388,7 @@ bool Channels::decryptForHash(ChannelIndex chIndex, ChannelHash channelHash)
// 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

@@ -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 using nonce: ", nonce, 13);
printBytes("Attempt encrypt using 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 using nonce: ", nonce, 13);
printBytes("Attempt decrypt using 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;
}

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) {
@@ -71,7 +71,7 @@ void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas
LOG_DEBUG("Not rebroadcasting: 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

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

@@ -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

@@ -88,10 +88,10 @@ int MeshService::handleFromRadio(const meshtastic_MeshPacket *mp)
} else if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag && !nodeDB->getMeshNode(mp->from)->has_user &&
nodeInfoModule && !isPreferredRebroadcaster) {
if (airTime->isTxAllowedChannelUtil(true)) {
LOG_INFO("Heard new node on chan %d, sending NodeInfo and asking for a response", mp->channel);
LOG_INFO("Heard new node on ch. %d, sending NodeInfo and asking for a response", mp->channel);
nodeInfoModule->sendOurNodeInfo(mp->from, true, mp->channel);
} else {
LOG_DEBUG("Skip sending NodeInfo due to > 25 percent chan util");
LOG_DEBUG("Skip sending NodeInfo > 25%% ch. util");
}
}
@@ -269,14 +269,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);
}
}
@@ -319,7 +319,7 @@ 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");
meshtastic_MqttClientProxyMessage *d = toPhoneMqttProxyQueue.dequeuePtr(0);
@@ -333,7 +333,7 @@ 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");
meshtastic_ClientNotification *d = toPhoneClientNotificationQueue.dequeuePtr(0);
@@ -389,7 +389,7 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
}
// 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);
}

View File

@@ -105,7 +105,7 @@ static uint8_t ourMacAddr[6];
NodeDB::NodeDB()
{
LOG_INFO("Initializing NodeDB");
LOG_INFO("Init NodeDB");
loadFromDisk();
cleanupMeshDB();
@@ -182,7 +182,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;
}
@@ -283,7 +283,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();
}
@@ -294,7 +294,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);
}
@@ -344,7 +344,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;
@@ -482,7 +482,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;
@@ -617,7 +617,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;
}
@@ -684,7 +684,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;
@@ -742,7 +742,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;
}
@@ -762,7 +762,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);

View File

@@ -152,12 +152,12 @@ class NodeDB
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,7 +57,7 @@ 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();
}
@@ -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:
@@ -186,11 +186,11 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// Advance states as needed
switch (state) {
case STATE_SEND_NOTHING:
LOG_DEBUG("getFromRadio=STATE_SEND_NOTHING");
LOG_DEBUG("FromRadio=STATE_SEND_NOTHING");
break;
case STATE_SEND_MY_INFO:
LOG_DEBUG("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;
@@ -202,7 +202,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
break;
case STATE_SEND_OWN_NODEINFO: {
LOG_DEBUG("Sending My NodeInfo");
LOG_DEBUG("Send My NodeInfo");
auto us = nodeDB->readNextMeshNode(readIndex);
if (us) {
nodeInfoForPhone = TypeConversions::ConvertToNodeInfo(us);
@@ -218,14 +218,14 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
}
case STATE_SEND_METADATA:
LOG_DEBUG("Sending 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_DEBUG("Sending Channels");
LOG_DEBUG("Send Channels");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_channel_tag;
fromRadioScratch.channel = channels.getByIndex(config_state);
config_state++;
@@ -237,7 +237,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
break;
case STATE_SEND_CONFIG:
LOG_DEBUG("Sending Radio config");
LOG_DEBUG("Send Radio config");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_tag;
switch (config_state) {
case meshtastic_Config_device_tag:
@@ -292,7 +292,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
break;
case STATE_SEND_MODULECONFIG:
LOG_DEBUG("Sending Module Config");
LOG_DEBUG("Send Module Config");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_moduleConfig_tag;
switch (config_state) {
case meshtastic_ModuleConfig_mqtt_tag:
@@ -361,7 +361,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
break;
case STATE_SEND_OTHER_NODEINFOS: {
LOG_DEBUG("Sending known nodes");
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);
@@ -379,7 +379,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
}
case STATE_SEND_FILEMANIFEST: {
LOG_DEBUG("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;
@@ -402,7 +402,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_DEBUG("getFromRadio=STATE_SEND_PACKETS");
LOG_DEBUG("FromRadio=STATE_SEND_PACKETS");
if (queueStatusPacketForPhone) {
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_queueStatus_tag;
fromRadioScratch.queueStatus = *queueStatusPacketForPhone;
@@ -596,7 +596,7 @@ 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
@@ -629,7 +629,7 @@ 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)");

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);
@@ -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

@@ -224,7 +224,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;
}
@@ -392,7 +392,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);
@@ -403,14 +403,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;
}
@@ -467,7 +467,7 @@ void RadioLibInterface::setStandby()
/** start an immediate transmit */
void RadioLibInterface::startSend(meshtastic_MeshPacket *txp)
{
printPacket("Starting low level send", txp);
printPacket("Start 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);

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("Generating 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");
}
}
@@ -228,7 +228,7 @@ int32_t ReliableRouter::doRetransmissions()
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

@@ -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)) {
@@ -468,7 +468,7 @@ meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p)
// 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) &&
@@ -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;
}

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

@@ -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;
@@ -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

@@ -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! :-) ");

View File

@@ -453,7 +453,7 @@ 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, defaulting to port 443");
webservport = 443;

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;

View File

@@ -77,12 +77,12 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
LOG_DEBUG("Allowing 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, as legacy admin is disabled");
myReply = allocErrorResponse(meshtastic_Routing_Error_NOT_AUTHORIZED, &mp);
return handled;
}
@@ -100,7 +100,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
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;
}
@@ -192,7 +192,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);
@@ -351,7 +351,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
LOG_DEBUG("We 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 nonrelevant admin %d", r->which_payload_variant);
}
break;
}
@@ -427,7 +427,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 &&
@@ -484,14 +484,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 &&
@@ -506,12 +506,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 &&
@@ -529,7 +529,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 &&
@@ -568,12 +568,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.
@@ -608,52 +608,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);
@@ -662,17 +662,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;
@@ -970,7 +970,7 @@ void AdminModule::handleGetChannel(const meshtastic_MeshPacket &req, uint32_t ch
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);
}
@@ -1030,7 +1030,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
}

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);
@@ -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();
@@ -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,

View File

@@ -79,7 +79,7 @@ int32_t DetectionSensorModule::runOnce()
LOG_WARN("Detection Sensor Module: Set to enabled but no monitor pin is set. Disabling module...");
return disable();
}
LOG_INFO("Detection Sensor Module: Initializing");
LOG_INFO("Detection Sensor Module: init");
return DELAYED_INTERVAL;
}
@@ -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

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);

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,7 +65,7 @@ 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 chan util");
LOG_DEBUG("Skip sending 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.
@@ -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,7 +108,7 @@ 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
@@ -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;
@@ -183,7 +182,7 @@ meshtastic_MeshPacket *PositionModule::allocReply()
}
// 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));
@@ -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 5s, then going to sleep");
LOG_DEBUG("Start next execution in 5s, then going to sleep");
sleepOnNextExecution = true;
setIntervalFromNow(5000);
}

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
}

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;

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;
@@ -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);
}
@@ -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) {
@@ -611,7 +611,7 @@ StoreForwardModule::StoreForwardModule()
// 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();

View File

@@ -33,7 +33,7 @@ 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...");
@@ -178,10 +178,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

@@ -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

@@ -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
@@ -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 5s, then going to sleep");
LOG_DEBUG("Start next execution in 5s, then going to sleep");
sleepOnNextExecution = true;
setIntervalFromNow(5000);
}

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

@@ -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();
@@ -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 5s, then going to sleep");
LOG_DEBUG("Start next execution in 5s, then going to 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

@@ -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())
@@ -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 going to 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

@@ -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)
{
}

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();
@@ -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

@@ -155,7 +155,7 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length)
if (e.packet && isFromUs(e.packet))
routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(e.packet), e.packet->id, ch.index);
else
LOG_INFO("Ignoring downlink message we originally sent");
LOG_INFO("Ignore downlink message we originally sent");
} else {
// Find channel by channel_id and check downlink_enabled
if ((strcmp(e.channel_id, "PKI") == 0 && e.packet) ||
@@ -165,18 +165,18 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length)
p->via_mqtt = true; // Mark that the packet was received via MQTT
if (isFromUs(p)) {
LOG_INFO("Ignoring downlink message we originally sent");
LOG_INFO("Ignore downlink message we originally sent");
packetPool.release(p);
return;
}
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
if (moduleConfig.mqtt.encryption_enabled) {
LOG_INFO("Ignoring decoded message on MQTT, encryption is enabled");
LOG_INFO("Ignore decoded message on MQTT, encryption is enabled");
packetPool.release(p);
return;
}
if (p->decoded.portnum == meshtastic_PortNum_ADMIN_APP) {
LOG_INFO("Ignoring decoded admin packet");
LOG_INFO("Ignore decoded admin packet");
packetPool.release(p);
return;
}
@@ -218,7 +218,7 @@ MQTT::MQTT() : concurrency::OSThread("mqtt"), mqttQueue(MAX_MQTT_QUEUE)
#endif
{
if (moduleConfig.mqtt.enabled) {
LOG_DEBUG("Initializing MQTT");
LOG_DEBUG("Init MQTT");
assert(!mqtt);
mqtt = this;
@@ -344,12 +344,12 @@ void MQTT::reconnect()
wifiSecureClient.setInsecure();
pubSub.setClient(wifiSecureClient);
LOG_INFO("Using TLS-encrypted session");
LOG_INFO("Use TLS-encrypted session");
} catch (const std::exception &e) {
LOG_ERROR("MQTT ERROR: %s", e.what());
}
} else {
LOG_INFO("Using non-TLS-encrypted session");
LOG_INFO("Use non-TLS-encrypted session");
pubSub.setClient(mqttClient);
}
#else
@@ -370,8 +370,8 @@ void MQTT::reconnect()
pubSub.setServer(serverAddr, serverPort);
pubSub.setBufferSize(512);
LOG_INFO("Attempting to connect directly to MQTT server %s, port: %d, username: %s, password: %s", serverAddr, serverPort,
mqttUsername, mqttPassword);
LOG_INFO("Connect directly to MQTT server %s, port: %d, username: %s, password: %s", serverAddr, serverPort, mqttUsername,
mqttPassword);
bool connected = pubSub.connect(owner.id, mqttUsername, mqttPassword);
if (connected) {
@@ -407,13 +407,13 @@ void MQTT::sendSubscriptions()
if (ch.settings.downlink_enabled) {
hasDownlink = true;
std::string topic = cryptTopic + channels.getGlobalId(i) + "/+";
LOG_INFO("Subscribing to %s", topic.c_str());
LOG_INFO("Subscribe to %s", topic.c_str());
pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right?
#if !defined(ARCH_NRF52) || \
defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ###
if (moduleConfig.mqtt.json_enabled == true) {
std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+";
LOG_INFO("Subscribing to %s", topicDecoded.c_str());
LOG_INFO("Subscribe to %s", topicDecoded.c_str());
pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right?
}
#endif // ARCH_NRF52 NRF52_USE_JSON
@@ -422,7 +422,7 @@ void MQTT::sendSubscriptions()
#if !MESHTASTIC_EXCLUDE_PKI
if (hasDownlink) {
std::string topic = cryptTopic + "PKI/+";
LOG_INFO("Subscribing to %s", topic.c_str());
LOG_INFO("Subscribe to %s", topic.c_str());
pubSub.subscribe(topic.c_str(), 1);
}
#endif
@@ -496,7 +496,7 @@ void MQTT::publishNodeInfo()
void MQTT::publishQueuedMessages()
{
if (!mqttQueue.isEmpty()) {
LOG_DEBUG("Publishing enqueued MQTT message");
LOG_DEBUG("Publish enqueued MQTT message");
meshtastic_ServiceEnvelope *env = mqttQueue.dequeuePtr(0);
size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env);
std::string topic;
@@ -606,7 +606,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp_encrypted, const meshtastic_Me
} else {
LOG_INFO("MQTT not connected, queueing packet");
if (mqttQueue.numFree() == 0) {
LOG_WARN("NOTE: MQTT queue is full, discarding oldest");
LOG_WARN("MQTT queue is full, discarding oldest");
meshtastic_ServiceEnvelope *d = mqttQueue.dequeuePtr(0);
if (d)
mqttPool.release(d);

View File

@@ -84,7 +84,7 @@ class NimbleBluetoothServerCallback : public NimBLEServerCallbacks
uint32_t passkey = config.bluetooth.fixed_pin;
if (config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_RANDOM_PIN) {
LOG_INFO("Using random passkey");
LOG_INFO("Use random passkey");
// This is the passkey to be entered on peer - we pick a number >100,000 to ensure 6 digits
passkey = random(100000, 999999);
}
@@ -193,7 +193,7 @@ void NimbleBluetooth::setup()
// Uncomment for testing
// NimbleBluetooth::clearBonds();
LOG_INFO("Initialise the NimBLE bluetooth module");
LOG_INFO("Init the NimBLE bluetooth module");
NimBLEDevice::init(getDeviceName());
NimBLEDevice::setPower(ESP_PWR_LVL_P9);

View File

@@ -101,7 +101,7 @@ void esp32Setup()
/* We explicitly don't want to do call randomSeed,
// as that triggers the esp32 core to use a less secure pseudorandom function.
uint32_t seed = esp_random();
LOG_DEBUG("Setting random seed %u", seed);
LOG_DEBUG("Set random seed %u", seed);
randomSeed(seed);
*/

View File

@@ -137,7 +137,7 @@ void onFromRadioAuthorize(uint16_t conn_hdl, BLECharacteristic *chr, ble_gatts_e
// or make empty if the queue is empty
fromRadio.write(fromRadioBytes, numBytes);
} else {
// LOG_INFO("Ignoring successor read");
// LOG_INFO("Ignore successor read");
}
authorizeRead(conn_hdl);
}
@@ -275,20 +275,20 @@ void NRF52Bluetooth::setup()
bledfusecure.begin(); // Install the DFU helper
#endif
// Configure and Start the Device Information Service
LOG_INFO("Configuring the Device Information Service");
LOG_INFO("Init the Device Information Service");
bledis.setModel(optstr(HW_VERSION));
bledis.setFirmwareRev(optstr(APP_VERSION));
bledis.begin();
// Start the BLE Battery Service and set it to 100%
LOG_INFO("Configuring the Battery Service");
LOG_INFO("Init the Battery Service");
blebas.begin();
blebas.write(0); // Unknown battery level for now
// Setup the Heart Rate Monitor service using
// BLEService and BLECharacteristic classes
LOG_INFO("Configuring the Mesh bluetooth service");
LOG_INFO("Init the Mesh bluetooth service");
setupMeshService();
// Setup the advertising packet(s)
LOG_INFO("Setting up the advertising payload(s)");
LOG_INFO("Set up the advertising payload(s)");
startAdv();
LOG_INFO("Advertising");
}

View File

@@ -97,7 +97,7 @@ void setBluetoothEnable(bool enable)
// If not yet set-up
if (!nrf52Bluetooth) {
LOG_DEBUG("Initializing NRF52 Bluetooth");
LOG_DEBUG("Init NRF52 Bluetooth");
nrf52Bluetooth = new NRF52Bluetooth();
nrf52Bluetooth->setup();
@@ -212,7 +212,7 @@ void nrf52Setup()
} seed;
nRFCrypto.begin();
nRFCrypto.Random.generate(seed.seed8, sizeof(seed.seed8));
LOG_DEBUG("Setting random seed %u", seed.seed32);
LOG_DEBUG("Set random seed %u", seed.seed32);
randomSeed(seed.seed32);
nRFCrypto.end();
}

View File

@@ -75,7 +75,7 @@ void portduinoCustomInit()
*/
void portduinoSetup()
{
printf("Setting up Meshtastic on Portduino...\n");
printf("Set up Meshtastic on Portduino...\n");
int max_GPIO = 0;
const configNames GPIO_lines[] = {cs,
irq,

View File

@@ -182,13 +182,13 @@ void SimRadio::onNotify(uint32_t notification)
/** start an immediate transmit */
void SimRadio::startSend(meshtastic_MeshPacket *txp)
{
printPacket("Starting low level send", txp);
printPacket("Start low level send", txp);
size_t numbytes = beginSending(txp);
meshtastic_MeshPacket *p = packetPool.allocCopy(*txp);
perhapsDecode(p);
meshtastic_Compressed c = meshtastic_Compressed_init_default;
c.portnum = p->decoded.portnum;
// LOG_DEBUG("Sending back to simulator with portNum %d", p->decoded.portnum);
// LOG_DEBUG("Send back to simulator with portNum %d", p->decoded.portnum);
if (p->decoded.payload.size <= sizeof(c.data.bytes)) {
memcpy(&c.data.bytes, p->decoded.payload.bytes, p->decoded.payload.size);
c.data.size = p->decoded.payload.size;

View File

@@ -43,7 +43,7 @@ void powerCommandsCheck()
#endif
if (shutdownAtMsec && millis() > shutdownAtMsec) {
LOG_INFO("Shutting down from admin command");
LOG_INFO("Shut down from admin command");
#if defined(ARCH_NRF52) || defined(ARCH_ESP32) || defined(ARCH_RP2040)
playShutdownMelody();
power->shutdown();

View File

@@ -71,7 +71,7 @@ void setCPUFast(bool on)
* (Added: Dec 23, 2021 by Jm Casler)
*/
#ifndef CONFIG_IDF_TARGET_ESP32C3
LOG_DEBUG("Setting CPU to 240MHz because WiFi is in use");
LOG_DEBUG("Set CPU to 240MHz because WiFi is in use");
setCpuFrequencyMhz(240);
#endif
return;
@@ -190,9 +190,9 @@ static void waitEnterSleep(bool skipPreflight = false)
void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false)
{
if (INCLUDE_vTaskSuspend && (msecToWake == portMAX_DELAY)) {
LOG_INFO("Entering deep sleep forever");
LOG_INFO("Enter deep sleep forever");
} else {
LOG_INFO("Entering deep sleep for %u seconds", msecToWake / 1000);
LOG_INFO("Enter deep sleep for %u seconds", msecToWake / 1000);
}
// not using wifi yet, but once we are this is needed to shutoff the radio hw