mirror of
https://github.com/meshtastic/firmware.git
synced 2025-02-26 22:33:24 +00:00
Merge branch 'master' into tft-gui-work
This commit is contained in:
commit
909f77a40b
@ -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
|
||||
|
@ -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,7 +78,7 @@ 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/TinyGPSPlus.git#f9f4fef2183514aa52be91d714c1455dd6f26e45
|
||||
https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3
|
||||
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
|
||||
|
@ -1 +1 @@
|
||||
Subproject commit 7e3ee8cd96740910d0611433cb9a05a7a692568c
|
||||
Subproject commit cf25b390d65113980b1a239e16faa79c7730a736
|
@ -7,16 +7,16 @@
|
||||
#include <Adafruit_LIS3DH.h>
|
||||
#include <Adafruit_MPU6050.h>
|
||||
#include <Arduino.h>
|
||||
#include <SensorBMA423.hpp>
|
||||
#include <Wire.h>
|
||||
#include <bma.h>
|
||||
|
||||
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;
|
||||
}
|
||||
|
@ -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();
|
||||
|
@ -290,6 +290,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
|
||||
@ -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
|
||||
@ -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
|
||||
@ -1169,6 +1210,10 @@ bool GPS::factoryReset()
|
||||
// _serial_gps->write(_message_CFG_RST_COLDSTART, sizeof(_message_CFG_RST_COLDSTART));
|
||||
// delay(1000);
|
||||
} 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,
|
||||
|
@ -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[];
|
||||
|
@ -7,6 +7,8 @@
|
||||
|
||||
#include <assert.h>
|
||||
|
||||
#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
|
||||
|
@ -105,6 +105,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
|
||||
*
|
||||
|
@ -101,16 +101,7 @@ bool NodeDB::resetRadioConfig(bool factory_reset)
|
||||
// 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;
|
||||
// Put your development config changes here
|
||||
}
|
||||
|
||||
// Update the global myRegion
|
||||
@ -199,7 +190,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);
|
||||
|
@ -203,6 +203,8 @@ extern NodeDB nodeDB;
|
||||
#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"
|
||||
|
@ -105,8 +105,12 @@ 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;
|
||||
default:
|
||||
|
@ -9,7 +9,4 @@
|
||||
PB_BIND(meshtastic_DeviceProfile, meshtastic_DeviceProfile, 2)
|
||||
|
||||
|
||||
PB_BIND(meshtastic_Heartbeat, meshtastic_Heartbeat, AUTO)
|
||||
|
||||
|
||||
|
||||
|
@ -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" */
|
||||
|
@ -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)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
@ -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 hearbeat;
|
||||
};
|
||||
} 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_hearbeat_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,hearbeat,hearbeat), 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_hearbeat_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
|
||||
|
@ -302,6 +302,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");
|
||||
|
@ -91,6 +91,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 getConfiguredOrDefaultMs(config.device.node_info_broadcast_secs, default_node_info_broadcast_secs);
|
||||
}
|
||||
|
@ -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);
|
||||
|
@ -371,22 +371,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 +388,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 +902,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
|
||||
}
|
||||
}
|
@ -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<meshtastic_ServiceEnvelope> mqttQueue;
|
||||
|
||||
|
@ -1,4 +1,7 @@
|
||||
#include "configuration.h"
|
||||
#include <hardware/clocks.h>
|
||||
#include <hardware/pll.h>
|
||||
#include <pico/stdlib.h>
|
||||
#include <pico/unique_id.h>
|
||||
#include <stdio.h>
|
||||
|
||||
@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
/* 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
|
Loading…
Reference in New Issue
Block a user