diff --git a/arch/rp2xx0/rp2040.ini b/arch/rp2xx0/rp2040.ini
index 3955fd2f4..62b4ac30c 100644
--- a/arch/rp2xx0/rp2040.ini
+++ b/arch/rp2xx0/rp2040.ini
@@ -1,14 +1,16 @@
; Common settings for rp2040 Processor based targets
[rp2040_base]
-platform = https://github.com/maxgerhardt/platform-raspberrypi.git#60d6ae81fcc73c34b1493ca9e261695e471bc0c2
+platform = https://github.com/maxgerhardt/platform-raspberrypi.git#v1.2.0-gcc12
extends = arduino_base
-platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2
+platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#4.0.3
board_build.core = earlephilhower
board_build.filesystem_size = 0.5m
build_flags =
${arduino_base.build_flags} -Wno-unused-variable -Wcast-align
-Isrc/platform/rp2xx0
+ -Isrc/platform/rp2xx0/hardware_rosc/include
+ -Isrc/platform/rp2xx0/pico_sleep/include
-D__PLAT_RP2040__
# -D _POSIX_THREADS
build_src_filter =
diff --git a/images/compass.png b/images/compass.png
index 8639dde52..c4e5b589b 100644
Binary files a/images/compass.png and b/images/compass.png differ
diff --git a/images/face-24px.svg b/images/face-24px.svg
index 293468664..08e8f5ffc 100644
--- a/images/face-24px.svg
+++ b/images/face-24px.svg
@@ -1 +1 @@
-
\ No newline at end of file
+
\ No newline at end of file
diff --git a/images/face.png b/images/face.png
index 036e29f73..eb6b91e13 100644
Binary files a/images/face.png and b/images/face.png differ
diff --git a/images/location_searching-24px.svg b/images/location_searching-24px.svg
index 7f72a31bc..abef0ef78 100644
--- a/images/location_searching-24px.svg
+++ b/images/location_searching-24px.svg
@@ -1 +1 @@
-
\ No newline at end of file
+
\ No newline at end of file
diff --git a/images/pin.png b/images/pin.png
index 112a7ce8e..3c91a726c 100644
Binary files a/images/pin.png and b/images/pin.png differ
diff --git a/images/room-24px.svg b/images/room-24px.svg
index 79a4807e7..48e55ab80 100644
--- a/images/room-24px.svg
+++ b/images/room-24px.svg
@@ -1 +1 @@
-
\ No newline at end of file
+
\ No newline at end of file
diff --git a/images/textsms-24px.svg b/images/textsms-24px.svg
index 4455f047e..84c4fdcc1 100644
--- a/images/textsms-24px.svg
+++ b/images/textsms-24px.svg
@@ -1 +1 @@
-
\ No newline at end of file
+
\ No newline at end of file
diff --git a/platformio.ini b/platformio.ini
index 2f76c8236..e437b572e 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -27,6 +27,7 @@ default_envs = tbeam
;default_envs = meshtastic-dr-dev
;default_envs = m5stack-coreink
;default_envs = rak4631
+;default_envs = rak4631_eth_gw
;default_envs = rak2560
;default_envs = rak10701
;default_envs = wio-e5
diff --git a/src/Power.cpp b/src/Power.cpp
index 2f5f441ae..2fe28633a 100644
--- a/src/Power.cpp
+++ b/src/Power.cpp
@@ -588,7 +588,7 @@ void Power::shutdown()
{
LOG_INFO("Shutting down\n");
-#if defined(ARCH_NRF52) || defined(ARCH_ESP32)
+#if defined(ARCH_NRF52) || defined(ARCH_ESP32) || defined(ARCH_RP2040)
#ifdef PIN_LED1
ledOff(PIN_LED1);
#endif
diff --git a/src/configuration.h b/src/configuration.h
index 1df40a797..8d0c99ff0 100644
--- a/src/configuration.h
+++ b/src/configuration.h
@@ -145,7 +145,7 @@ along with this program. If not, see .
#define DFROBOT_LARK_ADDR 0x42
#define NAU7802_ADDR 0x2A
#define MAX30102_ADDR 0x57
-#define MLX90614_ADDR 0x5A
+#define MLX90614_ADDR_DEF 0x5A
// -----------------------------------------------------------------------------
// ACCELEROMETER
@@ -187,6 +187,11 @@ along with this program. If not, see .
// -----------------------------------------------------------------------------
#define FT6336U_ADDR 0x48
+// -----------------------------------------------------------------------------
+// BIAS-T Generator
+// -----------------------------------------------------------------------------
+#define TPS65233_ADDR 0x60
+
// convert 24-bit color to 16-bit (56K)
#define COLOR565(r, g, b) (((r & 0xF8) << 8) | ((g & 0xFC) << 3) | ((b & 0xF8) >> 3))
diff --git a/src/detect/ScanI2C.h b/src/detect/ScanI2C.h
index 920af06c7..07db3fd57 100644
--- a/src/detect/ScanI2C.h
+++ b/src/detect/ScanI2C.h
@@ -60,7 +60,8 @@ class ScanI2C
FT6336U,
STK8BAXX,
ICM20948,
- MAX30102
+ MAX30102,
+ TPS65233
} DeviceType;
// typedef uint8_t DeviceAddress;
diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp
index 5cd07b7cc..bf9c5c2d8 100644
--- a/src/detect/ScanI2CTwoWire.cpp
+++ b/src/detect/ScanI2CTwoWire.cpp
@@ -405,7 +405,10 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
SCAN_SIMPLE_CASE(NAU7802_ADDR, NAU7802, "NAU7802 based scale found\n");
SCAN_SIMPLE_CASE(FT6336U_ADDR, FT6336U, "FT6336U touchscreen found\n");
SCAN_SIMPLE_CASE(MAX1704X_ADDR, MAX17048, "MAX17048 lipo fuel gauge found\n");
- SCAN_SIMPLE_CASE(MLX90614_ADDR, MLX90614, "MLX90614 IR temp sensor found\n");
+#ifdef HAS_TPS65233
+ SCAN_SIMPLE_CASE(TPS65233_ADDR, TPS65233, "TPS65233 BIAS-T found\n");
+#endif
+ SCAN_SIMPLE_CASE(MLX90614_ADDR_DEF, MLX90614, "MLX90614 IR temp sensor found\n");
case ICM20948_ADDR: // same as BMX160_ADDR
case ICM20948_ADDR_ALT: // same as MPU6050_ADDR
diff --git a/src/main.cpp b/src/main.cpp
index ba277414f..1e2d5e108 100644
--- a/src/main.cpp
+++ b/src/main.cpp
@@ -319,6 +319,11 @@ void setup()
digitalWrite(VEXT_ENABLE, VEXT_ON_VALUE); // turn on the display power
#endif
+#if defined(BIAS_T_ENABLE)
+ pinMode(BIAS_T_ENABLE, OUTPUT);
+ digitalWrite(BIAS_T_ENABLE, BIAS_T_VALUE); // turn on 5V for GPS Antenna
+#endif
+
#if defined(VTFT_CTRL)
pinMode(VTFT_CTRL, OUTPUT);
digitalWrite(VTFT_CTRL, LOW);
@@ -559,6 +564,21 @@ void setup()
rgb_found = i2cScanner->find(ScanI2C::DeviceType::NCP5623);
#endif
+#ifdef HAS_TPS65233
+ // TPS65233 is a power management IC for satellite modems, used in the Dreamcatcher
+ // We are switching it off here since we don't use an LNB.
+ if (i2cScanner->exists(ScanI2C::DeviceType::TPS65233)) {
+ Wire.beginTransmission(TPS65233_ADDR);
+ Wire.write(0); // Register 0
+ Wire.write(128); // Turn off the LNB power, keep I2C Control enabled
+ Wire.endTransmission();
+ Wire.beginTransmission(TPS65233_ADDR);
+ Wire.write(1); // Register 1
+ Wire.write(0); // Turn off Tone Generator 22kHz
+ Wire.endTransmission();
+ }
+#endif
+
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
auto acc_info = i2cScanner->firstAccelerometer();
accelerometer_found = acc_info.type != ScanI2C::DeviceType::NONE ? acc_info.address : accelerometer_found;
diff --git a/src/mesh/LR11x0Interface.cpp b/src/mesh/LR11x0Interface.cpp
index 6641634c4..a985a9006 100644
--- a/src/mesh/LR11x0Interface.cpp
+++ b/src/mesh/LR11x0Interface.cpp
@@ -72,6 +72,18 @@ template bool LR11x0Interface::init()
limitPower();
+#ifdef LR11X0_RF_SWITCH_SUBGHZ
+ pinMode(LR11X0_RF_SWITCH_SUBGHZ, OUTPUT);
+ digitalWrite(LR11X0_RF_SWITCH_SUBGHZ, getFreq() < 1e9 ? HIGH : LOW);
+ LOG_DEBUG("Setting RF0 switch to %s\n", getFreq() < 1e9 ? "SubGHz" : "2.4GHz");
+#endif
+
+#ifdef LR11X0_RF_SWITCH_2_4GHZ
+ pinMode(LR11X0_RF_SWITCH_2_4GHZ, OUTPUT);
+ digitalWrite(LR11X0_RF_SWITCH_2_4GHZ, getFreq() < 1e9 ? LOW : HIGH);
+ LOG_DEBUG("Setting RF1 switch to %s\n", getFreq() < 1e9 ? "SubGHz" : "2.4GHz");
+#endif
+
int res = lora.begin(getFreq(), bw, sf, cr, syncWord, power, preambleLength, tcxoVoltage);
// \todo Display actual typename of the adapter, not just `LR11x0`
LOG_INFO("LR11x0 init result %d\n", res);
diff --git a/src/mesh/RadioInterface.h b/src/mesh/RadioInterface.h
index 6df51ce1a..89a4c7087 100644
--- a/src/mesh/RadioInterface.h
+++ b/src/mesh/RadioInterface.h
@@ -55,7 +55,7 @@ typedef struct {
PacketHeader header;
/** The payload, of maximum length minus the header, aligned just to be sure */
- uint8_t payload[MAX_LORA_PAYLOAD_LEN + 1 - sizeof(PacketHeader)] __attribute__ ((__aligned__));
+ uint8_t payload[MAX_LORA_PAYLOAD_LEN + 1 - sizeof(PacketHeader)] __attribute__((__aligned__));
} RadioBuffer;
@@ -105,7 +105,7 @@ class RadioInterface
/**
* A temporary buffer used for sending/receiving packets, sized to hold the biggest buffer we might need
* */
- RadioBuffer radioBuffer __attribute__ ((__aligned__));
+ RadioBuffer radioBuffer __attribute__((__aligned__));
/**
* Enqueue a received packet for the registered receiver
*/
diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp
index b5732dee9..195572163 100644
--- a/src/mesh/Router.cpp
+++ b/src/mesh/Router.cpp
@@ -636,19 +636,25 @@ void Router::perhapsHandleReceived(meshtastic_MeshPacket *p)
#endif
// assert(radioConfig.has_preferences);
if (is_in_repeated(config.lora.ignore_incoming, p->from)) {
- LOG_DEBUG("Ignoring incoming message, 0x%x is in our ignore list\n", p->from);
+ LOG_DEBUG("Ignoring msg, 0x%x is in our ignore list\n", p->from);
+ packetPool.release(p);
+ return;
+ }
+
+ if (p->from == NODENUM_BROADCAST) {
+ LOG_DEBUG("Ignoring msg from broadcast address\n");
packetPool.release(p);
return;
}
if (config.lora.ignore_mqtt && p->via_mqtt) {
- LOG_DEBUG("Message came in via MQTT from 0x%x\n", p->from);
+ LOG_DEBUG("Msg came in via MQTT from 0x%x\n", p->from);
packetPool.release(p);
return;
}
if (shouldFilterReceived(p)) {
- LOG_DEBUG("Incoming message was filtered from 0x%x\n", p->from);
+ LOG_DEBUG("Incoming msg was filtered from 0x%x\n", p->from);
packetPool.release(p);
return;
}
diff --git a/src/motion/BMX160Sensor.cpp b/src/motion/BMX160Sensor.cpp
index f18c4b586..3f68a4a25 100755
--- a/src/motion/BMX160Sensor.cpp
+++ b/src/motion/BMX160Sensor.cpp
@@ -5,9 +5,11 @@
BMX160Sensor::BMX160Sensor(ScanI2C::FoundDevice foundDevice) : MotionSensor::MotionSensor(foundDevice) {}
#ifdef RAK_4631
+#if !defined(MESHTASTIC_EXCLUDE_SCREEN)
// screen is defined in main.cpp
extern graphics::Screen *screen;
+#endif
bool BMX160Sensor::init()
{
@@ -29,6 +31,7 @@ int32_t BMX160Sensor::runOnce()
/* Get a new sensor event */
sensor.getAllData(&magAccel, NULL, &gAccel);
+#if !defined(MESHTASTIC_EXCLUDE_SCREEN)
// experimental calibrate routine. Limited to between 10 and 30 seconds after boot
if (millis() > 12 * 1000 && millis() < 30 * 1000) {
if (!showingScreen) {
@@ -91,6 +94,7 @@ int32_t BMX160Sensor::runOnce()
break;
}
screen->setHeading(heading);
+#endif
return MOTION_SENSOR_CHECK_INTERVAL_MS;
}
diff --git a/src/motion/MotionSensor.cpp b/src/motion/MotionSensor.cpp
index 20e396bba..f1c0ba85e 100755
--- a/src/motion/MotionSensor.cpp
+++ b/src/motion/MotionSensor.cpp
@@ -29,7 +29,7 @@ ScanI2C::I2CPort MotionSensor::devicePort()
return device.address.port;
}
-#ifdef RAK_4631
+#if defined(RAK_4631) & !MESHTASTIC_EXCLUDE_SCREEN
void MotionSensor::drawFrameCalibration(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
// int x_offset = display->width() / 2;
diff --git a/src/motion/MotionSensor.h b/src/motion/MotionSensor.h
index 0f7f3479b..4da23cc70 100755
--- a/src/motion/MotionSensor.h
+++ b/src/motion/MotionSensor.h
@@ -46,7 +46,7 @@ class MotionSensor
// Register a button press when a double-tap is detected
virtual void buttonPress();
-#ifdef RAK_4631
+#if defined(RAK_4631) & !MESHTASTIC_EXCLUDE_SCREEN
// draw an OLED frame (currently only used by the RAK4631 BMX160 sensor)
static void drawFrameCalibration(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
#endif
diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp
index 0c1ce0c7c..c0399af38 100644
--- a/src/mqtt/MQTT.cpp
+++ b/src/mqtt/MQTT.cpp
@@ -402,13 +402,14 @@ void MQTT::sendSubscriptions()
std::string topic = cryptTopic + channels.getGlobalId(i) + "/+";
LOG_INFO("Subscribing to %s\n", topic.c_str());
pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right?
-#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804
+#if !defined(ARCH_NRF52) || \
+ defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ###
if (moduleConfig.mqtt.json_enabled == true) {
std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+";
LOG_INFO("Subscribing to %s\n", topicDecoded.c_str());
pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right?
}
-#endif // ARCH_NRF52
+#endif // ARCH_NRF52 NRF52_USE_JSON
}
}
#if !MESHTASTIC_EXCLUDE_PKI
@@ -501,7 +502,8 @@ void MQTT::publishQueuedMessages()
publish(topic.c_str(), bytes, numBytes, false);
-#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804
+#if !defined(ARCH_NRF52) || \
+ defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ###
if (moduleConfig.mqtt.json_enabled) {
// handle json topic
auto jsonString = MeshPacketSerializer::JsonSerialize(env->packet);
@@ -517,7 +519,7 @@ void MQTT::publishQueuedMessages()
publish(topicJson.c_str(), jsonString.c_str(), false);
}
}
-#endif // ARCH_NRF52
+#endif // ARCH_NRF52 NRF52_USE_JSON
mqttPool.release(env);
}
}
@@ -581,7 +583,8 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket &
publish(topic.c_str(), bytes, numBytes, false);
-#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804
+#if !defined(ARCH_NRF52) || \
+ defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ###
if (moduleConfig.mqtt.json_enabled) {
// handle json topic
auto jsonString = MeshPacketSerializer::JsonSerialize((meshtastic_MeshPacket *)&mp_decoded);
@@ -592,7 +595,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket &
publish(topicJson.c_str(), jsonString.c_str(), false);
}
}
-#endif // ARCH_NRF52
+#endif // ARCH_NRF52 NRF52_USE_JSON
} else {
LOG_INFO("MQTT not connected, queueing packet\n");
if (mqttQueue.numFree() == 0) {
diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp
index fbc0728d7..63d9331ad 100644
--- a/src/platform/nrf52/NRF52Bluetooth.cpp
+++ b/src/platform/nrf52/NRF52Bluetooth.cpp
@@ -320,6 +320,7 @@ bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passke
{
LOG_INFO("BLE pairing process started with passkey %.3s %.3s\n", passkey, passkey + 3);
powerFSM.trigger(EVENT_BLUETOOTH_PAIR);
+#if !defined(MESHTASTIC_EXCLUDE_SCREEN)
screen->startAlert([](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void {
char btPIN[16] = "888888";
snprintf(btPIN, sizeof(btPIN), "%06u", configuredPasskey);
@@ -345,6 +346,7 @@ bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passke
y_offset = display->height() == 64 ? y_offset + FONT_HEIGHT_LARGE - 6 : y_offset + FONT_HEIGHT_LARGE + 5;
display->drawString(x_offset + x, y_offset + y, deviceName);
});
+#endif
if (match_request) {
uint32_t start_time = millis();
while (millis() < start_time + 30000) {
diff --git a/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h b/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h
new file mode 100644
index 000000000..e1e014f33
--- /dev/null
+++ b/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h
@@ -0,0 +1,93 @@
+/*
+ * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef _HARDWARE_ROSC_H_
+#define _HARDWARE_ROSC_H_
+
+#include "hardware/structs/rosc.h"
+#include "pico.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/** \file rosc.h
+ * \defgroup hardware_rosc hardware_rosc
+ *
+ * Ring Oscillator (ROSC) API
+ *
+ * A Ring Oscillator is an on-chip oscillator that requires no external crystal. Instead, the output is generated from a series of
+ * inverters that are chained together to create a feedback loop. RP2040 boots from the ring oscillator initially, meaning the
+ * first stages of the bootrom, including booting from SPI flash, will be clocked by the ring oscillator. If your design has a
+ * crystal oscillator, you’ll likely want to switch to this as your reference clock as soon as possible, because the frequency is
+ * more accurate than the ring oscillator.
+ */
+
+/*! \brief Set frequency of the Ring Oscillator
+ * \ingroup hardware_rosc
+ *
+ * \param code The drive strengths. See the RP2040 datasheet for information on this value.
+ */
+void rosc_set_freq(uint32_t code);
+
+/*! \brief Set range of the Ring Oscillator
+ * \ingroup hardware_rosc
+ *
+ * Frequency range. Frequencies will vary with Process, Voltage & Temperature (PVT).
+ * Clock output will not glitch when changing the range up one step at a time.
+ *
+ * \param range 0x01 Low, 0x02 Medium, 0x03 High, 0x04 Too High.
+ */
+void rosc_set_range(uint range);
+
+/*! \brief Disable the Ring Oscillator
+ * \ingroup hardware_rosc
+ *
+ */
+void rosc_disable(void);
+
+/*! \brief Put Ring Oscillator in to dormant mode.
+ * \ingroup hardware_rosc
+ *
+ * The ROSC supports a dormant mode,which stops oscillation until woken up up by an asynchronous interrupt.
+ * This can either come from the RTC, being clocked by an external clock, or a GPIO pin going high or low.
+ * If no IRQ is configured before going into dormant mode the ROSC will never restart.
+ *
+ * PLLs should be stopped before selecting dormant mode.
+ */
+void rosc_set_dormant(void);
+
+// FIXME: Add doxygen
+
+uint32_t next_rosc_code(uint32_t code);
+
+uint rosc_find_freq(uint32_t low_mhz, uint32_t high_mhz);
+
+void rosc_set_div(uint32_t div);
+
+inline static void rosc_clear_bad_write(void)
+{
+ hw_clear_bits(&rosc_hw->status, ROSC_STATUS_BADWRITE_BITS);
+}
+
+inline static bool rosc_write_okay(void)
+{
+ return !(rosc_hw->status & ROSC_STATUS_BADWRITE_BITS);
+}
+
+inline static void rosc_write(io_rw_32 *addr, uint32_t value)
+{
+ rosc_clear_bad_write();
+ assert(rosc_write_okay());
+ *addr = value;
+ assert(rosc_write_okay());
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
\ No newline at end of file
diff --git a/src/platform/rp2xx0/hardware_rosc/rosc.c b/src/platform/rp2xx0/hardware_rosc/rosc.c
new file mode 100644
index 000000000..f79929f8d
--- /dev/null
+++ b/src/platform/rp2xx0/hardware_rosc/rosc.c
@@ -0,0 +1,70 @@
+/*
+ * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include "pico.h"
+
+// For MHZ definitions etc
+#include "hardware/clocks.h"
+#include "hardware/rosc.h"
+
+// Given a ROSC delay stage code, return the next-numerically-higher code.
+// Top result bit is set when called on maximum ROSC code.
+uint32_t next_rosc_code(uint32_t code)
+{
+ return ((code | 0x08888888u) + 1u) & 0xf7777777u;
+}
+
+uint rosc_find_freq(uint32_t low_mhz, uint32_t high_mhz)
+{
+ // TODO: This could be a lot better
+ rosc_set_div(1);
+ for (uint32_t code = 0; code <= 0x77777777u; code = next_rosc_code(code)) {
+ rosc_set_freq(code);
+ uint rosc_mhz = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_ROSC_CLKSRC) / 1000;
+ if ((rosc_mhz >= low_mhz) && (rosc_mhz <= high_mhz)) {
+ return rosc_mhz;
+ }
+ }
+ return 0;
+}
+
+void rosc_set_div(uint32_t div)
+{
+ assert(div <= 31 && div >= 1);
+ rosc_write(&rosc_hw->div, ROSC_DIV_VALUE_PASS + div);
+}
+
+void rosc_set_freq(uint32_t code)
+{
+ rosc_write(&rosc_hw->freqa, (ROSC_FREQA_PASSWD_VALUE_PASS << ROSC_FREQA_PASSWD_LSB) | (code & 0xffffu));
+ rosc_write(&rosc_hw->freqb, (ROSC_FREQA_PASSWD_VALUE_PASS << ROSC_FREQA_PASSWD_LSB) | (code >> 16u));
+}
+
+void rosc_set_range(uint range)
+{
+ // Range should use enumvals from the headers and thus have the password correct
+ rosc_write(&rosc_hw->ctrl, (ROSC_CTRL_ENABLE_VALUE_ENABLE << ROSC_CTRL_ENABLE_LSB) | range);
+}
+
+void rosc_disable(void)
+{
+ uint32_t tmp = rosc_hw->ctrl;
+ tmp &= (~ROSC_CTRL_ENABLE_BITS);
+ tmp |= (ROSC_CTRL_ENABLE_VALUE_DISABLE << ROSC_CTRL_ENABLE_LSB);
+ rosc_write(&rosc_hw->ctrl, tmp);
+ // Wait for stable to go away
+ while (rosc_hw->status & ROSC_STATUS_STABLE_BITS)
+ ;
+}
+
+void rosc_set_dormant(void)
+{
+ // WARNING: This stops the rosc until woken up by an irq
+ rosc_write(&rosc_hw->dormant, ROSC_DORMANT_VALUE_DORMANT);
+ // Wait for it to become stable once woken up
+ while (!(rosc_hw->status & ROSC_STATUS_STABLE_BITS))
+ ;
+}
\ No newline at end of file
diff --git a/src/platform/rp2xx0/main-rp2xx0.cpp b/src/platform/rp2xx0/main-rp2xx0.cpp
index 6306f34c1..67bf1eb08 100644
--- a/src/platform/rp2xx0/main-rp2xx0.cpp
+++ b/src/platform/rp2xx0/main-rp2xx0.cpp
@@ -2,22 +2,71 @@
#include "hardware/xosc.h"
#include
#include
+#include
#include
#include
-#include
void setBluetoothEnable(bool enable)
{
// not needed
}
+static bool awake;
+
+static void sleep_callback(void)
+{
+ awake = true;
+}
+
+void epoch_to_datetime(time_t epoch, datetime_t *dt)
+{
+ struct tm *tm_info;
+
+ tm_info = gmtime(&epoch);
+ dt->year = tm_info->tm_year;
+ dt->month = tm_info->tm_mon + 1;
+ dt->day = tm_info->tm_mday;
+ dt->dotw = tm_info->tm_wday;
+ dt->hour = tm_info->tm_hour;
+ dt->min = tm_info->tm_min;
+ dt->sec = tm_info->tm_sec;
+}
+
+void debug_date(datetime_t t)
+{
+ LOG_DEBUG("%d %d %d %d %d %d %d\n", t.year, t.month, t.day, t.hour, t.min, t.sec, t.dotw);
+ uart_default_tx_wait_blocking();
+}
+
void cpuDeepSleep(uint32_t msecs)
{
- /* Disable both PLL to avoid power dissipation */
- pll_deinit(pll_sys);
- pll_deinit(pll_usb);
+
+ time_t seconds = (time_t)(msecs / 1000);
+ datetime_t t_init, t_alarm;
+
+ awake = false;
+ // Start the RTC
+ rtc_init();
+ epoch_to_datetime(0, &t_init);
+ rtc_set_datetime(&t_init);
+ epoch_to_datetime(seconds, &t_alarm);
+ // debug_date(t_init);
+ // debug_date(t_alarm);
+ uart_default_tx_wait_blocking();
+ sleep_run_from_dormant_source(DORMANT_SOURCE_ROSC);
+ sleep_goto_sleep_until(&t_alarm, &sleep_callback);
+
+ // Make sure we don't wake
+ while (!awake) {
+ delay(1);
+ }
+
+ /* For now, I don't know how to revert this state
+ We just reboot in order to get back operational */
+ rp2040.reboot();
+
/* Set RP2040 in dormant mode. Will not wake up. */
- xosc_dormant();
+ // xosc_dormant();
}
void updateBatteryLevel(uint8_t level)
diff --git a/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h b/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h
new file mode 100644
index 000000000..17dff2468
--- /dev/null
+++ b/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h
@@ -0,0 +1,107 @@
+/*
+ * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef _PICO_SLEEP_H_
+#define _PICO_SLEEP_H_
+
+#include "hardware/rtc.h"
+#include "pico.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/** \file sleep.h
+ * \defgroup hardware_sleep hardware_sleep
+ *
+ * Lower Power Sleep API
+ *
+ * The difference between sleep and dormant is that ALL clocks are stopped in dormant mode,
+ * until the source (either xosc or rosc) is started again by an external event.
+ * In sleep mode some clocks can be left running controlled by the SLEEP_EN registers in the clocks
+ * block. For example you could keep clk_rtc running. Some destinations (proc0 and proc1 wakeup logic)
+ * can't be stopped in sleep mode otherwise there wouldn't be enough logic to wake up again.
+ *
+ * \subsection sleep_example Example
+ * \addtogroup hardware_sleep
+ * \include hello_sleep.c
+
+ */
+typedef enum { DORMANT_SOURCE_NONE, DORMANT_SOURCE_XOSC, DORMANT_SOURCE_ROSC } dormant_source_t;
+
+/*! \brief Set all clock sources to the the dormant clock source to prepare for sleep.
+ * \ingroup hardware_sleep
+ *
+ * \param dormant_source The dormant clock source to use
+ */
+void sleep_run_from_dormant_source(dormant_source_t dormant_source);
+
+/*! \brief Set the dormant clock source to be the crystal oscillator
+ * \ingroup hardware_sleep
+ */
+static inline void sleep_run_from_xosc(void)
+{
+ sleep_run_from_dormant_source(DORMANT_SOURCE_XOSC);
+}
+
+/*! \brief Set the dormant clock source to be the ring oscillator
+ * \ingroup hardware_sleep
+ */
+static inline void sleep_run_from_rosc(void)
+{
+ sleep_run_from_dormant_source(DORMANT_SOURCE_ROSC);
+}
+
+/*! \brief Send system to sleep until the specified time
+ * \ingroup hardware_sleep
+ *
+ * One of the sleep_run_* functions must be called prior to this call
+ *
+ * \param t The time to wake up
+ * \param callback Function to call on wakeup.
+ */
+void sleep_goto_sleep_until(datetime_t *t, rtc_callback_t callback);
+
+/*! \brief Send system to sleep until the specified GPIO changes
+ * \ingroup hardware_sleep
+ *
+ * One of the sleep_run_* functions must be called prior to this call
+ *
+ * \param gpio_pin The pin to provide the wake up
+ * \param edge true for leading edge, false for trailing edge
+ * \param high true for active high, false for active low
+ */
+void sleep_goto_dormant_until_pin(uint gpio_pin, bool edge, bool high);
+
+/*! \brief Send system to sleep until a leading high edge is detected on GPIO
+ * \ingroup hardware_sleep
+ *
+ * One of the sleep_run_* functions must be called prior to this call
+ *
+ * \param gpio_pin The pin to provide the wake up
+ */
+static inline void sleep_goto_dormant_until_edge_high(uint gpio_pin)
+{
+ sleep_goto_dormant_until_pin(gpio_pin, true, true);
+}
+
+/*! \brief Send system to sleep until a high level is detected on GPIO
+ * \ingroup hardware_sleep
+ *
+ * One of the sleep_run_* functions must be called prior to this call
+ *
+ * \param gpio_pin The pin to provide the wake up
+ */
+static inline void sleep_goto_dormant_until_level_high(uint gpio_pin)
+{
+ sleep_goto_dormant_until_pin(gpio_pin, false, true);
+}
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
\ No newline at end of file
diff --git a/src/platform/rp2xx0/pico_sleep/sleep.c b/src/platform/rp2xx0/pico_sleep/sleep.c
new file mode 100644
index 000000000..65096be85
--- /dev/null
+++ b/src/platform/rp2xx0/pico_sleep/sleep.c
@@ -0,0 +1,155 @@
+/*
+ * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include "pico.h"
+
+#include "pico/sleep.h"
+#include "pico/stdlib.h"
+
+#include "hardware/clocks.h"
+#include "hardware/pll.h"
+#include "hardware/regs/io_bank0.h"
+#include "hardware/rosc.h"
+#include "hardware/rtc.h"
+#include "hardware/xosc.h"
+// For __wfi
+#include "hardware/sync.h"
+// For scb_hw so we can enable deep sleep
+#include "hardware/structs/scb.h"
+// when using old SDK this macro is not defined
+#ifndef XOSC_HZ
+#define XOSC_HZ 12000000u
+#endif
+// The difference between sleep and dormant is that ALL clocks are stopped in dormant mode,
+// until the source (either xosc or rosc) is started again by an external event.
+// In sleep mode some clocks can be left running controlled by the SLEEP_EN registers in the clocks
+// block. For example you could keep clk_rtc running. Some destinations (proc0 and proc1 wakeup logic)
+// can't be stopped in sleep mode otherwise there wouldn't be enough logic to wake up again.
+
+// TODO: Optionally, memories can also be powered down.
+
+static dormant_source_t _dormant_source;
+
+bool dormant_source_valid(dormant_source_t dormant_source)
+{
+ return (dormant_source == DORMANT_SOURCE_XOSC) || (dormant_source == DORMANT_SOURCE_ROSC);
+}
+
+// In order to go into dormant mode we need to be running from a stoppable clock source:
+// either the xosc or rosc with no PLLs running. This means we disable the USB and ADC clocks
+// and all PLLs
+void sleep_run_from_dormant_source(dormant_source_t dormant_source)
+{
+ assert(dormant_source_valid(dormant_source));
+ _dormant_source = dormant_source;
+
+ // FIXME: Just defining average rosc freq here.
+ uint src_hz = (dormant_source == DORMANT_SOURCE_XOSC) ? XOSC_HZ : 6.5 * MHZ;
+ uint clk_ref_src = (dormant_source == DORMANT_SOURCE_XOSC) ? CLOCKS_CLK_REF_CTRL_SRC_VALUE_XOSC_CLKSRC
+ : CLOCKS_CLK_REF_CTRL_SRC_VALUE_ROSC_CLKSRC_PH;
+
+ // CLK_REF = XOSC or ROSC
+ clock_configure(clk_ref, clk_ref_src,
+ 0, // No aux mux
+ src_hz, src_hz);
+
+ // CLK SYS = CLK_REF
+ clock_configure(clk_sys, CLOCKS_CLK_SYS_CTRL_SRC_VALUE_CLK_REF,
+ 0, // Using glitchless mux
+ src_hz, src_hz);
+
+ // CLK USB = 0MHz
+ clock_stop(clk_usb);
+
+ // CLK ADC = 0MHz
+ clock_stop(clk_adc);
+
+ // CLK RTC = ideally XOSC (12MHz) / 256 = 46875Hz but could be rosc
+ uint clk_rtc_src = (dormant_source == DORMANT_SOURCE_XOSC) ? CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_XOSC_CLKSRC
+ : CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_ROSC_CLKSRC_PH;
+
+ clock_configure(clk_rtc,
+ 0, // No GLMUX
+ clk_rtc_src, src_hz, 46875);
+
+ // CLK PERI = clk_sys. Used as reference clock for Peripherals. No dividers so just select and enable
+ clock_configure(clk_peri, 0, CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLK_SYS, src_hz, src_hz);
+
+ pll_deinit(pll_sys);
+ pll_deinit(pll_usb);
+
+ // Assuming both xosc and rosc are running at the moment
+ if (dormant_source == DORMANT_SOURCE_XOSC) {
+ // Can disable rosc
+ rosc_disable();
+ } else {
+ // Can disable xosc
+ xosc_disable();
+ }
+
+ // Reconfigure uart with new clocks
+ /* This dones not work with our current core */
+ // setup_default_uart();
+}
+
+// Go to sleep until woken up by the RTC
+void sleep_goto_sleep_until(datetime_t *t, rtc_callback_t callback)
+{
+ // We should have already called the sleep_run_from_dormant_source function
+ assert(dormant_source_valid(_dormant_source));
+
+ // Turn off all clocks when in sleep mode except for RTC
+ clocks_hw->sleep_en0 = CLOCKS_SLEEP_EN0_CLK_RTC_RTC_BITS;
+ clocks_hw->sleep_en1 = 0x0;
+
+ rtc_set_alarm(t, callback);
+
+ uint save = scb_hw->scr;
+ // Enable deep sleep at the proc
+ scb_hw->scr = save | M0PLUS_SCR_SLEEPDEEP_BITS;
+
+ // Go to sleep
+ __wfi();
+}
+
+static void _go_dormant(void)
+{
+ assert(dormant_source_valid(_dormant_source));
+
+ if (_dormant_source == DORMANT_SOURCE_XOSC) {
+ xosc_dormant();
+ } else {
+ rosc_set_dormant();
+ }
+}
+
+void sleep_goto_dormant_until_pin(uint gpio_pin, bool edge, bool high)
+{
+ bool low = !high;
+ bool level = !edge;
+
+ // Configure the appropriate IRQ at IO bank 0
+ assert(gpio_pin < NUM_BANK0_GPIOS);
+
+ uint32_t event = 0;
+
+ if (level && low)
+ event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_LEVEL_LOW_BITS;
+ if (level && high)
+ event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_LEVEL_HIGH_BITS;
+ if (edge && high)
+ event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_EDGE_HIGH_BITS;
+ if (edge && low)
+ event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_EDGE_LOW_BITS;
+
+ gpio_set_dormant_irq_enabled(gpio_pin, event, true);
+
+ _go_dormant();
+ // Execution stops here until woken up
+
+ // Clear the irq so we can go back to dormant mode again if we want
+ gpio_acknowledge_irq(gpio_pin, event);
+}
\ No newline at end of file
diff --git a/src/serialization/MeshPacketSerializer.cpp b/src/serialization/MeshPacketSerializer.cpp
index acda94fac..ebcfaecab 100644
--- a/src/serialization/MeshPacketSerializer.cpp
+++ b/src/serialization/MeshPacketSerializer.cpp
@@ -1,3 +1,4 @@
+#ifndef NRF52_USE_JSON
#include "MeshPacketSerializer.h"
#include "JSON.h"
#include "NodeDB.h"
@@ -353,4 +354,5 @@ std::string MeshPacketSerializer::JsonSerializeEncrypted(const meshtastic_MeshPa
delete value;
return jsonStr;
-}
\ No newline at end of file
+}
+#endif
\ No newline at end of file
diff --git a/src/serialization/MeshPacketSerializer_nRF52.cpp b/src/serialization/MeshPacketSerializer_nRF52.cpp
new file mode 100644
index 000000000..cd3aa1630
--- /dev/null
+++ b/src/serialization/MeshPacketSerializer_nRF52.cpp
@@ -0,0 +1,353 @@
+#ifdef NRF52_USE_JSON
+#warning 'Using nRF52 Serializer'
+
+#include "ArduinoJson.h"
+#include "MeshPacketSerializer.h"
+#include "NodeDB.h"
+#include "mesh/generated/meshtastic/mqtt.pb.h"
+#include "mesh/generated/meshtastic/remote_hardware.pb.h"
+#include "mesh/generated/meshtastic/telemetry.pb.h"
+#include "modules/RoutingModule.h"
+#include
+#include
+
+StaticJsonDocument<1024> jsonObj;
+StaticJsonDocument<1024> arrayObj;
+
+std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, bool shouldLog)
+{
+ // the created jsonObj is immutable after creation, so
+ // we need to do the heavy lifting before assembling it.
+ std::string msgType;
+ jsonObj.clear();
+ arrayObj.clear();
+
+ if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
+ switch (mp->decoded.portnum) {
+ case meshtastic_PortNum_TEXT_MESSAGE_APP: {
+ msgType = "text";
+ // convert bytes to string
+ if (shouldLog)
+ LOG_DEBUG("got text message of size %u\n", mp->decoded.payload.size);
+
+ char payloadStr[(mp->decoded.payload.size) + 1];
+ memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size);
+ payloadStr[mp->decoded.payload.size] = 0; // null terminated string
+ // check if this is a JSON payload
+ StaticJsonDocument<512> text_doc;
+ DeserializationError error = deserializeJson(text_doc, payloadStr);
+ if (error) {
+ // if it isn't, then we need to create a json object
+ // with the string as the value
+ if (shouldLog)
+ LOG_INFO("text message payload is of type plaintext\n");
+ jsonObj["payload"]["text"] = payloadStr;
+ } else {
+ // if it is, then we can just use the json object
+ if (shouldLog)
+ LOG_INFO("text message payload is of type json\n");
+ jsonObj["payload"] = text_doc;
+ }
+ break;
+ }
+ case meshtastic_PortNum_TELEMETRY_APP: {
+ msgType = "telemetry";
+ meshtastic_Telemetry scratch;
+ meshtastic_Telemetry *decoded = NULL;
+ memset(&scratch, 0, sizeof(scratch));
+ if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Telemetry_msg, &scratch)) {
+ decoded = &scratch;
+ if (decoded->which_variant == meshtastic_Telemetry_device_metrics_tag) {
+ jsonObj["payload"]["battery_level"] = (unsigned int)decoded->variant.device_metrics.battery_level;
+ jsonObj["payload"]["voltage"] = decoded->variant.device_metrics.voltage;
+ jsonObj["payload"]["channel_utilization"] = decoded->variant.device_metrics.channel_utilization;
+ jsonObj["payload"]["air_util_tx"] = decoded->variant.device_metrics.air_util_tx;
+ jsonObj["payload"]["uptime_seconds"] = (unsigned int)decoded->variant.device_metrics.uptime_seconds;
+ } else if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) {
+ jsonObj["payload"]["temperature"] = decoded->variant.environment_metrics.temperature;
+ jsonObj["payload"]["relative_humidity"] = decoded->variant.environment_metrics.relative_humidity;
+ jsonObj["payload"]["barometric_pressure"] = decoded->variant.environment_metrics.barometric_pressure;
+ jsonObj["payload"]["gas_resistance"] = decoded->variant.environment_metrics.gas_resistance;
+ jsonObj["payload"]["voltage"] = decoded->variant.environment_metrics.voltage;
+ jsonObj["payload"]["current"] = decoded->variant.environment_metrics.current;
+ jsonObj["payload"]["lux"] = decoded->variant.environment_metrics.lux;
+ jsonObj["payload"]["white_lux"] = decoded->variant.environment_metrics.white_lux;
+ jsonObj["payload"]["iaq"] = (uint)decoded->variant.environment_metrics.iaq;
+ jsonObj["payload"]["wind_speed"] = decoded->variant.environment_metrics.wind_speed;
+ jsonObj["payload"]["wind_direction"] = (uint)decoded->variant.environment_metrics.wind_direction;
+ jsonObj["payload"]["wind_gust"] = decoded->variant.environment_metrics.wind_gust;
+ jsonObj["payload"]["wind_lull"] = decoded->variant.environment_metrics.wind_lull;
+ } else if (decoded->which_variant == meshtastic_Telemetry_air_quality_metrics_tag) {
+ jsonObj["payload"]["pm10"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_standard;
+ jsonObj["payload"]["pm25"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_standard;
+ jsonObj["payload"]["pm100"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_standard;
+ jsonObj["payload"]["pm10_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_environmental;
+ jsonObj["payload"]["pm25_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_environmental;
+ jsonObj["payload"]["pm100_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_environmental;
+ } else if (decoded->which_variant == meshtastic_Telemetry_power_metrics_tag) {
+ jsonObj["payload"]["voltage_ch1"] = decoded->variant.power_metrics.ch1_voltage;
+ jsonObj["payload"]["current_ch1"] = decoded->variant.power_metrics.ch1_current;
+ jsonObj["payload"]["voltage_ch2"] = decoded->variant.power_metrics.ch2_voltage;
+ jsonObj["payload"]["current_ch2"] = decoded->variant.power_metrics.ch2_current;
+ jsonObj["payload"]["voltage_ch3"] = decoded->variant.power_metrics.ch3_voltage;
+ jsonObj["payload"]["current_ch3"] = decoded->variant.power_metrics.ch3_current;
+ }
+ } else if (shouldLog) {
+ LOG_ERROR("Error decoding protobuf for telemetry message!\n");
+ return "";
+ }
+ break;
+ }
+ case meshtastic_PortNum_NODEINFO_APP: {
+ msgType = "nodeinfo";
+ meshtastic_User scratch;
+ meshtastic_User *decoded = NULL;
+ memset(&scratch, 0, sizeof(scratch));
+ if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_User_msg, &scratch)) {
+ decoded = &scratch;
+ jsonObj["payload"]["id"] = decoded->id;
+ jsonObj["payload"]["longname"] = decoded->long_name;
+ jsonObj["payload"]["shortname"] = decoded->short_name;
+ jsonObj["payload"]["hardware"] = decoded->hw_model;
+ jsonObj["payload"]["role"] = (int)decoded->role;
+ } else if (shouldLog) {
+ LOG_ERROR("Error decoding protobuf for nodeinfo message!\n");
+ return "";
+ }
+ break;
+ }
+ case meshtastic_PortNum_POSITION_APP: {
+ msgType = "position";
+ meshtastic_Position scratch;
+ meshtastic_Position *decoded = NULL;
+ memset(&scratch, 0, sizeof(scratch));
+ if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Position_msg, &scratch)) {
+ decoded = &scratch;
+ if ((int)decoded->time) {
+ jsonObj["payload"]["time"] = (unsigned int)decoded->time;
+ }
+ if ((int)decoded->timestamp) {
+ jsonObj["payload"]["timestamp"] = (unsigned int)decoded->timestamp;
+ }
+ jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i;
+ jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i;
+ if ((int)decoded->altitude) {
+ jsonObj["payload"]["altitude"] = (int)decoded->altitude;
+ }
+ if ((int)decoded->ground_speed) {
+ jsonObj["payload"]["ground_speed"] = (unsigned int)decoded->ground_speed;
+ }
+ if (int(decoded->ground_track)) {
+ jsonObj["payload"]["ground_track"] = (unsigned int)decoded->ground_track;
+ }
+ if (int(decoded->sats_in_view)) {
+ jsonObj["payload"]["sats_in_view"] = (unsigned int)decoded->sats_in_view;
+ }
+ if ((int)decoded->PDOP) {
+ jsonObj["payload"]["PDOP"] = (int)decoded->PDOP;
+ }
+ if ((int)decoded->HDOP) {
+ jsonObj["payload"]["HDOP"] = (int)decoded->HDOP;
+ }
+ if ((int)decoded->VDOP) {
+ jsonObj["payload"]["VDOP"] = (int)decoded->VDOP;
+ }
+ if ((int)decoded->precision_bits) {
+ jsonObj["payload"]["precision_bits"] = (int)decoded->precision_bits;
+ }
+ } else if (shouldLog) {
+ LOG_ERROR("Error decoding protobuf for position message!\n");
+ return "";
+ }
+ break;
+ }
+ case meshtastic_PortNum_WAYPOINT_APP: {
+ msgType = "position";
+ meshtastic_Waypoint scratch;
+ meshtastic_Waypoint *decoded = NULL;
+ memset(&scratch, 0, sizeof(scratch));
+ if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Waypoint_msg, &scratch)) {
+ decoded = &scratch;
+ jsonObj["payload"]["id"] = (unsigned int)decoded->id;
+ jsonObj["payload"]["name"] = decoded->name;
+ jsonObj["payload"]["description"] = decoded->description;
+ jsonObj["payload"]["expire"] = (unsigned int)decoded->expire;
+ jsonObj["payload"]["locked_to"] = (unsigned int)decoded->locked_to;
+ jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i;
+ jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i;
+ } else if (shouldLog) {
+ LOG_ERROR("Error decoding protobuf for position message!\n");
+ return "";
+ }
+ break;
+ }
+ case meshtastic_PortNum_NEIGHBORINFO_APP: {
+ msgType = "neighborinfo";
+ meshtastic_NeighborInfo scratch;
+ meshtastic_NeighborInfo *decoded = NULL;
+ memset(&scratch, 0, sizeof(scratch));
+ if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_NeighborInfo_msg,
+ &scratch)) {
+ decoded = &scratch;
+ jsonObj["payload"]["node_id"] = (unsigned int)decoded->node_id;
+ jsonObj["payload"]["node_broadcast_interval_secs"] = (unsigned int)decoded->node_broadcast_interval_secs;
+ jsonObj["payload"]["last_sent_by_id"] = (unsigned int)decoded->last_sent_by_id;
+ jsonObj["payload"]["neighbors_count"] = decoded->neighbors_count;
+
+ JsonObject neighbors_obj = arrayObj.to();
+ JsonArray neighbors = neighbors_obj.createNestedArray("neighbors");
+ JsonObject neighbors_0 = neighbors.createNestedObject();
+
+ for (uint8_t i = 0; i < decoded->neighbors_count; i++) {
+ neighbors_0["node_id"] = (unsigned int)decoded->neighbors[i].node_id;
+ neighbors_0["snr"] = (int)decoded->neighbors[i].snr;
+ neighbors[i + 1] = neighbors_0;
+ neighbors_0.clear();
+ }
+ neighbors.remove(0);
+ jsonObj["payload"]["neighbors"] = neighbors;
+ } else if (shouldLog) {
+ LOG_ERROR("Error decoding protobuf for neighborinfo message!\n");
+ return "";
+ }
+ break;
+ }
+ case meshtastic_PortNum_TRACEROUTE_APP: {
+ if (mp->decoded.request_id) { // Only report the traceroute response
+ msgType = "traceroute";
+ meshtastic_RouteDiscovery scratch;
+ meshtastic_RouteDiscovery *decoded = NULL;
+ memset(&scratch, 0, sizeof(scratch));
+ if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_RouteDiscovery_msg,
+ &scratch)) {
+ decoded = &scratch;
+ JsonArray route = arrayObj.createNestedArray("route");
+
+ auto addToRoute = [](JsonArray *route, NodeNum num) {
+ char long_name[40] = "Unknown";
+ meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(num);
+ bool name_known = node ? node->has_user : false;
+ if (name_known)
+ memcpy(long_name, node->user.long_name, sizeof(long_name));
+ route->add(long_name);
+ };
+
+ addToRoute(&route, mp->to); // route.add(mp->to);
+ for (uint8_t i = 0; i < decoded->route_count; i++) {
+ addToRoute(&route, decoded->route[i]); // route.add(decoded->route[i]);
+ }
+ addToRoute(&route,
+ mp->from); // route.add(mp->from); // Ended at the original destination (source of response)
+
+ jsonObj["payload"]["route"] = route;
+ } else if (shouldLog) {
+ LOG_ERROR("Error decoding protobuf for traceroute message!\n");
+ return "";
+ }
+ } else {
+ LOG_WARN("Traceroute response not reported");
+ return "";
+ }
+ break;
+ }
+ case meshtastic_PortNum_DETECTION_SENSOR_APP: {
+ msgType = "detection";
+ char payloadStr[(mp->decoded.payload.size) + 1];
+ memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size);
+ payloadStr[mp->decoded.payload.size] = 0; // null terminated string
+ jsonObj["payload"]["text"] = payloadStr;
+ break;
+ }
+ case meshtastic_PortNum_REMOTE_HARDWARE_APP: {
+ meshtastic_HardwareMessage scratch;
+ meshtastic_HardwareMessage *decoded = NULL;
+ memset(&scratch, 0, sizeof(scratch));
+ if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_HardwareMessage_msg,
+ &scratch)) {
+ decoded = &scratch;
+ if (decoded->type == meshtastic_HardwareMessage_Type_GPIOS_CHANGED) {
+ msgType = "gpios_changed";
+ jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value;
+ } else if (decoded->type == meshtastic_HardwareMessage_Type_READ_GPIOS_REPLY) {
+ msgType = "gpios_read_reply";
+ jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value;
+ jsonObj["payload"]["gpio_mask"] = (unsigned int)decoded->gpio_mask;
+ }
+ } else if (shouldLog) {
+ LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n");
+ return "";
+ }
+ break;
+ }
+ // add more packet types here if needed
+ default:
+ LOG_WARN("Unsupported packet type %d\n", mp->decoded.portnum);
+ return "";
+ break;
+ }
+ } else if (shouldLog) {
+ LOG_WARN("Couldn't convert encrypted payload of MeshPacket to JSON\n");
+ return "";
+ }
+
+ jsonObj["id"] = (unsigned int)mp->id;
+ jsonObj["timestamp"] = (unsigned int)mp->rx_time;
+ jsonObj["to"] = (unsigned int)mp->to;
+ jsonObj["from"] = (unsigned int)mp->from;
+ jsonObj["channel"] = (unsigned int)mp->channel;
+ jsonObj["type"] = msgType.c_str();
+ jsonObj["sender"] = owner.id;
+ if (mp->rx_rssi != 0)
+ jsonObj["rssi"] = (int)mp->rx_rssi;
+ if (mp->rx_snr != 0)
+ jsonObj["snr"] = (float)mp->rx_snr;
+ if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) {
+ jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit);
+ jsonObj["hop_start"] = (unsigned int)(mp->hop_start);
+ }
+
+ // serialize and write it to the stream
+
+ // Serial.printf("serialized json message: \r\n");
+ // serializeJson(jsonObj, Serial);
+ // Serial.println("");
+
+ std::string jsonStr = "";
+ serializeJson(jsonObj, jsonStr);
+
+ if (shouldLog)
+ LOG_INFO("serialized json message: %s\n", jsonStr.c_str());
+
+ return jsonStr;
+}
+
+std::string MeshPacketSerializer::JsonSerializeEncrypted(const meshtastic_MeshPacket *mp)
+{
+ jsonObj.clear();
+ jsonObj["id"] = (unsigned int)mp->id;
+ jsonObj["time_ms"] = (double)millis();
+ jsonObj["timestamp"] = (unsigned int)mp->rx_time;
+ jsonObj["to"] = (unsigned int)mp->to;
+ jsonObj["from"] = (unsigned int)mp->from;
+ jsonObj["channel"] = (unsigned int)mp->channel;
+ jsonObj["want_ack"] = mp->want_ack;
+
+ if (mp->rx_rssi != 0)
+ jsonObj["rssi"] = (int)mp->rx_rssi;
+ if (mp->rx_snr != 0)
+ jsonObj["snr"] = (float)mp->rx_snr;
+ if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) {
+ jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit);
+ jsonObj["hop_start"] = (unsigned int)(mp->hop_start);
+ }
+ jsonObj["size"] = (unsigned int)mp->encrypted.size;
+ auto encryptedStr = bytesToHex(mp->encrypted.bytes, mp->encrypted.size);
+ jsonObj["bytes"] = encryptedStr.c_str();
+
+ // serialize and write it to the stream
+ std::string jsonStr = "";
+ serializeJson(jsonObj, jsonStr);
+
+ return jsonStr;
+}
+#endif
\ No newline at end of file
diff --git a/src/shutdown.h b/src/shutdown.h
index 3f191eea8..481e7778d 100644
--- a/src/shutdown.h
+++ b/src/shutdown.h
@@ -44,7 +44,7 @@ void powerCommandsCheck()
if (shutdownAtMsec && millis() > shutdownAtMsec) {
LOG_INFO("Shutting down from admin command\n");
-#if defined(ARCH_NRF52) || defined(ARCH_ESP32)
+#if defined(ARCH_NRF52) || defined(ARCH_ESP32) || defined(ARCH_RP2040)
playShutdownMelody();
power->shutdown();
#elif defined(ARCH_PORTDUINO)
diff --git a/variants/dreamcatcher/platformio.ini b/variants/dreamcatcher/platformio.ini
new file mode 100644
index 000000000..46f9b9871
--- /dev/null
+++ b/variants/dreamcatcher/platformio.ini
@@ -0,0 +1,27 @@
+[env:dreamcatcher] ; 2301, latest revision
+extends = esp32s3_base
+board = esp32s3box
+board_level = extra
+
+build_flags =
+ ${esp32s3_base.build_flags}
+ -D PRIVATE_HW
+ -D OTHERNET_DC_REV=2301
+ -I variants/dreamcatcher
+ -DARDUINO_USB_CDC_ON_BOOT=1
+
+lib_deps = ${esp32s3_base.lib_deps}
+ earlephilhower/ESP8266Audio@^1.9.7
+ earlephilhower/ESP8266SAM@^1.0.1
+
+[env:dreamcatcher-2206]
+extends = esp32s3_base
+board = esp32s3box
+board_level = extra
+
+build_flags =
+ ${esp32s3_base.build_flags}
+ -D PRIVATE_HW
+ -D OTHERNET_DC_REV=2206
+ -I variants/dreamcatcher
+ -DARDUINO_USB_CDC_ON_BOOT=1
\ No newline at end of file
diff --git a/variants/dreamcatcher/rfswitch.h b/variants/dreamcatcher/rfswitch.h
new file mode 100644
index 000000000..74edb25d1
--- /dev/null
+++ b/variants/dreamcatcher/rfswitch.h
@@ -0,0 +1,17 @@
+#include "RadioLib.h"
+
+// RF Switch Matrix SubG RFO_HP_LF / RFO_LP_LF / RFI_[NP]_LF0
+// DIO5 -> RFSW0_V1
+// DIO6 -> RFSW1_V2
+// DIO7 -> ANT_CTRL_ON + ESP_IO9/LR_GPS_ANT_DC_EN -> RFI_GPS (Bias-T GPS)
+
+static const uint32_t rfswitch_dio_pins[] = {RADIOLIB_LR11X0_DIO5, RADIOLIB_LR11X0_DIO6, RADIOLIB_LR11X0_DIO7, RADIOLIB_NC,
+ RADIOLIB_NC};
+
+static const Module::RfSwitchMode_t rfswitch_table[] = {
+ // mode DIO5 DIO6 DIO7
+ {LR11x0::MODE_STBY, {LOW, LOW, LOW}}, {LR11x0::MODE_RX, {HIGH, LOW, LOW}},
+ {LR11x0::MODE_TX, {LOW, HIGH, LOW}}, {LR11x0::MODE_TX_HP, {LOW, HIGH, LOW}},
+ {LR11x0::MODE_TX_HF, {LOW, LOW, LOW}}, {LR11x0::MODE_GNSS, {LOW, LOW, HIGH}},
+ {LR11x0::MODE_WIFI, {LOW, LOW, LOW}}, END_OF_MODE_TABLE,
+};
\ No newline at end of file
diff --git a/variants/dreamcatcher/variant.h b/variants/dreamcatcher/variant.h
new file mode 100644
index 000000000..eb95a95dd
--- /dev/null
+++ b/variants/dreamcatcher/variant.h
@@ -0,0 +1,109 @@
+#undef I2C_SDA
+#undef I2C_SCL
+#define I2C_SDA 16 // I2C pins for this board
+#define I2C_SCL 17
+
+#define I2C_SDA1 45
+#define I2C_SCL1 46
+
+#define LED_PIN 6
+#define LED_STATE_ON 1
+#define BUTTON_PIN 0
+
+#define HAS_TPS65233
+
+// V1 of SubG Switch SMA 0 or F Selector 1
+// #define RF_SW_SUBG1 8
+// V2 of SubG Switch SMA 1 or F Selector 0
+// #define RF_SW_SUBG2 5
+
+#define RESET_OLED 8 // Emulate RF_SW_SUBG1, Use F Connector
+#define VTFT_CTRL 5 // Emulate RF_SW_SUBG2, for SMA swap the pin values
+
+#if OTHERNET_DC_REV == 2206
+#define USE_LR1120
+
+#define SPI_MISO 37
+#define SPI_MOSI 39
+#define SPI_SCK 38
+#define SDCARD_CS 40
+
+#define PIN_BUZZER 48
+
+// These can either be used for GPS or a serial link. Define through Protobufs
+// #define GPS_RX_PIN 10
+// #define GPS_TX_PIN 21
+
+#define PIN_POWER_EN 7 // RF section power supply enable
+#define PERIPHERAL_WARMUP_MS 1000 // wait for TPS chip to initialize
+#define TPS_EXTM 45 // connected, but not used
+#define BIAS_T_ENABLE 9 // needs to be low
+#define BIAS_T_VALUE 0
+#else // 2301
+#define USE_LR1121
+#define SPI_MISO 10
+#define SPI_MOSI 39
+#define SPI_SCK 38
+
+#define SDCARD_CS 40
+
+// This is only informational, we always use SD cards in 1 bit mode
+#define SPI_DATA1 15
+#define SPI_DATA2 18
+
+// These can either be used for GPS or a serial link. Define through Protobufs
+// #define GPS_RX_PIN 36
+// #define GPS_TX_PIN 37
+
+// dac / amp instead of buzzer
+#define HAS_I2S
+#define DAC_I2S_BCK 21
+#define DAC_I2S_WS 9
+#define DAC_I2S_DOUT 48
+
+#define BIAS_T_ENABLE 7 // needs to be low
+#define BIAS_T_VALUE 0
+#define BIAS_T_SUBGHZ 2 // also needs to be low, we hijack SENSOR_POWER_CTRL_PIN to emulate this
+#define SENSOR_POWER_CTRL_PIN BIAS_T_SUBGHZ
+#define SENSOR_POWER_ON 0
+#endif
+
+#define HAS_SDCARD // Have SPI interface SD card slot
+#define SDCARD_USE_SPI1
+
+#define LORA_RESET 3
+#define LORA_SCK 12
+#define LORA_MISO 13
+#define LORA_MOSI 11
+#define LORA_CS 14
+#define LORA_DIO9 4
+#define LORA_DIO2 47
+
+#define LR1120_IRQ_PIN LORA_DIO9
+#define LR1120_NRESET_PIN LORA_RESET
+#define LR1120_BUSY_PIN LORA_DIO2
+#define LR1120_SPI_NSS_PIN LORA_CS
+#define LR1120_SPI_SCK_PIN LORA_SCK
+#define LR1120_SPI_MOSI_PIN LORA_MOSI
+#define LR1120_SPI_MISO_PIN LORA_MISO
+
+#define LR1121_IRQ_PIN LORA_DIO9
+#define LR1121_NRESET_PIN LORA_RESET
+#define LR1121_BUSY_PIN LORA_DIO2
+#define LR1121_SPI_NSS_PIN LORA_CS
+#define LR1121_SPI_SCK_PIN LORA_SCK
+#define LR1121_SPI_MOSI_PIN LORA_MOSI
+#define LR1121_SPI_MISO_PIN LORA_MISO
+
+#define LR11X0_DIO3_TCXO_VOLTAGE 1.8
+#define LR11X0_DIO_AS_RF_SWITCH
+
+// This board needs external switching between sub-GHz and 2.4G circuits
+
+// V1 of RF1 selector SubG 1 or 2.4GHz 0
+// #define RF_SW_SMA1 42
+// V2 of RF1 Selector SubG 0 or 2.4GHz 1
+// #define RF_SW_SMA2 41
+
+#define LR11X0_RF_SWITCH_SUBGHZ 42
+#define LR11X0_RF_SWITCH_2_4GHZ 41
diff --git a/variants/rak11310/platformio.ini b/variants/rak11310/platformio.ini
index e1bd2b1b0..c7b3504fe 100644
--- a/variants/rak11310/platformio.ini
+++ b/variants/rak11310/platformio.ini
@@ -2,6 +2,8 @@
extends = rp2040_base
board = wiscore_rak11300
upload_protocol = picotool
+# keep an old SDK to use less memory.
+platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2
# add our variants files to the include and src paths
build_flags = ${rp2040_base.build_flags}
diff --git a/variants/rak11310/variant.h b/variants/rak11310/variant.h
index f9dcbd91a..54e403ee7 100644
--- a/variants/rak11310/variant.h
+++ b/variants/rak11310/variant.h
@@ -6,6 +6,7 @@
#define LED_CONN PIN_LED2
#define LED_PIN LED_BUILTIN
+#define ledOff(pin) pinMode(pin, INPUT)
#define BUTTON_PIN 9
#define BUTTON_NEED_PULLUP
diff --git a/variants/rak4631_eth_gw/platformio.ini b/variants/rak4631_eth_gw/platformio.ini
new file mode 100644
index 000000000..62b7e737d
--- /dev/null
+++ b/variants/rak4631_eth_gw/platformio.ini
@@ -0,0 +1,66 @@
+; The very slick RAK wireless RAK 4631 / 4630 board - Unified firmware for 5005/19003, with or without OLED RAK 1921
+[env:rak4631_eth_gw]
+extends = nrf52840_base
+board = wiscore_rak4631
+board_check = true
+build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_eth_gw -D RAK_4631
+ -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard"
+ -DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely.
+ -DEINK_DISPLAY_MODEL=GxEPD2_213_BN
+ -DEINK_WIDTH=250
+ -DEINK_HEIGHT=122
+ -DNRF52_USE_JSON=1
+ -DMESHTASTIC_EXCLUDE_GPS=1
+ -DMESHTASTIC_EXCLUDE_WIFI=1
+ -DMESHTASTIC_EXCLUDE_SCREEN=1
+; -DMESHTASTIC_EXCLUDE_PKI=1
+ -DMESHTASTIC_EXCLUDE_POWER_FSM=1
+ -DMESHTASTIC_EXCLUDE_POWERMON=1
+; -DMESHTASTIC_EXCLUDE_TZ=1
+ -DMESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION=1
+ -DMESHTASTIC_EXCLUDE_PAXCOUNTER=1
+ -DMESHTASTIC_EXCLUDE_REMOTEHARDWARE=1
+ -DMESHTASTIC_EXCLUDE_STOREFORWARD=1
+ -DMESHTASTIC_EXCLUDE_CANNEDMESSAGES=1
+ -DMESHTASTIC_EXCLUDE_WAYPOINT=1
+build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_eth_gw> + + +
+lib_deps =
+ ${nrf52840_base.lib_deps}
+ ${networking_base.lib_deps}
+ melopero/Melopero RV3028@^1.1.0
+ https://github.com/RAKWireless/RAK13800-W5100S.git#1.0.2
+ rakwireless/RAKwireless NCP5623 RGB LED library@^1.0.2
+ https://github.com/meshtastic/RAK12034-BMX160.git#4821355fb10390ba8557dc43ca29a023bcfbb9d9
+ bblanchon/ArduinoJson @ 6.21.4
+; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm)
+; Note: as of 6/2013 the serial/bootloader based programming takes approximately 30 seconds
+;upload_protocol = jlink
+
+; Allows programming and debug via the RAK NanoDAP as the default debugger tool for the RAK4631 (it is only $10!)
+; programming time is about the same as the bootloader version.
+; For information on this see the meshtastic developers documentation for "Development on the NRF52"
+[env:rak4631_eth_gw_dbg]
+extends = env:rak4631
+board_level = extra
+
+; if the builtin version of openocd has a buggy version of semihosting, so use the external version
+; platform_packages = platformio/tool-openocd@^3.1200.0
+
+build_flags =
+ ${env:rak4631_eth_gw.build_flags}
+ -D USE_SEMIHOSTING
+
+lib_deps =
+ ${env:rak4631_eth_gw.lib_deps}
+ https://github.com/geeksville/Armduino-Semihosting.git#35b538fdf208c3530c1434cd099a08e486672ee4
+
+; NOTE: the pyocd support for semihosting is buggy. So I switched to using the builtin platformio support for the stlink adapter which worked much better.
+; However the built in openocd version in platformio has buggy support for TCP to semihosting.
+;
+; So I'm now trying the external openocd - but the openocd scripts for nrf52.cfg assume you are using a DAP adapter not an STLINK adapter.
+; In theory I could change those scripts. But for now I'm trying going back to a DAP adapter but with the external openocd.
+
+upload_protocol = stlink
+; eventually use platformio/tool-pyocd@^2.3600.0 instad
+;upload_protocol = custom
+;upload_command = pyocd flash -t nrf52840 $UPLOADERFLAGS $SOURCE
\ No newline at end of file
diff --git a/variants/rak4631_eth_gw/variant.cpp b/variants/rak4631_eth_gw/variant.cpp
new file mode 100644
index 000000000..e84b60b3b
--- /dev/null
+++ b/variants/rak4631_eth_gw/variant.cpp
@@ -0,0 +1,45 @@
+/*
+ Copyright (c) 2014-2015 Arduino LLC. All right reserved.
+ Copyright (c) 2016 Sandeep Mistry All right reserved.
+ Copyright (c) 2018, Adafruit Industries (adafruit.com)
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ See the GNU Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+#include "variant.h"
+#include "nrf.h"
+#include "wiring_constants.h"
+#include "wiring_digital.h"
+
+const uint32_t g_ADigitalPinMap[] = {
+ // P0
+ 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31,
+
+ // P1
+ 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47};
+
+void initVariant()
+{
+ // LED1 & LED2
+ pinMode(PIN_LED1, OUTPUT);
+ ledOff(PIN_LED1);
+
+ pinMode(PIN_LED2, OUTPUT);
+ ledOff(PIN_LED2);
+
+ // 3V3 Power Rail
+ pinMode(PIN_3V3_EN, OUTPUT);
+ digitalWrite(PIN_3V3_EN, HIGH);
+}
diff --git a/variants/rak4631_eth_gw/variant.h b/variants/rak4631_eth_gw/variant.h
new file mode 100644
index 000000000..bc5541336
--- /dev/null
+++ b/variants/rak4631_eth_gw/variant.h
@@ -0,0 +1,273 @@
+/*
+ Copyright (c) 2014-2015 Arduino LLC. All right reserved.
+ Copyright (c) 2016 Sandeep Mistry All right reserved.
+ Copyright (c) 2018, Adafruit Industries (adafruit.com)
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ See the GNU Lesser General Public License for more details.
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+#ifndef _VARIANT_RAK4630_
+#define _VARIANT_RAK4630_
+
+#define RAK4630
+
+/** Master clock frequency */
+#define VARIANT_MCK (64000000ul)
+
+#define USE_LFXO // Board uses 32khz crystal for LF
+// define USE_LFRC // Board uses RC for LF
+
+/*----------------------------------------------------------------------------
+ * Headers
+ *----------------------------------------------------------------------------*/
+
+#include "WVariant.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+
+// Number of pins defined in PinDescription array
+#define PINS_COUNT (48)
+#define NUM_DIGITAL_PINS (48)
+#define NUM_ANALOG_INPUTS (6)
+#define NUM_ANALOG_OUTPUTS (0)
+
+// LEDs
+#define PIN_LED1 (35)
+#define PIN_LED2 (36)
+
+#define LED_BUILTIN PIN_LED1
+#define LED_CONN PIN_LED2
+
+#define LED_GREEN PIN_LED1
+#define LED_BLUE PIN_LED2
+
+#define LED_STATE_ON 1 // State when LED is litted
+
+/*
+ * Buttons
+ */
+
+#define PIN_BUTTON1 9 // Pin for button on E-ink button module or IO expansion
+#define BUTTON_NEED_PULLUP
+#define PIN_BUTTON2 12
+#define PIN_BUTTON3 24
+#define PIN_BUTTON4 25
+
+/*
+ * Analog pins
+ */
+#define PIN_A0 (5)
+#define PIN_A1 (31)
+#define PIN_A2 (28)
+#define PIN_A3 (29)
+#define PIN_A4 (30)
+#define PIN_A5 (31)
+#define PIN_A6 (0xff)
+#define PIN_A7 (0xff)
+
+static const uint8_t A0 = PIN_A0;
+static const uint8_t A1 = PIN_A1;
+static const uint8_t A2 = PIN_A2;
+static const uint8_t A3 = PIN_A3;
+static const uint8_t A4 = PIN_A4;
+static const uint8_t A5 = PIN_A5;
+static const uint8_t A6 = PIN_A6;
+static const uint8_t A7 = PIN_A7;
+#define ADC_RESOLUTION 14
+
+// Other pins
+#define PIN_AREF (2)
+#define PIN_NFC1 (9)
+#define PIN_NFC2 (10)
+
+static const uint8_t AREF = PIN_AREF;
+
+/*
+ * Serial interfaces
+ */
+#define PIN_SERIAL1_RX (15)
+#define PIN_SERIAL1_TX (16)
+
+// Connected to Jlink CDC
+#define PIN_SERIAL2_RX (8)
+#define PIN_SERIAL2_TX (6)
+
+/*
+ * SPI Interfaces
+ */
+#define SPI_INTERFACES_COUNT 2
+
+#define PIN_SPI_MISO (45)
+#define PIN_SPI_MOSI (44)
+#define PIN_SPI_SCK (43)
+
+#define PIN_SPI1_MISO (29) // (0 + 29)
+#define PIN_SPI1_MOSI (30) // (0 + 30)
+#define PIN_SPI1_SCK (3) // (0 + 3)
+
+static const uint8_t SS = 42;
+static const uint8_t MOSI = PIN_SPI_MOSI;
+static const uint8_t MISO = PIN_SPI_MISO;
+static const uint8_t SCK = PIN_SPI_SCK;
+
+/*
+ * eink display pins
+ */
+
+#define PIN_EINK_CS (0 + 26)
+#define PIN_EINK_BUSY (0 + 4)
+#define PIN_EINK_DC (0 + 17)
+#define PIN_EINK_RES (-1)
+#define PIN_EINK_SCLK (0 + 3)
+#define PIN_EINK_MOSI (0 + 30) // also called SDI
+
+// #define USE_EINK
+
+// RAKRGB
+#define HAS_NCP5623
+
+/*
+ * Wire Interfaces
+ */
+#define WIRE_INTERFACES_COUNT 1
+
+#define PIN_WIRE_SDA (13)
+#define PIN_WIRE_SCL (14)
+
+// QSPI Pins
+#define PIN_QSPI_SCK 3
+#define PIN_QSPI_CS 26
+#define PIN_QSPI_IO0 30
+#define PIN_QSPI_IO1 29
+#define PIN_QSPI_IO2 28
+#define PIN_QSPI_IO3 2
+
+// On-board QSPI Flash
+#define EXTERNAL_FLASH_DEVICES IS25LP080D
+#define EXTERNAL_FLASH_USE_QSPI
+
+/* @note RAK5005-O GPIO mapping to RAK4631 GPIO ports
+ RAK5005-O <-> nRF52840
+ IO1 <-> P0.17 (Arduino GPIO number 17)
+ IO2 <-> P1.02 (Arduino GPIO number 34)
+ IO3 <-> P0.21 (Arduino GPIO number 21)
+ IO4 <-> P0.04 (Arduino GPIO number 4)
+ IO5 <-> P0.09 (Arduino GPIO number 9)
+ IO6 <-> P0.10 (Arduino GPIO number 10)
+ IO7 <-> P0.28 (Arduino GPIO number 28)
+ SW1 <-> P0.01 (Arduino GPIO number 1)
+ A0 <-> P0.04/AIN2 (Arduino Analog A2
+ A1 <-> P0.31/AIN7 (Arduino Analog A7
+ SPI_CS <-> P0.26 (Arduino GPIO number 26)
+ */
+
+// RAK4630 LoRa module
+
+/* Setup of the SX1262 LoRa module ( https://docs.rakwireless.com/Product-Categories/WisBlock/RAK4631/Datasheet/ )
+
+P1.10 NSS SPI NSS (Arduino GPIO number 42)
+P1.11 SCK SPI CLK (Arduino GPIO number 43)
+P1.12 MOSI SPI MOSI (Arduino GPIO number 44)
+P1.13 MISO SPI MISO (Arduino GPIO number 45)
+P1.14 BUSY BUSY signal (Arduino GPIO number 46)
+P1.15 DIO1 DIO1 event interrupt (Arduino GPIO number 47)
+P1.06 NRESET NRESET manual reset of the SX1262 (Arduino GPIO number 38)
+
+Important for successful SX1262 initialization:
+
+* Setup DIO2 to control the antenna switch
+* Setup DIO3 to control the TCXO power supply
+* Setup the SX1262 to use it's DCDC regulator and not the LDO
+* RAK4630 schematics show GPIO P1.07 connected to the antenna switch, but it should not be initialized, as DIO2 will do the
+control of the antenna switch
+
+SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG
+
+*/
+
+#define DETECTION_SENSOR_EN 4
+
+#define USE_SX1262
+#define SX126X_CS (42)
+#define SX126X_DIO1 (47)
+#define SX126X_BUSY (46)
+#define SX126X_RESET (38)
+// #define SX126X_TXEN (39)
+// #define SX126X_RXEN (37)
+#define SX126X_POWER_EN (37)
+// DIO2 controlls an antenna switch and the TCXO voltage is controlled by DIO3
+#define SX126X_DIO2_AS_RF_SWITCH
+#define SX126X_DIO3_TCXO_VOLTAGE 1.8
+
+// Testing USB detection
+#define NRF_APM
+
+// enables 3.3V periphery like GPS or IO Module
+// Do not toggle this for GPS power savings
+#define PIN_3V3_EN (34)
+
+// RAK1910 GPS module
+// If using the wisblock GPS module and pluged into Port A on WisBlock base
+// IO1 is hooked to PPS (pin 12 on header) = gpio 17
+// IO2 is hooked to GPS RESET = gpio 34, but it can not be used to this because IO2 is ALSO used to control 3V3_S power (1 is on).
+// Therefore must be 1 to keep peripherals powered
+// Power is on the controllable 3V3_S rail
+// #define PIN_GPS_RESET (34)
+// #define PIN_GPS_EN PIN_3V3_EN
+#define PIN_GPS_PPS (17) // Pulse per second input from the GPS
+
+#define GPS_RX_PIN PIN_SERIAL1_RX
+#define GPS_TX_PIN PIN_SERIAL1_TX
+
+// Define pin to enable GPS toggle (set GPIO to LOW) via user button triple press
+
+// RAK12002 RTC Module
+#define RV3028_RTC (uint8_t)0b1010010
+
+// RAK18001 Buzzer in Slot C
+// #define PIN_BUZZER 21 // IO3 is PWM2
+// NEW: set this via protobuf instead!
+
+// Battery
+// The battery sense is hooked to pin A0 (5)
+#define BATTERY_PIN PIN_A0
+// and has 12 bit resolution
+#define BATTERY_SENSE_RESOLUTION_BITS 12
+#define BATTERY_SENSE_RESOLUTION 4096.0
+#undef AREF_VOLTAGE
+#define AREF_VOLTAGE 3.0
+#define VBAT_AR_INTERNAL AR_INTERNAL_3_0
+#define ADC_MULTIPLIER 1.73
+
+#define HAS_RTC 1
+
+#define HAS_ETHERNET 1
+
+#define RAK_4631 1
+
+#define PIN_ETHERNET_RESET 21
+#define PIN_ETHERNET_SS PIN_EINK_CS
+#define ETH_SPI_PORT SPI1
+#define AQ_SET_PIN 10
+
+#ifdef __cplusplus
+}
+#endif
+
+/*----------------------------------------------------------------------------
+ * Arduino objects - C++ only
+ *----------------------------------------------------------------------------*/
+
+#endif
\ No newline at end of file
diff --git a/variants/rp2040-lora/variant.h b/variants/rp2040-lora/variant.h
index d0bbc0ec3..f1826605f 100644
--- a/variants/rp2040-lora/variant.h
+++ b/variants/rp2040-lora/variant.h
@@ -23,6 +23,7 @@
// ratio of voltage divider = 3.0 (R17=200k, R18=100k)
// #define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic
+#define HAS_CPU_SHUTDOWN 1
#define USE_SX1262
#undef LORA_SCK