diff --git a/platformio.ini b/platformio.ini
index 5dd065503..9c6ae30f0 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -81,6 +81,7 @@ lib_deps =
adafruit/Adafruit Unified Sensor@^1.1.4
paulstoffregen/OneWire@^2.3.5
robtillaart/DS18B20@^0.1.11
+ adafruit/Adafruit BMP280 Library@^2.6.3
adafruit/Adafruit BME280 Library@^2.2.2
adafruit/Adafruit BME680 Library@^2.0.1
adafruit/Adafruit MCP9808 Library@^2.0.0
@@ -91,7 +92,7 @@ lib_deps =
extends = arduino_base
platform = espressif32@3.5.0
build_src_filter =
- ${arduino_base.build_src_filter} -
+ ${arduino_base.build_src_filter} - -
upload_speed = 115200
debug_init_break = tbreak setup
@@ -143,7 +144,7 @@ build_flags =
${arduino_base.build_flags} -Wno-unused-variable
-Isrc/nrf52
build_src_filter =
- ${arduino_base.build_src_filter} - - - - - -
+ ${arduino_base.build_src_filter} - - - - - - -
lib_ignore =
BluetoothOTA
diff --git a/protobufs b/protobufs
index 8c6ada3df..11d94c9b1 160000
--- a/protobufs
+++ b/protobufs
@@ -1 +1 @@
-Subproject commit 8c6ada3df4a9ea17a89d31b4f814d83a3c503b53
+Subproject commit 11d94c9b15e9085b0f2516735ad816a3a35d5680
diff --git a/src/ButtonThread.h b/src/ButtonThread.h
index 1549c748b..fe014246c 100644
--- a/src/ButtonThread.h
+++ b/src/ButtonThread.h
@@ -7,7 +7,7 @@
#include "power.h"
#include
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "nimble/BluetoothUtil.h"
#endif
@@ -127,7 +127,7 @@ class ButtonThread : public concurrency::OSThread
static void userButtonPressedLong()
{
// DEBUG_MSG("Long press!\n");
-#ifndef NRF52_SERIES
+#ifdef ARCH_ESP32
screen->adjustBrightness();
#endif
// If user button is held down for 5 seconds, shutdown the device.
@@ -137,7 +137,7 @@ class ButtonThread : public concurrency::OSThread
setLed(false);
power->shutdown();
}
-#elif NRF52_SERIES
+#elif defined(ARCH_NRF52)
// Do actual shutdown when button released, otherwise the button release
// may wake the board immediatedly.
if ((!shutdown_on_long_stop) && (millis() > 30 * 1000)) {
@@ -163,19 +163,19 @@ class ButtonThread : public concurrency::OSThread
static void userButtonDoublePressed()
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
disablePin();
-#elif defined(HAS_EINK)
+#elif defined(USE_EINK)
digitalWrite(PIN_EINK_EN, digitalRead(PIN_EINK_EN) == LOW);
#endif
}
static void userButtonMultiPressed()
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
clearNVS();
#endif
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
clearBonds();
#endif
}
diff --git a/src/DebugConfiguration.h b/src/DebugConfiguration.h
index 53ea303a2..c1d95256e 100644
--- a/src/DebugConfiguration.h
+++ b/src/DebugConfiguration.h
@@ -17,29 +17,6 @@
#define DEBUG_PORT (*console) // Serial debug port
-// What platforms should use SEGGER?
-#ifdef NRF52_SERIES
-
-// Always include the SEGGER code on NRF52 - because useful for debugging
-#include "SEGGER_RTT.h"
-
-// The channel we send stdout data to
-#define SEGGER_STDOUT_CH 0
-
-// Debug printing to segger console
-#define SEGGER_MSG(...) SEGGER_RTT_printf(SEGGER_STDOUT_CH, __VA_ARGS__)
-
-// If we are not on a NRF52840 (which has built in USB-ACM serial support) and we don't have serial pins hooked up, then we MUST
-// use SEGGER for debug output
-#if !defined(PIN_SERIAL_RX) && !defined(NRF52840_XXAA)
-// No serial ports on this board - ONLY use segger in memory console
-#define USE_SEGGER
-#endif
-
-#else
-#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32
-#endif
-
#ifdef USE_SEGGER
#define DEBUG_MSG(...) SEGGER_RTT_printf(0, __VA_ARGS__)
#else
diff --git a/src/FSCommon.h b/src/FSCommon.h
index 26d4f9f88..3493a8464 100644
--- a/src/FSCommon.h
+++ b/src/FSCommon.h
@@ -4,21 +4,25 @@
// Cross platform filesystem API
-#ifdef PORTDUINO
+#if defined(ARCH_PORTDUINO)
// Portduino version
#include "PortduinoFS.h"
#define FSCom PortduinoFS
#define FSBegin() true
#define FILE_O_WRITE "w"
#define FILE_O_READ "r"
-#elif !defined(NO_ESP32)
+#endif
+
+#if defined(ARCH_ESP32)
// ESP32 version
#include "LITTLEFS.h"
#define FSCom LITTLEFS
#define FSBegin() FSCom.begin(true)
#define FILE_O_WRITE "w"
#define FILE_O_READ "r"
-#else
+#endif
+
+#if defined(ARCH_NRF52)
// NRF52 version
#include "InternalFileSystem.h"
#define FSCom InternalFS
diff --git a/src/OSTimer.cpp b/src/OSTimer.cpp
index f2b38f17c..a0161cd42 100644
--- a/src/OSTimer.cpp
+++ b/src/OSTimer.cpp
@@ -15,7 +15,7 @@ bool scheduleOSCallback(PendableFunction callback, void *param1, uint32_t param2
return xTimerPendFunctionCall(callback, param1, param2, pdMS_TO_TICKS(delayMsec));
} */
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// Super skanky quick hack to use hardware timers of the ESP32
static hw_timer_t *timer;
diff --git a/src/Power.cpp b/src/Power.cpp
index fa09eaeba..d471955b7 100644
--- a/src/Power.cpp
+++ b/src/Power.cpp
@@ -46,7 +46,7 @@ Power *power;
using namespace meshtastic;
#ifndef AREF_VOLTAGE
-#if defined(NRF52_SERIES)
+#if defined(ARCH_NRF52)
/*
* Internal Reference is +/-0.6V, with an adjustable gain of 1/6, 1/5, 1/4,
* 1/3, 1/2 or 1, meaning 3.6, 3.0, 2.4, 1.8, 1.2 or 0.6V for the ADC levels.
@@ -84,7 +84,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
if (v < noBatVolt)
return -1; // If voltage is super low assume no battery installed
-#ifndef NRF52_SERIES
+#ifdef ARCH_ESP32
// This does not work on a RAK4631 with battery connected
if (v > chargingVolt)
return 0; // While charging we can't report % full on the battery
@@ -180,11 +180,11 @@ bool Power::analogInit()
// disable any internal pullups
pinMode(BATTERY_PIN, INPUT);
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// ESP32 needs special analog stuff
adcAttachPin(BATTERY_PIN);
#endif
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
#ifdef VBAT_AR_INTERNAL
analogReference(VBAT_AR_INTERNAL);
#else
@@ -225,7 +225,7 @@ void Power::shutdown()
DEBUG_MSG("Shutting down\n");
axp.setChgLEDMode(AXP20X_LED_OFF);
axp.shutdown();
-#elif NRF52_SERIES
+#elif defined(ARCH_NRF52)
playBeep();
ledOff(PIN_LED1);
ledOff(PIN_LED2);
@@ -267,7 +267,7 @@ void Power::readPowerStatus()
// If we have a battery at all and it is less than 10% full, force deep sleep if we have more than 3 low readings in a row
// Supect fluctuating voltage on the RAK4631 to force it to deep sleep even if battery is at 85% after only a few days
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
if (powerStatus2.getHasBattery() && !powerStatus2.getHasUSB()) {
if (batteryLevel->getBattVoltage() < MIN_BAT_MILLIVOLTS) {
low_voltage_counter++;
diff --git a/src/PowerFSM.cpp b/src/PowerFSM.cpp
index 306dd1390..4c84cecfc 100644
--- a/src/PowerFSM.cpp
+++ b/src/PowerFSM.cpp
@@ -63,7 +63,7 @@ static void lsIdle()
{
// DEBUG_MSG("lsIdle begin ls_secs=%u\n", getPref_ls_secs());
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// Do we have more sleeping to do?
if (secsSlept < config.power.ls_secs ? config.power.ls_secs : default_ls_secs * 1000) {
@@ -343,7 +343,7 @@ void PowerFSM_setup()
uint32_t meshSds = 0;
-#ifndef NRF52_SERIES
+#ifdef ARCH_ESP32
// We never enter light-sleep or NB states on NRF52 (because the CPU uses so little power normally)
// See: https://github.com/meshtastic/Meshtastic-device/issues/1071
diff --git a/src/SerialConsole.cpp b/src/SerialConsole.cpp
index 49e7e017a..b066caa08 100644
--- a/src/SerialConsole.cpp
+++ b/src/SerialConsole.cpp
@@ -30,7 +30,7 @@ SerialConsole::SerialConsole() : StreamAPI(&Port), RedirectablePrint(&Port)
// setDestination(&noopPrint); for testing, try turning off 'all' debug output and see what leaks
Port.begin(SERIAL_BAUD);
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
time_t timeout = millis();
while (!Port) {
if ((millis() - timeout) < 5000) {
diff --git a/src/configuration.h b/src/configuration.h
index 6ab956176..19e570024 100644
--- a/src/configuration.h
+++ b/src/configuration.h
@@ -62,79 +62,15 @@ along with this program. If not, see .
/// Convert a preprocessor name into a quoted string and if that string is empty use "unset"
#define optstr(s) (xstr(s)[0] ? xstr(s) : "unset")
-#ifdef PORTDUINO
-
-#define NO_ESP32 // Don't use ESP32 libs (mainly bluetooth)
-
-#elif defined(NRF52_SERIES) // All of the NRF52 targets are configured using variant.h, so this section shouldn't need to be
-// board specific
-
-//
-// Standard definitions for NRF52 targets
-//
-
-#define NO_ESP32 // Don't use ESP32 libs (mainly bluetooth)
-
-// We bind to the GPS using variant.h instead for this platform (Serial1)
-
-#define LED_PIN PIN_LED1 // LED1 on nrf52840-DK
-
-// If the variant filed defines as standard button
-#ifdef PIN_BUTTON1
-#define BUTTON_PIN PIN_BUTTON1
+// Nop definition for these attributes that are specific to ESP32
+#ifndef EXT_RAM_ATTR
+ #define EXT_RAM_ATTR
#endif
-
-#ifdef PIN_BUTTON2
-#define BUTTON_PIN_ALT PIN_BUTTON2
+#ifndef IRAM_ATTR
+ #define IRAM_ATTR
#endif
-
-#ifdef PIN_BUTTON_TOUCH
-#define BUTTON_PIN_TOUCH PIN_BUTTON_TOUCH
-#endif
-
-#else
-
-//
-// Standard definitions for ESP32 targets
-//
-
-#define HAS_WIFI
-
-#define GPS_SERIAL_NUM 1
-#define GPS_RX_PIN 34
-#ifdef USE_JTAG
-#define GPS_TX_PIN -1
-#else
-#define GPS_TX_PIN 12
-#endif
-
-// -----------------------------------------------------------------------------
-// LoRa SPI
-// -----------------------------------------------------------------------------
-
-// NRF52 boards will define this in variant.h
-#ifndef RF95_SCK
-#define RF95_SCK 5
-#define RF95_MISO 19
-#define RF95_MOSI 27
-#define RF95_NSS 18
-#endif
-
-#endif
-
-#ifndef TTGO_T_ECHO
-#define GPS_UBLOX
-#endif
-
-//
-// Standard definitions for !ESP32 targets
-//
-
-#ifdef NO_ESP32
-// Nop definition for these attributes - not used on NRF52
-#define EXT_RAM_ATTR
-#define IRAM_ATTR
-#define RTC_DATA_ATTR
+#ifndef RTC_DATA_ATTR
+ #define RTC_DATA_ATTR
#endif
// -----------------------------------------------------------------------------
@@ -190,109 +126,43 @@ along with this program. If not, see .
#define GPS_THREAD_INTERVAL 100
#endif
-#if defined(TBEAM_V10)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_TBEAM
-
-#elif defined(TBEAM_V07)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_TBEAM0p7
-
-#elif defined(DIY_V1)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_DIY_V1
-
-#elif defined(RAK_11200)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_RAK11200
-
-#elif defined(ARDUINO_HELTEC_WIFI_LORA_32_V2)
-
-#ifdef HELTEC_V2_0
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_HELTEC_V2_0
-
-#endif
-
-#ifdef HELTEC_V2_1
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_HELTEC_V2_1
-
-#endif
-
-#elif defined(ARDUINO_HELTEC_WIFI_LORA_32)
-
-#define HW_VENDOR HardwareModel_HELTEC_V1
-
-#elif defined(TLORA_V1)
-
-#define HW_VENDOR HardwareModel_TLORA_V1
-
-#elif defined(TLORA_V2)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_TLORA_V2
-
-#elif defined(TLORA_V1_3)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_TLORA_V1_1p3
-
-#elif defined(TLORA_V2_1_16)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_TLORA_V2_1_1p6
-
-#elif defined(GENIEBLOCKS)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_GENIEBLOCKS
-
-#elif defined(PRIVATE_HW)
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_PRIVATE_HW
-
-#endif
-
-#ifdef ARDUINO_NRF52840_PCA10056
-
-// This string must exactly match the case used in release file names or the android updater won't work
-#define HW_VENDOR HardwareModel_NRF52840DK
-
-// This board uses 0 to be mean LED on
-#undef LED_INVERTED
-#define LED_INVERTED 1
-
-#elif defined(ARDUINO_NRF52840_PPR)
-
-#define HW_VENDOR HardwareModel_PPR
-
-#elif defined(RAK4630)
-
-#define HW_VENDOR HardwareModel_RAK4631
-
-#elif defined(TTGO_T_ECHO)
-
-#define HW_VENDOR HardwareModel_T_ECHO
-
-#elif defined(NANO_G1)
-
-#define HW_VENDOR HardwareModel_NANO_G1
-
-#elif defined(NORDIC_PCA10059)
-
-#define HW_VENDOR HardwareModel_NRF52840_PCA10059
-
-#elif defined(M5STACK)
-
-#define HW_VENDOR HardwareModel_M5STACK
-
-#elif NRF52_SERIES
-
-#define HW_VENDOR HardwareModel_NRF52_UNKNOWN
-
-#elif PORTDUINO
-
-#define HW_VENDOR HardwareModel_PORTDUINO
-
-#endif
-
+/* Step #1: offer chance for variant-specific defines */
#include "variant.h"
+
+/* Step #2: follow with defines common to the architecture;
+ also enable HAS_ option not specifically disabled by variant.h */
+#include "architecture.h"
+
+/* Step #3: mop up with disabled values for HAS_ options not handled by the above two */
+
+#ifndef HAS_WIFI
+ #define HAS_WIFI 0
+#endif
+#ifndef HAS_SCREEN
+ #define HAS_SCREEN 0
+#endif
+#ifndef HAS_WIRE
+ #define HAS_WIRE 0
+#endif
+#ifndef HAS_GPS
+ #define HAS_GPS 0
+#endif
+#ifndef HAS_BUTTON
+ #define HAS_BUTTON 0
+#endif
+#ifndef HAS_TELEMETRY
+ #define HAS_TELEMETRY 0
+#endif
+#ifndef HAS_RADIO
+ #define HAS_RADIO 0
+#endif
+#ifndef HAS_RTC
+ #define HAS_RTC 0
+#endif
+
#include "RF95Configuration.h"
#include "DebugConfiguration.h"
+
+#ifndef HW_VENDOR
+ #error HW_VENDOR must be defined
+#endif
diff --git a/src/debug/i2cScan.h b/src/debug/i2cScan.h
index 29d7cdc95..3d737c692 100644
--- a/src/debug/i2cScan.h
+++ b/src/debug/i2cScan.h
@@ -3,7 +3,7 @@
#include
#include "mesh/generated/telemetry.pb.h"
-#ifndef NO_WIRE
+#if HAS_WIRE
uint16_t getRegisterValue(uint8_t address, uint8_t reg, uint8_t length) {
uint16_t value = 0x00;
Wire.beginTransmission(address);
@@ -124,6 +124,9 @@ void scanI2Cdevice(void)
} else if (registerValue == 0x60) {
DEBUG_MSG("BME-280 sensor found at address 0x%x\n", (uint8_t)addr);
nodeTelemetrySensorsMap[TelemetrySensorType_BME280] = addr;
+ } else {
+ DEBUG_MSG("BMP-280 sensor found at address 0x%x\n", (uint8_t)addr);
+ nodeTelemetrySensorsMap[TelemetrySensorType_BMP280] = addr;
}
}
if (addr == INA_ADDR || addr == INA_ADDR_ALTERNATE) {
diff --git a/src/esp32/architecture.h b/src/esp32/architecture.h
new file mode 100644
index 000000000..dd9031d6d
--- /dev/null
+++ b/src/esp32/architecture.h
@@ -0,0 +1,103 @@
+#pragma once
+
+#define ARCH_ESP32
+
+//
+// defaults for ESP32 architecture
+//
+
+#ifndef HAS_WIFI
+ #define HAS_WIFI 1
+#endif
+#ifndef HAS_SCREEN
+ #define HAS_SCREEN 1
+#endif
+#ifndef HAS_WIRE
+ #define HAS_WIRE 1
+#endif
+#ifndef HAS_GPS
+ #define HAS_GPS 1
+#endif
+#ifndef HAS_BUTTON
+ #define HAS_BUTTON 1
+#endif
+#ifndef HAS_TELEMETRY
+ #define HAS_TELEMETRY 1
+#endif
+#ifndef HAS_RADIO
+ #define HAS_RADIO 1
+#endif
+#ifndef HAS_RTC
+ #define HAS_RTC 1
+#endif
+
+//
+// set HW_VENDOR
+//
+
+// This string must exactly match the case used in release file names or the android updater won't work
+
+#if defined(TBEAM_V10)
+ #define HW_VENDOR HardwareModel_TBEAM
+#elif defined(TBEAM_V07)
+ #define HW_VENDOR HardwareModel_TBEAM0p7
+#elif defined(DIY_V1)
+ #define HW_VENDOR HardwareModel_DIY_V1
+#elif defined(RAK_11200)
+ #define HW_VENDOR HardwareModel_RAK11200
+#elif defined(ARDUINO_HELTEC_WIFI_LORA_32_V2)
+ #ifdef HELTEC_V2_0
+ #define HW_VENDOR HardwareModel_HELTEC_V2_0
+ #endif
+ #ifdef HELTEC_V2_1
+ #define HW_VENDOR HardwareModel_HELTEC_V2_1
+ #endif
+#elif defined(ARDUINO_HELTEC_WIFI_LORA_32)
+ #define HW_VENDOR HardwareModel_HELTEC_V1
+#elif defined(TLORA_V1)
+ #define HW_VENDOR HardwareModel_TLORA_V1
+#elif defined(TLORA_V2)
+ #define HW_VENDOR HardwareModel_TLORA_V2
+#elif defined(TLORA_V1_3)
+ #define HW_VENDOR HardwareModel_TLORA_V1_1p3
+#elif defined(TLORA_V2_1_16)
+ #define HW_VENDOR HardwareModel_TLORA_V2_1_1p6
+#elif defined(GENIEBLOCKS)
+ #define HW_VENDOR HardwareModel_GENIEBLOCKS
+#elif defined(PRIVATE_HW)
+ #define HW_VENDOR HardwareModel_PRIVATE_HW
+#elif defined(NANO_G1)
+ #define HW_VENDOR HardwareModel_NANO_G1
+#elif defined(M5STACK)
+ #define HW_VENDOR HardwareModel_M5STACK
+#endif
+
+//
+// Standard definitions for ESP32 targets
+//
+
+#define GPS_SERIAL_NUM 1
+#ifndef GPS_RX_PIN
+#define GPS_RX_PIN 34
+#endif
+#ifndef GPS_TX_PIN
+#ifdef USE_JTAG
+#define GPS_TX_PIN -1
+#else
+#define GPS_TX_PIN 12
+#endif
+#endif
+
+// -----------------------------------------------------------------------------
+// LoRa SPI
+// -----------------------------------------------------------------------------
+
+// NRF52 boards will define this in variant.h
+#ifndef RF95_SCK
+#define RF95_SCK 5
+#define RF95_MISO 19
+#define RF95_MOSI 27
+#define RF95_NSS 18
+#endif
+
+#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32
diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp
index 0536e5a11..b0a8164d0 100644
--- a/src/gps/GPS.cpp
+++ b/src/gps/GPS.cpp
@@ -65,12 +65,12 @@ bool GPS::setupGPS()
didSerialInit = true;
// ESP32 has a special set of parameters vs other arduino ports
-#if defined(GPS_RX_PIN) && !defined(NO_ESP32)
+#if defined(GPS_RX_PIN) && defined(ARCH_ESP32)
_serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, GPS_RX_PIN, GPS_TX_PIN);
#else
_serial_gps->begin(GPS_BAUDRATE);
#endif
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
_serial_gps->setRxBufferSize(2048); // the default is 256
#endif
#ifdef TTGO_T_ECHO
@@ -432,14 +432,14 @@ int GPS::prepareDeepSleep(void *unused)
return 0;
}
-#ifndef NO_GPS
+#if HAS_GPS
#include "NMEAGPS.h"
#endif
GPS *createGps()
{
-#ifdef NO_GPS
+#if !HAS_GPS
return nullptr;
#else
if (!config.position.gps_disabled) {
diff --git a/src/gps/RTC.cpp b/src/gps/RTC.cpp
index 04e7043e5..148782cd7 100644
--- a/src/gps/RTC.cpp
+++ b/src/gps/RTC.cpp
@@ -115,12 +115,12 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
rtc.setDateTime(t->tm_year + 1900, t->tm_mon + 1, t->tm_wday, t->tm_hour, t->tm_min, t->tm_sec);
DEBUG_MSG("PCF8563_RTC setDateTime %02d-%02d-%02d %02d:%02d:%02d %ld\n", t->tm_year + 1900, t->tm_mon + 1, t->tm_mday, t->tm_hour, t->tm_min, t->tm_sec, tv->tv_sec);
}
-#elif !defined(NO_ESP32)
+#elif defined(ARCH_ESP32)
settimeofday(tv, NULL);
#endif
// nrf52 doesn't have a readable RTC (yet - software not written)
-#if defined(PORTDUINO) || !defined(NO_ESP32) || defined(RV3028_RTC) || defined(PCF8563_RTC)
+#ifdef HAS_RTC
readFromRTC();
#endif
diff --git a/src/graphics/EInkDisplay2.cpp b/src/graphics/EInkDisplay2.cpp
index ad3488545..9062fc018 100644
--- a/src/graphics/EInkDisplay2.cpp
+++ b/src/graphics/EInkDisplay2.cpp
@@ -1,6 +1,6 @@
#include "configuration.h"
-#ifdef HAS_EINK
+#ifdef USE_EINK
#include "main.h"
#include "EInkDisplay2.h"
#include "SPILock.h"
diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp
index b8eb79178..fc447dc71 100644
--- a/src/graphics/Screen.cpp
+++ b/src/graphics/Screen.cpp
@@ -20,7 +20,7 @@ along with this program. If not, see .
*/
#include "configuration.h"
-#ifndef NO_SCREEN
+#if HAS_SCREEN
#include
#include "GPS.h"
@@ -39,7 +39,7 @@ along with this program. If not, see .
#include "target_specific.h"
#include "utils.h"
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "esp_task_wdt.h"
#include "mesh/http/WiFiAPClient.h"
#endif
@@ -94,7 +94,7 @@ static uint16_t displayWidth, displayHeight;
#define SCREEN_WIDTH displayWidth
#define SCREEN_HEIGHT displayHeight
-#if defined(HAS_EINK) || defined(ILI9341_DRIVER)
+#if defined(USE_EINK) || defined(ILI9341_DRIVER)
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16
#define FONT_MEDIUM ArialMT_Plain_24
@@ -212,7 +212,7 @@ static void drawSSLScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16
display->setFont(FONT_SMALL);
display->drawString(64 + x, y, "Creating SSL certificate");
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
yield();
esp_task_wdt_reset();
#endif
@@ -253,13 +253,13 @@ static void drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, i
display->drawString(x, y + FONT_HEIGHT_SMALL * 4 - 3, "");
}
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
yield();
esp_task_wdt_reset();
#endif
}
-#ifdef HAS_EINK
+#ifdef USE_EINK
/// Used on eink displays while in deep sleep
static void drawSleepScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
@@ -843,7 +843,7 @@ Screen::Screen(uint8_t address, int sda, int scl) : OSThread("Screen"), cmdQueue
*/
void Screen::doDeepSleep()
{
-#ifdef HAS_EINK
+#ifdef USE_EINK
static FrameCallback sleepFrames[] = {drawSleepScreen};
static const int sleepFrameCount = sizeof(sleepFrames) / sizeof(sleepFrames[0]);
ui.setFrames(sleepFrames, sleepFrameCount);
@@ -954,7 +954,7 @@ void Screen::setup()
void Screen::forceDisplay()
{
// Nasty hack to force epaper updates for 'key' frames. FIXME, cleanup.
-#ifdef HAS_EINK
+#ifdef USE_EINK
dispdev.forceDisplay();
#endif
}
@@ -1055,7 +1055,7 @@ int32_t Screen::runOnce()
DEBUG_MSG("Setting idle framerate\n");
targetFramerate = IDLE_FRAMERATE;
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
setCPUFast(false); // Turn up the CPU to improve screen animations
#endif
@@ -1180,7 +1180,7 @@ void Screen::setFrames()
// call a method on debugInfoScreen object (for more details)
normalFrames[numframes++] = &Screen::drawDebugInfoSettingsTrampoline;
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
if (isWifiAvailable()) {
// call a method on debugInfoScreen object (for more details)
normalFrames[numframes++] = &Screen::drawDebugInfoWiFiTrampoline;
@@ -1287,7 +1287,7 @@ void Screen::setFastFramerate()
// We are about to start a transition so speed up fps
targetFramerate = SCREEN_TRANSITION_FRAMERATE;
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
setCPUFast(true); // Turn up the CPU to improve screen animations
#endif
@@ -1342,7 +1342,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
// Jm
void DebugInfo::drawFrameWiFi(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
-#ifdef HAS_WIFI
+#if HAS_WIFI
const char *wifiName = config.wifi.ssid;
const char *wifiPsw = config.wifi.psk;
@@ -1665,4 +1665,4 @@ int Screen::handleUIFrameEvent(const UIFrameEvent *event)
}
} // namespace graphics
-#endif // NO_SCREEN
\ No newline at end of file
+#endif // HAS_SCREEN
\ No newline at end of file
diff --git a/src/graphics/Screen.h b/src/graphics/Screen.h
index 0073e034b..b8d3f6f58 100644
--- a/src/graphics/Screen.h
+++ b/src/graphics/Screen.h
@@ -1,6 +1,8 @@
#pragma once
-#ifdef NO_SCREEN
+#include "configuration.h"
+
+#if !HAS_SCREEN
#include "power.h"
namespace graphics
{
@@ -315,7 +317,7 @@ class Screen : public concurrency::OSThread
SSD1306Wire dispdev;
#elif defined(ST7735_CS) || defined(ILI9341_DRIVER)
TFTDisplay dispdev;
-#elif defined(HAS_EINK)
+#elif defined(USE_EINK)
EInkDisplay dispdev;
#elif defined(USE_ST7567)
ST7567Wire dispdev;
diff --git a/src/main.cpp b/src/main.cpp
index 88742aef3..66c4021c1 100644
--- a/src/main.cpp
+++ b/src/main.cpp
@@ -31,7 +31,7 @@
#include "mesh/http/WiFiAPClient.h"
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "mesh/http/WebServer.h"
#ifdef USE_NEW_ESP32_BLUETOOTH
@@ -42,7 +42,7 @@
#endif
-#if defined(HAS_WIFI) || defined(PORTDUINO)
+#if HAS_WIFI
#include "mesh/wifi/WiFiServerAPI.h"
#include "mqtt/MQTT.h"
#endif
@@ -52,7 +52,9 @@
#include "SX1262Interface.h"
#include "SX1268Interface.h"
+#if HAS_BUTTON
#include "ButtonThread.h"
+#endif
#include "PowerFSMThread.h"
using namespace concurrency;
@@ -91,7 +93,7 @@ uint32_t serialSinceMsec;
bool axp192_found;
// Array map of sensor types (as array index) and i2c address as value we'll find in the i2c scan
-uint8_t nodeTelemetrySensorsMap[6] = { 0, 0, 0, 0, 0, 0 };
+uint8_t nodeTelemetrySensorsMap[7] = { 0, 0, 0, 0, 0, 0, 0 };
Router *router = NULL; // Users of router don't care what sort of subclass implements that API
@@ -126,11 +128,15 @@ static int32_t ledBlinker()
uint32_t timeLastPowered = 0;
+#if HAS_BUTTON
bool ButtonThread::shutdown_on_long_stop = false;
+#endif
static Periodic *ledPeriodic;
static OSThread *powerFSMthread, *buttonThread;
+#if HAS_BUTTON
uint32_t ButtonThread::longPressTime = 0;
+#endif
RadioInterface *rIf = NULL;
@@ -187,7 +193,7 @@ void setup()
bool forceSoftAP = 0;
#ifdef BUTTON_PIN
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// If the button is connected to GPIO 12, don't enable the ability to use
// meshtasticAdmin on the device.
@@ -218,7 +224,7 @@ void setup()
#ifdef I2C_SDA
Wire.begin(I2C_SDA, I2C_SCL);
-#elif !defined(NO_WIRE)
+#elif HAS_WIRE
Wire.begin();
#endif
@@ -236,8 +242,10 @@ void setup()
// scanEInkDevice();
#endif
+#if HAS_BUTTON
// Buttons & LED
buttonThread = new ButtonThread();
+#endif
#ifdef LED_PIN
pinMode(LED_PIN, OUTPUT);
@@ -247,7 +255,7 @@ void setup()
// Hello
DEBUG_MSG("Meshtastic hwvendor=%d, swver=%s\n", HW_VENDOR, optstr(APP_VERSION));
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// Don't init display if we don't have one or we are waking headless due to a timer event
if (wakeCause == ESP_SLEEP_WAKEUP_TIMER)
screen_found = 0; // forget we even have the hardware
@@ -255,7 +263,7 @@ void setup()
esp32Setup();
#endif
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
nrf52Setup();
#endif
playStartMelody();
@@ -271,7 +279,7 @@ void setup()
// Init our SPI controller (must be before screen and lora)
initSPI();
-#ifdef NO_ESP32
+#ifndef ARCH_ESP32
SPI.begin();
#else
// ESP32
@@ -306,7 +314,7 @@ void setup()
// Don't call screen setup until after nodedb is setup (because we need
// the current region name)
-#if defined(ST7735_CS) || defined(HAS_EINK) || defined(ILI9341_DRIVER)
+#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER)
screen->setup();
#else
if (screen_found)
@@ -386,7 +394,7 @@ void setup()
}
#endif
-#ifdef USE_SIM_RADIO
+#if !HAS_RADIO
if (!rIf) {
rIf = new SimRadio;
if (!rIf->init()) {
@@ -399,19 +407,19 @@ void setup()
}
#endif
-#if defined(PORTDUINO) || defined(HAS_WIFI)
+#if HAS_WIFI
mqttInit();
#endif
// Initialize Wifi
initWifi(forceSoftAP);
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// Start web server thread.
webServerThread = new WebServerThread();
#endif
-#ifdef PORTDUINO
+#ifdef ARCH_PORTDUINO
initApiServer();
#endif
@@ -452,10 +460,10 @@ void loop()
// heap_caps_check_integrity_all(true); // FIXME - disable this expensive check
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
esp32Loop();
#endif
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
nrf52Loop();
#endif
powerCommandsCheck();
diff --git a/src/main.h b/src/main.h
index b9ae581ac..02dce04b3 100644
--- a/src/main.h
+++ b/src/main.h
@@ -19,7 +19,7 @@ extern bool axp192_found;
extern bool isCharging;
extern bool isUSBPowered;
-extern uint8_t nodeTelemetrySensorsMap[6];
+extern uint8_t nodeTelemetrySensorsMap[7];
// Global Screen singleton.
extern graphics::Screen *screen;
diff --git a/src/mesh/FloodingRouter.cpp b/src/mesh/FloodingRouter.cpp
index e01863de1..5e3126f77 100644
--- a/src/mesh/FloodingRouter.cpp
+++ b/src/mesh/FloodingRouter.cpp
@@ -29,8 +29,12 @@ bool FloodingRouter::shouldFilterReceived(MeshPacket *p)
void FloodingRouter::sniffReceived(const MeshPacket *p, const Routing *c)
{
-
- if ((p->to == NODENUM_BROADCAST) && (p->hop_limit > 0) && (getFrom(p) != getNodeNum())) {
+ PacketId ackId = ((c && c->error_reason == Routing_Error_NONE) || !c) ? p->decoded.request_id : 0;
+ if (ackId && p->to != getNodeNum()) {
+ // do not flood direct message that is ACKed
+ DEBUG_MSG("Receiving an ACK not for me, but don't need to rebroadcast this direct message anymore.\n");
+ Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM
+ } else if ((p->to != getNodeNum()) && (p->hop_limit > 0) && (getFrom(p) != getNodeNum())) {
if (p->id != 0) {
if (config.device.role != Config_DeviceConfig_Role_ClientMute) {
MeshPacket *tosend = packetPool.allocCopy(*p); // keep a copy because we will be sending it
diff --git a/src/mesh/MeshModule.h b/src/mesh/MeshModule.h
index cfc715497..c6f10f138 100644
--- a/src/mesh/MeshModule.h
+++ b/src/mesh/MeshModule.h
@@ -4,7 +4,7 @@
#include "mesh/MeshTypes.h"
#include
-#ifndef NO_SCREEN
+#if HAS_SCREEN
#include
#include
#endif
@@ -72,7 +72,7 @@ class MeshModule
static void observeUIEvents(Observer *observer);
static AdminMessageHandleResult handleAdminMessageForAllPlugins(
const MeshPacket &mp, AdminMessage *request, AdminMessage *response);
-#ifndef NO_SCREEN
+#if HAS_SCREEN
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { return; }
#endif
protected:
diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp
index e1779b2f7..63d67871e 100644
--- a/src/mesh/NodeDB.cpp
+++ b/src/mesh/NodeDB.cpp
@@ -17,14 +17,14 @@
#include
#include
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "mesh/http/WiFiAPClient.h"
#include "modules/esp32/StoreForwardModule.h"
#include
#include
#endif
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
#include
#include
#endif
@@ -132,11 +132,11 @@ bool NodeDB::factoryReset()
installDefaultDeviceState();
// third, write to disk
saveToDisk();
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// This will erase what's in NVS including ssl keys, persistant variables and ble pairing
nvs_flash_erase();
#endif
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
Bluefruit.begin();
DEBUG_MSG("Clearing bluetooth bonds!\n");
bond_print_list(BLE_GAP_ROLE_PERIPH);
@@ -248,7 +248,7 @@ void NodeDB::init()
strncpy(myNodeInfo.firmware_version, optstr(APP_VERSION), sizeof(myNodeInfo.firmware_version));
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
Preferences preferences;
preferences.begin("meshtastic", false);
myNodeInfo.reboot_count = preferences.getUInt("rebootCounter", 0);
@@ -339,11 +339,11 @@ void NodeDB::loadFromDisk()
if (devicestate.version < DEVICESTATE_MIN_VER) {
DEBUG_MSG("Warn: devicestate %d is old, discarding\n", devicestate.version);
installDefaultDeviceState();
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// This will erase what's in NVS including ssl keys, persistant variables and ble pairing
nvs_flash_erase();
#endif
-#ifdef NRF52_SERIES
+#ifdef ARCH_NRF52
Bluefruit.begin();
DEBUG_MSG("Clearing bluetooth bonds!\n");
bond_print_list(BLE_GAP_ROLE_PERIPH);
@@ -669,7 +669,7 @@ void recordCriticalError(CriticalErrorCode code, uint32_t address, const char *f
myNodeInfo.error_count++;
// Currently portuino is mostly used for simulation. Make sue the user notices something really bad happend
-#ifdef PORTDUINO
+#ifdef ARCH_PORTDUINO
DEBUG_MSG("A critical failure occurred, portduino is exiting...");
exit(2);
#endif
diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp
index a7cadf2ad..633a8dd56 100644
--- a/src/mesh/RadioLibInterface.cpp
+++ b/src/mesh/RadioLibInterface.cpp
@@ -11,7 +11,7 @@
// FIXME, we default to 4MHz SPI, SPI mode 0, check if the datasheet says it can really do that
static SPISettings spiSettings(4000000, MSBFIRST, SPI_MODE0);
-#ifdef PORTDUINO
+#ifdef ARCH_PORTDUINO
void LockingModule::SPItransfer(uint8_t cmd, uint8_t reg, uint8_t *dataOut, uint8_t *dataIn, uint8_t numBytes)
{
@@ -45,7 +45,7 @@ RadioLibInterface::RadioLibInterface(RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq
instance = this;
}
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// ESP32 doesn't use that flag
#define YIELD_FROM_ISR(x) portYIELD_FROM_ISR()
#else
@@ -96,7 +96,7 @@ bool RadioLibInterface::canSendImmediately()
if (busyTx && (millis() - lastTxStart > 60000)) {
DEBUG_MSG("Hardware Failure! busyTx for more than 60s\n");
RECORD_CRITICALERROR(CriticalErrorCode_TransmitFailed);
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
if (busyTx && (millis() - lastTxStart > 65000)) // After 5s more, reboot
ESP.restart();
#endif
diff --git a/src/mesh/RadioLibInterface.h b/src/mesh/RadioLibInterface.h
index 08aa84811..fbad830cd 100644
--- a/src/mesh/RadioLibInterface.h
+++ b/src/mesh/RadioLibInterface.h
@@ -41,7 +41,7 @@ class LockingModule : public Module
{
}
-#ifdef PORTDUINO
+#ifdef ARCH_PORTDUINO
void SPItransfer(uint8_t cmd, uint8_t reg, uint8_t *dataOut, uint8_t *dataIn, uint8_t numBytes) override;
#else
void SPIbeginTransaction() override;
diff --git a/src/mesh/ReliableRouter.cpp b/src/mesh/ReliableRouter.cpp
index a23adfa7d..9a65823ec 100644
--- a/src/mesh/ReliableRouter.cpp
+++ b/src/mesh/ReliableRouter.cpp
@@ -16,7 +16,7 @@ ErrorCode ReliableRouter::send(MeshPacket *p)
// If someone asks for acks on broadcast, we need the hop limit to be at least one, so that first node that receives our
// message will rebroadcast. But asking for hop_limit 0 in that context means the client app has no preference on hop
// counts and we want this message to get through the whole mesh, so use the default.
- if (p->to == NODENUM_BROADCAST && p->hop_limit == 0) {
+ if (p->hop_limit == 0) {
if (config.lora.hop_limit && config.lora.hop_limit <= HOP_MAX) {
p->hop_limit = (config.lora.hop_limit >= HOP_MAX) ? HOP_MAX : config.lora.hop_limit;
} else {
@@ -34,7 +34,7 @@ ErrorCode ReliableRouter::send(MeshPacket *p)
bool ReliableRouter::shouldFilterReceived(MeshPacket *p)
{
// Note: do not use getFrom() here, because we want to ignore messages sent from phone
- if (p->to == NODENUM_BROADCAST && p->from == getNodeNum()) {
+ if (p->from == getNodeNum()) {
printPacket("Rx someone rebroadcasting for us", p);
// We are seeing someone rebroadcast one of our broadcast attempts.
@@ -231,4 +231,4 @@ void ReliableRouter::setNextTx(PendingPacket *pending)
DEBUG_MSG("Setting next retransmission in %u msecs: ", d);
printPacket("", pending->packet);
setReceivedMessage(); // Run ASAP, so we can figure out our correct sleep time
-}
\ No newline at end of file
+}
diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp
index d7dd7afcb..f926c5c69 100644
--- a/src/mesh/Router.cpp
+++ b/src/mesh/Router.cpp
@@ -11,7 +11,7 @@ extern "C" {
#include "mesh/compression/unishox2.h"
}
-#if defined(HAS_WIFI) || defined(PORTDUINO)
+#if HAS_WIFI
#include "mqtt/MQTT.h"
#endif
@@ -213,7 +213,7 @@ ErrorCode Router::send(MeshPacket *p)
if (p->which_payloadVariant == MeshPacket_decoded_tag) {
ChannelIndex chIndex = p->channel; // keep as a local because we are about to change it
-#if defined(HAS_WIFI) || defined(PORTDUINO)
+#if HAS_WIFI
// check if we should send decrypted packets to mqtt
// truth table:
@@ -244,7 +244,7 @@ ErrorCode Router::send(MeshPacket *p)
return encodeResult; // FIXME - this isn't a valid ErrorCode
}
-#if defined(HAS_WIFI) || defined(PORTDUINO)
+#if HAS_WIFI
// the packet is now encrypted.
// check if we should send encrypted packets to mqtt
if (mqtt && shouldActuallyEncrypt)
diff --git a/src/mesh/generated/telemetry.pb.h b/src/mesh/generated/telemetry.pb.h
index d77c9ae49..9a75230dd 100644
--- a/src/mesh/generated/telemetry.pb.h
+++ b/src/mesh/generated/telemetry.pb.h
@@ -23,7 +23,9 @@ typedef enum _TelemetrySensorType {
/* Moderate accuracy current and voltage */
TelemetrySensorType_INA260 = 4,
/* Moderate accuracy current and voltage */
- TelemetrySensorType_INA219 = 5
+ TelemetrySensorType_INA219 = 5,
+ /* High accuracy temperature and pressure */
+ TelemetrySensorType_BMP280 = 6
} TelemetrySensorType;
/* Struct definitions */
@@ -75,8 +77,8 @@ typedef struct _Telemetry {
/* Helper constants for enums */
#define _TelemetrySensorType_MIN TelemetrySensorType_NotSet
-#define _TelemetrySensorType_MAX TelemetrySensorType_INA219
-#define _TelemetrySensorType_ARRAYSIZE ((TelemetrySensorType)(TelemetrySensorType_INA219+1))
+#define _TelemetrySensorType_MAX TelemetrySensorType_BMP280
+#define _TelemetrySensorType_ARRAYSIZE ((TelemetrySensorType)(TelemetrySensorType_BMP280+1))
#ifdef __cplusplus
diff --git a/src/mesh/http/ContentHandler.cpp b/src/mesh/http/ContentHandler.cpp
index bf6c79742..ea39775a5 100644
--- a/src/mesh/http/ContentHandler.cpp
+++ b/src/mesh/http/ContentHandler.cpp
@@ -14,7 +14,7 @@
#include
#include
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "esp_task_wdt.h"
#endif
@@ -787,7 +787,7 @@ void handleBlinkLED(HTTPRequest *req, HTTPResponse *res)
count = count - 1;
}
} else {
-#ifndef NO_SCREEN
+#if HAS_SCREEN
screen->blink();
#endif
}
diff --git a/src/mesh/http/WebServer.cpp b/src/mesh/http/WebServer.cpp
index 271adc6c2..48e084ed2 100644
--- a/src/mesh/http/WebServer.cpp
+++ b/src/mesh/http/WebServer.cpp
@@ -11,7 +11,7 @@
#include
#include
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "esp_task_wdt.h"
#endif
@@ -152,7 +152,7 @@ void createSSLCert()
yield();
esp_task_wdt_reset();
-#ifndef NO_SCREEN
+#if HAS_SCREEN
if (millis() / 1000 >= 3) {
screen->setSSLFrames();
}
diff --git a/src/mesh/http/WiFiAPClient.h b/src/mesh/http/WiFiAPClient.h
index fa9be8feb..2c6bc912c 100644
--- a/src/mesh/http/WiFiAPClient.h
+++ b/src/mesh/http/WiFiAPClient.h
@@ -4,7 +4,7 @@
#include
#include
-#ifdef HAS_WIFI
+#ifdef ARCH_ESP32
#include
#include
#endif
diff --git a/src/mesh/mesh-pb-constants.cpp b/src/mesh/mesh-pb-constants.cpp
index 5e901c799..6b9fc4986 100644
--- a/src/mesh/mesh-pb-constants.cpp
+++ b/src/mesh/mesh-pb-constants.cpp
@@ -32,6 +32,7 @@ bool pb_decode_from_bytes(const uint8_t *srcbuf, size_t srcbufsize, const pb_msg
}
}
+#ifdef FSCom
/// Read from an Arduino File
bool readcb(pb_istream_t *stream, uint8_t *buf, size_t count)
{
@@ -59,6 +60,7 @@ bool writecb(pb_ostream_t *stream, const uint8_t *buf, size_t count)
// DEBUG_MSG("writing %d bytes to protobuf file\n", count);
return file->write(buf, count) == count;
}
+#endif
bool is_in_helper(uint32_t n, const uint32_t *array, pb_size_t count)
{
diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp
index 6d25fd367..f969d5506 100644
--- a/src/modules/AdminModule.cpp
+++ b/src/modules/AdminModule.cpp
@@ -6,7 +6,7 @@
#include "configuration.h"
#include "main.h"
-#ifdef PORTDUINO
+#ifdef ARCH_PORTDUINO
#include "unistd.h"
#endif
@@ -110,7 +110,7 @@ bool AdminModule::handleReceivedProtobuf(const MeshPacket &mp, AdminMessage *r)
break;
}
-#ifdef PORTDUINO
+#ifdef ARCH_PORTDUINO
case AdminMessage_exit_simulator_tag:
DEBUG_MSG("Exiting simulator\n");
_exit(0);
diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp
index 6d7064c25..6959093e0 100644
--- a/src/modules/CannedMessageModule.cpp
+++ b/src/modules/CannedMessageModule.cpp
@@ -1,5 +1,5 @@
#include "configuration.h"
-#ifndef NO_SCREEN
+#if HAS_SCREEN
#include "CannedMessageModule.h"
#include "FSCommon.h"
#include "MeshService.h"
diff --git a/src/modules/CannedMessageModule.h b/src/modules/CannedMessageModule.h
index f393882d5..f703ba516 100644
--- a/src/modules/CannedMessageModule.h
+++ b/src/modules/CannedMessageModule.h
@@ -1,6 +1,5 @@
#pragma once
-#ifdef NO_SCREEN
-#else
+#if HAS_SCREEN
#include "ProtobufModule.h"
#include "input/InputBroker.h"
diff --git a/src/modules/ExternalNotificationModule.cpp b/src/modules/ExternalNotificationModule.cpp
index b9e946823..a49ba6f39 100644
--- a/src/modules/ExternalNotificationModule.cpp
+++ b/src/modules/ExternalNotificationModule.cpp
@@ -116,7 +116,7 @@ ExternalNotificationModule::ExternalNotificationModule()
// restrict to the admin channel for rx
boundChannel = Channels::gpioChannel;
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#ifdef EXT_NOTIFY_OUT
/*
@@ -154,7 +154,7 @@ ExternalNotificationModule::ExternalNotificationModule()
ProcessMessage ExternalNotificationModule::handleReceived(const MeshPacket &mp)
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#ifdef EXT_NOTIFY_OUT
if (moduleConfig.external_notification.enabled) {
diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp
index 2d308ca43..8fc7964ea 100644
--- a/src/modules/Modules.cpp
+++ b/src/modules/Modules.cpp
@@ -14,10 +14,10 @@
#include "modules/RoutingModule.h"
#include "modules/TextMessageModule.h"
#include "modules/Telemetry/DeviceTelemetry.h"
-#ifndef PORTDUINO
+#if HAS_TELEMETRY
#include "modules/Telemetry/EnvironmentTelemetry.h"
#endif
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "modules/esp32/RangeTestModule.h"
#include "modules/esp32/SerialModule.h"
#include "modules/esp32/StoreForwardModule.h"
@@ -28,7 +28,9 @@
*/
void setupModules()
{
+#if HAS_BUTTON
inputBroker = new InputBroker();
+#endif
adminModule = new AdminModule();
nodeInfoModule = new NodeInfoModule();
positionModule = new PositionModule();
@@ -39,6 +41,7 @@ void setupModules()
new RemoteHardwareModule();
new ReplyModule();
+#if HAS_BUTTON
rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1();
rotaryEncoderInterruptImpl1->init();
upDownInterruptImpl1 = new UpDownInterruptImpl1();
@@ -47,14 +50,15 @@ void setupModules()
cardKbI2cImpl->init();
facesKbI2cImpl = new FacesKbI2cImpl();
facesKbI2cImpl->init();
-#ifndef NO_SCREEN
+#endif
+#if HAS_SCREEN
cannedMessageModule = new CannedMessageModule();
#endif
-#ifndef PORTDUINO
+#if HAS_TELEMETRY
new DeviceTelemetryModule();
new EnvironmentTelemetryModule();
#endif
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// Only run on an esp32 based device.
/*
diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp
index b58441bf7..868f68d34 100644
--- a/src/modules/Telemetry/DeviceTelemetry.cpp
+++ b/src/modules/Telemetry/DeviceTelemetry.cpp
@@ -12,7 +12,7 @@
int32_t DeviceTelemetryModule::runOnce()
{
-#ifndef PORTDUINO
+#ifndef ARCH_PORTDUINO
if (firstTime) {
// This is the first time the OSThread library has called this function, so do some setup
firstTime = 0;
@@ -72,7 +72,7 @@ bool DeviceTelemetryModule::sendOurTelemetry(NodeNum dest, bool wantReplies)
lastMeasurementPacket = packetPool.allocCopy(*p);
DEBUG_MSG("Device Telemetry: Sending packet to mesh\n");
- service.sendToMesh(p);
+ service.sendToMesh(p, RX_SRC_LOCAL, true);
nodeDB.updateTelemetry(nodeDB.getNodeNum(), t, RX_SRC_LOCAL);
return true;
}
diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp
index 1fcc94723..14d9c2243 100644
--- a/src/modules/Telemetry/EnvironmentTelemetry.cpp
+++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp
@@ -11,12 +11,14 @@
#include
// Sensors
+#include "Sensor/BMP280Sensor.h"
#include "Sensor/BME280Sensor.h"
#include "Sensor/BME680Sensor.h"
#include "Sensor/MCP9808Sensor.h"
#include "Sensor/INA260Sensor.h"
#include "Sensor/INA219Sensor.h"
+BMP280Sensor bmp280Sensor;
BME280Sensor bme280Sensor;
BME680Sensor bme680Sensor;
MCP9808Sensor mcp9808Sensor;
@@ -26,7 +28,7 @@ INA219Sensor ina219Sensor;
#define FAILED_STATE_SENSOR_READ_MULTIPLIER 10
#define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true
-#ifdef HAS_EINK
+#ifdef USE_EINK
// The screen is bigger so use bigger fonts
#define FONT_SMALL ArialMT_Plain_16
#define FONT_MEDIUM ArialMT_Plain_24
@@ -44,7 +46,7 @@ INA219Sensor ina219Sensor;
int32_t EnvironmentTelemetryModule::runOnce()
{
-#ifndef PORTDUINO
+#ifndef ARCH_PORTDUINO
int32_t result = INT32_MAX;
/*
Uncomment the preferences below if you want to use the module
@@ -69,10 +71,12 @@ int32_t EnvironmentTelemetryModule::runOnce()
DEBUG_MSG("Environment Telemetry: Initializing\n");
// it's possible to have this module enabled, only for displaying values on the screen.
// therefore, we should only enable the sensor loop if measurement is also enabled
- if (bme680Sensor.hasSensor())
- result = bme680Sensor.runOnce();
+ if (bmp280Sensor.hasSensor())
+ result = bmp280Sensor.runOnce();
if (bme280Sensor.hasSensor())
result = bme280Sensor.runOnce();
+ if (bme680Sensor.hasSensor())
+ result = bme680Sensor.runOnce();
if (mcp9808Sensor.hasSensor())
result = mcp9808Sensor.runOnce();
if (ina260Sensor.hasSensor())
@@ -196,6 +200,8 @@ bool EnvironmentTelemetryModule::sendOurTelemetry(NodeNum dest, bool wantReplies
DEBUG_MSG("-----------------------------------------\n");
DEBUG_MSG("Environment Telemetry: Read data\n");
+ if (bmp280Sensor.hasSensor())
+ bmp280Sensor.getMetrics(&m);
if (bme280Sensor.hasSensor())
bme280Sensor.getMetrics(&m);
if (bme680Sensor.hasSensor())
@@ -223,6 +229,6 @@ bool EnvironmentTelemetryModule::sendOurTelemetry(NodeNum dest, bool wantReplies
lastMeasurementPacket = packetPool.allocCopy(*p);
DEBUG_MSG("Environment Telemetry: Sending packet to mesh");
- service.sendToMesh(p);
+ service.sendToMesh(p, RX_SRC_LOCAL, true);
return true;
}
diff --git a/src/modules/Telemetry/EnvironmentTelemetry.h b/src/modules/Telemetry/EnvironmentTelemetry.h
index e6e526e3f..e1a612288 100644
--- a/src/modules/Telemetry/EnvironmentTelemetry.h
+++ b/src/modules/Telemetry/EnvironmentTelemetry.h
@@ -15,7 +15,7 @@ class EnvironmentTelemetryModule : private concurrency::OSThread, public Protobu
lastMeasurementPacket = nullptr;
}
virtual bool wantUIFrame() override;
-#ifdef NO_SCREEN
+#if !HAS_SCREEN
void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y);
#else
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) override;
diff --git a/src/modules/Telemetry/Sensor/BMP280Sensor.cpp b/src/modules/Telemetry/Sensor/BMP280Sensor.cpp
new file mode 100644
index 000000000..1a41f9236
--- /dev/null
+++ b/src/modules/Telemetry/Sensor/BMP280Sensor.cpp
@@ -0,0 +1,30 @@
+#include "../mesh/generated/telemetry.pb.h"
+#include "configuration.h"
+#include "TelemetrySensor.h"
+#include "BMP280Sensor.h"
+#include
+#include
+
+BMP280Sensor::BMP280Sensor() :
+ TelemetrySensor(TelemetrySensorType_BME280, "BMP280")
+{
+}
+
+int32_t BMP280Sensor::runOnce() {
+ DEBUG_MSG("Init sensor: %s\n", sensorName);
+ if (!hasSensor()) {
+ return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS;
+ }
+ status = bmp280.begin(nodeTelemetrySensorsMap[sensorType]);
+ return initI2CSensor();
+}
+
+void BMP280Sensor::setup() { }
+
+bool BMP280Sensor::getMetrics(Telemetry *measurement) {
+ DEBUG_MSG("BMP280Sensor::getMetrics\n");
+ measurement->variant.environment_metrics.temperature = bmp280.readTemperature();
+ measurement->variant.environment_metrics.barometric_pressure = bmp280.readPressure() / 100.0F;
+
+ return true;
+}
\ No newline at end of file
diff --git a/src/modules/Telemetry/Sensor/BMP280Sensor.h b/src/modules/Telemetry/Sensor/BMP280Sensor.h
new file mode 100644
index 000000000..3525f3fa3
--- /dev/null
+++ b/src/modules/Telemetry/Sensor/BMP280Sensor.h
@@ -0,0 +1,16 @@
+#include "../mesh/generated/telemetry.pb.h"
+#include "TelemetrySensor.h"
+#include
+
+class BMP280Sensor : virtual public TelemetrySensor {
+private:
+ Adafruit_BMP280 bmp280;
+
+protected:
+ virtual void setup() override;
+
+public:
+ BMP280Sensor();
+ virtual int32_t runOnce() override;
+ virtual bool getMetrics(Telemetry *measurement) override;
+};
\ No newline at end of file
diff --git a/src/modules/esp32/RangeTestModule.cpp b/src/modules/esp32/RangeTestModule.cpp
index 1a871e81f..c9713d94e 100644
--- a/src/modules/esp32/RangeTestModule.cpp
+++ b/src/modules/esp32/RangeTestModule.cpp
@@ -29,7 +29,7 @@ uint32_t packetSequence = 0;
int32_t RangeTestModule::runOnce()
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
/*
Uncomment the preferences below if you want to use the module
@@ -129,7 +129,7 @@ void RangeTestModuleRadio::sendPayload(NodeNum dest, bool wantReplies)
ProcessMessage RangeTestModuleRadio::handleReceived(const MeshPacket &mp)
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
if (moduleConfig.range_test.enabled) {
diff --git a/src/modules/esp32/SerialModule.cpp b/src/modules/esp32/SerialModule.cpp
index f0bf1666c..b74f4c118 100644
--- a/src/modules/esp32/SerialModule.cpp
+++ b/src/modules/esp32/SerialModule.cpp
@@ -69,7 +69,7 @@ SerialModuleRadio::SerialModuleRadio() : SinglePortModule("SerialModuleRadio", P
int32_t SerialModule::runOnce()
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
/*
Uncomment the preferences below if you want to use the module
@@ -209,7 +209,7 @@ void SerialModuleRadio::sendPayload(NodeNum dest, bool wantReplies)
ProcessMessage SerialModuleRadio::handleReceived(const MeshPacket &mp)
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
if (moduleConfig.serial.enabled) {
diff --git a/src/modules/esp32/StoreForwardModule.cpp b/src/modules/esp32/StoreForwardModule.cpp
index 90d82646d..4c4122e82 100644
--- a/src/modules/esp32/StoreForwardModule.cpp
+++ b/src/modules/esp32/StoreForwardModule.cpp
@@ -17,7 +17,7 @@ StoreForwardModule *storeForwardModule;
int32_t StoreForwardModule::runOnce()
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
if (moduleConfig.store_forward.enabled) {
@@ -241,7 +241,7 @@ void StoreForwardModule::sendMessage(NodeNum dest, char *str)
ProcessMessage StoreForwardModule::handleReceived(const MeshPacket &mp)
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
if (moduleConfig.store_forward.enabled) {
DEBUG_MSG("--- S&F Received something\n");
@@ -381,7 +381,7 @@ StoreForwardModule::StoreForwardModule()
: SinglePortModule("StoreForwardModule", PortNum_TEXT_MESSAGE_APP), concurrency::OSThread("StoreForwardModule")
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
isPromiscuous = true; // Brown chicken brown cow
diff --git a/src/nimble/BluetoothUtil.cpp b/src/nimble/BluetoothUtil.cpp
index fc4501ccb..021358453 100644
--- a/src/nimble/BluetoothUtil.cpp
+++ b/src/nimble/BluetoothUtil.cpp
@@ -15,7 +15,7 @@
#include "sleep.h"
#include
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "mesh/http/WiFiAPClient.h"
#include
#endif
@@ -508,7 +508,7 @@ void disablePin()
// This should go somewhere else.
void clearNVS()
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
// As soon as the LED flashing from double click is done, immediately do a tripple click to
// erase nvs memory.
diff --git a/src/nrf52/architecture.h b/src/nrf52/architecture.h
new file mode 100644
index 000000000..8a84cde8c
--- /dev/null
+++ b/src/nrf52/architecture.h
@@ -0,0 +1,91 @@
+#pragma once
+
+#define ARCH_NRF52
+
+//
+// defaults for NRF52 architecture
+//
+
+#ifndef HAS_SCREEN
+ #define HAS_SCREEN 1
+#endif
+#ifndef HAS_WIRE
+ #define HAS_WIRE 1
+#endif
+#ifndef HAS_GPS
+ #define HAS_GPS 1
+#endif
+#ifndef HAS_BUTTON
+ #define HAS_BUTTON 1
+#endif
+#ifndef HAS_TELEMETRY
+ #define HAS_TELEMETRY 1
+#endif
+#ifndef HAS_RADIO
+ #define HAS_RADIO 1
+#endif
+
+//
+// set HW_VENDOR
+//
+
+// This string must exactly match the case used in release file names or the android updater won't work
+#ifdef ARDUINO_NRF52840_PCA10056
+ #define HW_VENDOR HardwareModel_NRF52840DK
+#elif defined(ARDUINO_NRF52840_PPR)
+ #define HW_VENDOR HardwareModel_PPR
+#elif defined(RAK4630)
+ #define HW_VENDOR HardwareModel_RAK4631
+#elif defined(TTGO_T_ECHO)
+ #define HW_VENDOR HardwareModel_T_ECHO
+#elif defined(NORDIC_PCA10059)
+ #define HW_VENDOR HardwareModel_NRF52840_PCA10059
+#else
+ #define HW_VENDOR HardwareModel_NRF52_UNKNOWN
+#endif
+
+//
+// Standard definitions for NRF52 targets
+//
+
+#ifdef ARDUINO_NRF52840_PCA10056
+
+// This board uses 0 to be mean LED on
+#undef LED_INVERTED
+#define LED_INVERTED 1
+
+#endif
+
+#ifndef TTGO_T_ECHO
+#define GPS_UBLOX
+#endif
+
+#define LED_PIN PIN_LED1 // LED1 on nrf52840-DK
+
+#ifdef PIN_BUTTON1
+#define BUTTON_PIN PIN_BUTTON1
+#endif
+
+#ifdef PIN_BUTTON2
+#define BUTTON_PIN_ALT PIN_BUTTON2
+#endif
+
+#ifdef PIN_BUTTON_TOUCH
+#define BUTTON_PIN_TOUCH PIN_BUTTON_TOUCH
+#endif
+
+// Always include the SEGGER code on NRF52 - because useful for debugging
+#include "SEGGER_RTT.h"
+
+// The channel we send stdout data to
+#define SEGGER_STDOUT_CH 0
+
+// Debug printing to segger console
+#define SEGGER_MSG(...) SEGGER_RTT_printf(SEGGER_STDOUT_CH, __VA_ARGS__)
+
+// If we are not on a NRF52840 (which has built in USB-ACM serial support) and we don't have serial pins hooked up, then we MUST
+// use SEGGER for debug output
+#if !defined(PIN_SERIAL_RX) && !defined(NRF52840_XXAA)
+// No serial ports on this board - ONLY use segger in memory console
+#define USE_SEGGER
+#endif
diff --git a/src/nrf52/main-nrf52.cpp b/src/nrf52/main-nrf52.cpp
index 90ab0113f..668565650 100644
--- a/src/nrf52/main-nrf52.cpp
+++ b/src/nrf52/main-nrf52.cpp
@@ -161,7 +161,7 @@ void cpuDeepSleep(uint64_t msecToWake)
{
// FIXME, configure RTC or button press to wake us
// FIXME, power down SPI, I2C, RAMs
-#ifndef NO_WIRE
+#if HAS_WIRE
Wire.end();
#endif
SPI.end();
diff --git a/src/portduino/architecture.h b/src/portduino/architecture.h
new file mode 100644
index 000000000..1b77afaa6
--- /dev/null
+++ b/src/portduino/architecture.h
@@ -0,0 +1,16 @@
+#pragma once
+
+#define ARCH_PORTDUINO
+
+//
+// defaults for NRF52 architecture
+//
+
+//
+// set HW_VENDOR
+//
+
+#define HW_VENDOR HardwareModel_PORTDUINO
+
+#define HAS_RTC 1
+#define HAS_WIFI 1
diff --git a/src/shutdown.h b/src/shutdown.h
index 718ed0e0b..4c82b16c4 100644
--- a/src/shutdown.h
+++ b/src/shutdown.h
@@ -8,16 +8,16 @@ void powerCommandsCheck()
{
if (rebootAtMsec && millis() > rebootAtMsec) {
DEBUG_MSG("Rebooting\n");
-#ifndef NO_ESP32
+#if defined(ARCH_ESP32)
ESP.restart();
-#elif NRF52_SERIES
+#elif defined(ARCH_NRF52)
NVIC_SystemReset();
#else
DEBUG_MSG("FIXME implement reboot for this platform");
#endif
}
-#if NRF52_SERIES
+#if defined(ARCH_NRF52)
if (shutdownAtMsec) {
screen->startShutdownScreen();
playBeep();
@@ -40,7 +40,7 @@ void powerCommandsCheck()
playShutdownMelody();
power->shutdown();
}
-#elif NRF52_SERIES
+#elif defined(ARCH_NRF52)
playShutdownMelody();
power->shutdown();
#else
diff --git a/src/sleep.cpp b/src/sleep.cpp
index 849ec33a1..e02bb8b35 100644
--- a/src/sleep.cpp
+++ b/src/sleep.cpp
@@ -8,7 +8,7 @@
#include "main.h"
#include "target_specific.h"
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "esp32/pm.h"
#include "esp_pm.h"
#include "mesh/http/WiFiAPClient.h"
@@ -48,7 +48,7 @@ RTC_DATA_ATTR int bootCount = 0;
*/
void setCPUFast(bool on)
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
if (isWifiAvailable()) {
/*
@@ -101,7 +101,7 @@ void setGPSPower(bool on)
// Perform power on init that we do on each wake from deep sleep
void initDeepSleep()
{
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
bootCount++;
wakeCause = esp_sleep_get_wakeup_cause();
/*
@@ -207,7 +207,7 @@ void doDeepSleep(uint64_t msecToWake)
cpuDeepSleep(msecToWake);
}
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
/**
* enter light sleep (preserves ram but stops everything about CPU).
*
diff --git a/src/sleep.h b/src/sleep.h
index 6bcb23352..7f0592af4 100644
--- a/src/sleep.h
+++ b/src/sleep.h
@@ -6,7 +6,7 @@
void doDeepSleep(uint64_t msecToWake), cpuDeepSleep(uint64_t msecToWake);
-#ifndef NO_ESP32
+#ifdef ARCH_ESP32
#include "esp_sleep.h"
esp_sleep_wakeup_cause_t doLightSleep(uint64_t msecToWake);
diff --git a/src/wifi-stubs.cpp b/src/wifi-stubs.cpp
index 87470c528..faf58b620 100644
--- a/src/wifi-stubs.cpp
+++ b/src/wifi-stubs.cpp
@@ -1,7 +1,7 @@
//#include "mesh/wifi/WebServer.h"
#include "configuration.h"
-#ifdef NO_ESP32
+#ifndef ARCH_ESP32
//#include "mesh/wifi/WiFiAPClient.h"
diff --git a/variants/Dongle_nRF52840-pca10059-v1/variant.h b/variants/Dongle_nRF52840-pca10059-v1/variant.h
index 32ab073e8..c846573aa 100644
--- a/variants/Dongle_nRF52840-pca10059-v1/variant.h
+++ b/variants/Dongle_nRF52840-pca10059-v1/variant.h
@@ -123,7 +123,7 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define PIN_EINK_SCLK (9) // EPD_SCLK
#define PIN_EINK_MOSI (10) // EPD_MOSI
-#define HAS_EINK
+#define USE_EINK
/*
* Wire Interfaces
diff --git a/variants/lora_isp4520/variant.h b/variants/lora_isp4520/variant.h
index 946a6cd3d..1d1ad8b97 100644
--- a/variants/lora_isp4520/variant.h
+++ b/variants/lora_isp4520/variant.h
@@ -90,7 +90,4 @@
#define SX126X_E22 // Not really an E22 but this board clones using DIO3 for tcxo control
-#define NO_WIRE
-#define NO_GPS
-#define NO_SCREEN
#endif
diff --git a/variants/m5stack_coreink/variant.h b/variants/m5stack_coreink/variant.h
index ff9eda6f4..ef490415c 100644
--- a/variants/m5stack_coreink/variant.h
+++ b/variants/m5stack_coreink/variant.h
@@ -32,12 +32,11 @@
#define LORA_DIO1 RADIOLIB_NC
#define LORA_DIO2 RADIOLIB_NC
-#define NO_GPS
// This board has no GPS for now
#undef GPS_RX_PIN
#undef GPS_TX_PIN
-#define HAS_EINK
+#define USE_EINK
//https://docs.m5stack.com/en/core/coreink
//https://m5stack.oss-cn-shenzhen.aliyuncs.com/resource/docs/schematic/Core/coreink/coreink_sch.pdf
#define PIN_EINK_EN -1
@@ -47,3 +46,5 @@
#define PIN_EINK_RES -1 // Connected to GPIO0 but no needed !!!! maybe causing issue ?
#define PIN_EINK_SCLK 18 // EPD_SCLK
#define PIN_EINK_MOSI 23 // EPD_MOSI
+
+#define HAS_RTC 1
diff --git a/variants/portduino/platformio.ini b/variants/portduino/platformio.ini
index 0030ae4b6..1a9dda202 100644
--- a/variants/portduino/platformio.ini
+++ b/variants/portduino/platformio.ini
@@ -5,6 +5,7 @@ build_src_filter =
-
-
-
+ -
-
-
-
@@ -14,10 +15,11 @@ lib_deps =
${networking_base.lib_deps}
rweather/Crypto
https://github.com/meshtastic/RadioLib.git#5582ac30578ff3f53f20630a00b2a8a4b8f92c74
+build_flags = ${arduino_base.build_flags} -Isrc/portduino
[env:native]
platform = https://github.com/meshtastic/platform-native.git
-build_flags = ${arduino_base.build_flags} -O0 -I variants/portduino
+build_flags = ${portduino_base.build_flags} -O0 -I variants/portduino
framework = arduino
board = cross_platform
lib_deps = ${portduino_base.lib_deps}
@@ -26,8 +28,8 @@ build_src_filter = ${portduino_base.build_src_filter}
; The Portduino based sim environment on top of a linux OS and touching linux hardware devices
[env:linux]
platform = https://github.com/meshtastic/platform-native.git
-build_flags = ${arduino_base.build_flags} -O0 -lgpiod -I variants/portduino
+build_flags = ${portduino_base.build_flags} -O0 -lgpiod -I variants/portduino
framework = arduino
board = linux_hardware
lib_deps = ${portduino_base.lib_deps}
-build_src_filter = ${portduino_base.build_src_filter}
\ No newline at end of file
+build_src_filter = ${portduino_base.build_src_filter}
diff --git a/variants/portduino/variant.h b/variants/portduino/variant.h
index ea827868a..328afaf19 100644
--- a/variants/portduino/variant.h
+++ b/variants/portduino/variant.h
@@ -1,5 +1,3 @@
-#define USE_SIM_RADIO
-
// Pine64 uses a common pinout for their SX1262 vs RF95 modules - both can be enabled and we will probe at runtime for RF95 and if
// not found then probe for SX1262. Currently the RF95 code is disabled because I think the RF95 module won't need to ship.
// #define USE_RF95
@@ -37,4 +35,4 @@
#define RADIOLIB_SX127X_REG_TCXO SX127X_REG_TCXO
#define RADIOLIB_SX127X_REG_MODEM_STAT SX127X_REG_MODEM_STAT
#define RADIOLIB_SX127X_SYNC_WORD SX127X_SYNC_WORD
-#define RADIOLIB_SX127X_MASK_IRQ_FLAG_VALID_HEADER SX127X_MASK_IRQ_FLAG_VALID_HEADER
\ No newline at end of file
+#define RADIOLIB_SX127X_MASK_IRQ_FLAG_VALID_HEADER SX127X_MASK_IRQ_FLAG_VALID_HEADER
diff --git a/variants/rak4631/variant.h b/variants/rak4631/variant.h
index f1e144324..3648b8510 100644
--- a/variants/rak4631/variant.h
+++ b/variants/rak4631/variant.h
@@ -139,7 +139,7 @@ static const uint8_t SCK = PIN_SPI_SCK;
// FIXME - I think this is actually just the board power enable - it enables power to the CPU also
//#define PIN_EINK_PWR_ON (-1)
-// #define HAS_EINK
+// #define USE_EINK
/*
* Wire Interfaces
@@ -224,6 +224,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define ADC_MULTIPLIER VBAT_DIVIDER_COMP //REAL_VBAT_MV_PER_LSB
#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x)
+#define HAS_RTC 1
+
#ifdef __cplusplus
}
#endif
diff --git a/variants/rak4631_epaper/variant.h b/variants/rak4631_epaper/variant.h
index 12f379d06..df68dac41 100644
--- a/variants/rak4631_epaper/variant.h
+++ b/variants/rak4631_epaper/variant.h
@@ -139,7 +139,7 @@ static const uint8_t SCK = PIN_SPI_SCK;
// FIXME - I think this is actually just the board power enable - it enables power to the CPU also
//#define PIN_EINK_PWR_ON (-1)
-#define HAS_EINK
+#define USE_EINK
/*
* Wire Interfaces
@@ -221,6 +221,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define ADC_MULTIPLIER VBAT_DIVIDER_COMP //REAL_VBAT_MV_PER_LSB
#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x)
+#define HAS_RTC 1
+
#ifdef __cplusplus
}
#endif
diff --git a/variants/t-echo/variant.h b/variants/t-echo/variant.h
index 094894c74..f74a19c9b 100644
--- a/variants/t-echo/variant.h
+++ b/variants/t-echo/variant.h
@@ -139,7 +139,6 @@ External serial flash WP25R1635FZUIL0
// #define LORA_DISABLE_SENDING // Define this to disable transmission for testing (power testing etc...)
// #undef SX126X_CS
-// #define USE_SIM_RADIO // define to not use the lora radio hardware at all
/*
* eink display pins
@@ -157,7 +156,7 @@ External serial flash WP25R1635FZUIL0
// FIXME - I think this is actually just the board power enable - it enables power to the CPU also
#define PIN_EINK_PWR_ON (0 + 12)
-#define HAS_EINK
+#define USE_EINK
// No screen wipes on eink
#define SCREEN_TRANSITION_MSECS 0
@@ -220,6 +219,8 @@ External serial flash WP25R1635FZUIL0
#define ADC_MULTIPLIER VBAT_DIVIDER_COMP
#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x)
+#define HAS_RTC 1
+
#ifdef __cplusplus
}
#endif
diff --git a/version.properties b/version.properties
index 3eb2c9ab4..e6f5a11df 100644
--- a/version.properties
+++ b/version.properties
@@ -1,4 +1,4 @@
[VERSION]
major = 1
minor = 3
-build = 27
+build = 28