diff --git a/arch/rp2040/rp2040.ini b/arch/rp2040/rp2040.ini index 42b73294c..984d98bea 100644 --- a/arch/rp2040/rp2040.ini +++ b/arch/rp2040/rp2040.ini @@ -1,8 +1,8 @@ ; Common settings for rp2040 Processor based targets [rp2040_base] -platform = https://github.com/maxgerhardt/platform-raspberrypi.git#612de5399d68b359053f1307ed223d400aea975c +platform = https://github.com/maxgerhardt/platform-raspberrypi.git#60d6ae81fcc73c34b1493ca9e261695e471bc0c2 extends = arduino_base -platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.6.2 +platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2 board_build.core = earlephilhower board_build.filesystem_size = 0.5m diff --git a/lib/device-ui b/lib/device-ui index a436fcbc6..890ff469b 160000 --- a/lib/device-ui +++ b/lib/device-ui @@ -1 +1 @@ -Subproject commit a436fcbc6ed778e9d24bc58b3b76cee996b1e91b +Subproject commit 890ff469b5fb9c71ab81976567c2db4d5dede7a5 diff --git a/platformio.ini b/platformio.ini index 392b38fd7..2c373ab00 100644 --- a/platformio.ini +++ b/platformio.ini @@ -69,6 +69,7 @@ build_flags = -Wno-missing-field-initializers -DRADIOLIB_EXCLUDE_PAGER -DRADIOLIB_EXCLUDE_FSK4 -DRADIOLIB_EXCLUDE_APRS + -DRADIOLIB_EXCLUDE_LORAWAN monitor_speed = 115200 @@ -77,8 +78,8 @@ lib_deps = https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306 mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 - https://github.com/meshtastic/TinyGPSPlus.git#2044b2c51e91ab4cd8cc93b15e40658cd808dd06 - https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3 + https://github.com/meshtastic/TinyGPSPlus.git#f9f4fef2183514aa52be91d714c1455dd6f26e45 + https://github.com/meshtastic/ArduinoThread.git#1ae8778c85d0a2a729f989e0b1e7d7c4dc84eef0 nanopb/Nanopb@^0.4.7 erriez/ErriezCRC32@^1.0.1 @@ -130,4 +131,4 @@ lib_deps = adafruit/Adafruit PM25 AQI Sensor@^1.0.6 adafruit/Adafruit MPU6050@^2.2.4 adafruit/Adafruit LIS3DH@^1.2.4 - https://github.com/lewisxhe/BMA423_Library@^0.0.1 + https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17 diff --git a/protobufs b/protobufs index 7e3ee8cd9..556e49ba6 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 7e3ee8cd96740910d0611433cb9a05a7a692568c +Subproject commit 556e49ba619e2f4d8fa3c2dee2a94129a43d5f08 diff --git a/src/AccelerometerThread.h b/src/AccelerometerThread.h index 9898f4d49..6827908b7 100644 --- a/src/AccelerometerThread.h +++ b/src/AccelerometerThread.h @@ -7,16 +7,16 @@ #include #include #include +#include #include -#include -BMA423 bmaSensor; +SensorBMA423 bmaSensor; bool BMA_IRQ = false; #define ACCELEROMETER_CHECK_INTERVAL_MS 100 #define ACCELEROMETER_CLICK_THRESHOLD 40 -uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len) +int readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint8_t len) { Wire.beginTransmission(address); Wire.write(reg); @@ -29,7 +29,7 @@ uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len) return 0; // Pass } -uint16_t writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len) +int writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint8_t len) { Wire.beginTransmission(address); Wire.write(reg); @@ -72,24 +72,14 @@ class AccelerometerThread : public concurrency::OSThread lis.setRange(LIS3DH_RANGE_2_G); // Adjust threshold, higher numbers are less sensitive lis.setClick(config.device.double_tap_as_button_press ? 2 : 1, ACCELEROMETER_CLICK_THRESHOLD); - } else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.begin(readRegister, writeRegister, delay)) { + } else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && + bmaSensor.begin(accelerometer_found.address, &readRegister, &writeRegister)) { LOG_DEBUG("BMA423 initializing\n"); - Acfg cfg; - cfg.odr = BMA4_OUTPUT_DATA_RATE_100HZ; - cfg.range = BMA4_ACCEL_RANGE_2G; - cfg.bandwidth = BMA4_ACCEL_NORMAL_AVG4; - cfg.perf_mode = BMA4_CONTINUOUS_MODE; - bmaSensor.setAccelConfig(cfg); - bmaSensor.enableAccel(); - - struct bma4_int_pin_config pin_config; - pin_config.edge_ctrl = BMA4_LEVEL_TRIGGER; - pin_config.lvl = BMA4_ACTIVE_HIGH; - pin_config.od = BMA4_PUSH_PULL; - pin_config.output_en = BMA4_OUTPUT_ENABLE; - pin_config.input_en = BMA4_INPUT_DISABLE; - // The correct trigger interrupt needs to be configured as needed - bmaSensor.setINTPinConfig(pin_config, BMA4_INTR1_MAP); + bmaSensor.configAccelerometer(bmaSensor.RANGE_2G, bmaSensor.ODR_100HZ, bmaSensor.BW_NORMAL_AVG4, + bmaSensor.PERF_CONTINUOUS_MODE); + bmaSensor.enableAccelerometer(); + bmaSensor.configInterrupt(BMA4_LEVEL_TRIGGER, BMA4_ACTIVE_HIGH, BMA4_PUSH_PULL, BMA4_OUTPUT_ENABLE, + BMA4_INPUT_DISABLE); #ifdef BMA423_INT pinMode(BMA4XX_INT, INPUT); @@ -102,34 +92,22 @@ class AccelerometerThread : public concurrency::OSThread RISING); // Select the interrupt mode according to the actual circuit #endif - struct bma423_axes_remap remap_data; #ifdef T_WATCH_S3 - remap_data.x_axis = 1; - remap_data.x_axis_sign = 0; - remap_data.y_axis = 0; - remap_data.y_axis_sign = 0; - remap_data.z_axis = 2; - remap_data.z_axis_sign = 1; -#else - remap_data.x_axis = 0; - remap_data.x_axis_sign = 1; - remap_data.y_axis = 1; - remap_data.y_axis_sign = 0; - remap_data.z_axis = 2; - remap_data.z_axis_sign = 1; -#endif // Need to raise the wrist function, need to set the correct axis - bmaSensor.setRemapAxes(&remap_data); - // sensor.enableFeature(BMA423_STEP_CNTR, true); - bmaSensor.enableFeature(BMA423_TILT, true); - bmaSensor.enableFeature(BMA423_WAKEUP, true); - // sensor.resetStepCounter(); + bmaSensor.setReampAxes(bmaSensor.REMAP_TOP_LAYER_RIGHT_CORNER); +#else + bmaSensor.setReampAxes(bmaSensor.REMAP_BOTTOM_LAYER_BOTTOM_LEFT_CORNER); +#endif + // bmaSensor.enableFeature(bmaSensor.FEATURE_STEP_CNTR, true); + bmaSensor.enableFeature(bmaSensor.FEATURE_TILT, true); + bmaSensor.enableFeature(bmaSensor.FEATURE_WAKEUP, true); + // bmaSensor.resetPedometer(); // Turn on feature interrupt - bmaSensor.enableStepCountInterrupt(); - bmaSensor.enableTiltInterrupt(); + bmaSensor.enablePedometerIRQ(); + bmaSensor.enableTiltIRQ(); // It corresponds to isDoubleClick interrupt - bmaSensor.enableWakeupInterrupt(); + bmaSensor.enableWakeupIRQ(); } } @@ -150,8 +128,8 @@ class AccelerometerThread : public concurrency::OSThread buttonPress(); return 500; } - } else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.getINT()) { - if (bmaSensor.isTilt() || bmaSensor.isDoubleClick()) { + } else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.readIrqStatus() != DEV_WIRE_NONE) { + if (bmaSensor.isTilt() || bmaSensor.isDoubleTap()) { wakeScreen(); return 500; } diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp index c359e4c12..5d86987df 100644 --- a/src/PowerFSM.cpp +++ b/src/PowerFSM.cpp @@ -8,6 +8,7 @@ * actions to be taken upon entering or exiting each state. */ #include "PowerFSM.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "configuration.h" @@ -45,7 +46,7 @@ static void sdsEnter() { LOG_DEBUG("Enter state: SDS\n"); // FIXME - make sure GPS and LORA radio are off first - because we want close to zero current draw - doDeepSleep(getConfiguredOrDefaultMs(config.power.sds_secs), false); + doDeepSleep(Default::getConfiguredOrDefaultMs(config.power.sds_secs), false); } extern Power *power; @@ -343,13 +344,13 @@ void PowerFSM_setup() powerFSM.add_transition(&stateDARK, &stateDARK, EVENT_CONTACT_FROM_PHONE, NULL, "Contact from phone"); powerFSM.add_timed_transition(&stateON, &stateDARK, - getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, + Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout"); powerFSM.add_timed_transition(&statePOWER, &stateDARK, - getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, + Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout"); powerFSM.add_timed_transition(&stateDARK, &stateDARK, - getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, + Default::getConfiguredOrDefaultMs(config.display.screen_on_secs, default_screen_on_secs), NULL, "Screen-on timeout"); // We never enter light-sleep or NB states on NRF52 (because the CPU uses so little power normally) @@ -358,12 +359,13 @@ void PowerFSM_setup() // Don't add power saving transitions if we are a power saving tracker or sensor. Sleep will be initiatiated through the // modules if ((isRouter || config.power.is_power_saving) && !isTrackerOrSensor) { - powerFSM.add_timed_transition(&stateNB, isInfrastructureRole ? &stateSDS : &stateLS, - getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, + powerFSM.add_timed_transition(&stateNB, &stateLS, + Default::getConfiguredOrDefaultMs(config.power.min_wake_secs, default_min_wake_secs), NULL, "Min wake timeout"); - powerFSM.add_timed_transition(&stateDARK, isInfrastructureRole ? &stateSDS : &stateLS, - getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), - NULL, "Bluetooth timeout"); + powerFSM.add_timed_transition( + &stateDARK, &stateLS, + Default::getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs), NULL, + "Bluetooth timeout"); } #endif diff --git a/src/PowerFSMThread.h b/src/PowerFSMThread.h index 584c955aa..fb640dd8b 100644 --- a/src/PowerFSMThread.h +++ b/src/PowerFSMThread.h @@ -1,3 +1,4 @@ +#include "Default.h" #include "NodeDB.h" #include "PowerFSM.h" #include "concurrency/OSThread.h" @@ -28,7 +29,7 @@ class PowerFSMThread : public OSThread timeLastPowered = millis(); } else if (config.power.on_battery_shutdown_after_secs > 0 && config.power.on_battery_shutdown_after_secs != UINT32_MAX && millis() > (timeLastPowered + - getConfiguredOrDefaultMs( + Default::getConfiguredOrDefaultMs( config.power.on_battery_shutdown_after_secs))) { // shutdown after 30 minutes unpowered powerFSM.trigger(EVENT_SHUTDOWN); } diff --git a/src/SerialConsole.cpp b/src/SerialConsole.cpp index ed217c3ed..e17c8f99e 100644 --- a/src/SerialConsole.cpp +++ b/src/SerialConsole.cpp @@ -3,7 +3,11 @@ #include "PowerFSM.h" #include "configuration.h" +#ifdef RP2040_SLOW_CLOCK +#define Port Serial2 +#else #define Port Serial +#endif // Defaulting to the formerly removed phone_timeout_secs value of 15 minutes #define SERIAL_CONNECTION_TIMEOUT (15 * 60) * 1000UL @@ -31,6 +35,10 @@ SerialConsole::SerialConsole() : StreamAPI(&Port), RedirectablePrint(&Port), con canWrite = false; // We don't send packets to our port until it has talked to us first // setDestination(&noopPrint); for testing, try turning off 'all' debug output and see what leaks +#ifdef RP2040_SLOW_CLOCK + Port.setTX(SERIAL2_TX); + Port.setRX(SERIAL2_RX); +#endif Port.begin(SERIAL_BAUD); #if defined(ARCH_NRF52) || defined(CONFIG_IDF_TARGET_ESP32S2) || defined(CONFIG_IDF_TARGET_ESP32S3) || defined(ARCH_RP2040) time_t timeout = millis(); @@ -64,7 +72,7 @@ bool SerialConsole::checkIsConnected() /** * we override this to notice when we've received a protobuf over the serial - * stream. Then we shunt off debug serial output. + * stream. Then we shut off debug serial output. */ bool SerialConsole::handleToRadio(const uint8_t *buf, size_t len) { diff --git a/src/configuration.h b/src/configuration.h index b1286fd3e..c2b4e40c8 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -111,6 +111,7 @@ along with this program. If not, see . #define MCP9808_ADDR 0x18 #define INA_ADDR 0x40 #define INA_ADDR_ALTERNATE 0x41 +#define INA_ADDR_WAVESHARE_UPS 0x43 #define INA3221_ADDR 0x42 #define QMC6310_ADDR 0x1C #define QMI8658_ADDR 0x6B diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index b6eca5fa4..146daa3dc 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -183,8 +183,13 @@ void ScanI2CTwoWire::scanPort(I2CPort port) #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) case ATECC608B_ADDR: - type = ATECC608B; - if (atecc.begin(addr.address) == true) { +#ifdef RP2040_SLOW_CLOCK + if (atecc.begin(addr.address, Wire, Serial2) == true) +#else + if (atecc.begin(addr.address) == true) +#endif + + { LOG_INFO("ATECC608B initialized\n"); } else { LOG_WARN("ATECC608B initialization failed\n"); @@ -254,6 +259,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port) case INA_ADDR: case INA_ADDR_ALTERNATE: + case INA_ADDR_WAVESHARE_UPS: registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0xFE), 2); LOG_DEBUG("Register MFG_UID: 0x%x\n", registerValue); if (registerValue == 0x5449) { diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index 849c38794..5595172dd 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1,4 +1,5 @@ #include "GPS.h" +#include "Default.h" #include "NodeDB.h" #include "RTC.h" #include "configuration.h" @@ -290,6 +291,26 @@ bool GPS::setup() // Switch to Vehicle Mode, since SoftRF enables Aviation < 2g _serial_gps->write("$PCAS11,3*1E\r\n"); delay(250); + } else if (gnssModel == GNSS_MODEL_MTK_L76B) { + // Waveshare Pico-GPS hat uses the L76B with 9600 baud + // Initialize the L76B Chip, use GPS + GLONASS + // See note in L76_Series_GNSS_Protocol_Specification, chapter 3.29 + _serial_gps->write("$PMTK353,1,1,0,0,0*2B\r\n"); + // Above command will reset the GPS and takes longer before it will accept new commands + delay(1000); + // only ask for RMC and GGA (GNRMC and GNGGA) + // See note in L76_Series_GNSS_Protocol_Specification, chapter 2.1 + _serial_gps->write("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n"); + delay(250); + // Enable SBAS + _serial_gps->write("$PMTK301,2*2E\r\n"); + delay(250); + // Enable PPS for 2D/3D fix only + _serial_gps->write("$PMTK285,3,100*3F\r\n"); + delay(250); + // Switch to Fitness Mode, for running and walking purpose with low speed (<5 m/s) + _serial_gps->write("$PMTK886,1*29\r\n"); + delay(250); } else if (gnssModel == GNSS_MODEL_UC6580) { // The Unicore UC6580 can use a lot of sat systems, enable it to // use GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS @@ -475,7 +496,6 @@ bool GPS::setup() } } } - } else { // LOG_INFO("u-blox M10 hardware found.\n"); delay(1000); @@ -625,17 +645,27 @@ void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime) return; } #endif -#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76K and clones +#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76B, L76K and clones if (on) { LOG_INFO("Waking GPS\n"); pinMode(PIN_GPS_STANDBY, OUTPUT); + // Some PCB's use an inverse logic due to a transistor driver + // Example for this is the Pico-Waveshare Lora+GPS HAT +#ifdef PIN_GPS_STANDBY_INVERTED + digitalWrite(PIN_GPS_STANDBY, 0); +#else digitalWrite(PIN_GPS_STANDBY, 1); +#endif return; } else { LOG_INFO("GPS entering sleep\n"); // notifyGPSSleep.notifyObservers(NULL); pinMode(PIN_GPS_STANDBY, OUTPUT); +#ifdef PIN_GPS_STANDBY_INVERTED + digitalWrite(PIN_GPS_STANDBY, 1); +#else digitalWrite(PIN_GPS_STANDBY, 0); +#endif return; } #endif @@ -729,7 +759,7 @@ uint32_t GPS::getWakeTime() const if (t == UINT32_MAX) return t; // already maxint - return getConfiguredOrDefaultMs(t, default_broadcast_interval_secs); + return Default::Default::getConfiguredOrDefaultMs(t, default_broadcast_interval_secs); } /** Get how long we should sleep between aqusition attempts in msecs @@ -916,7 +946,7 @@ GnssModel_t GPS::probe(int serialSpeed) uint8_t buffer[768] = {0}; delay(100); - // Close all NMEA sentences , Only valid for MTK platform + // Close all NMEA sentences , Only valid for L76K MTK platform _serial_gps->write("$PCAS03,0,0,0,0,0,0,0,0,0,0,,,0,0*02\r\n"); delay(20); @@ -928,6 +958,18 @@ GnssModel_t GPS::probe(int serialSpeed) return GNSS_MODEL_MTK; } + // Close all NMEA sentences, valid for L76B MTK platform (Waveshare Pico GPS) + _serial_gps->write("$PMTK514,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*2E\r\n"); + delay(20); + + // Get version information + clearBuffer(); + _serial_gps->write("$PMTK605*31\r\n"); + if (getACK("Quectel-L76B", 500) == GNSS_RESPONSE_OK) { + LOG_INFO("L76B GNSS init succeeded, using L76B GNSS Module\n"); + return GNSS_MODEL_MTK_L76B; + } + uint8_t cfg_rate[] = {0xB5, 0x62, 0x06, 0x08, 0x00, 0x00, 0x00, 0x00}; UBXChecksum(cfg_rate, sizeof(cfg_rate)); clearBuffer(); @@ -1109,7 +1151,6 @@ GPS *GPS::createGps() LOG_DEBUG("Using GPIO%d for GPS RX\n", new_gps->rx_gpio); LOG_DEBUG("Using GPIO%d for GPS TX\n", new_gps->tx_gpio); _serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, new_gps->rx_gpio, new_gps->tx_gpio); - #else _serial_gps->begin(GPS_BAUDRATE); #endif @@ -1168,7 +1209,16 @@ bool GPS::factoryReset() // byte _message_CFG_RST_COLDSTART[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0xB9, 0x00, 0x00, 0xC6, 0x8B}; // _serial_gps->write(_message_CFG_RST_COLDSTART, sizeof(_message_CFG_RST_COLDSTART)); // delay(1000); + } else if (gnssModel == GNSS_MODEL_MTK) { + // send the CAS10 to perform a factory restart of the device (and other device that support PCAS statements) + LOG_INFO("GNSS Factory Reset via PCAS10,3\n"); + _serial_gps->write("$PCAS10,3*1F\r\n"); + delay(100); } else { + // fire this for good measure, if we have an L76B - won't harm other devices. + _serial_gps->write("$PMTK104*37\r\n"); + // No PMTK_ACK for this command. + delay(100); // send the UBLOX Factory Reset Command regardless of detect state, something is very wrong, just assume it's UBLOX. // Factory Reset byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFB, 0x00, 0x00, 0x00, diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 77e1d8042..502763bb6 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -20,12 +20,7 @@ struct uBloxGnssModelInfo { char extension[10][30]; }; -typedef enum { - GNSS_MODEL_MTK, - GNSS_MODEL_UBLOX, - GNSS_MODEL_UC6580, - GNSS_MODEL_UNKNOWN, -} GnssModel_t; +typedef enum { GNSS_MODEL_MTK, GNSS_MODEL_UBLOX, GNSS_MODEL_UC6580, GNSS_MODEL_UNKNOWN, GNSS_MODEL_MTK_L76B } GnssModel_t; typedef enum { GNSS_RESPONSE_NONE, @@ -92,8 +87,11 @@ class GPS : private concurrency::OSThread public: /** If !NULL we will use this serial port to construct our GPS */ +#if defined(RPI_PICO_WAVESHARE) + static SerialUART *_serial_gps; +#else static HardwareSerial *_serial_gps; - +#endif static uint8_t _message_PMREQ[]; static uint8_t _message_PMREQ_10[]; static const uint8_t _message_CFG_RXM_PSM[]; diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 3297c21eb..05fb0a70d 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1513,8 +1513,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 char channelStr[20]; { concurrency::LockGuard guard(&lock); - auto chName = channels.getPrimaryName(); - snprintf(channelStr, sizeof(channelStr), "%s", chName); + snprintf(channelStr, sizeof(channelStr), "#%s", channels.getName(channels.getPrimaryIndex())); } // Display power status diff --git a/src/main.cpp b/src/main.cpp index 667ae007f..f87683b02 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -236,7 +236,7 @@ void setup() #if defined(TTGO_T_ECHO) && defined(PIN_POWER_EN) pinMode(PIN_POWER_EN, OUTPUT); digitalWrite(PIN_POWER_EN, HIGH); - digitalWrite(PIN_POWER_EN1, INPUT); + // digitalWrite(PIN_POWER_EN1, INPUT); #endif #if defined(LORA_TCXO_GPIO) @@ -1005,10 +1005,10 @@ void tft_task_handler(void *param = nullptr) if (deviceScreen) deviceScreen->task_handler(); #ifdef HAS_FREE_RTOS - vTaskDelay((TickType_t)10); + vTaskDelay((TickType_t)5); #else delay(10); #endif } } -#endif \ No newline at end of file +#endif diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index 3e9c78241..840e65bca 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -7,6 +7,8 @@ #include +#include "mqtt/MQTT.h" + /// 16 bytes of random PSK for our _public_ default channel that all devices power up on (AES128) static const uint8_t defaultpsk[] = {0xd4, 0xf1, 0xbb, 0x3a, 0x20, 0x29, 0x07, 0x59, 0xf0, 0xbc, 0xff, 0xab, 0xcf, 0x4e, 0x69, 0x01}; @@ -193,6 +195,10 @@ void Channels::onConfigChanged() if (ch.role == meshtastic_Channel_Role_PRIMARY) primaryIndex = i; } + if (channels.anyMqttEnabled() && mqtt && !mqtt->isEnabled()) { + LOG_DEBUG("MQTT is enabled on at least one channel, so set MQTT thread to run immediately\n"); + mqtt->start(); + } } meshtastic_Channel &Channels::getByIndex(ChannelIndex chIndex) @@ -237,6 +243,16 @@ void Channels::setChannel(const meshtastic_Channel &c) old = c; // slam in the new settings/role } +bool Channels::anyMqttEnabled() +{ + for (int i = 0; i < getNumChannels(); i++) + if (channelFile.channels[i].role != meshtastic_Channel_Role_DISABLED && channelFile.channels[i].has_settings && + (channelFile.channels[i].settings.downlink_enabled || channelFile.channels[i].settings.uplink_enabled)) + return true; + + return false; +} + const char *Channels::getName(size_t chIndex) { // Convert the short "" representation for Default into a usable string @@ -274,40 +290,6 @@ bool Channels::hasDefaultChannel() return false; } -/** -* Generate a short suffix used to disambiguate channels that might have the same "name" entered by the human but different PSKs. -* The ideas is that the PSK changing should be visible to the user so that they see they probably messed up and that's why they -their nodes -* aren't talking to each other. -* -* This string is of the form "#name-X". -* -* Where X is either: -* (for custom PSKS) a letter from A to Z (base26), and formed by xoring all the bytes of the PSK together, -* -* This function will also need to be implemented in GUI apps that talk to the radio. -* -* https://github.com/meshtastic/firmware/issues/269 -*/ -const char *Channels::getPrimaryName() -{ - static char buf[32]; - - char suffix; - // auto channelSettings = getPrimary(); - // if (channelSettings.psk.size != 1) { - // We have a standard PSK, so generate a letter based hash. - uint8_t code = getHash(primaryIndex); - - suffix = 'A' + (code % 26); - /* } else { - suffix = '0' + channelSettings.psk.bytes[0]; - } */ - - snprintf(buf, sizeof(buf), "#%s-%c", getName(primaryIndex), suffix); - return buf; -} - /** Given a channel hash setup crypto for decoding that channel (or the primary channel if that channel is unsecured) * * This method is called before decoding inbound packets diff --git a/src/mesh/Channels.h b/src/mesh/Channels.h index 0e11605c4..952445a1d 100644 --- a/src/mesh/Channels.h +++ b/src/mesh/Channels.h @@ -61,25 +61,6 @@ class Channels ChannelIndex getNumChannels() { return channelFile.channels_count; } - /** - * Generate a short suffix used to disambiguate channels that might have the same "name" entered by the human but different - PSKs. - * The ideas is that the PSK changing should be visible to the user so that they see they probably messed up and that's why - they their nodes - * aren't talking to each other. - * - * This string is of the form "#name-X". - * - * Where X is either: - * (for custom PSKS) a letter from A to Z (base26), and formed by xoring all the bytes of the PSK together, - * OR (for the standard minimially secure PSKs) a number from 0 to 9. - * - * This function will also need to be implemented in GUI apps that talk to the radio. - * - * https://github.com/meshtastic/firmware/issues/269 - */ - const char *getPrimaryName(); - /// Called by NodeDB on initial boot when the radio config settings are unset. Set a default single channel config. void initDefaults(); @@ -105,6 +86,9 @@ class Channels // Returns true if we can be reached via a channel with the default settings given a region and modem preset bool hasDefaultChannel(); + // Returns true if any of our channels have enabled MQTT uplink or downlink + bool anyMqttEnabled(); + private: /** Given a channel index, change to use the crypto key specified by that index * diff --git a/src/mesh/Default.cpp b/src/mesh/Default.cpp new file mode 100644 index 000000000..db058c5b0 --- /dev/null +++ b/src/mesh/Default.cpp @@ -0,0 +1,23 @@ +#include "Default.h" + +uint32_t Default::getConfiguredOrDefaultMs(uint32_t configuredInterval) +{ + if (configuredInterval > 0) + return configuredInterval * 1000; + return default_broadcast_interval_secs * 1000; +} + +uint32_t Default::getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval) +{ + if (configuredInterval > 0) + return configuredInterval * 1000; + return defaultInterval * 1000; +} + +uint32_t Default::getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue) +{ + if (configured > 0) + return configured; + + return defaultValue; +} \ No newline at end of file diff --git a/src/mesh/Default.h b/src/mesh/Default.h new file mode 100644 index 000000000..734cdf519 --- /dev/null +++ b/src/mesh/Default.h @@ -0,0 +1,30 @@ +#pragma once +#include +#include +#define ONE_DAY 24 * 60 * 60 + +#define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60) +#define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60) +#define default_wait_bluetooth_secs IF_ROUTER(1, 60) +#define default_sds_secs IF_ROUTER(ONE_DAY, UINT32_MAX) // Default to forever super deep sleep +#define default_ls_secs IF_ROUTER(ONE_DAY, 5 * 60) +#define default_min_wake_secs 10 +#define default_screen_on_secs IF_ROUTER(1, 60 * 10) +#define default_node_info_broadcast_secs 3 * 60 * 60 +#define min_node_info_broadcast_secs 60 * 60 // No regular broadcasts of more than once an hour + +#define default_mqtt_address "mqtt.meshtastic.org" +#define default_mqtt_username "meshdev" +#define default_mqtt_password "large4cats" +#define default_mqtt_root "msh" + +#define IF_ROUTER(routerVal, normalVal) \ + ((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal)) + +class Default +{ + public: + static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval); + static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval); + static uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue); +}; diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 9d7647138..04b6fe89d 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -3,6 +3,7 @@ #include "../detect/ScanI2C.h" #include "Channels.h" #include "CryptoEngine.h" +#include "Default.h" #include "FSCommon.h" #include "GPS.h" #include "MeshRadio.h" @@ -97,22 +98,6 @@ bool NodeDB::resetRadioConfig(bool factory_reset) channels.onConfigChanged(); - // temp hack for quicker testing - // devicestate.no_save = true; - if (devicestate.no_save) { - LOG_DEBUG("***** DEVELOPMENT MODE - DO NOT RELEASE *****\n"); - - // Sleep quite frequently to stress test the BLE comms, broadcast position every 6 mins - config.display.screen_on_secs = 10; - config.power.wait_bluetooth_secs = 10; - config.position.position_broadcast_secs = 6 * 60; - config.power.ls_secs = 60; - config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_TW; - - // Enter super deep sleep soon and stay there not very long - // radioConfig.preferences.sds_secs = 60; - } - // Update the global myRegion initRegion(); @@ -199,7 +184,7 @@ void NodeDB::installDefaultConfig() config.position.broadcast_smart_minimum_distance = 100; config.position.broadcast_smart_minimum_interval_secs = 30; if (config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER) - config.device.node_info_broadcast_secs = 3 * 60 * 60; + config.device.node_info_broadcast_secs = default_node_info_broadcast_secs; config.device.serial_enabled = true; resetRadioConfig(); strncpy(config.network.ntp_server, "0.pool.ntp.org", 32); @@ -653,61 +638,52 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_ void NodeDB::saveChannelsToDisk() { - if (!devicestate.no_save) { #ifdef FSCom - FSCom.mkdir("/prefs"); + FSCom.mkdir("/prefs"); #endif - saveProto(channelFileName, meshtastic_ChannelFile_size, &meshtastic_ChannelFile_msg, &channelFile); - } + saveProto(channelFileName, meshtastic_ChannelFile_size, &meshtastic_ChannelFile_msg, &channelFile); } void NodeDB::saveDeviceStateToDisk() { - if (!devicestate.no_save) { #ifdef FSCom - FSCom.mkdir("/prefs"); + FSCom.mkdir("/prefs"); #endif - saveProto(prefFileName, meshtastic_DeviceState_size, &meshtastic_DeviceState_msg, &devicestate); - } } void NodeDB::saveToDisk(int saveWhat) { - if (!devicestate.no_save) { #ifdef FSCom - FSCom.mkdir("/prefs"); + FSCom.mkdir("/prefs"); #endif - if (saveWhat & SEGMENT_DEVICESTATE) { - saveDeviceStateToDisk(); - } + if (saveWhat & SEGMENT_DEVICESTATE) { + saveDeviceStateToDisk(); + } - if (saveWhat & SEGMENT_CONFIG) { - config.has_device = true; - config.has_display = true; - config.has_lora = true; - config.has_position = true; - config.has_power = true; - config.has_network = true; - config.has_bluetooth = true; - saveProto(configFileName, meshtastic_LocalConfig_size, &meshtastic_LocalConfig_msg, &config); - } + if (saveWhat & SEGMENT_CONFIG) { + config.has_device = true; + config.has_display = true; + config.has_lora = true; + config.has_position = true; + config.has_power = true; + config.has_network = true; + config.has_bluetooth = true; + saveProto(configFileName, meshtastic_LocalConfig_size, &meshtastic_LocalConfig_msg, &config); + } - if (saveWhat & SEGMENT_MODULECONFIG) { - moduleConfig.has_canned_message = true; - moduleConfig.has_external_notification = true; - moduleConfig.has_mqtt = true; - moduleConfig.has_range_test = true; - moduleConfig.has_serial = true; - moduleConfig.has_store_forward = true; - moduleConfig.has_telemetry = true; - saveProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, &meshtastic_LocalModuleConfig_msg, &moduleConfig); - } + if (saveWhat & SEGMENT_MODULECONFIG) { + moduleConfig.has_canned_message = true; + moduleConfig.has_external_notification = true; + moduleConfig.has_mqtt = true; + moduleConfig.has_range_test = true; + moduleConfig.has_serial = true; + moduleConfig.has_store_forward = true; + moduleConfig.has_telemetry = true; + saveProto(moduleConfigFileName, meshtastic_LocalModuleConfig_size, &meshtastic_LocalModuleConfig_msg, &moduleConfig); + } - if (saveWhat & SEGMENT_CHANNELS) { - saveChannelsToDisk(); - } - } else { - LOG_DEBUG("***** DEVELOPMENT MODE - DO NOT RELEASE - not saving to flash *****\n"); + if (saveWhat & SEGMENT_CHANNELS) { + saveChannelsToDisk(); } } diff --git a/src/mesh/NodeDB.h b/src/mesh/NodeDB.h index 20cc5c25b..930b3483e 100644 --- a/src/mesh/NodeDB.h +++ b/src/mesh/NodeDB.h @@ -191,46 +191,6 @@ extern NodeDB nodeDB; // Our delay functions check for this for times that should never expire #define NODE_DELAY_FOREVER 0xffffffff -#define IF_ROUTER(routerVal, normalVal) \ - ((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal)) - -#define ONE_DAY 24 * 60 * 60 - -#define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60) -#define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60) -#define default_wait_bluetooth_secs IF_ROUTER(1, 60) -#define default_sds_secs IF_ROUTER(ONE_DAY, UINT32_MAX) // Default to forever super deep sleep -#define default_ls_secs IF_ROUTER(ONE_DAY, 5 * 60) -#define default_min_wake_secs 10 -#define default_screen_on_secs IF_ROUTER(1, 60 * 10) - -#define default_mqtt_address "mqtt.meshtastic.org" -#define default_mqtt_username "meshdev" -#define default_mqtt_password "large4cats" -#define default_mqtt_root "msh" - -inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval) -{ - if (configuredInterval > 0) - return configuredInterval * 1000; - return default_broadcast_interval_secs * 1000; -} - -inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval) -{ - if (configuredInterval > 0) - return configuredInterval * 1000; - return defaultInterval * 1000; -} - -inline uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue) -{ - if (configured > 0) - return configured; - - return defaultValue; -} - /// Sometimes we will have Position objects that only have a time, so check for /// valid lat/lon static inline bool hasValidPosition(const meshtastic_NodeInfoLite *n) diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index 270bf613f..d8e842149 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -1,5 +1,6 @@ #include "PhoneAPI.h" #include "Channels.h" +#include "Default.h" #include "GPS.h" #include "MeshService.h" #include "NodeDB.h" @@ -105,10 +106,17 @@ bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength) break; case meshtastic_ToRadio_mqttClientProxyMessage_tag: LOG_INFO("Got MqttClientProxy message\n"); - if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled) { + if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled && moduleConfig.mqtt.enabled && + (channels.anyMqttEnabled() || moduleConfig.mqtt.map_reporting_enabled)) { mqtt->onClientProxyReceive(toRadioScratch.mqttClientProxyMessage); + } else { + LOG_WARN("MqttClientProxy received but proxy is not enabled, no channels have up/downlink, or map reporting " + "not enabled\n"); } break; + case meshtastic_ToRadio_heartbeat_tag: + LOG_DEBUG("Got client heartbeat\n"); + break; default: // Ignore nop messages // LOG_DEBUG("Error: unexpected ToRadio variant\n"); diff --git a/src/mesh/generated/meshtastic/clientonly.pb.c b/src/mesh/generated/meshtastic/clientonly.pb.c index 90e8e2d8a..ebc2ffabc 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.c +++ b/src/mesh/generated/meshtastic/clientonly.pb.c @@ -9,7 +9,4 @@ PB_BIND(meshtastic_DeviceProfile, meshtastic_DeviceProfile, 2) -PB_BIND(meshtastic_Heartbeat, meshtastic_Heartbeat, AUTO) - - diff --git a/src/mesh/generated/meshtastic/clientonly.pb.h b/src/mesh/generated/meshtastic/clientonly.pb.h index 19b0a0e5f..0f70e09c6 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.h +++ b/src/mesh/generated/meshtastic/clientonly.pb.h @@ -30,12 +30,6 @@ typedef struct _meshtastic_DeviceProfile { meshtastic_LocalModuleConfig module_config; } meshtastic_DeviceProfile; -/* A heartbeat message is sent by a node to indicate that it is still alive. - This is currently only needed to keep serial connections alive. */ -typedef struct _meshtastic_Heartbeat { - char dummy_field; -} meshtastic_Heartbeat; - #ifdef __cplusplus extern "C" { @@ -43,9 +37,7 @@ extern "C" { /* Initializer values for message structs */ #define meshtastic_DeviceProfile_init_default {false, "", false, "", {{NULL}, NULL}, false, meshtastic_LocalConfig_init_default, false, meshtastic_LocalModuleConfig_init_default} -#define meshtastic_Heartbeat_init_default {0} #define meshtastic_DeviceProfile_init_zero {false, "", false, "", {{NULL}, NULL}, false, meshtastic_LocalConfig_init_zero, false, meshtastic_LocalModuleConfig_init_zero} -#define meshtastic_Heartbeat_init_zero {0} /* Field tags (for use in manual encoding/decoding) */ #define meshtastic_DeviceProfile_long_name_tag 1 @@ -66,21 +58,13 @@ X(a, STATIC, OPTIONAL, MESSAGE, module_config, 5) #define meshtastic_DeviceProfile_config_MSGTYPE meshtastic_LocalConfig #define meshtastic_DeviceProfile_module_config_MSGTYPE meshtastic_LocalModuleConfig -#define meshtastic_Heartbeat_FIELDLIST(X, a) \ - -#define meshtastic_Heartbeat_CALLBACK NULL -#define meshtastic_Heartbeat_DEFAULT NULL - extern const pb_msgdesc_t meshtastic_DeviceProfile_msg; -extern const pb_msgdesc_t meshtastic_Heartbeat_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_DeviceProfile_fields &meshtastic_DeviceProfile_msg -#define meshtastic_Heartbeat_fields &meshtastic_Heartbeat_msg /* Maximum encoded size of messages (where known) */ /* meshtastic_DeviceProfile_size depends on runtime parameters */ -#define meshtastic_Heartbeat_size 0 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index 79800d4b4..d6a2a0272 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -141,7 +141,8 @@ typedef struct _meshtastic_DeviceState { NodeDB.cpp in the device code. */ uint32_t version; /* Used only during development. - Indicates developer is testing and changes should never be saved to flash. */ + Indicates developer is testing and changes should never be saved to flash. + Deprecated in 2.3.1 */ bool no_save; /* Some GPS receivers seem to have bogus settings from the factory, so we always do one factory reset. */ bool did_gps_reset; diff --git a/src/mesh/generated/meshtastic/mesh.pb.c b/src/mesh/generated/meshtastic/mesh.pb.c index 790f8be2d..97bb7e53b 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.c +++ b/src/mesh/generated/meshtastic/mesh.pb.c @@ -60,6 +60,9 @@ PB_BIND(meshtastic_Neighbor, meshtastic_Neighbor, AUTO) PB_BIND(meshtastic_DeviceMetadata, meshtastic_DeviceMetadata, AUTO) +PB_BIND(meshtastic_Heartbeat, meshtastic_Heartbeat, AUTO) + + diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index 04590210e..2f57f1ae2 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -682,32 +682,6 @@ typedef struct _meshtastic_QueueStatus { uint32_t mesh_packet_id; } meshtastic_QueueStatus; -/* Packets/commands to the radio will be written (reliably) to the toRadio characteristic. - Once the write completes the phone can assume it is handled. */ -typedef struct _meshtastic_ToRadio { - pb_size_t which_payload_variant; - union { - /* Send this packet on the mesh */ - meshtastic_MeshPacket packet; - /* Phone wants radio to send full node db to the phone, This is - typically the first packet sent to the radio when the phone gets a - bluetooth connection. The radio will respond by sending back a - MyNodeInfo, a owner, a radio config and a series of - FromRadio.node_infos, and config_complete - the integer you write into this field will be reported back in the - config_complete_id response this allows clients to never be confused by - a stale old partially sent config. */ - uint32_t want_config_id; - /* Tell API server we are disconnecting now. - This is useful for serial links where there is no hardware/protocol based notification that the client has dropped the link. - (Sending this message is optional for clients) */ - bool disconnect; - meshtastic_XModem xmodemPacket; - /* MQTT Client Proxy Message (for client / phone subscribed to MQTT sending to device) */ - meshtastic_MqttClientProxyMessage mqttClientProxyMessage; - }; -} meshtastic_ToRadio; - typedef PB_BYTES_ARRAY_T(237) meshtastic_Compressed_data_t; /* Compressed message payload */ typedef struct _meshtastic_Compressed { @@ -815,6 +789,40 @@ typedef struct _meshtastic_FromRadio { }; } meshtastic_FromRadio; +/* A heartbeat message is sent to the node from the client to keep the connection alive. + This is currently only needed to keep serial connections alive, but can be used by any PhoneAPI. */ +typedef struct _meshtastic_Heartbeat { + char dummy_field; +} meshtastic_Heartbeat; + +/* Packets/commands to the radio will be written (reliably) to the toRadio characteristic. + Once the write completes the phone can assume it is handled. */ +typedef struct _meshtastic_ToRadio { + pb_size_t which_payload_variant; + union { + /* Send this packet on the mesh */ + meshtastic_MeshPacket packet; + /* Phone wants radio to send full node db to the phone, This is + typically the first packet sent to the radio when the phone gets a + bluetooth connection. The radio will respond by sending back a + MyNodeInfo, a owner, a radio config and a series of + FromRadio.node_infos, and config_complete + the integer you write into this field will be reported back in the + config_complete_id response this allows clients to never be confused by + a stale old partially sent config. */ + uint32_t want_config_id; + /* Tell API server we are disconnecting now. + This is useful for serial links where there is no hardware/protocol based notification that the client has dropped the link. + (Sending this message is optional for clients) */ + bool disconnect; + meshtastic_XModem xmodemPacket; + /* MQTT Client Proxy Message (for client / phone subscribed to MQTT sending to device) */ + meshtastic_MqttClientProxyMessage mqttClientProxyMessage; + /* Heartbeat message (used to keep the device connection awake on serial) */ + meshtastic_Heartbeat heartbeat; + }; +} meshtastic_ToRadio; + #ifdef __cplusplus extern "C" { @@ -888,6 +896,7 @@ extern "C" { #define meshtastic_DeviceMetadata_hw_model_ENUMTYPE meshtastic_HardwareModel + /* Initializer values for message structs */ #define meshtastic_Position_init_default {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_User_init_default {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} @@ -907,6 +916,7 @@ extern "C" { #define meshtastic_NeighborInfo_init_default {0, 0, 0, 0, {meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default, meshtastic_Neighbor_init_default}} #define meshtastic_Neighbor_init_default {0, 0, 0, 0} #define meshtastic_DeviceMetadata_init_default {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0} +#define meshtastic_Heartbeat_init_default {0} #define meshtastic_Position_init_zero {0, 0, 0, 0, _meshtastic_Position_LocSource_MIN, _meshtastic_Position_AltSource_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_User_init_zero {"", "", "", {0}, _meshtastic_HardwareModel_MIN, 0, _meshtastic_Config_DeviceConfig_Role_MIN} #define meshtastic_RouteDiscovery_init_zero {0, {0, 0, 0, 0, 0, 0, 0, 0}} @@ -925,6 +935,7 @@ extern "C" { #define meshtastic_NeighborInfo_init_zero {0, 0, 0, 0, {meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero, meshtastic_Neighbor_init_zero}} #define meshtastic_Neighbor_init_zero {0, 0, 0, 0} #define meshtastic_DeviceMetadata_init_zero {"", 0, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_Role_MIN, 0, _meshtastic_HardwareModel_MIN, 0} +#define meshtastic_Heartbeat_init_zero {0} /* Field tags (for use in manual encoding/decoding) */ #define meshtastic_Position_latitude_i_tag 1 @@ -1016,11 +1027,6 @@ extern "C" { #define meshtastic_QueueStatus_free_tag 2 #define meshtastic_QueueStatus_maxlen_tag 3 #define meshtastic_QueueStatus_mesh_packet_id_tag 4 -#define meshtastic_ToRadio_packet_tag 1 -#define meshtastic_ToRadio_want_config_id_tag 3 -#define meshtastic_ToRadio_disconnect_tag 4 -#define meshtastic_ToRadio_xmodemPacket_tag 5 -#define meshtastic_ToRadio_mqttClientProxyMessage_tag 6 #define meshtastic_Compressed_portnum_tag 1 #define meshtastic_Compressed_data_tag 2 #define meshtastic_Neighbor_node_id_tag 1 @@ -1055,6 +1061,12 @@ extern "C" { #define meshtastic_FromRadio_xmodemPacket_tag 12 #define meshtastic_FromRadio_metadata_tag 13 #define meshtastic_FromRadio_mqttClientProxyMessage_tag 14 +#define meshtastic_ToRadio_packet_tag 1 +#define meshtastic_ToRadio_want_config_id_tag 3 +#define meshtastic_ToRadio_disconnect_tag 4 +#define meshtastic_ToRadio_xmodemPacket_tag 5 +#define meshtastic_ToRadio_mqttClientProxyMessage_tag 6 +#define meshtastic_ToRadio_heartbeat_tag 7 /* Struct field encoding specification for nanopb */ #define meshtastic_Position_FIELDLIST(X, a) \ @@ -1234,12 +1246,14 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,packet,packet), 1) \ X(a, STATIC, ONEOF, UINT32, (payload_variant,want_config_id,want_config_id), 3) \ X(a, STATIC, ONEOF, BOOL, (payload_variant,disconnect,disconnect), 4) \ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,xmodemPacket,xmodemPacket), 5) \ -X(a, STATIC, ONEOF, MESSAGE, (payload_variant,mqttClientProxyMessage,mqttClientProxyMessage), 6) +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,mqttClientProxyMessage,mqttClientProxyMessage), 6) \ +X(a, STATIC, ONEOF, MESSAGE, (payload_variant,heartbeat,heartbeat), 7) #define meshtastic_ToRadio_CALLBACK NULL #define meshtastic_ToRadio_DEFAULT NULL #define meshtastic_ToRadio_payload_variant_packet_MSGTYPE meshtastic_MeshPacket #define meshtastic_ToRadio_payload_variant_xmodemPacket_MSGTYPE meshtastic_XModem #define meshtastic_ToRadio_payload_variant_mqttClientProxyMessage_MSGTYPE meshtastic_MqttClientProxyMessage +#define meshtastic_ToRadio_payload_variant_heartbeat_MSGTYPE meshtastic_Heartbeat #define meshtastic_Compressed_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, UENUM, portnum, 1) \ @@ -1278,6 +1292,11 @@ X(a, STATIC, SINGULAR, BOOL, hasRemoteHardware, 10) #define meshtastic_DeviceMetadata_CALLBACK NULL #define meshtastic_DeviceMetadata_DEFAULT NULL +#define meshtastic_Heartbeat_FIELDLIST(X, a) \ + +#define meshtastic_Heartbeat_CALLBACK NULL +#define meshtastic_Heartbeat_DEFAULT NULL + extern const pb_msgdesc_t meshtastic_Position_msg; extern const pb_msgdesc_t meshtastic_User_msg; extern const pb_msgdesc_t meshtastic_RouteDiscovery_msg; @@ -1296,6 +1315,7 @@ extern const pb_msgdesc_t meshtastic_Compressed_msg; extern const pb_msgdesc_t meshtastic_NeighborInfo_msg; extern const pb_msgdesc_t meshtastic_Neighbor_msg; extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; +extern const pb_msgdesc_t meshtastic_Heartbeat_msg; /* Defines for backwards compatibility with code written before nanopb-0.4.0 */ #define meshtastic_Position_fields &meshtastic_Position_msg @@ -1316,12 +1336,14 @@ extern const pb_msgdesc_t meshtastic_DeviceMetadata_msg; #define meshtastic_NeighborInfo_fields &meshtastic_NeighborInfo_msg #define meshtastic_Neighbor_fields &meshtastic_Neighbor_msg #define meshtastic_DeviceMetadata_fields &meshtastic_DeviceMetadata_msg +#define meshtastic_Heartbeat_fields &meshtastic_Heartbeat_msg /* Maximum encoded size of messages (where known) */ #define meshtastic_Compressed_size 243 #define meshtastic_Data_size 270 #define meshtastic_DeviceMetadata_size 46 #define meshtastic_FromRadio_size 510 +#define meshtastic_Heartbeat_size 0 #define meshtastic_LogRecord_size 81 #define meshtastic_MeshPacket_size 326 #define meshtastic_MqttClientProxyMessage_size 501 diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index abd7c2e54..6c4c80dbb 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -16,6 +16,7 @@ #ifdef ARCH_PORTDUINO #include "unistd.h" #endif +#include "Default.h" #include "mqtt/MQTT.h" @@ -302,6 +303,10 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) // If we're setting router role for the first time, install its intervals if (existingRole != c.payload_variant.device.role) nodeDB.installRoleDefaults(c.payload_variant.device.role); + if (config.device.node_info_broadcast_secs < min_node_info_broadcast_secs) { + LOG_DEBUG("Tried to set node_info_broadcast_secs too low, setting to %d\n", min_node_info_broadcast_secs); + config.device.node_info_broadcast_secs = min_node_info_broadcast_secs; + } break; case meshtastic_Config_position_tag: LOG_INFO("Setting config: Position\n"); diff --git a/src/modules/AtakPluginModule.cpp b/src/modules/AtakPluginModule.cpp index ffc4fe68a..64a85e2bf 100644 --- a/src/modules/AtakPluginModule.cpp +++ b/src/modules/AtakPluginModule.cpp @@ -1,4 +1,5 @@ #include "AtakPluginModule.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" diff --git a/src/modules/DetectionSensorModule.cpp b/src/modules/DetectionSensorModule.cpp index 6c35e94ae..fd26749c1 100644 --- a/src/modules/DetectionSensorModule.cpp +++ b/src/modules/DetectionSensorModule.cpp @@ -1,10 +1,10 @@ #include "DetectionSensorModule.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" #include "configuration.h" #include "main.h" - DetectionSensorModule *detectionSensorModule; #define GPIO_POLLING_INTERVAL 100 @@ -49,7 +49,7 @@ int32_t DetectionSensorModule::runOnce() // LOG_DEBUG("Detection Sensor Module: Current pin state: %i\n", digitalRead(moduleConfig.detection_sensor.monitor_pin)); - if ((millis() - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs) && + if ((millis() - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs) && hasDetectionEvent()) { sendDetectionMessage(); return DELAYED_INTERVAL; @@ -58,7 +58,8 @@ int32_t DetectionSensorModule::runOnce() // of heartbeat. We only do this if the minimum broadcast interval is greater than zero, otherwise we'll only broadcast state // change detections. else if (moduleConfig.detection_sensor.state_broadcast_secs > 0 && - (millis() - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.detection_sensor.state_broadcast_secs)) { + (millis() - lastSentToMesh) >= + Default::getConfiguredOrDefaultMs(moduleConfig.detection_sensor.state_broadcast_secs)) { sendCurrentStateMessage(); return DELAYED_INTERVAL; } diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 2e0b04afa..024f321e6 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -1,4 +1,5 @@ #include "NeighborInfoModule.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "RTC.h" @@ -194,7 +195,7 @@ int32_t NeighborInfoModule::runOnce() { bool requestReplies = false; sendNeighborInfo(NODENUM_BROADCAST, requestReplies); - return getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs); + return Default::getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs); } /* diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index b0b4bbdcd..370847b94 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -1,4 +1,5 @@ #include "NodeInfoModule.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "RTC.h" @@ -58,8 +59,8 @@ void NodeInfoModule::sendOurNodeInfo(NodeNum dest, bool wantReplies, uint8_t cha meshtastic_MeshPacket *NodeInfoModule::allocReply() { uint32_t now = millis(); - // If we sent our NodeInfo less than 1 min. ago, don't send it again as it may be still underway. - if (lastSentToMesh && (now - lastSentToMesh) < 60 * 1000) { + // If we sent our NodeInfo less than 5 min. ago, don't send it again as it may be still underway. + if (lastSentToMesh && (now - lastSentToMesh) < (5 * 60 * 1000)) { LOG_DEBUG("Sending NodeInfo will be ignored since we just sent it.\n"); ignoreRequest = true; // Mark it as ignored for MeshModule return NULL; @@ -91,6 +92,5 @@ int32_t NodeInfoModule::runOnce() LOG_INFO("Sending our nodeinfo to mesh (wantReplies=%d)\n", requestReplies); sendOurNodeInfo(NODENUM_BROADCAST, requestReplies); // Send our info (don't request replies) } - - return getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_broadcast_interval_secs); + return Default::getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_node_info_broadcast_secs); } diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index 59f62bd5c..853808f44 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -1,4 +1,5 @@ #include "PositionModule.h" +#include "Default.h" #include "GPS.h" #include "MeshService.h" #include "NodeDB.h" @@ -280,7 +281,7 @@ int32_t PositionModule::runOnce() { if (sleepOnNextExecution == true) { sleepOnNextExecution = false; - uint32_t nightyNightMs = getConfiguredOrDefaultMs(config.position.position_broadcast_secs); + uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(config.position.position_broadcast_secs); LOG_DEBUG("Sleeping for %ims, then awaking to send position again.\n", nightyNightMs); doDeepSleep(nightyNightMs, false); } @@ -291,7 +292,8 @@ int32_t PositionModule::runOnce() // We limit our GPS broadcasts to a max rate uint32_t now = millis(); - uint32_t intervalMs = getConfiguredOrDefaultMs(config.position.position_broadcast_secs, default_broadcast_interval_secs); + uint32_t intervalMs = + Default::getConfiguredOrDefaultMs(config.position.position_broadcast_secs, default_broadcast_interval_secs); uint32_t msSinceLastSend = now - lastGpsSend; // Only send packets if the channel util. is less than 25% utilized or we're a tracker with less than 40% utilized. if (!airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_TRACKER && @@ -322,7 +324,7 @@ int32_t PositionModule::runOnce() if (hasValidPosition(node2)) { // The minimum time (in seconds) that would pass before we are able to send a new position packet. const uint32_t minimumTimeThreshold = - getConfiguredOrDefaultMs(config.position.broadcast_smart_minimum_interval_secs, 30); + Default::getConfiguredOrDefaultMs(config.position.broadcast_smart_minimum_interval_secs, 30); auto smartPosition = getDistanceTraveledSinceLastSend(node->position); @@ -369,7 +371,8 @@ void PositionModule::sendLostAndFoundText() struct SmartPosition PositionModule::getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition) { // The minimum distance to travel before we are able to send a new position packet. - const uint32_t distanceTravelThreshold = getConfiguredOrDefault(config.position.broadcast_smart_minimum_distance, 100); + const uint32_t distanceTravelThreshold = + Default::getConfiguredOrDefault(config.position.broadcast_smart_minimum_distance, 100); // Determine the distance in meters between two points on the globe float distanceTraveledSinceLastSend = GeoCoord::latLongToMeter( diff --git a/src/modules/SerialModule.cpp b/src/modules/SerialModule.cpp index 820e1fb62..1dee42a8d 100644 --- a/src/modules/SerialModule.cpp +++ b/src/modules/SerialModule.cpp @@ -126,8 +126,13 @@ int32_t SerialModule::runOnce() uint32_t baud = getBaudRate(); if (moduleConfig.serial.override_console_serial_port) { +#ifdef RP2040_SLOW_CLOCK + Serial2.flush(); + serialPrint = &Serial2; +#else Serial.flush(); serialPrint = &Serial; +#endif // Give it a chance to flush out 💩 delay(10); } @@ -151,8 +156,13 @@ int32_t SerialModule::runOnce() Serial2.begin(baud, SERIAL_8N1); Serial2.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT); } else { +#ifdef RP2040_SLOW_CLOCK + Serial2.begin(baud, SERIAL_8N1); + Serial2.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT); +#else Serial.begin(baud, SERIAL_8N1); Serial.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT); +#endif } #else Serial.begin(baud, SERIAL_8N1); diff --git a/src/modules/Telemetry/AirQualityTelemetry.cpp b/src/modules/Telemetry/AirQualityTelemetry.cpp index ada1fdef8..3e9b069c4 100644 --- a/src/modules/Telemetry/AirQualityTelemetry.cpp +++ b/src/modules/Telemetry/AirQualityTelemetry.cpp @@ -1,5 +1,6 @@ #include "AirQualityTelemetry.h" #include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -43,7 +44,7 @@ int32_t AirQualityTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.air_quality_interval))) && + ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.air_quality_interval))) && airTime->isTxAllowedAirUtil()) { sendTelemetry(); lastSentToMesh = now; diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp index 55000e4c6..3ed106d1c 100644 --- a/src/modules/Telemetry/DeviceTelemetry.cpp +++ b/src/modules/Telemetry/DeviceTelemetry.cpp @@ -1,5 +1,6 @@ #include "DeviceTelemetry.h" #include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -16,7 +17,7 @@ int32_t DeviceTelemetryModule::runOnce() { uint32_t now = millis(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) && + ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.device_update_interval))) && airTime->isTxAllowedChannelUtil() && airTime->isTxAllowedAirUtil() && config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER && config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_HIDDEN) { diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index 7b59c28a6..203b632a7 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -1,5 +1,6 @@ #include "EnvironmentTelemetry.h" #include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -41,7 +42,7 @@ int32_t EnvironmentTelemetryModule::runOnce() { if (sleepOnNextExecution == true) { sleepOnNextExecution = false; - uint32_t nightyNightMs = getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval); + uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval); LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.\n", nightyNightMs); doDeepSleep(nightyNightMs, true); } @@ -102,7 +103,7 @@ int32_t EnvironmentTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval))) && + ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.environment_update_interval))) && airTime->isTxAllowedAirUtil()) { sendTelemetry(); lastSentToMesh = now; diff --git a/src/modules/Telemetry/PowerTelemetry.cpp b/src/modules/Telemetry/PowerTelemetry.cpp index 300ab1f62..713f6aacb 100644 --- a/src/modules/Telemetry/PowerTelemetry.cpp +++ b/src/modules/Telemetry/PowerTelemetry.cpp @@ -1,5 +1,6 @@ #include "PowerTelemetry.h" #include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" #include "MeshService.h" #include "NodeDB.h" #include "PowerFSM.h" @@ -20,7 +21,7 @@ int32_t PowerTelemetryModule::runOnce() { if (sleepOnNextExecution == true) { sleepOnNextExecution = false; - uint32_t nightyNightMs = getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval); + uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval); LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.\n", nightyNightMs); doDeepSleep(nightyNightMs, true); } @@ -66,7 +67,7 @@ int32_t PowerTelemetryModule::runOnce() uint32_t now = millis(); if (((lastSentToMesh == 0) || - ((now - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval))) && + ((now - lastSentToMesh) >= Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.power_update_interval))) && airTime->isTxAllowedAirUtil()) { sendTelemetry(); lastSentToMesh = now; diff --git a/src/modules/Telemetry/Sensor/INA219Sensor.cpp b/src/modules/Telemetry/Sensor/INA219Sensor.cpp index 5a1faa99f..ecb564368 100644 --- a/src/modules/Telemetry/Sensor/INA219Sensor.cpp +++ b/src/modules/Telemetry/Sensor/INA219Sensor.cpp @@ -4,6 +4,10 @@ #include "configuration.h" #include +#ifndef INA219_MULTIPLIER +#define INA219_MULTIPLIER 1.0f +#endif + INA219Sensor::INA219Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_INA219, "INA219") {} int32_t INA219Sensor::runOnce() @@ -26,7 +30,7 @@ void INA219Sensor::setup() {} bool INA219Sensor::getMetrics(meshtastic_Telemetry *measurement) { measurement->variant.environment_metrics.voltage = ina219.getBusVoltage_V(); - measurement->variant.environment_metrics.current = ina219.getCurrent_mA(); + measurement->variant.environment_metrics.current = ina219.getCurrent_mA() * INA219_MULTIPLIER; return true; } diff --git a/src/modules/esp32/PaxcounterModule.cpp b/src/modules/esp32/PaxcounterModule.cpp index 54c67fad7..aad7b5d63 100644 --- a/src/modules/esp32/PaxcounterModule.cpp +++ b/src/modules/esp32/PaxcounterModule.cpp @@ -1,8 +1,8 @@ #include "configuration.h" #if defined(ARCH_ESP32) +#include "Default.h" #include "MeshService.h" #include "PaxcounterModule.h" - #include PaxcounterModule *paxcounterModule; @@ -82,9 +82,9 @@ int32_t PaxcounterModule::runOnce() if (isActive()) { if (firstTime) { firstTime = false; - LOG_DEBUG( - "Paxcounter starting up with interval of %d seconds\n", - getConfiguredOrDefault(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs)); + LOG_DEBUG("Paxcounter starting up with interval of %d seconds\n", + Default::getConfiguredOrDefault(moduleConfig.paxcounter.paxcounter_update_interval, + default_broadcast_interval_secs)); struct libpax_config_t configuration; libpax_default_config(&configuration); @@ -104,7 +104,8 @@ int32_t PaxcounterModule::runOnce() } else { sendInfo(NODENUM_BROADCAST); } - return getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval, default_broadcast_interval_secs); + return Default::getConfiguredOrDefaultMs(moduleConfig.paxcounter.paxcounter_update_interval, + default_broadcast_interval_secs); } else { return disable(); } diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index c518bc4b5..7e341a18c 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -17,6 +17,7 @@ #include "mesh/wifi/WiFiAPClient.h" #include #endif +#include "Default.h" #include const int reconnectMax = 5; @@ -371,22 +372,9 @@ void MQTT::sendSubscriptions() bool MQTT::wantsLink() const { - bool hasChannelorMapReport = false; + bool hasChannelorMapReport = + moduleConfig.mqtt.enabled && (moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled()); - if (moduleConfig.mqtt.enabled) { - hasChannelorMapReport = moduleConfig.mqtt.map_reporting_enabled; - if (!hasChannelorMapReport) { - // No need for link if no channel needed it - size_t numChan = channels.getNumChannels(); - for (size_t i = 0; i < numChan; i++) { - const auto &ch = channels.getByIndex(i); - if (ch.settings.uplink_enabled || ch.settings.downlink_enabled) { - hasChannelorMapReport = true; - break; - } - } - } - } if (hasChannelorMapReport && moduleConfig.mqtt.proxy_to_client_enabled) return true; @@ -401,7 +389,7 @@ bool MQTT::wantsLink() const int32_t MQTT::runOnce() { - if (!moduleConfig.mqtt.enabled) + if (!moduleConfig.mqtt.enabled || !(moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled())) return disable(); bool wantConnection = wantsLink(); @@ -915,4 +903,4 @@ bool MQTT::isValidJsonEnvelope(JSONObject &json) (json["from"]->AsNumber() == nodeDB.getNodeNum()) && // only accept message if the "from" is us (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type (json.find("payload") != json.end()); // should have a payload -} +} \ No newline at end of file diff --git a/src/mqtt/MQTT.h b/src/mqtt/MQTT.h index eeeb00d92..dbc0c77b3 100644 --- a/src/mqtt/MQTT.h +++ b/src/mqtt/MQTT.h @@ -71,6 +71,10 @@ class MQTT : private concurrency::OSThread void onClientProxyReceive(meshtastic_MqttClientProxyMessage msg); + bool isEnabled() { return this->enabled; }; + + void start() { setIntervalFromNow(0); }; + protected: PointerQueue mqttQueue; diff --git a/src/platform/rp2040/main-rp2040.cpp b/src/platform/rp2040/main-rp2040.cpp index 283b801f1..af3aeadc3 100644 --- a/src/platform/rp2040/main-rp2040.cpp +++ b/src/platform/rp2040/main-rp2040.cpp @@ -1,4 +1,7 @@ #include "configuration.h" +#include +#include +#include #include #include @@ -35,9 +38,56 @@ void rp2040Setup() Taken from CPU cycle counter and ROSC oscillator, so should be pretty random. */ randomSeed(rp2040.hwrand32()); + +#ifdef RP2040_SLOW_CLOCK + uint f_pll_sys = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_PLL_SYS_CLKSRC_PRIMARY); + uint f_pll_usb = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_PLL_USB_CLKSRC_PRIMARY); + uint f_rosc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_ROSC_CLKSRC); + uint f_clk_sys = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_SYS); + uint f_clk_peri = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_PERI); + uint f_clk_usb = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_USB); + uint f_clk_adc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_ADC); + uint f_clk_rtc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_RTC); + + LOG_INFO("Clock speed:\n"); + LOG_INFO("pll_sys = %dkHz\n", f_pll_sys); + LOG_INFO("pll_usb = %dkHz\n", f_pll_usb); + LOG_INFO("rosc = %dkHz\n", f_rosc); + LOG_INFO("clk_sys = %dkHz\n", f_clk_sys); + LOG_INFO("clk_peri = %dkHz\n", f_clk_peri); + LOG_INFO("clk_usb = %dkHz\n", f_clk_usb); + LOG_INFO("clk_adc = %dkHz\n", f_clk_adc); + LOG_INFO("clk_rtc = %dkHz\n", f_clk_rtc); +#endif } void enterDfuMode() { reset_usb_boot(0, 0); -} \ No newline at end of file +} + +/* Init in early boot state. */ +#ifdef RP2040_SLOW_CLOCK +void initVariant() +{ + /* Set the system frequency to 18 MHz. */ + set_sys_clock_khz(18 * KHZ, false); + /* The previous line automatically detached clk_peri from clk_sys, and + attached it to pll_usb. We need to attach clk_peri back to system PLL to keep SPI + working at this low speed. + For details see https://github.com/jgromes/RadioLib/discussions/938 + */ + clock_configure(clk_peri, + 0, // No glitchless mux + CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLKSRC_PLL_SYS, // System PLL on AUX mux + 18 * MHZ, // Input frequency + 18 * MHZ // Output (must be same as no divider) + ); + /* Run also ADC on lower clk_sys. */ + clock_configure(clk_adc, 0, CLOCKS_CLK_ADC_CTRL_AUXSRC_VALUE_CLKSRC_PLL_SYS, 18 * MHZ, 18 * MHZ); + /* Run RTC from XOSC since USB clock is off */ + clock_configure(clk_rtc, 0, CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_XOSC_CLKSRC, 12 * MHZ, 47 * KHZ); + /* Turn off USB PLL */ + pll_deinit(pll_usb); +} +#endif \ No newline at end of file diff --git a/src/sleep.cpp b/src/sleep.cpp index bfacffeb9..6d8e4f3cc 100644 --- a/src/sleep.cpp +++ b/src/sleep.cpp @@ -203,7 +203,7 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false) #ifdef TTGO_T_ECHO #ifdef PIN_POWER_EN pinMode(PIN_POWER_EN, INPUT); // power off peripherals - pinMode(PIN_POWER_EN1, INPUT_PULLDOWN); + // pinMode(PIN_POWER_EN1, INPUT_PULLDOWN); #endif #endif diff --git a/variants/portduino/platformio.ini b/variants/portduino/platformio.ini index 447020ba7..f123b9f07 100644 --- a/variants/portduino/platformio.ini +++ b/variants/portduino/platformio.ini @@ -34,6 +34,7 @@ lib_deps = ${portduino_base.lib_deps} build_src_filter = ${portduino_base.build_src_filter} - +<../lib/device-ui/generated/ui_320x240> + +<../lib/device-ui/generated/ui_320x240/fonts> +<../lib/device-ui/resources> +<../lib/device-ui/source> + diff --git a/variants/rpipico-slowclock/platformio.ini b/variants/rpipico-slowclock/platformio.ini new file mode 100644 index 000000000..e583c4b0d --- /dev/null +++ b/variants/rpipico-slowclock/platformio.ini @@ -0,0 +1,28 @@ +[env:pico_slowclock] +extends = rp2040_base +board = rpipico +upload_protocol = jlink +# debug settings for external openocd with RP2040 support (custom build) +debug_tool = custom +debug_init_cmds = + target extended-remote localhost:3333 + $INIT_BREAK + monitor reset halt + $LOAD_CMDS + monitor init + monitor reset halt + +# add our variants files to the include and src paths +build_flags = ${rp2040_base.build_flags} + -DRPI_PICO + -Ivariants/rpipico_slowclock + -DDEBUG_RP2040_PORT=Serial2 + -DHW_SPI1_DEVICE + -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m0plus" + -g + -DNO_USB +lib_deps = + ${rp2040_base.lib_deps} +debug_build_flags = ${rp2040_base.build_flags} + -g + -DNO_USB \ No newline at end of file diff --git a/variants/rpipico-slowclock/variant.h b/variants/rpipico-slowclock/variant.h new file mode 100644 index 000000000..fb97ec0fb --- /dev/null +++ b/variants/rpipico-slowclock/variant.h @@ -0,0 +1,87 @@ +#define ARDUINO_ARCH_AVR + +// Build with slow system clock enabled to reduce power consumption. +#define RP2040_SLOW_CLOCK + +#ifdef RP2040_SLOW_CLOCK +// Redefine UART1 serial log output to avoid collision with UART0 for GPS. +#define SERIAL2_TX 4 +#define SERIAL2_RX 5 +// Reroute log output in SensorLib when USB is not available +#define log_e(...) Serial2.printf(__VA_ARGS__) +#define log_i(...) Serial2.printf(__VA_ARGS__) +#define log_d(...) Serial2.printf(__VA_ARGS__) +#endif + +// Expecting the Waveshare Pico GPS hat +#define HAS_GPS 1 + +// Enable OLED Screen +#define HAS_SCREEN 1 +#define USE_SH1106 1 +#define RESET_OLED 13 + +// Redefine I2C0 pins to avoid collision with UART1/Serial2. +#define I2C_SDA 8 +#define I2C_SCL 9 + +// Redefine Waveshare UPS-A/B I2C_1 pins: +#define I2C_SDA1 6 +#define I2C_SCL1 7 +// Waveshare UPS-A/B uses a 0.01 Ohm shunt for the INA219 sensor +#define INA219_MULTIPLIER 10.0f + +// Waveshare Pico GPS L76B pins: +#define GPS_RX_PIN 1 +#define GPS_TX_PIN 0 + +// Wakeup from backup mode +// #define PIN_GPS_FORCE_ON 14 +// No GPS reset available +#undef PIN_GPS_RESET +/* + * For PPS output the resistor R20 needs to be populated with 0 Ohm + * on the Waveshare Pico GPS board. + */ +#define PIN_GPS_PPS 16 +/* + * For standby mode switching the resistor R18 needs to be populated + * with 0 Ohm on the Waveshare Pico GPS board. + */ +#define PIN_GPS_STANDBY 17 + +#define BUTTON_PIN 18 +#define EXT_NOTIFY_OUT 22 +#define LED_PIN PIN_LED + +#define BATTERY_PIN 26 +// ratio of voltage divider = 3.0 (R17=200k, R18=100k) +#define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic +#define BATTERY_SENSE_RESOLUTION_BITS ADC_RESOLUTION + +#define USE_SX1262 + +#undef LORA_SCK +#undef LORA_MISO +#undef LORA_MOSI +#undef LORA_CS + +#define LORA_SCK 10 +#define LORA_MISO 12 +#define LORA_MOSI 11 +#define LORA_CS 3 + +#define LORA_DIO0 RADIOLIB_NC +#define LORA_RESET 15 +#define LORA_DIO1 20 +#define LORA_DIO2 2 +#define LORA_DIO3 RADIOLIB_NC + +#ifdef USE_SX1262 +#define SX126X_CS LORA_CS +#define SX126X_DIO1 LORA_DIO1 +#define SX126X_BUSY LORA_DIO2 +#define SX126X_RESET LORA_RESET +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 +#endif \ No newline at end of file diff --git a/variants/t-deck/platformio.ini b/variants/t-deck/platformio.ini index b1a5c0da9..770a39869 100644 --- a/variants/t-deck/platformio.ini +++ b/variants/t-deck/platformio.ini @@ -6,6 +6,7 @@ board_build.partitions = default_16MB.csv ; just for test upload_protocol = esp-builtin build_flags = ${esp32_base.build_flags} -fno-omit-frame-pointer -D T_DECK + -D MAX_THREADS=40 -D HAS_SCREEN=0 -D HAS_TFT=1 -D GPS_POWER_TOGGLE @@ -24,6 +25,7 @@ build_flags = ${esp32_base.build_flags} -fno-omit-frame-pointer -I variants/t-deck build_src_filter = ${esp32_base.build_src_filter} +<../lib/device-ui/generated/ui_320x240> + +<../lib/device-ui/resources> +<../lib/device-ui/source> lib_deps = ${esp32_base.lib_deps} diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h index 19a66719f..13f74d303 100644 --- a/variants/t-echo/variant.h +++ b/variants/t-echo/variant.h @@ -158,7 +158,7 @@ External serial flash WP25R1635FZUIL0 // Controls power for all peripherals (eink + GPS + LoRa + Sensor) #define PIN_POWER_EN (0 + 12) -#define PIN_POWER_EN1 (0 + 13) +// #define PIN_POWER_EN1 (0 + 13) #define USE_EINK diff --git a/version.properties b/version.properties index 07fadd0d8..12603eda7 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 3 -build = 1 +build = 2