Merge branch 'develop' into XEdDSA-merge

This commit is contained in:
Ben Meadors
2026-06-03 06:02:26 -05:00
committed by GitHub
71 changed files with 2005 additions and 2287 deletions

View File

@@ -0,0 +1,54 @@
{
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
["0x239A", "0x4405"],
["0x239A", "0x0029"],
["0x239A", "0x002A"],
["0x2886", "0x1667"]
],
"usb_product": "HT-n5262",
"mcu": "nrf52840",
"variant": "heltec_mesh_node_t1",
"variants_dir": "variants",
"bsp": {
"name": "adafruit"
},
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
},
"bootloader": {
"settings_addr": "0xFF000"
}
},
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"onboard_tools": ["jlink"],
"svd_path": "nrf52840.svd",
"openocd_target": "nrf52840-mdk-rs"
},
"frameworks": ["arduino"],
"name": "Heltec Mesh Node T1",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": ["jlink", "nrfjprog", "nrfutil", "stlink"],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
},
"url": "https://heltec.org",
"vendor": "Heltec"
}

View File

@@ -186,12 +186,16 @@ lib_deps =
https://github.com/sparkfun/SparkFun_MAX3010x_Sensor_Library/archive/refs/tags/v1.1.2.zip
# renovate: datasource=github-tags depName=SparkFun 9DoF IMU Breakout ICM 20948 packageName=sparkfun/SparkFun_ICM-20948_ArduinoLibrary
https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/archive/refs/tags/v1.3.2.zip
# renovate: datasource=github-tags depName=TDK InvenSense ICM42670P packageName=tdk-invn-oss/motion.arduino.ICM42670P
https://github.com/tdk-invn-oss/motion.arduino.ICM42670P/archive/refs/tags/1.0.8.zip
# renovate: datasource=github-tags depName=Adafruit LTR390 Library packageName=adafruit/Adafruit_LTR390
https://github.com/adafruit/Adafruit_LTR390/archive/refs/tags/1.1.2.zip
# renovate: datasource=github-tags depName=Adafruit PCT2075 packageName=adafruit/Adafruit_PCT2075
https://github.com/adafruit/Adafruit_PCT2075/archive/refs/tags/1.0.6.zip
# renovate: datasource=github-tags depName=DFRobot_BMM150 packageName=dfrobot/DFRobot_BMM150
https://github.com/DFRobot/DFRobot_BMM150/archive/refs/tags/V1.0.0.zip
# renovate: datasource=github-tags depName=SparkFun MMC5983MA Magnetometer packageName=sparkfun/SparkFun_MMC5983MA_Magnetometer_Arduino_Library
https://github.com/sparkfun/SparkFun_MMC5983MA_Magnetometer_Arduino_Library/archive/refs/tags/v1.1.4.zip
# renovate: datasource=github-tags depName=Adafruit_TSL2561 packageName=adafruit/Adafruit_TSL2561
https://github.com/adafruit/Adafruit_TSL2561/archive/refs/tags/1.1.3.zip
# renovate: datasource=github-tags depName=BH1750_WE packageName=wollewald/BH1750_WE
@@ -204,16 +208,10 @@ lib_deps =
https://github.com/adafruit/Adafruit_BMP3XX/archive/refs/tags/2.1.6.zip
# renovate: datasource=github-tags depName=Adafruit MAX1704X packageName=adafruit/Adafruit_MAX1704X
https://github.com/adafruit/Adafruit_MAX1704X/archive/refs/tags/1.0.3.zip
# renovate: datasource=github-tags depName=Adafruit SHTC3 packageName=adafruit/Adafruit_SHTC3
https://github.com/adafruit/Adafruit_SHTC3/archive/refs/tags/1.0.2.zip
# renovate: datasource=github-tags depName=Adafruit LPS2X packageName=adafruit/Adafruit_LPS2X
https://github.com/adafruit/Adafruit_LPS2X/archive/refs/tags/2.0.6.zip
# renovate: datasource=github-tags depName=Adafruit SHT31 packageName=adafruit/Adafruit_SHT31
https://github.com/adafruit/Adafruit_SHT31/archive/refs/tags/2.2.2.zip
# renovate: datasource=github-tags depName=Adafruit VEML7700 packageName=adafruit/Adafruit_VEML7700
https://github.com/adafruit/Adafruit_VEML7700/archive/refs/tags/2.1.6.zip
# renovate: datasource=github-tags depName=Adafruit SHT4x packageName=adafruit/Adafruit_SHT4X
https://github.com/adafruit/Adafruit_SHT4X/archive/refs/tags/1.0.5.zip
# renovate: datasource=github-tags depName=SparkFun Qwiic Scale NAU7802 packageName=sparkfun/SparkFun_Qwiic_Scale_NAU7802_Arduino_Library
https://github.com/sparkfun/SparkFun_Qwiic_Scale_NAU7802_Arduino_Library/archive/refs/tags/v1.0.6.zip
# renovate: datasource=custom.pio depName=ClosedCube OPT3001 packageName=closedcube/library/ClosedCube OPT3001

View File

@@ -152,7 +152,9 @@ extern "C" void logLegacy(const char *level, const char *fmt, ...);
// Default Bluetooth PIN
#define defaultBLEPin 123456
#if HAS_ETHERNET && defined(USE_CH390D)
#if HAS_ETHERNET && defined(USE_ARDUINO_ETHERNET)
#include <Ethernet.h> // arduino-libraries/Ethernet — supports W5500 auto-detect
#elif HAS_ETHERNET && defined(USE_CH390D)
#include <ESP32_CH390.h>
#elif HAS_ETHERNET && !defined(USE_WS5500)
#include <RAK13800_W5100S.h>

View File

@@ -31,6 +31,11 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#endif
#if __has_include("SensorRtcHelper.hpp")
#include "SensorRtcHelper.hpp"
// SensorLib defines isBitSet as a macro; undefine it here to avoid conflicts
// with the SparkFun MMC5983MA library, which has a class method of the same name.
#ifdef isBitSet
#undef isBitSet
#endif
#endif
/* Offer chance for variant-specific defines */
@@ -243,6 +248,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define QMI8658_ADDR 0x6B
#define QMC5883L_ADDR 0x0D
#define HMC5883L_ADDR 0x1E
#define MMC5983MA_ADDR 0x30
#define SHTC3_ADDR 0x70
#define LPS22HB_ADDR 0x5C
#define LPS22HB_ADDR_ALT 0x5D
@@ -292,6 +298,8 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define DA217_ADDR 0x26
#define BMI270_ADDR 0x68
#define BMI270_ADDR_ALT 0x69
#define ICM42607P_ADDR 0x68
#define ICM42607P_ADDR_ALT 0x69
// -----------------------------------------------------------------------------
// LED

View File

@@ -37,8 +37,15 @@ ScanI2C::FoundDevice ScanI2C::firstKeyboard() const
ScanI2C::FoundDevice ScanI2C::firstAccelerometer() const
{
ScanI2C::DeviceType types[] = {MPU6050, LIS3DH, BMA423, LSM6DS3, BMX160, STK8BAXX, ICM20948, QMA6100P, BMM150, BMI270};
return firstOfOrNONE(10, types);
ScanI2C::DeviceType types[] = {MPU6050, LIS3DH, BMA423, LSM6DS3, BMX160, STK8BAXX,
ICM20948, QMA6100P, BMM150, BMI270, ICM42607P};
return firstOfOrNONE(11, types);
}
ScanI2C::FoundDevice ScanI2C::firstMagnetometer() const
{
ScanI2C::DeviceType types[] = {MMC5983MA};
return firstOfOrNONE(1, types);
}
ScanI2C::FoundDevice ScanI2C::firstAQI() const

View File

@@ -41,6 +41,7 @@ class ScanI2C
QMI8658,
QMC5883L,
HMC5883L,
MMC5983MA,
PMSA003I,
QMA6100P,
MPU6050,
@@ -65,6 +66,7 @@ class ScanI2C
FT6336U,
STK8BAXX,
ICM20948,
ICM42607P,
SCD4X,
MAX30102,
TPS65233,
@@ -149,6 +151,8 @@ class ScanI2C
FoundDevice firstAccelerometer() const;
FoundDevice firstMagnetometer() const;
FoundDevice firstAQI() const;
FoundDevice firstRGBLED() const;

View File

@@ -179,8 +179,22 @@ String readSEN5xProductName(TwoWire *i2cBus, uint8_t address)
#endif
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
static uint8_t crcSHT2X(const uint8_t *data, uint8_t len)
{
uint8_t crc = 0;
for (uint8_t i = 0; i < len; i++) {
crc ^= data[i];
for (uint8_t bit = 0; bit < 8; bit++) {
crc = (crc & 0x80) ? (crc << 1) ^ 0x31 : crc << 1;
}
}
return crc;
}
bool detectSHT21SerialNumber(TwoWire *i2cBus, uint8_t address)
{
uint8_t serialA[8] = {0};
uint8_t serialB[6] = {0};
i2cBus->beginTransmission(address);
i2cBus->write(0xFA);
@@ -189,12 +203,13 @@ bool detectSHT21SerialNumber(TwoWire *i2cBus, uint8_t address)
if (i2cBus->endTransmission() != 0)
return false;
if (i2cBus->requestFrom(address, (uint8_t)8) != 8)
if (i2cBus->requestFrom(address, (uint8_t)sizeof(serialA)) != sizeof(serialA))
return false;
// Just flush the data
while (i2cBus->available() < 8) {
i2cBus->read();
for (uint8_t i = 0; i < sizeof(serialA); i++) {
if (!i2cBus->available())
return false;
serialA[i] = i2cBus->read();
}
i2cBus->beginTransmission(address);
@@ -204,16 +219,18 @@ bool detectSHT21SerialNumber(TwoWire *i2cBus, uint8_t address)
if (i2cBus->endTransmission() != 0)
return false;
if (i2cBus->requestFrom(address, (uint8_t)6) != 6)
if (i2cBus->requestFrom(address, (uint8_t)sizeof(serialB)) != sizeof(serialB))
return false;
// Just flush the data
while (i2cBus->available() < 6) {
i2cBus->read();
for (uint8_t i = 0; i < sizeof(serialB); i++) {
if (!i2cBus->available())
return false;
serialB[i] = i2cBus->read();
}
// Assume we detect the SHT21 if something came back from the request
return true;
return crcSHT2X(&serialA[0], 1) == serialA[1] && crcSHT2X(&serialA[2], 1) == serialA[3] &&
crcSHT2X(&serialA[4], 1) == serialA[5] && crcSHT2X(&serialA[6], 1) == serialA[7] &&
crcSHT2X(&serialB[0], 2) == serialB[2] && crcSHT2X(&serialB[3], 2) == serialB[5];
}
#endif
@@ -343,9 +360,6 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
SCAN_SIMPLE_CASE(ST7567_ADDRESS, SCREEN_ST7567, "ST7567", (uint8_t)addr.address);
#ifdef HAS_NCP5623
SCAN_SIMPLE_CASE(NCP5623_ADDR, NCP5623, "NCP5623", (uint8_t)addr.address);
#endif
#ifdef HAS_LP5562
SCAN_SIMPLE_CASE(LP5562_ADDR, LP5562, "LP5562", (uint8_t)addr.address);
#endif
case XPOWERS_AXP192_AXP2101_ADDRESS:
// Do we have the axp2101/192 or the TCA8418
@@ -583,6 +597,18 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
#else
SCAN_SIMPLE_CASE(PMSA003I_ADDR, PMSA003I, "PMSA003I", (uint8_t)addr.address)
#endif
case MMC5983MA_ADDR:
registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0x2F), 1);
if (registerValue == 0x30) {
type = MMC5983MA;
logFoundDevice("MMC5983MA", (uint8_t)addr.address);
#ifdef HAS_LP5562
} else {
type = LP5562;
logFoundDevice("LP5562", (uint8_t)addr.address);
#endif
}
break;
case BMA423_ADDR: // this can also be LIS3DH_ADDR_ALT
registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0x0F), 2);
if (registerValue == 0x3300 || registerValue == 0x3333) { // RAK4631 WisBlock has LIS3DH register at 0x3333
@@ -737,8 +763,8 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
}
break;
case ICM20948_ADDR: // same as BMX160_ADDR, BMI270_ADDR_ALT, and SEN5X_ADDR
case ICM20948_ADDR_ALT: // same as MPU6050_ADDR, BMI270_ADDR
case ICM20948_ADDR: // same as BMX160_ADDR, BMI270_ADDR_ALT, ICM42607P_ADDR_ALT, and SEN5X_ADDR
case ICM20948_ADDR_ALT: // same as MPU6050_ADDR, BMI270_ADDR, and ICM42607P_ADDR
registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0x00), 1);
#ifdef HAS_ICM20948
type = ICM20948;
@@ -758,6 +784,12 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
logFoundDevice("BMX160", (uint8_t)addr.address);
break;
} else {
registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0x75), 1); // WHO_AM_I
if (registerValue == 0x60) {
type = ICM42607P;
logFoundDevice("ICM-42607-P", (uint8_t)addr.address);
break;
}
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_AIR_QUALITY_SENSOR
String prod = "";
prod = readSEN5xProductName(i2cBus, addr.address);

View File

@@ -1458,7 +1458,8 @@ void TFTDisplay::sendCommand(uint8_t com)
digitalWrite(portduino_config.displayBacklight.pin, TFT_BACKLIGHT_ON);
#elif defined(HACKADAY_COMMUNICATOR)
tft->displayOn();
#elif !defined(RAK14014) && !defined(M5STACK) && !defined(UNPHONE) && !defined(HELTEC_MESH_NODE_T096)
#elif !defined(RAK14014) && !defined(M5STACK) && !defined(UNPHONE) && !defined(HELTEC_MESH_NODE_T096) && \
!defined(HELTEC_MESH_NODE_T1)
tft->wakeup();
tft->powerSaveOff();
#endif
@@ -1469,7 +1470,7 @@ void TFTDisplay::sendCommand(uint8_t com)
#ifdef UNPHONE
unphone.backlight(true); // using unPhone library
#endif
#if defined(RAK14014) || defined(HELTEC_MESH_NODE_T096)
#if defined(RAK14014) || defined(HELTEC_MESH_NODE_T096) || defined(HELTEC_MESH_NODE_T1)
#elif !defined(M5STACK) && !defined(ST7789_CS) && \
!defined(HACKADAY_COMMUNICATOR) // T-Deck gets brightness set in Screen.cpp in the handleSetOn function
tft->setBrightness(172);
@@ -1485,7 +1486,8 @@ void TFTDisplay::sendCommand(uint8_t com)
digitalWrite(portduino_config.displayBacklight.pin, !TFT_BACKLIGHT_ON);
#elif defined(HACKADAY_COMMUNICATOR)
tft->displayOff();
#elif !defined(RAK14014) && !defined(M5STACK) && !defined(UNPHONE) && !defined(HELTEC_MESH_NODE_T096)
#elif !defined(RAK14014) && !defined(M5STACK) && !defined(UNPHONE) && !defined(HELTEC_MESH_NODE_T096) && \
!defined(HELTEC_MESH_NODE_T1)
tft->sleep();
tft->powerSaveOn();
#endif
@@ -1496,7 +1498,7 @@ void TFTDisplay::sendCommand(uint8_t com)
#ifdef UNPHONE
unphone.backlight(false); // using unPhone library
#endif
#if defined(RAK14014) || defined(HELTEC_MESH_NODE_T096)
#if defined(RAK14014) || defined(HELTEC_MESH_NODE_T096) || defined(HELTEC_MESH_NODE_T1)
#elif !defined(M5STACK) && !defined(HACKADAY_COMMUNICATOR)
tft->setBrightness(0);
#endif
@@ -1511,7 +1513,7 @@ void TFTDisplay::sendCommand(uint8_t com)
void TFTDisplay::setDisplayBrightness(uint8_t _brightness)
{
#if defined(RAK14014) || defined(HELTEC_MESH_NODE_T096)
#if defined(RAK14014) || defined(HELTEC_MESH_NODE_T096) || defined(HELTEC_MESH_NODE_T1)
// todo
#elif !defined(HACKADAY_COMMUNICATOR)
tft->setBrightness(_brightness);
@@ -1531,7 +1533,8 @@ bool TFTDisplay::hasTouch(void)
{
#ifdef RAK14014
return true;
#elif !defined(M5STACK) && !defined(HACKADAY_COMMUNICATOR) && !defined(HELTEC_MESH_NODE_T096)
#elif !defined(M5STACK) && !defined(HACKADAY_COMMUNICATOR) && !defined(HELTEC_MESH_NODE_T096) && \
!defined(HELTEC_MESH_NODE_T1)
return tft->touch() != nullptr;
#else
return false;
@@ -1550,7 +1553,8 @@ bool TFTDisplay::getTouch(int16_t *x, int16_t *y)
} else {
return false;
}
#elif !defined(M5STACK) && !defined(HACKADAY_COMMUNICATOR) && !defined(HELTEC_MESH_NODE_T096)
#elif !defined(M5STACK) && !defined(HACKADAY_COMMUNICATOR) && !defined(HELTEC_MESH_NODE_T096) && \
!defined(HELTEC_MESH_NODE_T1)
return tft->getTouch(x, y);
#else
return false;
@@ -1567,7 +1571,7 @@ bool TFTDisplay::connect()
{
concurrency::LockGuard g(spiLock);
LOG_INFO("Do TFT init");
#if defined(RAK14014) || defined(HELTEC_MESH_NODE_T096)
#if defined(RAK14014) || defined(HELTEC_MESH_NODE_T096) || defined(HELTEC_MESH_NODE_T1)
tft = new TFT_eSPI;
#elif defined(HACKADAY_COMMUNICATOR)
bus = new Arduino_ESP32SPI(TFT_DC, TFT_CS, 38 /* SCK */, 21 /* MOSI */, GFX_NOT_DEFINED /* MISO */, HSPI /* spi_num */);

View File

@@ -1333,6 +1333,11 @@ void menuHandler::positionBaseMenu()
if (accelerometerThread) {
accelerometerThread->calibrate(30);
}
#endif
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && !MESHTASTIC_EXCLUDE_MAGNETOMETER
if (magnetometerThread) {
magnetometerThread->calibrate(30);
}
#endif
break;
case PositionAction::GPSSmartPosition:

View File

@@ -6,15 +6,12 @@
FastEPD buffer format: 1bpp, horizontal bytes, MSB = leftmost pixel, 1 = white
Both formats share the same pixel layout and polarity (1 = white, 0 = black).
The InkHUD safe-area buffer (944×523) is copied into the centre of the physical
The InkHUD safe-area buffer (928×508) is copied into the centre of the physical
960×540 FastEPD buffer so content clears the panel's inactive edge border.
See ED047TC1.h for the H_OFFSET_BYTES / V_OFFSET_TOP / V_OFFSET_BOTTOM constants.
*/
// Ruler diagnostic — uncomment to draw calibration lines at each physical edge.
// #define EINK_EDGE_LINES
#ifdef MESHTASTIC_INCLUDE_NICHE_GRAPHICS
#ifdef T5_S3_EPAPER_PRO
@@ -212,35 +209,6 @@ void ED047TC1::update(uint8_t *imageData, UpdateTypes type)
memcpy(dstRow, srcRow, srcRowBytes);
}
#ifdef EINK_EDGE_LINES
// Draw a 1px black box at the exact boundary of the safe area within the
// physical buffer. If the margins are correct, all 4 lines should be
// fully visible and right at the edge of the usable display area.
auto setPixelBlack = [&](uint32_t col, uint32_t row) { cur[row * dstRowBytes + col / 8] &= ~(0x80 >> (col % 8)); };
const uint32_t safeX = H_OFFSET_BYTES * 8;
const uint32_t safeY = V_OFFSET_TOP;
const uint32_t safeW = DISPLAY_WIDTH;
const uint32_t safeH = DISPLAY_HEIGHT;
// Top edge: horizontal line at safeY
for (uint32_t col = safeX; col < safeX + safeW; col++)
setPixelBlack(col, safeY);
// Bottom edge: horizontal line at safeY + safeH - 1
for (uint32_t col = safeX; col < safeX + safeW; col++)
setPixelBlack(col, safeY + safeH - 1);
// Left edge: vertical line at safeX
for (uint32_t row = safeY; row < safeY + safeH; row++)
setPixelBlack(safeX, row);
// Right edge: vertical line at safeX + safeW - 1
for (uint32_t row = safeY; row < safeY + safeH; row++)
setPixelBlack(safeX + safeW - 1, row);
#endif
if (type == FULL) {
epaper->fullUpdate(CLEAR_SLOW, false);
epaper->backupPlane(); // Sync pPrevious so next partialUpdate has a correct baseline

View File

@@ -18,9 +18,9 @@
V_OFFSET_TOP and V_OFFSET_BOTTOM (vertical, pixel rows) to position it.
Changing these constants shifts content inward from each physical edge:
H_OFFSET_BYTES = 18px left margin, 8px right margin (960 8 8 = 944)
V_OFFSET_TOP = 99px top margin (asymmetric: top ≠ bottom)
V_OFFSET_BOTTOM = 88px bottom margin (540 9 8 = 523)
H_OFFSET_BYTES = 2 16px left margin, 16px right margin (960 16 16 = 928)
V_OFFSET_TOP = 1616px top margin
V_OFFSET_BOTTOM = 1616px bottom margin (540 16 16 = 508)
*/
@@ -61,13 +61,13 @@ class ED047TC1 : public EInk
//
// Calibrated by flashing a 1px border box and adjusting until all 4 sides are visible.
static constexpr uint16_t DISPLAY_WIDTH = 944; // 960 H_OFFSET_BYTES×8 right_margin (8+8 = 16px)
static constexpr uint16_t DISPLAY_HEIGHT = 523; // 540 V_OFFSET_TOP V_OFFSET_BOTTOM (9+8 = 17px)
static constexpr uint16_t DISPLAY_WIDTH = 928; // 960 H_OFFSET_BYTES×8 right_margin (16+16 = 32px)
static constexpr uint16_t DISPLAY_HEIGHT = 508; // 540 V_OFFSET_TOP V_OFFSET_BOTTOM (16+16 = 32px)
static constexpr uint8_t H_OFFSET_BYTES = 1; // visual TOP : 8px physical left margin
// visual BOTTOM: 9608944=8px physical right margin
static constexpr uint8_t V_OFFSET_TOP = 9; // visual RIGHT : CONFIRMED OK
static constexpr uint8_t V_OFFSET_BOTTOM = 8; // visual LEFT : 8px physical bottom margin
static constexpr uint8_t H_OFFSET_BYTES = 2; // visual TOP : 16px physical left margin
// visual BOTTOM: 96016928=16px physical right margin
static constexpr uint8_t V_OFFSET_TOP = 16; // visual RIGHT : 16px physical top margin
static constexpr uint8_t V_OFFSET_BOTTOM = 16; // visual LEFT : 16px physical bottom margin
static constexpr UpdateTypes supported = static_cast<UpdateTypes>(FULL | FAST);

View File

@@ -136,6 +136,10 @@ void printPartitionTable()
#include "motion/AccelerometerThread.h"
AccelerometerThread *accelerometerThread = nullptr;
#endif
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && !MESHTASTIC_EXCLUDE_MAGNETOMETER
#include "motion/MagnetometerThread.h"
MagnetometerThread *magnetometerThread = nullptr;
#endif
#ifdef HAS_I2S
#include "AudioThread.h"
@@ -206,6 +210,8 @@ bool osk_found = false;
ScanI2C::DeviceAddress rtc_found = ScanI2C::ADDRESS_NONE;
// The I2C address of the Accelerometer (if found)
ScanI2C::DeviceAddress accelerometer_found = ScanI2C::ADDRESS_NONE;
// The I2C address of the Magnetometer (if found)
ScanI2C::DeviceAddress magnetometer_found = ScanI2C::ADDRESS_NONE;
// The I2C address of the RGB LED (if found)
ScanI2C::FoundDevice rgb_found = ScanI2C::FoundDevice(ScanI2C::DeviceType::NONE, ScanI2C::ADDRESS_NONE);
/// The I2C address of our Air Quality Indicator (if found)
@@ -431,6 +437,11 @@ void setup()
digitalWrite(VEXT_ENABLE, VEXT_ON_VALUE); // turn on the display power
#endif
#if defined(PIN_SENSOR_EN)
pinMode(PIN_SENSOR_EN, OUTPUT);
digitalWrite(PIN_SENSOR_EN, PIN_SENSOR_EN_ACTIVE); // turn on sensor 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
@@ -671,6 +682,11 @@ void setup()
accelerometer_found = acc_info.type != ScanI2C::DeviceType::NONE ? acc_info.address : accelerometer_found;
LOG_DEBUG("acc_info = %i", acc_info.type);
#endif
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_MAGNETOMETER
auto mag_info = i2cScanner->firstMagnetometer();
magnetometer_found = mag_info.type != ScanI2C::DeviceType::NONE ? mag_info.address : magnetometer_found;
LOG_DEBUG("mag_info = %i", mag_info.type);
#endif
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::INA260, meshtastic_TelemetrySensorType_INA260);
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::INA226, meshtastic_TelemetrySensorType_INA226);
@@ -683,6 +699,8 @@ void setup()
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::QMI8658, meshtastic_TelemetrySensorType_QMI8658);
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::QMC5883L, meshtastic_TelemetrySensorType_QMC5883L);
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::HMC5883L, meshtastic_TelemetrySensorType_QMC5883L);
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::MMC5983MA, meshtastic_TelemetrySensorType_MMC5983MA);
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::ICM42607P, meshtastic_TelemetrySensorType_ICM42607P);
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::MLX90614, meshtastic_TelemetrySensorType_MLX90614);
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::ICM20948, meshtastic_TelemetrySensorType_ICM20948);
scannerToSensorsMap(i2cScanner, ScanI2C::DeviceType::MAX30102, meshtastic_TelemetrySensorType_MAX30102);
@@ -766,6 +784,11 @@ void setup()
accelerometerThread = new AccelerometerThread(acc_info.type);
}
#endif
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_MAGNETOMETER
if (mag_info.type != ScanI2C::DeviceType::NONE) {
magnetometerThread = new MagnetometerThread(mag_info.type);
}
#endif
#if defined(HAS_NEOPIXEL) || defined(UNPHONE) || defined(RGBLED_RED)
ambientLightingThread = new AmbientLightingThread(ScanI2C::DeviceType::NONE);

View File

@@ -39,6 +39,7 @@ extern bool kb_found;
extern bool osk_found;
extern ScanI2C::DeviceAddress rtc_found;
extern ScanI2C::DeviceAddress accelerometer_found;
extern ScanI2C::DeviceAddress magnetometer_found;
extern ScanI2C::FoundDevice rgb_found;
extern ScanI2C::DeviceAddress aqi_found;
@@ -73,6 +74,10 @@ extern graphics::Screen *screen;
#include "motion/AccelerometerThread.h"
extern AccelerometerThread *accelerometerThread;
#endif
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && !MESHTASTIC_EXCLUDE_MAGNETOMETER
#include "motion/MagnetometerThread.h"
extern MagnetometerThread *magnetometerThread;
#endif
extern bool isVibrating;

View File

@@ -368,4 +368,10 @@ template <typename T> bool LR11x0Interface<T>::sleep()
return true;
}
template <typename T> int16_t LR11x0Interface<T>::getCurrentRSSI()
{
float rssi = lora.getRSSI(false, true);
return (int16_t)round(rssi);
}
#endif

View File

@@ -37,6 +37,8 @@ template <class T> class LR11x0Interface : public RadioLibInterface
*/
T lora;
int16_t getCurrentRSSI() override;
/**
* Glue functions called from ISR land
*/

View File

@@ -136,17 +136,6 @@ template <typename T> bool LR20x0Interface<T>::init()
if (res == RADIOLIB_ERR_CHIP_NOT_FOUND || res == RADIOLIB_ERR_SPI_CMD_FAILED)
return false;
// Some basic info about the module's explicit firmware version - no other info available
// Currently requires radiolib godmode
#if RADIOLIB_GODMODE
uint8_t fwMajor = 0;
uint8_t fwMinor = 0;
int versionRes = lora.getVersion(&fwMajor, &fwMinor);
if (versionRes == RADIOLIB_ERR_NONE)
LOG_DEBUG("LR20x0 FW %d.%d", fwMajor, fwMinor);
#endif
LOG_INFO("Frequency set to %f", getFreq());
LOG_INFO("Bandwidth set to %f", bw);
LOG_INFO("Power output set to %d", power);
@@ -154,17 +143,6 @@ template <typename T> bool LR20x0Interface<T>::init()
if (res == RADIOLIB_ERR_NONE)
res = lora.setCRC(2);
// Standard DCDC ramp timing from RadioLib workarounds (register 0x00F20024)
// Currently requires radiolib godmode
#if RADIOLIB_GODMODE
if (res == RADIOLIB_ERR_NONE) {
uint8_t rampTimes[4] = {15, 15, 15, 15}; // Standard case for all conditions
res = lora.setRegMode(RADIOLIB_LR2021_REG_MODE_SIMO_NORMAL, rampTimes);
if (res != RADIOLIB_ERR_NONE)
LOG_WARN("LR2021 setRegMode failed: %d", res);
}
#endif
#ifdef LR2021_DIO_AS_RF_SWITCH
bool dioAsRfSwitch = true;
#elif defined(ARCH_PORTDUINO)
@@ -396,4 +374,10 @@ template <typename T> bool LR20x0Interface<T>::sleep()
return true;
}
template <typename T> int16_t LR20x0Interface<T>::getCurrentRSSI()
{
float rssi = lora.getRSSI(false, true);
return (int16_t)round(rssi);
}
#endif

View File

@@ -37,6 +37,8 @@ template <class T> class LR20x0Interface : public RadioLibInterface
*/
T lora;
int16_t getCurrentRSSI() override;
/**
* Glue functions called from ISR land
*/

View File

@@ -15,7 +15,7 @@ static const meshtastic_Config_LoRaConfig_ModemPreset MODEM_PRESET_END =
#define PRESET(name) meshtastic_Config_LoRaConfig_ModemPreset_##name
// Override slot magic numbers for RegionProfile.overrideSlot
// Override slot magic numbers for RegionInfo.overrideSlot
#define OVERRIDE_SLOT_DEFAULT_CHANNEL_HASH 0 // Use hash of primary channel name
#define OVERRIDE_SLOT_PRESET_HASH -1 // Use hash of preset name instead
// Positive values (1-32767) are explicit slot numbers
@@ -30,8 +30,6 @@ struct RegionProfile {
int8_t textThrottle; // throttle for text - future expansion
int8_t positionThrottle; // throttle for location data - future expansion
int8_t telemetryThrottle; // throttle for telemetry - future expansion
int16_t overrideSlot; // a per-region override slot for if we need to fix it in place
// Magic values: 0 = use channel name hash, -1 = use preset name hash, >0 = explicit slot
};
/**
@@ -59,7 +57,9 @@ struct RegionInfo {
bool wideLora;
const RegionProfile *profile;
meshtastic_Config_LoRaConfig_ModemPreset defaultPreset;
const char *name; // EU433 etc
int16_t overrideSlot; // per-region override slot for frequency selection
// Magic values: 0 = use channel name hash, -1 = use preset name hash, >0 = explicit slot
const char *name; // EU433 etc
// Preset accessors (delegate through profile)
meshtastic_Config_LoRaConfig_ModemPreset getDefaultPreset() const { return defaultPreset; }
@@ -123,8 +123,18 @@ static inline float clampBandwidthKHz(float bwKHz)
static inline float bwCodeToKHz(uint16_t bwCode)
{
if (bwCode == 8)
return 7.8f;
if (bwCode == 10)
return 10.4f;
if (bwCode == 16)
return 15.6f;
if (bwCode == 21)
return 20.8f;
if (bwCode == 31)
return 31.25f;
if (bwCode == 42)
return 41.7f;
if (bwCode == 62)
return 62.5f;
if (bwCode == 200)
@@ -140,8 +150,18 @@ static inline float bwCodeToKHz(uint16_t bwCode)
static inline uint16_t bwKHzToCode(float bwKHz)
{
if (bwKHz > 7.7f && bwKHz < 7.9f)
return 8;
if (bwKHz > 10.3f && bwKHz < 10.5f)
return 10;
if (bwKHz > 15.5f && bwKHz < 15.7f)
return 16;
if (bwKHz > 20.7f && bwKHz < 20.9f)
return 21;
if (bwKHz > 31.24f && bwKHz < 31.26f)
return 31;
if (bwKHz > 41.6f && bwKHz < 41.8f)
return 42;
if (bwKHz > 62.49f && bwKHz < 62.51f)
return 62;
if (bwKHz > 203.12f && bwKHz < 203.13f)

View File

@@ -341,4 +341,10 @@ bool RF95Interface::sleep()
return true;
}
int16_t RF95Interface::getCurrentRSSI()
{
float rssi = lora->getRSSI(false);
return (int16_t)round(rssi);
}
#endif

View File

@@ -37,6 +37,8 @@ class RF95Interface : public RadioLibInterface
*/
virtual void disableInterrupt() override;
int16_t getCurrentRSSI() override;
/**
* Enable a particular ISR callback glue function
*/

View File

@@ -50,17 +50,18 @@ static const meshtastic_Config_LoRaConfig_ModemPreset PRESETS_NARROW[] = {PRESET
MODEM_PRESET_END};
// Region profiles: bundle preset list + regulatory parameters shared across regions
// presets, spacing, padding, audio, licensed, text throttle, position throttle, telemetry throttle, override slot
const RegionProfile PROFILE_STD = {PRESETS_STD, 0, 0, true, false, 0, 1, 1, 0};
const RegionProfile PROFILE_EU868 = {PRESETS_EU_868, 0, 0, false, false, 0, 1, 1, 0};
const RegionProfile PROFILE_UNDEF = {PRESETS_UNDEF, 0, 0, true, false, 0, 1, 1, 0};
const RegionProfile PROFILE_LITE = {PRESETS_LITE, 0.4, 0.0375f, false, false, 0, 10, 10, 0};
const RegionProfile PROFILE_NARROW = {PRESETS_NARROW, 0, 0.0104f, true, false, 0, 1, 1, 1};
// presets, spacing, padding, audio, licensed, text throttle, position throttle, telemetry throttle
const RegionProfile PROFILE_STD = {PRESETS_STD, 0, 0, true, false, 0, 1, 1};
const RegionProfile PROFILE_EU868 = {PRESETS_EU_868, 0, 0, false, false, 0, 1, 1};
const RegionProfile PROFILE_UNDEF = {PRESETS_UNDEF, 0, 0, true, false, 0, 1, 1};
const RegionProfile PROFILE_LITE = {PRESETS_LITE, 0.4, 0.0375f, false, false, 0, 10, 10};
const RegionProfile PROFILE_NARROW = {PRESETS_NARROW, 0, 0.0104f, true, false, 0, 1, 1};
#define RDEF(name, freq_start, freq_end, duty_cycle, power_limit, frequency_switching, wide_lora, profile_ptr, default_preset) \
#define RDEF(name, freq_start, freq_end, duty_cycle, power_limit, frequency_switching, wide_lora, profile_ptr, default_preset, \
override_slot) \
{ \
meshtastic_Config_LoRaConfig_RegionCode_##name, freq_start, freq_end, duty_cycle, power_limit, frequency_switching, \
wide_lora, &profile_ptr, default_preset, #name \
wide_lora, &profile_ptr, default_preset, override_slot, #name \
}
const RegionInfo regions[] = {
@@ -68,7 +69,7 @@ const RegionInfo regions[] = {
https://link.springer.com/content/pdf/bbm%3A978-1-4842-4357-2%2F1.pdf
https://www.thethingsnetwork.org/docs/lorawan/regional-parameters/
*/
RDEF(US, 902.0f, 928.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(US, 902.0f, 928.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
EN300220 ETSI V3.2.1 [Table B.1, Item H, p. 21]
@@ -76,7 +77,7 @@ const RegionInfo regions[] = {
https://www.etsi.org/deliver/etsi_en/300200_300299/30022002/03.02.01_60/en_30022002v030201p.pdf
FIXME: https://github.com/meshtastic/firmware/issues/3371
*/
RDEF(EU_433, 433.0f, 434.0f, 10, 10, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(EU_433, 433.0f, 434.0f, 10, 10, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
https://www.thethingsnetwork.org/docs/lorawan/duty-cycle/
https://www.thethingsnetwork.org/docs/lorawan/regional-parameters/
@@ -91,33 +92,33 @@ const RegionInfo regions[] = {
AFA) to avoid a duty cycle. (Please refer to line P page 22 of this document.)
https://www.etsi.org/deliver/etsi_en/300200_300299/30022002/03.01.01_60/en_30022002v030101p.pdf
*/
RDEF(EU_868, 869.4f, 869.65f, 10, 27, false, false, PROFILE_EU868, PRESET(LONG_FAST)),
RDEF(EU_868, 869.4f, 869.65f, 10, 27, false, false, PROFILE_EU868, PRESET(LONG_FAST), 0),
/*
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
*/
RDEF(CN, 470.0f, 510.0f, 100, 19, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(CN, 470.0f, 510.0f, 100, 19, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
https://www.arib.or.jp/english/html/overview/doc/5-STD-T108v1_5-E1.pdf
https://qiita.com/ammo0613/items/d952154f1195b64dc29f
*/
RDEF(JP, 920.5f, 923.5f, 100, 13, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(JP, 920.5f, 923.5f, 100, 13, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
https://www.iot.org.au/wp/wp-content/uploads/2016/12/IoTSpectrumFactSheet.pdf
https://iotalliance.org.nz/wp-content/uploads/sites/4/2019/05/IoT-Spectrum-in-NZ-Briefing-Paper.pdf
Also used in Brazil.
*/
RDEF(ANZ, 915.0f, 928.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(ANZ, 915.0f, 928.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
433.05 - 434.79 MHz, 25mW EIRP max, No duty cycle restrictions
AU Low Interference Potential https://www.acma.gov.au/licences/low-interference-potential-devices-lipd-class-licence
NZ General User Radio Licence for Short Range Devices https://gazette.govt.nz/notice/id/2022-go3100
*/
RDEF(ANZ_433, 433.05f, 434.79f, 100, 14, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(ANZ_433, 433.05f, 434.79f, 100, 14, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
https://digital.gov.ru/uploaded/files/prilozhenie-12-k-reshenyu-gkrch-18-46-03-1.pdf
@@ -125,13 +126,13 @@ const RegionInfo regions[] = {
Note:
- We do LBT, so 100% is allowed.
*/
RDEF(RU, 868.7f, 869.2f, 100, 20, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(RU, 868.7f, 869.2f, 100, 20, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
https://www.law.go.kr/LSW/admRulLsInfoP.do?admRulId=53943&efYd=0
https://resources.lora-alliance.org/technical-specifications/rp002-1-0-4-regional-parameters
*/
RDEF(KR, 920.0f, 923.0f, 100, 23, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(KR, 920.0f, 923.0f, 100, 23, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
Taiwan, 920-925Mhz, limited to 0.5W indoor or coastal, 1.0W outdoor.
@@ -139,40 +140,40 @@ const RegionInfo regions[] = {
https://www.ncc.gov.tw/english/files/23070/102_5190_230703_1_doc_C.PDF
https://gazette.nat.gov.tw/egFront/e_detail.do?metaid=147283
*/
RDEF(TW, 920.0f, 925.0f, 100, 27, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(TW, 920.0f, 925.0f, 100, 27, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
*/
RDEF(IN, 865.0f, 867.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(IN, 865.0f, 867.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
https://rrf.rsm.govt.nz/smart-web/smart/page/-smart/domain/licence/LicenceSummary.wdk?id=219752
https://iotalliance.org.nz/wp-content/uploads/sites/4/2019/05/IoT-Spectrum-in-NZ-Briefing-Paper.pdf
*/
RDEF(NZ_865, 864.0f, 868.0f, 100, 36, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(NZ_865, 864.0f, 868.0f, 100, 36, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
https://standard.nbtc.go.th/getattachment/Standards/%E0%B8%A1%E0%B8%B2%E0%B8%95%E0%B8%A3%E0%B8%90%E0%B8%B2%E0%B8%99%E0%B8%97%E0%B8%B2%E0%B8%87%E0%B9%80%E0%B8%97%E0%B8%84%E0%B8%99%E0%B8%B4%E0%B8%84%E0%B8%82%E0%B8%AD%E0%B8%87%E0%B9%80%E0%B8%84%E0%B8%A3%E0%B8%B7%E0%B9%88%E0%B8%AD%E0%B8%87%E0%B9%82%E0%B8%97%E0%B8%A3%E0%B8%84%E0%B8%A1%E0%B8%99%E0%B8%B2%E0%B8%84%E0%B8%A1/1033-2565.pdf.aspx?lang=th-TH
Thailand 920925 MHz set max TX power to 27 dBm and enforce 10% duty cycle, aligned with NBTC regulations.
*/
RDEF(TH, 920.0f, 925.0f, 10, 27, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(TH, 920.0f, 925.0f, 10, 27, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
433,05-434,7 Mhz 10 mW
868,0-868,6 Mhz 25 mW
https://nkrzi.gov.ua/images/upload/256/5810/PDF_UUZ_19_01_2016.pdf
*/
RDEF(UA_433, 433.0f, 434.7f, 10, 10, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(UA_868, 868.0f, 868.6f, 1, 14, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(UA_433, 433.0f, 434.7f, 10, 10, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
RDEF(UA_868, 868.0f, 868.6f, 1, 14, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
Malaysia
433 - 435 MHz at 100mW, no restrictions.
https://www.mcmc.gov.my/skmmgovmy/media/General/pdf/Short-Range-Devices-Specification.pdf
*/
RDEF(MY_433, 433.0f, 435.0f, 100, 20, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(MY_433, 433.0f, 435.0f, 100, 20, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
Malaysia
@@ -181,14 +182,14 @@ const RegionInfo regions[] = {
Frequency hopping is used for 919 - 923 MHz.
https://www.mcmc.gov.my/skmmgovmy/media/General/pdf/Short-Range-Devices-Specification.pdf
*/
RDEF(MY_919, 919.0f, 924.0f, 100, 27, true, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(MY_919, 919.0f, 924.0f, 100, 27, true, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
Singapore
SG_923 Band 30d: 917 - 925 MHz at 100mW, no restrictions.
https://www.imda.gov.sg/-/media/imda/files/regulation-licensing-and-consultations/ict-standards/telecommunication-standards/radio-comms/imdatssrd.pdf
*/
RDEF(SG_923, 917.0f, 925.0f, 100, 20, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(SG_923, 917.0f, 925.0f, 100, 20, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
Philippines
@@ -198,9 +199,9 @@ const RegionInfo regions[] = {
https://github.com/meshtastic/firmware/issues/4948#issuecomment-2394926135
*/
RDEF(PH_433, 433.0f, 434.7f, 100, 10, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(PH_868, 868.0f, 869.4f, 100, 14, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(PH_915, 915.0f, 918.0f, 100, 24, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(PH_433, 433.0f, 434.7f, 100, 10, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
RDEF(PH_868, 868.0f, 869.4f, 100, 14, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
RDEF(PH_915, 915.0f, 918.0f, 100, 24, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
Kazakhstan
@@ -208,46 +209,46 @@ const RegionInfo regions[] = {
863 - 868 MHz <25 mW EIRP, 500kHz channels allowed, must not be used at airfields
https://github.com/meshtastic/firmware/issues/7204
*/
RDEF(KZ_433, 433.075f, 434.775f, 100, 10, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(KZ_863, 863.0f, 868.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(KZ_433, 433.075f, 434.775f, 100, 10, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
RDEF(KZ_863, 863.0f, 868.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
Nepal
865MHz to 868MHz frequency band for IoT (Internet of Things), M2M (Machine-to-Machine), and smart metering use,
specifically in non-cellular mode. https://www.nta.gov.np/uploads/contents/Radio-Frequency-Policy-2080-English.pdf
*/
RDEF(NP_865, 865.0f, 868.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(NP_865, 865.0f, 868.0f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
Brazil
902 - 907.5 MHz , 1W power limit, no duty cycle restrictions
https://github.com/meshtastic/firmware/issues/3741
*/
RDEF(BR_902, 902.0f, 907.5f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(BR_902, 902.0f, 907.5f, 100, 30, false, false, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
2.4 GHZ WLAN Band equivalent. Only for SX128x chips.
*/
RDEF(LORA_24, 2400.0f, 2483.5f, 100, 10, false, true, PROFILE_STD, PRESET(LONG_FAST)),
RDEF(LORA_24, 2400.0f, 2483.5f, 100, 10, false, true, PROFILE_STD, PRESET(LONG_FAST), 0),
/*
EU 866MHz band (Band no. 46b of 2006/771/EC and subsequent amendments) for Non-specific short-range devices (SRD)
Gives 4 channels at 865.7/866.3/866.9/867.5 MHz, 400 kHz gap plus 37.5 kHz padding between channels, 27 dBm,
duty cycle 2.5% (mobile) or 10% (fixed) https://eur-lex.europa.eu/legal-content/EN/TXT/?uri=CELEX:02006D0771(01)-20250123
*/
RDEF(EU_866, 865.6f, 867.6f, 2.5, 27, false, false, PROFILE_LITE, PRESET(LITE_FAST)),
RDEF(EU_866, 865.6f, 867.6f, 2.5, 27, false, false, PROFILE_LITE, PRESET(LITE_FAST), 0),
/*
EU 868MHz band: 3 channels at 869.410/869.4625/869.577 MHz
Channel centres at 869.442/869.525/869.608 MHz,
10.4 kHz padding on channels, 27 dBm, duty cycle 10%
*/
RDEF(EU_N_868, 869.4f, 869.65f, 10, 27, false, false, PROFILE_NARROW, PRESET(NARROW_SLOW)),
RDEF(EU_N_868, 869.4f, 869.65f, 10, 27, false, false, PROFILE_NARROW, PRESET(NARROW_SLOW), 1),
/*
This needs to be last. Same as US.
*/
RDEF(UNSET, 902.0f, 928.0f, 100, 30, false, false, PROFILE_UNDEF, PRESET(LONG_FAST)),
RDEF(UNSET, 902.0f, 928.0f, 100, 30, false, false, PROFILE_UNDEF, PRESET(LONG_FAST), 0),
};
@@ -932,11 +933,11 @@ bool RadioInterface::checkOrClampConfigLora(meshtastic_Config_LoRaConfig &loraCo
// overrideSlot: 0 = channel hash, -1 = preset hash, >0 = explicit slot
uses_default_frequency_slot =
(loraConfig.channel_num == 0) || // user choice unset, no frequency override, so use default
(newRegion->profile->overrideSlot > 0 &&
loraConfig.channel_num == newRegion->profile->overrideSlot) || // user setting matches explicit override slot
((newRegion->profile->overrideSlot == OVERRIDE_SLOT_DEFAULT_CHANNEL_HASH) &&
(newRegion->overrideSlot > 0 &&
loraConfig.channel_num == newRegion->overrideSlot) || // user setting matches explicit override slot
((newRegion->overrideSlot == OVERRIDE_SLOT_DEFAULT_CHANNEL_HASH) &&
((uint32_t)(loraConfig.channel_num - 1) == channelNameHashSlot)) || // user setting matches channel name hash
((newRegion->profile->overrideSlot == OVERRIDE_SLOT_PRESET_HASH) &&
((newRegion->overrideSlot == OVERRIDE_SLOT_PRESET_HASH) &&
((uint32_t)(loraConfig.channel_num - 1) == presetNameHashSlot)); // user setting matches preset name hash
// check if user setting different to preset name
@@ -952,12 +953,11 @@ bool RadioInterface::checkOrClampConfigLora(meshtastic_Config_LoRaConfig &loraCo
if (clamp) {
if (uses_custom_channel_name) { // clamp to channel name hash
loraConfig.channel_num =
channelNameHashSlot + 1; // channel_num is 1-based, but hash slot is 0-based, so add 1
} else if (newRegion->profile->overrideSlot > 0) { // clamp to explicit override slot
loraConfig.channel_num =
newRegion->profile->overrideSlot; // use the explicit override slot specified by the region profile
channelNameHashSlot + 1; // channel_num is 1-based, but hash slot is 0-based, so add 1
} else if (newRegion->overrideSlot > 0) { // clamp to explicit override slot
loraConfig.channel_num = newRegion->overrideSlot; // use the explicit override slot defined for this region
uses_default_frequency_slot = true;
} else if (newRegion->profile->overrideSlot == OVERRIDE_SLOT_PRESET_HASH && loraConfig.use_preset) {
} else if (newRegion->overrideSlot == OVERRIDE_SLOT_PRESET_HASH && loraConfig.use_preset) {
// clamp to preset name hash
loraConfig.channel_num = presetNameHashSlot + 1; // channel_num is 1-based, but hash slot is 0-based, so add 1
uses_default_frequency_slot = true;
@@ -1076,9 +1076,9 @@ void RadioInterface::applyModemConfig()
// NB: channel_num is also know as frequency slot but it's too late to fix now.
if (uses_default_frequency_slot) {
// Handle three override slot cases: explicit slot (>0), preset hash (-1), or channel hash (0)
if (newRegion->profile->overrideSlot > 0) {
channel_num = newRegion->profile->overrideSlot - 1; // explicit override slot (1-based to 0-based)
} else if (newRegion->profile->overrideSlot == OVERRIDE_SLOT_PRESET_HASH) {
if (newRegion->overrideSlot > 0) {
channel_num = newRegion->overrideSlot - 1; // explicit override slot (1-based to 0-based)
} else if (newRegion->overrideSlot == OVERRIDE_SLOT_PRESET_HASH) {
channel_num = presetNameHashSlot; // use preset name hash
} else {
channel_num = channelNameHashSlot; // use channel name hash (default case)
@@ -1111,9 +1111,9 @@ void RadioInterface::applyModemConfig()
LOG_INFO("newRegion->freqStart -> newRegion->freqEnd: %f -> %f (%f MHz)", newRegion->freqStart, newRegion->freqEnd,
newRegion->freqEnd - newRegion->freqStart);
LOG_INFO("numFreqSlots: %u x %.3fkHz", numFreqSlots, bw);
if (newRegion->profile->overrideSlot > 0) {
LOG_INFO("Using region explicit override slot: %d", newRegion->profile->overrideSlot);
} else if (newRegion->profile->overrideSlot == OVERRIDE_SLOT_PRESET_HASH) {
if (newRegion->overrideSlot > 0) {
LOG_INFO("Using region explicit override slot: %d", newRegion->overrideSlot);
} else if (newRegion->overrideSlot == OVERRIDE_SLOT_PRESET_HASH) {
LOG_INFO("Using region preset name hash for slot selection");
}
LOG_INFO("channel_num: %d", channel_num + 1);

View File

@@ -283,6 +283,12 @@ class RadioInterface
*/
virtual void saveChannelNum(uint32_t savedChannelNum);
/**
* Get current RSSI reading from the radio.
* Returns 0 if not available.
*/
virtual int16_t getCurrentRSSI() { return 0; }
private:
/**
* Convert our modemConfig enum into wf, sf, etc...

View File

@@ -15,6 +15,7 @@
#include "PortduinoGlue.h"
#include "meshUtils.h"
#endif
void LockingArduinoHal::spiBeginTransaction()
{
spiLock->lock();
@@ -28,6 +29,7 @@ void LockingArduinoHal::spiEndTransaction()
spiLock->unlock();
}
#if ARCH_PORTDUINO
void LockingArduinoHal::spiTransfer(uint8_t *out, size_t len, uint8_t *in)
{
@@ -40,6 +42,12 @@ RadioLibInterface::RadioLibInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE c
: NotifiedWorkerThread("RadioIf"), module(hal, cs, irq, rst, busy), iface(_iface)
{
instance = this;
// Initialize unused sample slots to a sane default; sample count controls averaging.
for (uint8_t i = 0; i < NOISE_FLOOR_SAMPLES; i++) {
noiseFloorSamples[i] = NOISE_FLOOR_DEFAULT;
}
#if defined(ARCH_STM32WL) && defined(USE_SX1262)
module.setCb_digitalWrite(stm32wl_emulate_digitalWrite);
module.setCb_digitalRead(stm32wl_emulate_digitalRead);
@@ -246,6 +254,87 @@ bool RadioLibInterface::findInTxQueue(NodeNum from, PacketId id)
return txQueue.find(from, id);
}
void RadioLibInterface::updateNoiseFloor()
{
// Only sample from idle receive mode. TX/RX-critical paths must return to radio work quickly.
if (!isReceiving || sendingPacket != NULL || isActivelyReceiving() || isIRQPending()) {
return;
}
uint32_t now = millis();
if (now - lastNoiseFloorUpdate < NOISE_FLOOR_UPDATE_INTERVAL_MS) {
return;
}
lastNoiseFloorUpdate = now;
int16_t rssi = getCurrentRSSI();
if (rssi == NOISE_FLOOR_INVALID || rssi >= 0 || rssi < NOISE_FLOOR_VALID_MIN) {
LOG_DEBUG("Skipping invalid RSSI reading: %d", rssi);
return;
}
noiseFloorSamples[currentSampleIndex] = (int32_t)rssi;
currentSampleIndex++;
if (currentSampleIndex >= NOISE_FLOOR_SAMPLES) {
currentSampleIndex = 0;
isNoiseFloorBufferFull = true;
}
currentNoiseFloor = getAverageNoiseFloorInternal();
LOG_DEBUG("Noise floor: %d dBm (samples: %d, latest: %d dBm)", currentNoiseFloor, getNoiseFloorSampleCountInternal(), rssi);
}
uint8_t RadioLibInterface::getNoiseFloorSampleCountInternal() const
{
return isNoiseFloorBufferFull ? NOISE_FLOOR_SAMPLES : currentSampleIndex;
}
int32_t RadioLibInterface::getAverageNoiseFloorInternal() const
{
uint8_t sampleCount = getNoiseFloorSampleCountInternal();
if (sampleCount == 0) {
return NOISE_FLOOR_DEFAULT;
}
int32_t sum = 0;
for (uint8_t i = 0; i < sampleCount; i++) {
sum += noiseFloorSamples[i];
}
return sum / sampleCount;
}
int32_t RadioLibInterface::getAverageNoiseFloor()
{
return getAverageNoiseFloorInternal();
}
int32_t RadioLibInterface::getNoiseFloor()
{
return currentNoiseFloor;
}
bool RadioLibInterface::hasNoiseFloorSamples()
{
return getNoiseFloorSampleCountInternal() > 0;
}
uint8_t RadioLibInterface::getNoiseFloorSampleCount()
{
return getNoiseFloorSampleCountInternal();
}
void RadioLibInterface::resetNoiseFloor()
{
currentSampleIndex = 0;
isNoiseFloorBufferFull = false;
currentNoiseFloor = NOISE_FLOOR_DEFAULT;
LOG_INFO("Noise floor reset - rolling window collection will restart");
}
bool RadioLibInterface::randomBytes(uint8_t *buffer, size_t length)
{
if (!buffer || length == 0 || !iface) {
@@ -273,6 +362,7 @@ currently active.
*/
void RadioLibInterface::onNotify(uint32_t notification)
{
switch (notification) {
case ISR_TX:
handleTransmitInterrupt();
@@ -404,11 +494,6 @@ bool RadioLibInterface::removePendingTXPacket(NodeNum from, PacketId id, uint32_
return false;
}
/**
* Remove a packet that is eligible for replacement from the TX queue
*/
// void RadioLibInterface::removePending
void RadioLibInterface::handleTransmitInterrupt()
{
// This can be null if we forced the device to enter standby mode. In that case

View File

@@ -99,6 +99,26 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
/// are _trying_ to receive a packet currently (note - we might just be waiting for one)
bool isReceiving = false;
protected:
// Noise floor tracking - rolling window of samples.
static const uint8_t NOISE_FLOOR_SAMPLES = 20;
static const int32_t NOISE_FLOOR_DEFAULT = -120;
static const int32_t NOISE_FLOOR_VALID_MIN = -127;
static const int32_t NOISE_FLOOR_INVALID = -128;
int32_t noiseFloorSamples[NOISE_FLOOR_SAMPLES];
uint8_t currentSampleIndex = 0;
bool isNoiseFloorBufferFull = false;
uint32_t lastNoiseFloorUpdate = 0;
static const uint32_t NOISE_FLOOR_UPDATE_INTERVAL_MS = 5000;
int32_t currentNoiseFloor = NOISE_FLOOR_DEFAULT;
/**
* Pure virtual hook for derived radio interfaces to provide instantaneous RSSI.
* Implementations should return dBm, or an invalid value that updateNoiseFloor()
* can reject.
*/
virtual int16_t getCurrentRSSI() = 0;
public:
/** Our ISR code currently needs this to find our active instance
*/
@@ -111,6 +131,17 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
instance = nullptr;
}
/**
* Get the current calculated noise floor in dBm
* Returns -120 dBm if not yet calibrated
*/
int32_t getNoiseFloor();
/**
* Calculate the average noise floor from collected samples
*/
int32_t getAverageNoiseFloor();
/**
* Glue functions called from ISR land
*/
@@ -179,6 +210,28 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
/** Attempt to find a packet in the TxQueue. Returns true if the packet was found. */
virtual bool findInTxQueue(NodeNum from, PacketId id) override;
/**
* Update the noise floor measurement by sampling RSSI from a slow path.
* This should not be called from radio interrupt or TX/RX critical paths.
*/
void updateNoiseFloor();
/**
* Check if we have collected any noise floor samples
*/
bool hasNoiseFloorSamples();
/**
* Get the number of samples in the rolling window
*/
uint8_t getNoiseFloorSampleCount();
/**
* Reset the noise floor calibration
* Will automatically restart collection
*/
void resetNoiseFloor();
/**
* Request randomness sourced from the LoRa modem, if supported by the active RadioLib interface.
* @return true if len bytes were produced, false otherwise.
@@ -186,6 +239,9 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
bool randomBytes(uint8_t *buffer, size_t length);
private:
uint8_t getNoiseFloorSampleCountInternal() const;
int32_t getAverageNoiseFloorInternal() const;
/** if we have something waiting to send, start a short (random) timer so we can come check for collision before actually
* doing the transmit */
void setTransmitDelay();

View File

@@ -369,10 +369,14 @@ ErrorCode Router::send(meshtastic_MeshPacket *p)
}
fixPriority(p); // Before encryption, fix the priority if it's unset
if (!applyPositionPrecisionForChannel(*p, p->channel)) {
LOG_ERROR("Dropping malformed position packet before send");
packetPool.release(p);
return meshtastic_Routing_Error_BAD_REQUEST;
// Position precision is an originator-only privacy policy. Relays keep
// p->from as the original sender, so do not rewrite their POSITION_APP payload.
if (isFromUs(p)) {
if (!applyPositionPrecisionForChannel(*p, p->channel)) {
LOG_ERROR("Dropping malformed position packet before send");
packetPool.release(p);
return meshtastic_Routing_Error_BAD_REQUEST;
}
}
// If the packet is not yet encrypted, do so now

View File

@@ -265,6 +265,12 @@ template <typename T> bool SX126xInterface<T>::reconfigure()
return true;
}
template <typename T> int16_t SX126xInterface<T>::getCurrentRSSI()
{
float rssi = lora.getRSSI(false);
return (int16_t)round(rssi);
}
template <typename T> void SX126xInterface<T>::disableInterrupt()
{
lora.clearDio1Action();

View File

@@ -41,6 +41,8 @@ template <class T> class SX126xInterface : public RadioLibInterface
*/
T lora;
int16_t getCurrentRSSI() override;
/**
* Glue functions called from ISR land
*/

View File

@@ -325,4 +325,10 @@ template <typename T> bool SX128xInterface<T>::sleep()
return true;
}
template <typename T> int16_t SX128xInterface<T>::getCurrentRSSI()
{
float rssi = lora.getRSSI(false);
return (int16_t)round(rssi);
}
#endif

View File

@@ -35,6 +35,8 @@ template <class T> class SX128xInterface : public RadioLibInterface
*/
T lora;
int16_t getCurrentRSSI() override;
/**
* Glue functions called from ISR land
*/

View File

@@ -2,7 +2,11 @@
#include "ServerAPI.h"
#if !defined(USE_WS5500) && !defined(USE_CH390D)
#if defined(USE_ARDUINO_ETHERNET)
#include <Ethernet.h>
#else
#include <RAK13800_W5100S.h>
#endif
/**
* Provides both debug printing and, if the client starts sending protobufs to us, switches to send/receive protobufs

View File

File diff suppressed because it is too large Load Diff

View File

@@ -1,347 +0,0 @@
/*
* Copyright (C) 2020 Siara Logics (cc)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* @author Arundale Ramanathan
*
* Port for Particle (particle.io) / Aruino - Jonathan Greenblatt
*
* This file describes each function of the Unishox2 API \n
* For finding out how this API can be used in your program, \n
* please see test_unishox2.c.
*/
#ifndef unishox2
#define unishox2
#define UNISHOX_VERSION "2.0" ///< Unicode spec version
/**
* Macro switch to enable/disable output buffer length parameter in low level api \n
* Disabled by default \n
* When this macro is defined, the all the API functions \n
* except the simple API functions accept an additional parameter olen \n
* that enables the developer to pass the size of the output buffer provided \n
* so that the api function may not write beyond that length. \n
* This can be disabled if the developer knows that the buffer provided is sufficient enough \n
* so no additional parameter is passed and the program is faster since additional check \n
* for output length is not performed at each step \n
* The simple api, i.e. unishox2_(de)compress_simple will always omit the buffer length
*/
#ifndef UNISHOX_API_WITH_OUTPUT_LEN
#define UNISHOX_API_WITH_OUTPUT_LEN 1
#endif
/// Upto 8 bits of initial magic bit sequence can be included. Bit count can be specified with UNISHOX_MAGIC_BIT_LEN
#ifndef UNISHOX_MAGIC_BITS
#define UNISHOX_MAGIC_BITS 0xFF
#endif
/// Desired length of Magic bits defined by UNISHOX_MAGIC_BITS
#ifdef UNISHOX_MAGIC_BIT_LEN
#if UNISHOX_MAGIC_BIT_LEN < 0 || 9 <= UNISHOX_MAGIC_BIT_LEN
#error "UNISHOX_MAGIC_BIT_LEN need between [0, 8)"
#endif
#else
#define UNISHOX_MAGIC_BIT_LEN 1
#endif
// enum {USX_ALPHA = 0, USX_SYM, USX_NUM, USX_DICT, USX_DELTA};
/// Default Horizontal codes. When composition of text is know beforehand, the other hcodes in this section can be used to achieve
/// more compression.
#define USX_HCODES_DFLT \
(const unsigned char[]) \
{ \
0x00, 0x40, 0x80, 0xC0, 0xE0 \
}
/// Length of each default hcode
#define USX_HCODE_LENS_DFLT \
(const unsigned char[]) \
{ \
2, 2, 2, 3, 3 \
}
/// Horizontal codes preset for English Alphabet content only
#define USX_HCODES_ALPHA_ONLY \
(const unsigned char[]) \
{ \
0x00, 0x00, 0x00, 0x00, 0x00 \
}
/// Length of each Alpha only hcode
#define USX_HCODE_LENS_ALPHA_ONLY \
(const unsigned char[]) \
{ \
0, 0, 0, 0, 0 \
}
/// Horizontal codes preset for Alpha Numeric content only
#define USX_HCODES_ALPHA_NUM_ONLY \
(const unsigned char[]) \
{ \
0x00, 0x00, 0x80, 0x00, 0x00 \
}
/// Length of each Alpha numeric hcode
#define USX_HCODE_LENS_ALPHA_NUM_ONLY \
(const unsigned char[]) \
{ \
1, 0, 1, 0, 0 \
}
/// Horizontal codes preset for Alpha Numeric and Symbol content only
#define USX_HCODES_ALPHA_NUM_SYM_ONLY \
(const unsigned char[]) \
{ \
0x00, 0x80, 0xC0, 0x00, 0x00 \
}
/// Length of each Alpha numeric and symbol hcodes
#define USX_HCODE_LENS_ALPHA_NUM_SYM_ONLY \
(const unsigned char[]) \
{ \
1, 2, 2, 0, 0 \
}
/// Horizontal codes preset favouring Alphabet content
#define USX_HCODES_FAVOR_ALPHA \
(const unsigned char[]) \
{ \
0x00, 0x80, 0xA0, 0xC0, 0xE0 \
}
/// Length of each hcode favouring Alpha content
#define USX_HCODE_LENS_FAVOR_ALPHA \
(const unsigned char[]) \
{ \
1, 3, 3, 3, 3 \
}
/// Horizontal codes preset favouring repeating sequences
#define USX_HCODES_FAVOR_DICT \
(const unsigned char[]) \
{ \
0x00, 0x40, 0xC0, 0x80, 0xE0 \
}
/// Length of each hcode favouring repeating sequences
#define USX_HCODE_LENS_FAVOR_DICT \
(const unsigned char[]) \
{ \
2, 2, 3, 2, 3 \
}
/// Horizontal codes preset favouring symbols
#define USX_HCODES_FAVOR_SYM \
(const unsigned char[]) \
{ \
0x80, 0x00, 0xA0, 0xC0, 0xE0 \
}
/// Length of each hcode favouring symbols
#define USX_HCODE_LENS_FAVOR_SYM \
(const unsigned char[]) \
{ \
3, 1, 3, 3, 3 \
}
// #define USX_HCODES_FAVOR_UMLAUT {0x00, 0x40, 0xE0, 0xC0, 0x80}
// #define USX_HCODE_LENS_FAVOR_UMLAUT {2, 2, 3, 3, 2}
/// Horizontal codes preset favouring umlaut letters
#define USX_HCODES_FAVOR_UMLAUT \
(const unsigned char[]) \
{ \
0x80, 0xA0, 0xC0, 0xE0, 0x00 \
}
/// Length of each hcode favouring umlaut letters
#define USX_HCODE_LENS_FAVOR_UMLAUT \
(const unsigned char[]) \
{ \
3, 3, 3, 3, 1 \
}
/// Horizontal codes preset for no repeating sequences
#define USX_HCODES_NO_DICT \
(const unsigned char[]) \
{ \
0x00, 0x40, 0x80, 0x00, 0xC0 \
}
/// Length of each hcode for no repeating sequences
#define USX_HCODE_LENS_NO_DICT \
(const unsigned char[]) \
{ \
2, 2, 2, 0, 2 \
}
/// Horizontal codes preset for no Unicode characters
#define USX_HCODES_NO_UNI \
(const unsigned char[]) \
{ \
0x00, 0x40, 0x80, 0xC0, 0x00 \
}
/// Length of each hcode for no Unicode characters
#define USX_HCODE_LENS_NO_UNI \
(const unsigned char[]) \
{ \
2, 2, 2, 2, 0 \
}
extern const char *USX_FREQ_SEQ_DFLT[];
extern const char *USX_FREQ_SEQ_TXT[];
extern const char *USX_FREQ_SEQ_URL[];
extern const char *USX_FREQ_SEQ_JSON[];
extern const char *USX_FREQ_SEQ_HTML[];
extern const char *USX_FREQ_SEQ_XML[];
extern const char *USX_TEMPLATES[];
/// Default preset parameter set. When composition of text is know beforehand, the other parameter sets in this section can be
/// used to achieve more compression.
#define USX_PSET_DFLT USX_HCODES_DFLT, USX_HCODE_LENS_DFLT, USX_FREQ_SEQ_DFLT, USX_TEMPLATES
/// Preset parameter set for English Alphabet only content
#define USX_PSET_ALPHA_ONLY USX_HCODES_ALPHA_ONLY, USX_HCODE_LENS_ALPHA_ONLY, USX_FREQ_SEQ_TXT, USX_TEMPLATES
/// Preset parameter set for Alpha numeric content
#define USX_PSET_ALPHA_NUM_ONLY USX_HCODES_ALPHA_NUM_ONLY, USX_HCODE_LENS_ALPHA_NUM_ONLY, USX_FREQ_SEQ_TXT, USX_TEMPLATES
/// Preset parameter set for Alpha numeric and symbol content
#define USX_PSET_ALPHA_NUM_SYM_ONLY \
USX_HCODES_ALPHA_NUM_SYM_ONLY, USX_HCODE_LENS_ALPHA_NUM_SYM_ONLY, USX_FREQ_SEQ_DFLT, USX_TEMPLATES
/// Preset parameter set for Alpha numeric symbol content having predominantly text
#define USX_PSET_ALPHA_NUM_SYM_ONLY_TXT \
USX_HCODES_ALPHA_NUM_SYM_ONLY, USX_HCODE_LENS_ALPHA_NUM_SYM_ONLY, USX_FREQ_SEQ_DFLT, USX_TEMPLATES
/// Preset parameter set favouring Alphabet content
#define USX_PSET_FAVOR_ALPHA USX_HCODES_FAVOR_ALPHA, USX_HCODE_LENS_FAVOR_ALPHA, USX_FREQ_SEQ_TXT, USX_TEMPLATES
/// Preset parameter set favouring repeating sequences
#define USX_PSET_FAVOR_DICT USX_HCODES_FAVOR_DICT, USX_HCODE_LENS_FAVOR_DICT, USX_FREQ_SEQ_DFLT, USX_TEMPLATES
/// Preset parameter set favouring symbols
#define USX_PSET_FAVOR_SYM USX_HCODES_FAVOR_SYM, USX_HCODE_LENS_FAVOR_SYM, USX_FREQ_SEQ_DFLT, USX_TEMPLATES
/// Preset parameter set favouring unlaut letters
#define USX_PSET_FAVOR_UMLAUT USX_HCODES_FAVOR_UMLAUT, USX_HCODE_LENS_FAVOR_UMLAUT, USX_FREQ_SEQ_DFLT, USX_TEMPLATES
/// Preset parameter set for when there are no repeating sequences
#define USX_PSET_NO_DICT USX_HCODES_NO_DICT, USX_HCODE_LENS_NO_DICT, USX_FREQ_SEQ_DFLT, USX_TEMPLATES
/// Preset parameter set for when there are no unicode symbols
#define USX_PSET_NO_UNI USX_HCODES_NO_UNI, USX_HCODE_LENS_NO_UNI, USX_FREQ_SEQ_DFLT, USX_TEMPLATES
/// Preset parameter set for when there are no unicode symbols favouring text
#define USX_PSET_NO_UNI_FAVOR_TEXT USX_HCODES_NO_UNI, USX_HCODE_LENS_NO_UNI, USX_FREQ_SEQ_TXT, USX_TEMPLATES
/// Preset parameter set favouring URL content
#define USX_PSET_URL USX_HCODES_DFLT, USX_HCODE_LENS_DFLT, USX_FREQ_SEQ_URL, USX_TEMPLATES
/// Preset parameter set favouring JSON content
#define USX_PSET_JSON USX_HCODES_DFLT, USX_HCODE_LENS_DFLT, USX_FREQ_SEQ_JSON, USX_TEMPLATES
/// Preset parameter set favouring JSON content having no Unicode symbols
#define USX_PSET_JSON_NO_UNI USX_HCODES_NO_UNI, USX_HCODE_LENS_NO_UNI, USX_FREQ_SEQ_JSON, USX_TEMPLATES
/// Preset parameter set favouring XML content
#define USX_PSET_XML USX_HCODES_DFLT, USX_HCODE_LENS_DFLT, USX_FREQ_SEQ_XML, USX_TEMPLATES
/// Preset parameter set favouring HTML content
#define USX_PSET_HTML USX_HCODES_DFLT, USX_HCODE_LENS_DFLT, USX_FREQ_SEQ_HTML, USX_TEMPLATES
/**
* This structure is used when a string array needs to be compressed.
* This is passed as a parameter to the unishox2_decompress_lines() function
*/
struct us_lnk_lst {
char *data;
struct us_lnk_lst *previous;
};
/**
* This macro is for internal use, but builds upon the macro UNISHOX_API_WITH_OUTPUT_LEN
* When the macro UNISHOX_API_WITH_OUTPUT_LEN is defined, the all the API functions
* except the simple API functions accept an additional parameter olen
* that enables the developer to pass the size of the output buffer provided
* so that the api function may not write beyond that length.
* This can be disabled if the developer knows that the buffer provided is sufficient enough
* so no additional parameter is passed and the program is faster since additional check
* for output length is not performed at each step
*/
#if defined(UNISHOX_API_WITH_OUTPUT_LEN) && UNISHOX_API_WITH_OUTPUT_LEN != 0
#define UNISHOX_API_OUT_AND_LEN(out, olen) out, olen
#else
#define UNISHOX_API_OUT_AND_LEN(out, olen) out
#endif
/**
* Simple API for compressing a string
* @param[in] in Input ASCII / UTF-8 string
* @param[in] len length in bytes
* @param[out] out output buffer - should be large enough to hold compressed output
*/
extern int unishox2_compress_simple(const char *in, int len, char *out);
/**
* Simple API for decompressing a string
* @param[in] in Input compressed bytes (output of unishox2_compress functions)
* @param[in] len length of 'in' in bytes
* @param[out] out output buffer for ASCII / UTF-8 string - should be large enough
*/
extern int unishox2_decompress_simple(const char *in, int len, char *out);
/**
* Comprehensive API for compressing a string
*
* Presets are available for the last four parameters so they can be passed as single parameter. \n
* See USX_PSET_* macros. Example call: \n
* unishox2_compress(in, len, out, olen, USX_PSET_ALPHA_ONLY);
*
* @param[in] in Input ASCII / UTF-8 string
* @param[in] len length in bytes
* @param[out] out output buffer - should be large enough to hold compressed output
* @param[in] olen length of 'out' buffer in bytes. Can be omitted if sufficient buffer is provided
* @param[in] usx_hcodes Horizontal codes (array of bytes). See macro section for samples.
* @param[in] usx_hcode_lens Length of each element in usx_hcodes array
* @param[in] usx_freq_seq Frequently occurring sequences. See USX_FREQ_SEQ_* macros for samples
* @param[in] usx_templates Templates of frequently occurring patterns. See USX_TEMPLATES macro.
*/
extern int unishox2_compress(const char *in, int len, UNISHOX_API_OUT_AND_LEN(char *out, int olen),
const unsigned char usx_hcodes[], const unsigned char usx_hcode_lens[], const char *usx_freq_seq[],
const char *usx_templates[]);
/**
* Comprehensive API for de-compressing a string
*
* Presets are available for the last four parameters so they can be passed as single parameter. \n
* See USX_PSET_* macros. Example call: \n
* unishox2_decompress(in, len, out, olen, USX_PSET_ALPHA_ONLY);
*
* @param[in] in Input compressed bytes (output of unishox2_compress functions)
* @param[in] len length of 'in' in bytes
* @param[out] out output buffer - should be large enough to hold de-compressed output
* @param[in] olen length of 'out' buffer in bytes. Can be omitted if sufficient buffer is provided
* @param[in] usx_hcodes Horizontal codes (array of bytes). See macro section for samples.
* @param[in] usx_hcode_lens Length of each element in usx_hcodes array
* @param[in] usx_freq_seq Frequently occurring sequences. See USX_FREQ_SEQ_* macros for samples
* @param[in] usx_templates Templates of frequently occurring patterns. See USX_TEMPLATES macro.
*/
extern int unishox2_decompress(const char *in, int len, UNISHOX_API_OUT_AND_LEN(char *out, int olen),
const unsigned char usx_hcodes[], const unsigned char usx_hcode_lens[], const char *usx_freq_seq[],
const char *usx_templates[]);
/**
* More Comprehensive API for compressing array of strings
*
* See unishox2_compress() function for parameter definitions. \n
* This function takes an additional parameter, i.e. 'prev_lines' - the usx_lnk_lst structure \n
* See -g parameter in test_unishox2.c to find out how this can be used. \n
* This function is used when an array of strings need to be compressed \n
* and stored in a compressed array of bytes for use as a constant in other programs \n
* where each element of the array can be decompressed and used at runtime.
*/
extern int unishox2_compress_lines(const char *in, int len, UNISHOX_API_OUT_AND_LEN(char *out, int olen),
const unsigned char usx_hcodes[], const unsigned char usx_hcode_lens[],
const char *usx_freq_seq[], const char *usx_templates[], struct us_lnk_lst *prev_lines);
/**
* More Comprehensive API for de-compressing array of strings \n
* This function is not be used in conjuction with unishox2_compress_lines()
*
* See unishox2_decompress() function for parameter definitions. \n
* Typically an array is compressed using unishox2_compress_lines() and \n
* a header (.h) file is generated using the resultant compressed array. \n
* This header file can be used in another program with another decompress \n
* routine which takes this compressed array as parameter and index to be \n
* decompressed.
*/
extern int unishox2_decompress_lines(const char *in, int len, UNISHOX_API_OUT_AND_LEN(char *out, int olen),
const unsigned char usx_hcodes[], const unsigned char usx_hcode_lens[],
const char *usx_freq_seq[], const char *usx_templates[], struct us_lnk_lst *prev_lines);
#endif

View File

@@ -6,7 +6,13 @@
#include "main.h"
#include "mesh/api/ethServerAPI.h"
#include "target_specific.h"
#ifdef USE_ARDUINO_ETHERNET
#include <Ethernet.h> // arduino-libraries/Ethernet — supports W5100/W5200/W5500
// Shorter DHCP timeout so LoRa startup isn't blocked when no DHCP server is present.
#define ETH_DHCP_TIMEOUT_MS 10000
#else
#include <RAK13800_W5100S.h>
#endif
#include <SPI.h>
#if HAS_NETWORKING && !defined(USE_WS5500) && !defined(USE_CH390D)
@@ -69,6 +75,13 @@ static int32_t reconnectETH()
delay(100);
#endif
#ifdef USE_ARDUINO_ETHERNET // Re-configure SPI0 for the W5500 module
SPI.setRX(ETH_SPI0_MISO);
SPI.setSCK(ETH_SPI0_SCK);
SPI.setTX(ETH_SPI0_MOSI);
SPI.begin();
Ethernet.init(PIN_ETHERNET_SS);
#else
#ifdef RAK11310
ETH_SPI_PORT.setSCK(PIN_SPI0_SCK);
ETH_SPI_PORT.setTX(PIN_SPI0_MOSI);
@@ -76,10 +89,15 @@ static int32_t reconnectETH()
ETH_SPI_PORT.begin();
#endif
Ethernet.init(ETH_SPI_PORT, PIN_ETHERNET_SS);
#endif
int status = 0;
if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_DHCP) {
#ifdef ETH_DHCP_TIMEOUT_MS
status = Ethernet.begin(expectedMac, ETH_DHCP_TIMEOUT_MS);
#else
status = Ethernet.begin(expectedMac);
#endif
} else if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_STATIC) {
Ethernet.begin(expectedMac, config.network.ipv4_config.ip, config.network.ipv4_config.dns,
config.network.ipv4_config.gateway, config.network.ipv4_config.subnet);
@@ -182,6 +200,13 @@ bool initEthernet()
digitalWrite(PIN_ETHERNET_RESET, HIGH); // Reset Time.
#endif
#ifdef USE_ARDUINO_ETHERNET // Configure SPI0 for the W5500 module
SPI.setRX(ETH_SPI0_MISO);
SPI.setSCK(ETH_SPI0_SCK);
SPI.setTX(ETH_SPI0_MOSI);
SPI.begin();
Ethernet.init(PIN_ETHERNET_SS);
#else
#ifdef RAK11310 // Initialize the SPI port
ETH_SPI_PORT.setSCK(PIN_SPI0_SCK);
ETH_SPI_PORT.setTX(PIN_SPI0_MOSI);
@@ -189,6 +214,7 @@ bool initEthernet()
ETH_SPI_PORT.begin();
#endif
Ethernet.init(ETH_SPI_PORT, PIN_ETHERNET_SS);
#endif
uint8_t mac[6];
@@ -201,7 +227,11 @@ bool initEthernet()
if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_DHCP) {
LOG_INFO("Start Ethernet DHCP");
#ifdef ETH_DHCP_TIMEOUT_MS
status = Ethernet.begin(mac, ETH_DHCP_TIMEOUT_MS);
#else
status = Ethernet.begin(mac);
#endif
} else if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_STATIC) {
LOG_INFO("Start Ethernet Static");
Ethernet.begin(mac, config.network.ipv4_config.ip, config.network.ipv4_config.dns, config.network.ipv4_config.gateway,

View File

@@ -198,6 +198,28 @@ typedef struct _meshtastic_LockdownAuth {
way to reset the session clock is a reboot, which costs a boot
from the on-flash, HMAC-bound counter. */
uint32_t max_session_seconds;
/* Disable lockdown mode. Requires a valid passphrase in the same
message (the device must prove the operator owns it before
reverting at-rest encryption). On success the firmware decrypts
every stored config / channel / nodedb file back to plaintext,
removes the wrapped DEK, unlock token, monotonic-counter, and
backoff files, and reboots out of lockdown.
This is the inverse of the provision/unlock path: it is how the
client app's "lockdown mode" toggle returns a device to normal
operation.
NOT reversed by this operation: APPROTECT. Once the debug port
lockout has been burned (on silicon where it is effective) it is
permanent — disabling lockdown decrypts your data and removes the
access gates, but the SWD/JTAG port stays locked for the life of
the device (recoverable only via a full chip erase over a debug
probe, which destroys all data). Clients should make this
irreversibility clear at the moment lockdown is first enabled.
When true the passphrase field is still required; boots_remaining,
valid_until_epoch, max_session_seconds, and lock_now are ignored. */
bool disable;
} meshtastic_LockdownAuth;
/* Parameters for setting up Meshtastic for ameteur radio usage */
@@ -521,7 +543,7 @@ extern "C" {
#define meshtastic_AdminMessage_init_default {0, {0}, {0, {0}}}
#define meshtastic_AdminMessage_InputEvent_init_default {0, 0, 0, 0}
#define meshtastic_AdminMessage_OTAEvent_init_default {_meshtastic_OTAMode_MIN, {0, {0}}}
#define meshtastic_LockdownAuth_init_default {{0, {0}}, 0, 0, 0, 0}
#define meshtastic_LockdownAuth_init_default {{0, {0}}, 0, 0, 0, 0, 0}
#define meshtastic_HamParameters_init_default {"", 0, 0, ""}
#define meshtastic_NodeRemoteHardwarePinsResponse_init_default {0, {meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default, meshtastic_NodeRemoteHardwarePin_init_default}}
#define meshtastic_SharedContact_init_default {0, false, meshtastic_User_init_default, 0, 0}
@@ -534,7 +556,7 @@ extern "C" {
#define meshtastic_AdminMessage_init_zero {0, {0}, {0, {0}}}
#define meshtastic_AdminMessage_InputEvent_init_zero {0, 0, 0, 0}
#define meshtastic_AdminMessage_OTAEvent_init_zero {_meshtastic_OTAMode_MIN, {0, {0}}}
#define meshtastic_LockdownAuth_init_zero {{0, {0}}, 0, 0, 0, 0}
#define meshtastic_LockdownAuth_init_zero {{0, {0}}, 0, 0, 0, 0, 0}
#define meshtastic_HamParameters_init_zero {"", 0, 0, ""}
#define meshtastic_NodeRemoteHardwarePinsResponse_init_zero {0, {meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero, meshtastic_NodeRemoteHardwarePin_init_zero}}
#define meshtastic_SharedContact_init_zero {0, false, meshtastic_User_init_zero, 0, 0}
@@ -557,6 +579,7 @@ extern "C" {
#define meshtastic_LockdownAuth_valid_until_epoch_tag 3
#define meshtastic_LockdownAuth_lock_now_tag 4
#define meshtastic_LockdownAuth_max_session_seconds_tag 5
#define meshtastic_LockdownAuth_disable_tag 6
#define meshtastic_HamParameters_call_sign_tag 1
#define meshtastic_HamParameters_tx_power_tag 2
#define meshtastic_HamParameters_frequency_tag 3
@@ -754,7 +777,8 @@ X(a, STATIC, SINGULAR, BYTES, passphrase, 1) \
X(a, STATIC, SINGULAR, UINT32, boots_remaining, 2) \
X(a, STATIC, SINGULAR, UINT32, valid_until_epoch, 3) \
X(a, STATIC, SINGULAR, BOOL, lock_now, 4) \
X(a, STATIC, SINGULAR, UINT32, max_session_seconds, 5)
X(a, STATIC, SINGULAR, UINT32, max_session_seconds, 5) \
X(a, STATIC, SINGULAR, BOOL, disable, 6)
#define meshtastic_LockdownAuth_CALLBACK NULL
#define meshtastic_LockdownAuth_DEFAULT NULL
@@ -869,7 +893,7 @@ extern const pb_msgdesc_t meshtastic_SHTXX_config_msg;
#define meshtastic_AdminMessage_size 511
#define meshtastic_HamParameters_size 31
#define meshtastic_KeyVerificationAdmin_size 25
#define meshtastic_LockdownAuth_size 54
#define meshtastic_LockdownAuth_size 56
#define meshtastic_NodeRemoteHardwarePinsResponse_size 496
#define meshtastic_SCD30_config_size 27
#define meshtastic_SCD4X_config_size 29

View File

@@ -30,7 +30,7 @@ PB_BIND(meshtastic_AircraftTrack, meshtastic_AircraftTrack, AUTO)
PB_BIND(meshtastic_CotGeoPoint, meshtastic_CotGeoPoint, AUTO)
PB_BIND(meshtastic_DrawnShape, meshtastic_DrawnShape, 2)
PB_BIND(meshtastic_DrawnShape, meshtastic_DrawnShape, AUTO)
PB_BIND(meshtastic_Marker, meshtastic_Marker, AUTO)
@@ -63,6 +63,15 @@ PB_BIND(meshtastic_TAKEnvironment, meshtastic_TAKEnvironment, AUTO)
PB_BIND(meshtastic_SensorFov, meshtastic_SensorFov, AUTO)
PB_BIND(meshtastic_TakTalkMessage, meshtastic_TakTalkMessage, AUTO)
PB_BIND(meshtastic_TakTalkRoomData, meshtastic_TakTalkRoomData, AUTO)
PB_BIND(meshtastic_Marti, meshtastic_Marti, AUTO)
PB_BIND(meshtastic_TAKPacketV2, meshtastic_TAKPacketV2, 2)

View File

@@ -325,7 +325,15 @@ typedef enum _meshtastic_CotType {
meshtastic_CotType_CotType_b_a_o_c = 123,
/* t-s: Task / engage request. Structured payload carried via the new
TaskRequest typed variant. */
meshtastic_CotType_CotType_t_s = 124
meshtastic_CotType_CotType_t_s = 124,
/* m-t-t: TAKTALK voice/text chat message. Payload carried via the
TakTalkMessage typed variant (text, chatroom_id, lang, from_voice). */
meshtastic_CotType_CotType_m_t_t = 125,
/* y-: TAKTALK room/membership broadcast. Payload carried via the
TakTalkRoomData typed variant (sender_callsign, room_id, room_name,
participants). The CoT type literally has a trailing dash and no
second atom — not a typo. */
meshtastic_CotType_CotType_y = 126
} meshtastic_CotType;
/* Geopoint and altitude source */
@@ -553,6 +561,18 @@ typedef struct _meshtastic_GeoChat {
/* Receipt kind discriminator. See ReceiptType doc. Default ReceiptType_None
means this is a regular chat message, not a receipt. */
meshtastic_GeoChat_ReceiptType receipt_type;
/* BCP-47-ish language tag or human-readable name (e.g. "en", "English")
that the originator's TAKTALK plugin recorded for the message. */
pb_callback_t lang;
/* TAKTALK chatroom UUID (e.g. "30b2755c-c547-44ef-a0cc-cdbd8a15616f") that
the receiver's TAKTALK plugin uses to thread the message under the
right room. Resolved to a friendly name via TakTalkRoomData broadcasts. */
pb_callback_t room_id;
/* TAKTALK voice profile pointer. Often empty in practice (the empty
marker `<voice_profile_id/>` still signals TAKTALK origination), so
receivers should treat empty-but-present as the equivalent of the
marker rather than a missing field. */
pb_callback_t voice_profile_id;
} meshtastic_GeoChat;
/* ATAK Group
@@ -715,12 +735,7 @@ typedef struct _meshtastic_DrawnShape {
uint32_t fill_argb;
/* Whether labels are rendered on this shape. */
bool labels_on;
/* Vertex list for polyline/polygon/rectangle shapes. Capped at 32 by
the nanopb pool; senders MUST truncate longer inputs and set
`truncated = true`. */
pb_size_t vertices_count;
meshtastic_CotGeoPoint vertices[32];
/* True if the sender truncated `vertices` to fit the pool. */
/* True if the sender truncated the vertex columns to fit the pool. */
bool truncated; /* --- Bullseye-only fields. All ignored unless kind == Kind_Bullseye. --- */
/* Bullseye distance in meters * 10 (e.g. 3285 = 328.5 m). 0 = unset. */
uint32_t bullseye_distance_dm;
@@ -734,6 +749,8 @@ typedef struct _meshtastic_DrawnShape {
uint8_t bullseye_flags;
/* Bullseye reference UID (anchor marker). Empty = anchor is self. */
char bullseye_uid_ref[48];
pb_callback_t vertex_lat_deltas;
pb_callback_t vertex_lon_deltas;
} meshtastic_DrawnShape;
/* Fixed point of interest: spot marker, waypoint, checkpoint, 2525 symbol,
@@ -1068,6 +1085,87 @@ typedef struct _meshtastic_SensorFov {
pb_callback_t model;
} meshtastic_SensorFov;
/* TAKTALK chat message payload (CoT type m-t-t).
TAKTALK is an ATAK plugin for voice + text team messaging. The voice
audio stream goes over UDP/RTP and is NOT carried by the mesh — only
the text envelope (this message) is. `from_voice` marks messages sent
via push-to-talk speech-to-text so receivers can render a mic icon
next to the text.
Wire shape inside <event type="m-t-t">/<detail>:
<callsign>...</callsign> - mapped to TAKPacketV2.callsign
<lang>English</lang> - lang
<text>...</text> - text
<chatroom-id>1</chatroom-id> - chatroom_id
<voice/> - presence sets from_voice = true */
typedef struct _meshtastic_TakTalkMessage {
/* The text body of the TAKTALK message (speech-to-text transcript when
from_voice = true, typed message otherwise). */
pb_callback_t text;
/* TAKTALK chatroom identifier. May be a short id like "1" for the
default room or a UUID like "30b2755c-c547-44ef-a0cc-cdbd8a15616f"
for custom rooms (resolved by TakTalkRoomData broadcasts).
Empty = broadcast room. */
pb_callback_t chatroom_id;
/* BCP-47-ish language tag or human-readable name (e.g. "en", "English").
Empty = unspecified. */
pb_callback_t lang;
/* True when the source CoT carried a <voice/> marker, i.e. the message
originated as push-to-talk speech-to-text. Lets receivers show a mic
icon. Proto3 only encodes when true so empty payload cost is 0 bytes. */
bool from_voice;
} meshtastic_TakTalkMessage;
/* TAKTALK room/membership broadcast (CoT type y-).
Announces a TAKTALK chatroom's friendly name and roster so peers can
resolve room UUIDs (used in TakTalkMessage.chatroom_id and
GeoChat.room_id) to a display name and participant list. Not a chat
message itself — these events are emitted by TAKTALK when rooms are
created or memberships change. */
typedef struct _meshtastic_TakTalkRoomData {
/* Callsign of the device broadcasting the room state (typically the
room owner / latest writer).
DEPRECATED in v0.3.2: always equals TAKPacketV2.callsign, so the wire
byte was redundant. Builders stop emitting this field in v0.3.2;
parsers still read it for one release so v0.3.1-encoded packets decode
cleanly. To be removed entirely in v0.4.x. */
pb_callback_t sender_callsign;
/* Room UUID, matches TakTalkMessage.chatroom_id / GeoChat.room_id on
messages routed into this room. */
pb_callback_t room_id;
/* Friendly display name for the room (e.g. "test", "Alpha Team"). */
pb_callback_t room_name;
/* Member callsigns. Wire-encoded as repeated strings; the underlying
CoT carries them as a single <chatroom-participants>A,B,C</> element
which parsers split / builders join on ','. */
pb_callback_t participants;
} meshtastic_TakTalkRoomData;
/* ATAK directed-routing recipient list (CoT <marti><dest callsign='X'/>…</marti>).
Present when an event is addressed to specific TAK users rather than the
broadcast group. TAKTALK gates voice TTS on this element matching the
receiver's callsign; directed b-t-f chats use it for the same purpose. A
missing <marti> means "broadcast to all peers", which is the default for
PLI, alerts, drawings, and most situational-awareness events.
Carried as repeated strings (not indexes into a per-packet table) because
the typical event has 1-2 destinations and table overhead would erase the
savings. Receivers that need the original XML element rebuild it from
dest_callsign on emit. */
typedef struct _meshtastic_Marti {
/* Recipient callsigns. Order is preserved end-to-end so receivers can show
primary-vs-cc distinction the same way ATAK does.
If dest_callsign is [TAKPacketV2.callsign] (self-addressed, unusual but
legal — e.g. ATAK echoing back to its own room), the builder still emits
the element so loopback shapes round-trip cleanly. */
pb_callback_t dest_callsign;
} meshtastic_Marti;
typedef PB_BYTES_ARRAY_T(220) meshtastic_TAKPacketV2_raw_detail_t;
/* ATAK v2 packet with expanded CoT field support and zstd dictionary compression.
Sent on ATAK_PLUGIN_V2 port. The wire payload is:
@@ -1089,7 +1187,14 @@ typedef struct _meshtastic_TAKPacketV2 {
int32_t latitude_i;
/* Longitude, multiply by 1e-7 to get degrees in floating point */
int32_t longitude_i;
/* Altitude in meters (HAE) */
/* Altitude in meters (HAE). ATAK's "no altitude" sentinel is hae=9999999.0.
NOTE: an earlier v0.4.0 attempt made this `optional` to omit the 9999999
sentinel from the wire, but measurement showed it was net-negative: the
zstd dictionary already compresses the literal 9999999 to ~nothing, while
proto3 `optional` forces a genuine 0 m HAE (common on routes/drawings that
carry hae="0.0" or omit hae → parsed as 0) to encode explicitly (+2 bytes),
which REGRESSED the worst-case route fixture. Kept as a plain field. */
int32_t altitude;
/* Speed in cm/s */
uint32_t speed;
@@ -1135,10 +1240,18 @@ typedef struct _meshtastic_TAKPacketV2 {
/* Sensor field-of-view cone (camera, FLIR, laser, etc.). From <sensor>. */
bool has_sensor_fov;
meshtastic_SensorFov sensor_fov;
/* Directed-routing recipient list (CoT <marti><dest callsign='X'/>…</marti>).
Empty / unset = broadcast to all peers (the default for situational-awareness
events). Populated for TAKTALK m-t-t, directed b-t-f DMs, and any other CoT
shape that ATAK addresses to specific recipients. TAKTALK gates voice TTS
playback on this element matching the receiver's callsign, so dropping it
silently breaks voice messaging end-to-end.
See Marti. */
bool has_marti;
meshtastic_Marti marti;
pb_size_t which_payload_variant;
union {
/* Position report (true = PLI, no extra fields beyond the common ones above) */
bool pli;
/* ATAK GeoChat message */
meshtastic_GeoChat chat;
/* Aircraft track data (ADS-B, military air) */
@@ -1163,6 +1276,14 @@ typedef struct _meshtastic_TAKPacketV2 {
meshtastic_EmergencyAlert emergency;
/* Task / engage request. See TaskRequest. */
meshtastic_TaskRequest task;
/* TAKTALK chat message (CoT type m-t-t). See TakTalkMessage.
Voice audio itself rides UDP/RTP outside the mesh; this carries the
text envelope plus a from_voice marker for receiver UX. */
meshtastic_TakTalkMessage taktalk;
/* TAKTALK room/membership broadcast (CoT type y-). See TakTalkRoomData.
Resolves room UUIDs (used in TakTalkMessage.chatroom_id and
GeoChat.room_id) to display name + roster on receivers. */
meshtastic_TakTalkRoomData taktalk_room;
} payload_variant;
} meshtastic_TAKPacketV2;
@@ -1185,8 +1306,8 @@ extern "C" {
#define _meshtastic_CotHow_ARRAYSIZE ((meshtastic_CotHow)(meshtastic_CotHow_CotHow_m_s+1))
#define _meshtastic_CotType_MIN meshtastic_CotType_CotType_Other
#define _meshtastic_CotType_MAX meshtastic_CotType_CotType_t_s
#define _meshtastic_CotType_ARRAYSIZE ((meshtastic_CotType)(meshtastic_CotType_CotType_t_s+1))
#define _meshtastic_CotType_MAX meshtastic_CotType_CotType_y
#define _meshtastic_CotType_ARRAYSIZE ((meshtastic_CotType)(meshtastic_CotType_CotType_y+1))
#define _meshtastic_GeoPointSource_MIN meshtastic_GeoPointSource_GeoPointSource_Unspecified
#define _meshtastic_GeoPointSource_MAX meshtastic_GeoPointSource_GeoPointSource_NETWORK
@@ -1282,6 +1403,9 @@ extern "C" {
#define meshtastic_SensorFov_type_ENUMTYPE meshtastic_SensorFov_SensorType
#define meshtastic_TAKPacketV2_cot_type_id_ENUMTYPE meshtastic_CotType
#define meshtastic_TAKPacketV2_how_ENUMTYPE meshtastic_CotHow
#define meshtastic_TAKPacketV2_team_ENUMTYPE meshtastic_Team
@@ -1292,14 +1416,14 @@ extern "C" {
/* Initializer values for message structs */
#define meshtastic_TAKPacket_init_default {0, false, meshtastic_Contact_init_default, false, meshtastic_Group_init_default, false, meshtastic_Status_init_default, 0, {meshtastic_PLI_init_default}}
#define meshtastic_GeoChat_init_default {"", false, "", false, "", "", _meshtastic_GeoChat_ReceiptType_MIN}
#define meshtastic_GeoChat_init_default {"", false, "", false, "", "", _meshtastic_GeoChat_ReceiptType_MIN, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}}
#define meshtastic_Group_init_default {_meshtastic_MemberRole_MIN, _meshtastic_Team_MIN}
#define meshtastic_Status_init_default {0}
#define meshtastic_Contact_init_default {"", ""}
#define meshtastic_PLI_init_default {0, 0, 0, 0, 0}
#define meshtastic_AircraftTrack_init_default {"", "", "", "", 0, "", 0, 0, ""}
#define meshtastic_CotGeoPoint_init_default {0, 0}
#define meshtastic_DrawnShape_init_default {_meshtastic_DrawnShape_Kind_MIN, _meshtastic_DrawnShape_StyleMode_MIN, 0, 0, 0, _meshtastic_Team_MIN, 0, 0, _meshtastic_Team_MIN, 0, 0, 0, {meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default, meshtastic_CotGeoPoint_init_default}, 0, 0, 0, 0, ""}
#define meshtastic_DrawnShape_init_default {_meshtastic_DrawnShape_Kind_MIN, _meshtastic_DrawnShape_StyleMode_MIN, 0, 0, 0, _meshtastic_Team_MIN, 0, 0, _meshtastic_Team_MIN, 0, 0, 0, 0, 0, 0, "", {{NULL}, NULL}, {{NULL}, NULL}}
#define meshtastic_Marker_init_default {_meshtastic_Marker_Kind_MIN, _meshtastic_Team_MIN, 0, 0, "", "", "", ""}
#define meshtastic_RangeAndBearing_init_default {false, meshtastic_CotGeoPoint_init_default, "", 0, 0, _meshtastic_Team_MIN, 0, 0}
#define meshtastic_Route_init_default {_meshtastic_Route_Method_MIN, _meshtastic_Route_Direction_MIN, "", 0, 0, {meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default, meshtastic_Route_Link_init_default}, 0}
@@ -1310,16 +1434,19 @@ extern "C" {
#define meshtastic_TaskRequest_init_default {"", "", "", _meshtastic_TaskRequest_Priority_MIN, _meshtastic_TaskRequest_Status_MIN, ""}
#define meshtastic_TAKEnvironment_init_default {0, 0, 0}
#define meshtastic_SensorFov_init_default {_meshtastic_SensorFov_SensorType_MIN, 0, false, 0, 0, 0, 0, 0, {{NULL}, NULL}}
#define meshtastic_TAKPacketV2_init_default {_meshtastic_CotType_MIN, _meshtastic_CotHow_MIN, "", _meshtastic_Team_MIN, _meshtastic_MemberRole_MIN, 0, 0, 0, 0, 0, 0, _meshtastic_GeoPointSource_MIN, _meshtastic_GeoPointSource_MIN, "", "", 0, "", "", "", "", "", "", "", {{NULL}, NULL}, false, meshtastic_TAKEnvironment_init_default, false, meshtastic_SensorFov_init_default, 0, {0}}
#define meshtastic_TakTalkMessage_init_default {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, 0}
#define meshtastic_TakTalkRoomData_init_default {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}}
#define meshtastic_Marti_init_default {{{NULL}, NULL}}
#define meshtastic_TAKPacketV2_init_default {_meshtastic_CotType_MIN, _meshtastic_CotHow_MIN, "", _meshtastic_Team_MIN, _meshtastic_MemberRole_MIN, 0, 0, 0, 0, 0, 0, _meshtastic_GeoPointSource_MIN, _meshtastic_GeoPointSource_MIN, "", "", 0, "", "", "", "", "", "", "", {{NULL}, NULL}, false, meshtastic_TAKEnvironment_init_default, false, meshtastic_SensorFov_init_default, false, meshtastic_Marti_init_default, 0, {meshtastic_GeoChat_init_default}}
#define meshtastic_TAKPacket_init_zero {0, false, meshtastic_Contact_init_zero, false, meshtastic_Group_init_zero, false, meshtastic_Status_init_zero, 0, {meshtastic_PLI_init_zero}}
#define meshtastic_GeoChat_init_zero {"", false, "", false, "", "", _meshtastic_GeoChat_ReceiptType_MIN}
#define meshtastic_GeoChat_init_zero {"", false, "", false, "", "", _meshtastic_GeoChat_ReceiptType_MIN, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}}
#define meshtastic_Group_init_zero {_meshtastic_MemberRole_MIN, _meshtastic_Team_MIN}
#define meshtastic_Status_init_zero {0}
#define meshtastic_Contact_init_zero {"", ""}
#define meshtastic_PLI_init_zero {0, 0, 0, 0, 0}
#define meshtastic_AircraftTrack_init_zero {"", "", "", "", 0, "", 0, 0, ""}
#define meshtastic_CotGeoPoint_init_zero {0, 0}
#define meshtastic_DrawnShape_init_zero {_meshtastic_DrawnShape_Kind_MIN, _meshtastic_DrawnShape_StyleMode_MIN, 0, 0, 0, _meshtastic_Team_MIN, 0, 0, _meshtastic_Team_MIN, 0, 0, 0, {meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero, meshtastic_CotGeoPoint_init_zero}, 0, 0, 0, 0, ""}
#define meshtastic_DrawnShape_init_zero {_meshtastic_DrawnShape_Kind_MIN, _meshtastic_DrawnShape_StyleMode_MIN, 0, 0, 0, _meshtastic_Team_MIN, 0, 0, _meshtastic_Team_MIN, 0, 0, 0, 0, 0, 0, "", {{NULL}, NULL}, {{NULL}, NULL}}
#define meshtastic_Marker_init_zero {_meshtastic_Marker_Kind_MIN, _meshtastic_Team_MIN, 0, 0, "", "", "", ""}
#define meshtastic_RangeAndBearing_init_zero {false, meshtastic_CotGeoPoint_init_zero, "", 0, 0, _meshtastic_Team_MIN, 0, 0}
#define meshtastic_Route_init_zero {_meshtastic_Route_Method_MIN, _meshtastic_Route_Direction_MIN, "", 0, 0, {meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero, meshtastic_Route_Link_init_zero}, 0}
@@ -1330,7 +1457,10 @@ extern "C" {
#define meshtastic_TaskRequest_init_zero {"", "", "", _meshtastic_TaskRequest_Priority_MIN, _meshtastic_TaskRequest_Status_MIN, ""}
#define meshtastic_TAKEnvironment_init_zero {0, 0, 0}
#define meshtastic_SensorFov_init_zero {_meshtastic_SensorFov_SensorType_MIN, 0, false, 0, 0, 0, 0, 0, {{NULL}, NULL}}
#define meshtastic_TAKPacketV2_init_zero {_meshtastic_CotType_MIN, _meshtastic_CotHow_MIN, "", _meshtastic_Team_MIN, _meshtastic_MemberRole_MIN, 0, 0, 0, 0, 0, 0, _meshtastic_GeoPointSource_MIN, _meshtastic_GeoPointSource_MIN, "", "", 0, "", "", "", "", "", "", "", {{NULL}, NULL}, false, meshtastic_TAKEnvironment_init_zero, false, meshtastic_SensorFov_init_zero, 0, {0}}
#define meshtastic_TakTalkMessage_init_zero {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, 0}
#define meshtastic_TakTalkRoomData_init_zero {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}}
#define meshtastic_Marti_init_zero {{{NULL}, NULL}}
#define meshtastic_TAKPacketV2_init_zero {_meshtastic_CotType_MIN, _meshtastic_CotHow_MIN, "", _meshtastic_Team_MIN, _meshtastic_MemberRole_MIN, 0, 0, 0, 0, 0, 0, _meshtastic_GeoPointSource_MIN, _meshtastic_GeoPointSource_MIN, "", "", 0, "", "", "", "", "", "", "", {{NULL}, NULL}, false, meshtastic_TAKEnvironment_init_zero, false, meshtastic_SensorFov_init_zero, false, meshtastic_Marti_init_zero, 0, {meshtastic_GeoChat_init_zero}}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_GeoChat_message_tag 1
@@ -1338,6 +1468,9 @@ extern "C" {
#define meshtastic_GeoChat_to_callsign_tag 3
#define meshtastic_GeoChat_receipt_for_uid_tag 4
#define meshtastic_GeoChat_receipt_type_tag 5
#define meshtastic_GeoChat_lang_tag 6
#define meshtastic_GeoChat_room_id_tag 7
#define meshtastic_GeoChat_voice_profile_id_tag 8
#define meshtastic_Group_role_tag 1
#define meshtastic_Group_team_tag 2
#define meshtastic_Status_battery_tag 1
@@ -1377,12 +1510,13 @@ extern "C" {
#define meshtastic_DrawnShape_fill_color_tag 9
#define meshtastic_DrawnShape_fill_argb_tag 10
#define meshtastic_DrawnShape_labels_on_tag 11
#define meshtastic_DrawnShape_vertices_tag 12
#define meshtastic_DrawnShape_truncated_tag 13
#define meshtastic_DrawnShape_bullseye_distance_dm_tag 14
#define meshtastic_DrawnShape_bullseye_bearing_ref_tag 15
#define meshtastic_DrawnShape_bullseye_flags_tag 16
#define meshtastic_DrawnShape_bullseye_uid_ref_tag 17
#define meshtastic_DrawnShape_vertex_lat_deltas_tag 18
#define meshtastic_DrawnShape_vertex_lon_deltas_tag 19
#define meshtastic_Marker_kind_tag 1
#define meshtastic_Marker_color_tag 2
#define meshtastic_Marker_color_argb_tag 3
@@ -1467,6 +1601,15 @@ extern "C" {
#define meshtastic_SensorFov_elevation_deg_tag 6
#define meshtastic_SensorFov_roll_deg_tag 7
#define meshtastic_SensorFov_model_tag 8
#define meshtastic_TakTalkMessage_text_tag 1
#define meshtastic_TakTalkMessage_chatroom_id_tag 2
#define meshtastic_TakTalkMessage_lang_tag 3
#define meshtastic_TakTalkMessage_from_voice_tag 4
#define meshtastic_TakTalkRoomData_sender_callsign_tag 1
#define meshtastic_TakTalkRoomData_room_id_tag 2
#define meshtastic_TakTalkRoomData_room_name_tag 3
#define meshtastic_TakTalkRoomData_participants_tag 4
#define meshtastic_Marti_dest_callsign_tag 1
#define meshtastic_TAKPacketV2_cot_type_id_tag 1
#define meshtastic_TAKPacketV2_how_tag 2
#define meshtastic_TAKPacketV2_callsign_tag 3
@@ -1493,7 +1636,7 @@ extern "C" {
#define meshtastic_TAKPacketV2_remarks_tag 24
#define meshtastic_TAKPacketV2_environment_tag 25
#define meshtastic_TAKPacketV2_sensor_fov_tag 26
#define meshtastic_TAKPacketV2_pli_tag 30
#define meshtastic_TAKPacketV2_marti_tag 29
#define meshtastic_TAKPacketV2_chat_tag 31
#define meshtastic_TAKPacketV2_aircraft_tag 32
#define meshtastic_TAKPacketV2_raw_detail_tag 33
@@ -1504,6 +1647,8 @@ extern "C" {
#define meshtastic_TAKPacketV2_casevac_tag 38
#define meshtastic_TAKPacketV2_emergency_tag 39
#define meshtastic_TAKPacketV2_task_tag 40
#define meshtastic_TAKPacketV2_taktalk_tag 41
#define meshtastic_TAKPacketV2_taktalk_room_tag 42
/* Struct field encoding specification for nanopb */
#define meshtastic_TAKPacket_FIELDLIST(X, a) \
@@ -1527,8 +1672,11 @@ X(a, STATIC, SINGULAR, STRING, message, 1) \
X(a, STATIC, OPTIONAL, STRING, to, 2) \
X(a, STATIC, OPTIONAL, STRING, to_callsign, 3) \
X(a, STATIC, SINGULAR, STRING, receipt_for_uid, 4) \
X(a, STATIC, SINGULAR, UENUM, receipt_type, 5)
#define meshtastic_GeoChat_CALLBACK NULL
X(a, STATIC, SINGULAR, UENUM, receipt_type, 5) \
X(a, CALLBACK, OPTIONAL, STRING, lang, 6) \
X(a, CALLBACK, OPTIONAL, STRING, room_id, 7) \
X(a, CALLBACK, OPTIONAL, STRING, voice_profile_id, 8)
#define meshtastic_GeoChat_CALLBACK pb_default_field_callback
#define meshtastic_GeoChat_DEFAULT NULL
#define meshtastic_Group_FIELDLIST(X, a) \
@@ -1588,15 +1736,15 @@ X(a, STATIC, SINGULAR, UINT32, stroke_weight_x10, 8) \
X(a, STATIC, SINGULAR, UENUM, fill_color, 9) \
X(a, STATIC, SINGULAR, FIXED32, fill_argb, 10) \
X(a, STATIC, SINGULAR, BOOL, labels_on, 11) \
X(a, STATIC, REPEATED, MESSAGE, vertices, 12) \
X(a, STATIC, SINGULAR, BOOL, truncated, 13) \
X(a, STATIC, SINGULAR, UINT32, bullseye_distance_dm, 14) \
X(a, STATIC, SINGULAR, UINT32, bullseye_bearing_ref, 15) \
X(a, STATIC, SINGULAR, UINT32, bullseye_flags, 16) \
X(a, STATIC, SINGULAR, STRING, bullseye_uid_ref, 17)
#define meshtastic_DrawnShape_CALLBACK NULL
X(a, STATIC, SINGULAR, STRING, bullseye_uid_ref, 17) \
X(a, CALLBACK, REPEATED, SINT32, vertex_lat_deltas, 18) \
X(a, CALLBACK, REPEATED, SINT32, vertex_lon_deltas, 19)
#define meshtastic_DrawnShape_CALLBACK pb_default_field_callback
#define meshtastic_DrawnShape_DEFAULT NULL
#define meshtastic_DrawnShape_vertices_MSGTYPE meshtastic_CotGeoPoint
#define meshtastic_Marker_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UENUM, kind, 1) \
@@ -1726,6 +1874,27 @@ X(a, CALLBACK, SINGULAR, STRING, model, 8)
#define meshtastic_SensorFov_CALLBACK pb_default_field_callback
#define meshtastic_SensorFov_DEFAULT NULL
#define meshtastic_TakTalkMessage_FIELDLIST(X, a) \
X(a, CALLBACK, SINGULAR, STRING, text, 1) \
X(a, CALLBACK, SINGULAR, STRING, chatroom_id, 2) \
X(a, CALLBACK, SINGULAR, STRING, lang, 3) \
X(a, STATIC, SINGULAR, BOOL, from_voice, 4)
#define meshtastic_TakTalkMessage_CALLBACK pb_default_field_callback
#define meshtastic_TakTalkMessage_DEFAULT NULL
#define meshtastic_TakTalkRoomData_FIELDLIST(X, a) \
X(a, CALLBACK, SINGULAR, STRING, sender_callsign, 1) \
X(a, CALLBACK, SINGULAR, STRING, room_id, 2) \
X(a, CALLBACK, SINGULAR, STRING, room_name, 3) \
X(a, CALLBACK, REPEATED, STRING, participants, 4)
#define meshtastic_TakTalkRoomData_CALLBACK pb_default_field_callback
#define meshtastic_TakTalkRoomData_DEFAULT NULL
#define meshtastic_Marti_FIELDLIST(X, a) \
X(a, CALLBACK, REPEATED, STRING, dest_callsign, 1)
#define meshtastic_Marti_CALLBACK pb_default_field_callback
#define meshtastic_Marti_DEFAULT NULL
#define meshtastic_TAKPacketV2_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UENUM, cot_type_id, 1) \
X(a, STATIC, SINGULAR, UENUM, how, 2) \
@@ -1753,7 +1922,7 @@ X(a, STATIC, SINGULAR, STRING, cot_type_str, 23) \
X(a, CALLBACK, SINGULAR, STRING, remarks, 24) \
X(a, STATIC, OPTIONAL, MESSAGE, environment, 25) \
X(a, STATIC, OPTIONAL, MESSAGE, sensor_fov, 26) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,pli,payload_variant.pli), 30) \
X(a, STATIC, OPTIONAL, MESSAGE, marti, 29) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,chat,payload_variant.chat), 31) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,aircraft,payload_variant.aircraft), 32) \
X(a, STATIC, ONEOF, BYTES, (payload_variant,raw_detail,payload_variant.raw_detail), 33) \
@@ -1763,11 +1932,14 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,rab,payload_variant.rab), 3
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,route,payload_variant.route), 37) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,casevac,payload_variant.casevac), 38) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,emergency,payload_variant.emergency), 39) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,task,payload_variant.task), 40)
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,task,payload_variant.task), 40) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,taktalk,payload_variant.taktalk), 41) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,taktalk_room,payload_variant.taktalk_room), 42)
#define meshtastic_TAKPacketV2_CALLBACK pb_default_field_callback
#define meshtastic_TAKPacketV2_DEFAULT NULL
#define meshtastic_TAKPacketV2_environment_MSGTYPE meshtastic_TAKEnvironment
#define meshtastic_TAKPacketV2_sensor_fov_MSGTYPE meshtastic_SensorFov
#define meshtastic_TAKPacketV2_marti_MSGTYPE meshtastic_Marti
#define meshtastic_TAKPacketV2_payload_variant_chat_MSGTYPE meshtastic_GeoChat
#define meshtastic_TAKPacketV2_payload_variant_aircraft_MSGTYPE meshtastic_AircraftTrack
#define meshtastic_TAKPacketV2_payload_variant_shape_MSGTYPE meshtastic_DrawnShape
@@ -1777,6 +1949,8 @@ X(a, STATIC, ONEOF, MESSAGE, (payload_variant,task,payload_variant.task),
#define meshtastic_TAKPacketV2_payload_variant_casevac_MSGTYPE meshtastic_CasevacReport
#define meshtastic_TAKPacketV2_payload_variant_emergency_MSGTYPE meshtastic_EmergencyAlert
#define meshtastic_TAKPacketV2_payload_variant_task_MSGTYPE meshtastic_TaskRequest
#define meshtastic_TAKPacketV2_payload_variant_taktalk_MSGTYPE meshtastic_TakTalkMessage
#define meshtastic_TAKPacketV2_payload_variant_taktalk_room_MSGTYPE meshtastic_TakTalkRoomData
extern const pb_msgdesc_t meshtastic_TAKPacket_msg;
extern const pb_msgdesc_t meshtastic_GeoChat_msg;
@@ -1797,6 +1971,9 @@ extern const pb_msgdesc_t meshtastic_EmergencyAlert_msg;
extern const pb_msgdesc_t meshtastic_TaskRequest_msg;
extern const pb_msgdesc_t meshtastic_TAKEnvironment_msg;
extern const pb_msgdesc_t meshtastic_SensorFov_msg;
extern const pb_msgdesc_t meshtastic_TakTalkMessage_msg;
extern const pb_msgdesc_t meshtastic_TakTalkRoomData_msg;
extern const pb_msgdesc_t meshtastic_Marti_msg;
extern const pb_msgdesc_t meshtastic_TAKPacketV2_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
@@ -1819,20 +1996,27 @@ extern const pb_msgdesc_t meshtastic_TAKPacketV2_msg;
#define meshtastic_TaskRequest_fields &meshtastic_TaskRequest_msg
#define meshtastic_TAKEnvironment_fields &meshtastic_TAKEnvironment_msg
#define meshtastic_SensorFov_fields &meshtastic_SensorFov_msg
#define meshtastic_TakTalkMessage_fields &meshtastic_TakTalkMessage_msg
#define meshtastic_TakTalkRoomData_fields &meshtastic_TakTalkRoomData_msg
#define meshtastic_Marti_fields &meshtastic_Marti_msg
#define meshtastic_TAKPacketV2_fields &meshtastic_TAKPacketV2_msg
/* Maximum encoded size of messages (where known) */
/* meshtastic_TAKPacket_size depends on runtime parameters */
/* meshtastic_GeoChat_size depends on runtime parameters */
/* meshtastic_DrawnShape_size depends on runtime parameters */
/* meshtastic_CasevacReport_size depends on runtime parameters */
/* meshtastic_ZMistEntry_size depends on runtime parameters */
/* meshtastic_SensorFov_size depends on runtime parameters */
/* meshtastic_TakTalkMessage_size depends on runtime parameters */
/* meshtastic_TakTalkRoomData_size depends on runtime parameters */
/* meshtastic_Marti_size depends on runtime parameters */
/* meshtastic_TAKPacketV2_size depends on runtime parameters */
#define MESHTASTIC_MESHTASTIC_ATAK_PB_H_MAX_SIZE meshtastic_Route_size
#define meshtastic_AircraftTrack_size 134
#define meshtastic_Contact_size 242
#define meshtastic_CotGeoPoint_size 12
#define meshtastic_DrawnShape_size 553
#define meshtastic_EmergencyAlert_size 100
#define meshtastic_GeoChat_size 495
#define meshtastic_Group_size 4
#define meshtastic_Marker_size 191
#define meshtastic_PLI_size 31
@@ -1841,7 +2025,6 @@ extern const pb_msgdesc_t meshtastic_TAKPacketV2_msg;
#define meshtastic_Route_size 1379
#define meshtastic_Status_size 3
#define meshtastic_TAKEnvironment_size 18
#define meshtastic_TAKPacket_size 756
#define meshtastic_TaskRequest_size 132
#ifdef __cplusplus

View File

@@ -290,15 +290,26 @@ typedef enum _meshtastic_Config_LoRaConfig_RegionCode {
meshtastic_Config_LoRaConfig_RegionCode_BR_902 = 26,
/* ITU Region 1 Amateur Radio 2m band (144-146 MHz) */
meshtastic_Config_LoRaConfig_RegionCode_ITU1_2M = 27,
/* ITU Region 2 / 3 Amateur Radio 2m band (144-148 MHz) */
meshtastic_Config_LoRaConfig_RegionCode_ITU23_2M = 28,
/* ITU Region 2 Amateur Radio 2m band (144-148 MHz) */
meshtastic_Config_LoRaConfig_RegionCode_ITU2_2M = 28,
/* EU 866MHz band (Band no. 47b of 2006/771/EC and subsequent amendments) for Non-specific short-range devices (SRD) */
meshtastic_Config_LoRaConfig_RegionCode_EU_866 = 29,
/* EU 874MHz and 917MHz bands (Band no. 1 and 4 of 2022/172/EC and subsequent amendments) for Non-specific short-range devices (SRD) */
meshtastic_Config_LoRaConfig_RegionCode_EU_874 = 30,
meshtastic_Config_LoRaConfig_RegionCode_EU_917 = 31,
/* EU 868MHz band, with narrow presets */
meshtastic_Config_LoRaConfig_RegionCode_EU_N_868 = 32
meshtastic_Config_LoRaConfig_RegionCode_EU_N_868 = 32,
/* ITU Region 3 Amateur Radio 2m band (144-148 MHz) */
meshtastic_Config_LoRaConfig_RegionCode_ITU3_2M = 33,
/* ITU Region 1 Amateur Radio 70cm band (430-440 MHz) */
meshtastic_Config_LoRaConfig_RegionCode_ITU1_70CM = 34,
/* ITU Region 2 Amateur Radio 70cm band (420-450 MHz)
Note: Some countries do not allocate 420-430 MHz or 440-450 MHz.
Check local law! */
meshtastic_Config_LoRaConfig_RegionCode_ITU2_70CM = 35,
/* ITU Region 3 Amateur Radio 70cm band (430-450 MHz)
Note: Some countries do not allocate 440-450 MHz. Check local law! */
meshtastic_Config_LoRaConfig_RegionCode_ITU3_70CM = 36
} meshtastic_Config_LoRaConfig_RegionCode;
/* Standard predefined channel settings
@@ -345,7 +356,21 @@ typedef enum _meshtastic_Config_LoRaConfig_ModemPreset {
/* Narrow Slow
Moderate range preset optimized for EU 868MHz band with 62.5kHz bandwidth.
Comparable link budget and data rate to LONG_FAST. */
meshtastic_Config_LoRaConfig_ModemPreset_NARROW_SLOW = 13
meshtastic_Config_LoRaConfig_ModemPreset_NARROW_SLOW = 13,
/* Tiny Fast
Preset optimized for compliance with Amateur Radio restrictions with 20kHz bandwidth.
Many regions limit data transmission bandwidth in lower amateur bands (2 Meter).
Note: TCXO with tight tolerances (±5 ppm or better) is *absolutely required* at these narrow bandwidths.
Only compatible with SX127x and SX126x chipsets.
Comparable link budget and data rate to LONG_FAST. */
meshtastic_Config_LoRaConfig_ModemPreset_TINY_FAST = 14,
/* Tiny Slow
Preset optimized for compliance with Amateur Radio restrictions with 20kHz bandwidth.
Many regions limit data transmission bandwidth in lower amateur bands (2 Meter).
Note: TCXO with tight tolerances (±5 ppm or better) is *absolutely required* at these narrow bandwidths.
Only compatible with SX127x and SX126x chipsets.
Comparable link budget and data rate to LONG_MODERATE. */
meshtastic_Config_LoRaConfig_ModemPreset_TINY_SLOW = 15
} meshtastic_Config_LoRaConfig_ModemPreset;
typedef enum _meshtastic_Config_LoRaConfig_FEM_LNA_Mode {
@@ -734,12 +759,12 @@ extern "C" {
#define _meshtastic_Config_DisplayConfig_CompassOrientation_ARRAYSIZE ((meshtastic_Config_DisplayConfig_CompassOrientation)(meshtastic_Config_DisplayConfig_CompassOrientation_DEGREES_270_INVERTED+1))
#define _meshtastic_Config_LoRaConfig_RegionCode_MIN meshtastic_Config_LoRaConfig_RegionCode_UNSET
#define _meshtastic_Config_LoRaConfig_RegionCode_MAX meshtastic_Config_LoRaConfig_RegionCode_EU_N_868
#define _meshtastic_Config_LoRaConfig_RegionCode_ARRAYSIZE ((meshtastic_Config_LoRaConfig_RegionCode)(meshtastic_Config_LoRaConfig_RegionCode_EU_N_868+1))
#define _meshtastic_Config_LoRaConfig_RegionCode_MAX meshtastic_Config_LoRaConfig_RegionCode_ITU3_70CM
#define _meshtastic_Config_LoRaConfig_RegionCode_ARRAYSIZE ((meshtastic_Config_LoRaConfig_RegionCode)(meshtastic_Config_LoRaConfig_RegionCode_ITU3_70CM+1))
#define _meshtastic_Config_LoRaConfig_ModemPreset_MIN meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST
#define _meshtastic_Config_LoRaConfig_ModemPreset_MAX meshtastic_Config_LoRaConfig_ModemPreset_NARROW_SLOW
#define _meshtastic_Config_LoRaConfig_ModemPreset_ARRAYSIZE ((meshtastic_Config_LoRaConfig_ModemPreset)(meshtastic_Config_LoRaConfig_ModemPreset_NARROW_SLOW+1))
#define _meshtastic_Config_LoRaConfig_ModemPreset_MAX meshtastic_Config_LoRaConfig_ModemPreset_TINY_SLOW
#define _meshtastic_Config_LoRaConfig_ModemPreset_ARRAYSIZE ((meshtastic_Config_LoRaConfig_ModemPreset)(meshtastic_Config_LoRaConfig_ModemPreset_TINY_SLOW+1))
#define _meshtastic_Config_LoRaConfig_FEM_LNA_Mode_MIN meshtastic_Config_LoRaConfig_FEM_LNA_Mode_DISABLED
#define _meshtastic_Config_LoRaConfig_FEM_LNA_Mode_MAX meshtastic_Config_LoRaConfig_FEM_LNA_Mode_NOT_PRESENT

View File

@@ -658,7 +658,14 @@ typedef enum _meshtastic_LockdownStatus_State {
token's TTL. */
meshtastic_LockdownStatus_State_UNLOCKED = 3,
/* Passphrase rejected. backoff_seconds is non-zero when rate-limited. */
meshtastic_LockdownStatus_State_UNLOCK_FAILED = 4
meshtastic_LockdownStatus_State_UNLOCK_FAILED = 4,
/* Lockdown is supported by this firmware but not currently active
(no passphrase has been provisioned, or it was disabled via
AdminMessage.lockdown_auth.disable). The device is operating in
normal, non-encrypted mode. Clients render the lockdown-mode
toggle as OFF on receiving this. Distinct from NEEDS_PROVISION,
which is only used during an in-progress enable flow. */
meshtastic_LockdownStatus_State_DISABLED = 5
} meshtastic_LockdownStatus_State;
/* Struct definitions */
@@ -1533,8 +1540,8 @@ extern "C" {
#define _meshtastic_LogRecord_Level_ARRAYSIZE ((meshtastic_LogRecord_Level)(meshtastic_LogRecord_Level_CRITICAL+1))
#define _meshtastic_LockdownStatus_State_MIN meshtastic_LockdownStatus_State_STATE_UNSPECIFIED
#define _meshtastic_LockdownStatus_State_MAX meshtastic_LockdownStatus_State_UNLOCK_FAILED
#define _meshtastic_LockdownStatus_State_ARRAYSIZE ((meshtastic_LockdownStatus_State)(meshtastic_LockdownStatus_State_UNLOCK_FAILED+1))
#define _meshtastic_LockdownStatus_State_MAX meshtastic_LockdownStatus_State_DISABLED
#define _meshtastic_LockdownStatus_State_ARRAYSIZE ((meshtastic_LockdownStatus_State)(meshtastic_LockdownStatus_State_DISABLED+1))
#define meshtastic_Position_location_source_ENUMTYPE meshtastic_Position_LocSource
#define meshtastic_Position_altitude_source_ENUMTYPE meshtastic_Position_AltSource

View File

@@ -1005,11 +1005,11 @@ bool AdminModule::handleSetModuleConfig(const meshtastic_ModuleConfig &c)
case meshtastic_ModuleConfig_neighbor_info_tag:
LOG_INFO("Set module config: Neighbor Info");
moduleConfig.has_neighbor_info = true;
moduleConfig.neighbor_info = c.payload_variant.neighbor_info;
if (moduleConfig.neighbor_info.update_interval < min_neighbor_info_broadcast_secs) {
LOG_DEBUG("Tried to set update_interval too low, setting to %d", default_neighbor_info_broadcast_secs);
moduleConfig.neighbor_info.update_interval = default_neighbor_info_broadcast_secs;
}
moduleConfig.neighbor_info = c.payload_variant.neighbor_info;
break;
case meshtastic_ModuleConfig_detection_sensor_tag:
LOG_INFO("Set module config: Detection Sensor");

View File

@@ -1,207 +1,11 @@
#include "AtakPluginModule.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "main.h"
#include "mesh/compression/unishox2.h"
#include "meshUtils.h"
#include "meshtastic/atak.pb.h"
AtakPluginModule *atakPluginModule;
AtakPluginModule::AtakPluginModule()
: ProtobufModule("atak", meshtastic_PortNum_ATAK_PLUGIN, &meshtastic_TAKPacket_msg), concurrency::OSThread("AtakPlugin")
AtakPluginModule::AtakPluginModule() : SinglePortModule("atak", meshtastic_PortNum_ATAK_PLUGIN_V2) {}
ProcessMessage AtakPluginModule::handleReceived(const meshtastic_MeshPacket &mp)
{
ourPortNum = meshtastic_PortNum_ATAK_PLUGIN;
(void)mp; // Passthrough — no processing needed, apps handle compression/decompression
return ProcessMessage::CONTINUE;
}
/*
Encompasses the full construction and sending packet to mesh
Will be used for broadcast.
*/
int32_t AtakPluginModule::runOnce()
{
return default_broadcast_interval_secs;
}
bool AtakPluginModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_TAKPacket *r)
{
return false;
}
meshtastic_TAKPacket AtakPluginModule::cloneTAKPacketData(meshtastic_TAKPacket *t)
{
meshtastic_TAKPacket clone = meshtastic_TAKPacket_init_zero;
if (t->has_group) {
clone.has_group = true;
clone.group = t->group;
}
if (t->has_status) {
clone.has_status = true;
clone.status = t->status;
}
if (t->has_contact) {
clone.has_contact = true;
clone.contact = {0};
}
if (t->which_payload_variant == meshtastic_TAKPacket_pli_tag) {
clone.which_payload_variant = meshtastic_TAKPacket_pli_tag;
clone.payload_variant.pli = t->payload_variant.pli;
} else if (t->which_payload_variant == meshtastic_TAKPacket_chat_tag) {
clone.which_payload_variant = meshtastic_TAKPacket_chat_tag;
clone.payload_variant.chat = {0};
} else if (t->which_payload_variant == meshtastic_TAKPacket_detail_tag) {
clone.which_payload_variant = meshtastic_TAKPacket_detail_tag;
clone.payload_variant.detail.size = t->payload_variant.detail.size;
memcpy(clone.payload_variant.detail.bytes, t->payload_variant.detail.bytes, t->payload_variant.detail.size);
}
return clone;
}
void AtakPluginModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtastic_TAKPacket *t)
{
// From Phone (EUD)
if (mp.from == 0) {
LOG_DEBUG("Received uncompressed TAK payload from phone: %d bytes", mp.decoded.payload.size);
// Compress for LoRA transport
auto compressed = cloneTAKPacketData(t);
compressed.is_compressed = true;
if (t->has_contact) {
auto length = unishox2_compress_lines(
t->contact.callsign, pb_string_length(t->contact.callsign, sizeof(t->contact.callsign)),
compressed.contact.callsign, sizeof(compressed.contact.callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compress overflow contact.callsign. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed callsign: %d bytes", length);
length = unishox2_compress_lines(
t->contact.device_callsign, pb_string_length(t->contact.device_callsign, sizeof(t->contact.device_callsign)),
compressed.contact.device_callsign, sizeof(compressed.contact.device_callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compress overflow contact.device_callsign. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed device_callsign: %d bytes", length);
}
if (t->which_payload_variant == meshtastic_TAKPacket_chat_tag) {
auto length = unishox2_compress_lines(
t->payload_variant.chat.message,
pb_string_length(t->payload_variant.chat.message, sizeof(t->payload_variant.chat.message)),
compressed.payload_variant.chat.message, sizeof(compressed.payload_variant.chat.message) - 1, USX_PSET_DFLT,
NULL);
if (length < 0) {
LOG_WARN("Compress overflow chat.message. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed chat message: %d bytes", length);
if (t->payload_variant.chat.has_to) {
compressed.payload_variant.chat.has_to = true;
length = unishox2_compress_lines(
t->payload_variant.chat.to, pb_string_length(t->payload_variant.chat.to, sizeof(t->payload_variant.chat.to)),
compressed.payload_variant.chat.to, sizeof(compressed.payload_variant.chat.to) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compress overflow chat.to. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed chat to: %d bytes", length);
}
if (t->payload_variant.chat.has_to_callsign) {
compressed.payload_variant.chat.has_to_callsign = true;
length = unishox2_compress_lines(
t->payload_variant.chat.to_callsign,
pb_string_length(t->payload_variant.chat.to_callsign, sizeof(t->payload_variant.chat.to_callsign)),
compressed.payload_variant.chat.to_callsign, sizeof(compressed.payload_variant.chat.to_callsign) - 1,
USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Compress overflow chat.to_callsign. Revert to uncompressed packet");
return;
}
LOG_DEBUG("Compressed chat to_callsign: %d bytes", length);
}
}
mp.decoded.payload.size = pb_encode_to_bytes(mp.decoded.payload.bytes, sizeof(mp.decoded.payload.bytes),
meshtastic_TAKPacket_fields, &compressed);
LOG_DEBUG("Final payload: %d bytes", mp.decoded.payload.size);
} else {
if (!t->is_compressed) {
// Not compressed. Something is wrong
LOG_WARN("Received uncompressed TAKPacket over radio! Skip");
return;
}
// Decompress for Phone (EUD)
auto uncompressed = cloneTAKPacketData(t);
uncompressed.is_compressed = false;
if (t->has_contact) {
auto length = unishox2_decompress_lines(
t->contact.callsign, pb_string_length(t->contact.callsign, sizeof(t->contact.callsign)),
uncompressed.contact.callsign, sizeof(uncompressed.contact.callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompress overflow contact.callsign. Bailing out");
return;
}
LOG_DEBUG("Decompressed callsign: %d bytes", length);
length = unishox2_decompress_lines(
t->contact.device_callsign, pb_string_length(t->contact.device_callsign, sizeof(t->contact.device_callsign)),
uncompressed.contact.device_callsign, sizeof(uncompressed.contact.device_callsign) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompress overflow contact.device_callsign. Bailing out");
return;
}
LOG_DEBUG("Decompressed device_callsign: %d bytes", length);
}
if (uncompressed.which_payload_variant == meshtastic_TAKPacket_chat_tag) {
auto length = unishox2_decompress_lines(
t->payload_variant.chat.message,
pb_string_length(t->payload_variant.chat.message, sizeof(t->payload_variant.chat.message)),
uncompressed.payload_variant.chat.message, sizeof(uncompressed.payload_variant.chat.message) - 1, USX_PSET_DFLT,
NULL);
if (length < 0) {
LOG_WARN("Decompress overflow chat.message. Bailing out");
return;
}
LOG_DEBUG("Decompressed chat message: %d bytes", length);
if (t->payload_variant.chat.has_to) {
uncompressed.payload_variant.chat.has_to = true;
length = unishox2_decompress_lines(
t->payload_variant.chat.to, pb_string_length(t->payload_variant.chat.to, sizeof(t->payload_variant.chat.to)),
uncompressed.payload_variant.chat.to, sizeof(uncompressed.payload_variant.chat.to) - 1, USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompress overflow chat.to. Bailing out");
return;
}
LOG_DEBUG("Decompressed chat to: %d bytes", length);
}
if (t->payload_variant.chat.has_to_callsign) {
uncompressed.payload_variant.chat.has_to_callsign = true;
length = unishox2_decompress_lines(
t->payload_variant.chat.to_callsign,
pb_string_length(t->payload_variant.chat.to_callsign, sizeof(t->payload_variant.chat.to_callsign)),
uncompressed.payload_variant.chat.to_callsign, sizeof(uncompressed.payload_variant.chat.to_callsign) - 1,
USX_PSET_DFLT, NULL);
if (length < 0) {
LOG_WARN("Decompress overflow chat.to_callsign. Bailing out");
return;
}
LOG_DEBUG("Decompressed chat to_callsign: %d bytes", length);
}
}
auto decompressedCopy = packetPool.allocCopy(mp);
decompressedCopy->decoded.payload.size =
pb_encode_to_bytes(decompressedCopy->decoded.payload.bytes, sizeof(decompressedCopy->decoded.payload),
meshtastic_TAKPacket_fields, &uncompressed);
service->sendToPhone(decompressedCopy);
}
return;
}

View File

@@ -1,11 +1,15 @@
#pragma once
#include "ProtobufModule.h"
#include "meshtastic/atak.pb.h"
#include "SinglePortModule.h"
/**
* Waypoint message handling for meshtastic
* ATAK Plugin V2 module - passthrough for ATAK_PLUGIN_V2 payloads.
* The wire format includes a leading flags byte followed by opaque payload bytes.
* Depending on the flags, the payload may be zstd dictionary-compressed or raw/uncompressed protobuf.
* Compression/decompression and payload interpretation are handled by the apps
* (Android, iOS, ATAK plugin); firmware forwards the bytes unchanged on the
* ATAK_PLUGIN_V2 port.
*/
class AtakPluginModule : public ProtobufModule<meshtastic_TAKPacket>, private concurrency::OSThread
class AtakPluginModule : public SinglePortModule
{
public:
/** Constructor
@@ -14,13 +18,7 @@ class AtakPluginModule : public ProtobufModule<meshtastic_TAKPacket>, private co
AtakPluginModule();
protected:
virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_TAKPacket *t) override;
virtual void alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtastic_TAKPacket *t) override;
/* Does our periodic broadcast */
int32_t runOnce() override;
private:
meshtastic_TAKPacket cloneTAKPacketData(meshtastic_TAKPacket *t);
virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp) override;
};
extern AtakPluginModule *atakPluginModule;
extern AtakPluginModule *atakPluginModule;

View File

@@ -13,7 +13,6 @@
#include "configuration.h"
#include "gps/GeoCoord.h"
#include "main.h"
#include "mesh/compression/unishox2.h"
#include "meshUtils.h"
#include "meshtastic/atak.pb.h"
#include "sleep.h"
@@ -291,37 +290,78 @@ meshtastic_MeshPacket *PositionModule::allocReply()
meshtastic_MeshPacket *PositionModule::allocAtakPli()
{
LOG_INFO("Send TAK PLI packet");
LOG_INFO("Send TAK V2 PLI packet");
meshtastic_MeshPacket *mp = allocDataPacket();
mp->decoded.portnum = meshtastic_PortNum_ATAK_PLUGIN;
mp->decoded.portnum = meshtastic_PortNum_ATAK_PLUGIN_V2;
meshtastic_TAKPacket takPacket = {.is_compressed = true,
.has_contact = true,
.contact = meshtastic_Contact_init_default,
.has_group = true,
.group = {meshtastic_MemberRole_TeamMember, meshtastic_Team_Cyan},
.has_status = true,
.status =
{
.battery = powerStatus->getBatteryChargePercent(),
},
.which_payload_variant = meshtastic_TAKPacket_pli_tag,
.payload_variant = {.pli = {
.latitude_i = localPosition.latitude_i,
.longitude_i = localPosition.longitude_i,
.altitude = localPosition.altitude_hae,
.speed = localPosition.ground_speed,
.course = static_cast<uint16_t>(localPosition.ground_track),
}}};
meshtastic_TAKPacketV2 takPacket = meshtastic_TAKPacketV2_init_zero;
takPacket.cot_type_id = meshtastic_CotType_CotType_a_f_G_U_C;
auto length = unishox2_compress_lines(owner.long_name, strlen(owner.long_name), takPacket.contact.device_callsign,
sizeof(takPacket.contact.device_callsign) - 1, USX_PSET_DFLT, NULL);
LOG_DEBUG("Uncompressed device_callsign '%s' - %d bytes", owner.long_name, strlen(owner.long_name));
LOG_DEBUG("Compressed device_callsign '%s' - %d bytes", takPacket.contact.device_callsign, length);
length = unishox2_compress_lines(owner.long_name, strlen(owner.long_name), takPacket.contact.callsign,
sizeof(takPacket.contact.callsign) - 1, USX_PSET_DFLT, NULL);
mp->decoded.payload.size =
pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes), &meshtastic_TAKPacket_msg, &takPacket);
// Use TAK config for team/role if configured, otherwise use defaults (Cyan/TeamMember)
if (moduleConfig.has_tak && moduleConfig.tak.team != meshtastic_Team_Unspecifed_Color) {
takPacket.team = moduleConfig.tak.team;
} else {
takPacket.team = meshtastic_Team_Cyan;
}
if (moduleConfig.has_tak && moduleConfig.tak.role != meshtastic_MemberRole_Unspecifed) {
takPacket.role = moduleConfig.tak.role;
} else {
takPacket.role = meshtastic_MemberRole_TeamMember;
}
takPacket.latitude_i = localPosition.latitude_i;
takPacket.longitude_i = localPosition.longitude_i;
takPacket.altitude = localPosition.altitude_hae;
takPacket.speed = localPosition.ground_speed;
// ground_track is stored as degrees * 1e5, course field expects degrees * 100
int32_t course = localPosition.ground_track / 1000;
if (course < 0)
course = 0;
else if (course > 36000)
course = 36000;
takPacket.course = static_cast<uint16_t>(course);
takPacket.battery = powerStatus->getBatteryChargePercent();
// Map position source to CoT how/geo_src/alt_src
if (config.position.fixed_position || localPosition.location_source == meshtastic_Position_LocSource_LOC_MANUAL) {
takPacket.how = meshtastic_CotHow_CotHow_h_e;
takPacket.geo_src = meshtastic_GeoPointSource_GeoPointSource_USER;
takPacket.alt_src = meshtastic_GeoPointSource_GeoPointSource_USER;
} else {
takPacket.how = meshtastic_CotHow_CotHow_m_g;
takPacket.geo_src = meshtastic_GeoPointSource_GeoPointSource_GPS;
takPacket.alt_src = meshtastic_GeoPointSource_GeoPointSource_GPS;
}
// Callsign - stored as plain string (no compression, apps handle that)
strncpy(takPacket.callsign, owner.long_name, sizeof(takPacket.callsign) - 1);
takPacket.callsign[sizeof(takPacket.callsign) - 1] = '\0';
strncpy(takPacket.device_callsign, owner.long_name, sizeof(takPacket.device_callsign) - 1);
takPacket.device_callsign[sizeof(takPacket.device_callsign) - 1] = '\0';
// CoT uid — ATAK drops PLI entities with empty uid; derive stable "!<nodenum>" id.
snprintf(takPacket.uid, sizeof(takPacket.uid), "!%08x", nodeDB->getNodeNum());
// Encode TAKPacketV2 protobuf, leaving room for flags byte prefix
uint8_t protobuf_bytes[sizeof(mp->decoded.payload.bytes) - 1];
size_t proto_size = pb_encode_to_bytes(protobuf_bytes, sizeof(protobuf_bytes), &meshtastic_TAKPacketV2_msg, &takPacket);
if (proto_size == 0) {
LOG_ERROR("Failed to encode TAK V2 PLI packet");
packetPool.release(mp);
return nullptr;
}
// Wire format: [flags byte][protobuf bytes]
// Flags byte 0xFF is a reserved sentinel meaning the remainder is an
// uncompressed raw protobuf payload (that is, no zstd dictionary ID is
// encoded in the flags byte). Decoders must check for this sentinel before
// applying any dictionary-ID masking/interpretation.
mp->decoded.payload.bytes[0] = 0xFF;
memcpy(mp->decoded.payload.bytes + 1, protobuf_bytes, proto_size);
mp->decoded.payload.size = proto_size + 1;
LOG_DEBUG("TAK V2 PLI payload: %zu bytes (1 flags + %zu protobuf)", mp->decoded.payload.size, proto_size);
return mp;
}

View File

@@ -20,6 +20,7 @@ static constexpr uint16_t TX_HISTORY_KEY_DEVICE_TELEMETRY = 0x8001;
int32_t DeviceTelemetryModule::runOnce()
{
refreshUptime();
uint32_t lastTelemetry = transmitHistory ? transmitHistory->getLastSentToMeshMillis(TX_HISTORY_KEY_DEVICE_TELEMETRY) : 0;
bool isImpoliteRole = isSensorOrRouterRole();
@@ -99,17 +100,21 @@ meshtastic_Telemetry DeviceTelemetryModule::getDeviceTelemetry()
t.variant.device_metrics.has_air_util_tx = true;
t.variant.device_metrics.has_battery_level = true;
t.variant.device_metrics.has_channel_utilization = true;
t.variant.device_metrics.has_voltage = true;
t.variant.device_metrics.has_uptime_seconds = true;
t.variant.device_metrics.air_util_tx = airTime->utilizationTXPercent();
t.variant.device_metrics.battery_level = (!powerStatus->getHasBattery() || powerStatus->getIsCharging())
? MAGIC_USB_BATTERY_LEVEL
: powerStatus->getBatteryChargePercent();
t.variant.device_metrics.channel_utilization = airTime->channelUtilizationPercent();
t.variant.device_metrics.voltage = powerStatus->getBatteryVoltageMv() / 1000.0;
// Only populate voltage when we actually have a battery reading. Previously this assigned
// -0.001 (from -1 mV / 1000) whenever the ADC returned -1, leaking a sentinel onto the wire
// that clients then displayed as a real negative voltage. See GH #7958.
int32_t batteryMv = powerStatus->getBatteryVoltageMv();
if (powerStatus->getHasBattery() && batteryMv > 0) {
t.variant.device_metrics.has_voltage = true;
t.variant.device_metrics.voltage = batteryMv / 1000.0f;
}
t.variant.device_metrics.uptime_seconds = getUptimeSeconds();
return t;
}
@@ -125,6 +130,8 @@ meshtastic_Telemetry DeviceTelemetryModule::getLocalStatsTelemetry()
telemetry.variant.local_stats.num_online_nodes = numOnlineNodes;
telemetry.variant.local_stats.num_total_nodes = nodeDB->getNumMeshNodes();
if (RadioLibInterface::instance) {
RadioLibInterface::instance->updateNoiseFloor();
telemetry.variant.local_stats.noise_floor = RadioLibInterface::instance->getAverageNoiseFloor();
telemetry.variant.local_stats.num_packets_tx = RadioLibInterface::instance->txGood;
telemetry.variant.local_stats.num_packets_rx = RadioLibInterface::instance->rxGood + RadioLibInterface::instance->rxBad;
telemetry.variant.local_stats.num_packets_rx_bad = RadioLibInterface::instance->rxBad;
@@ -133,6 +140,8 @@ meshtastic_Telemetry DeviceTelemetryModule::getLocalStatsTelemetry()
}
#ifdef ARCH_PORTDUINO
if (SimRadio::instance) {
if (!RadioLibInterface::instance)
telemetry.variant.local_stats.noise_floor = SimRadio::instance->getCurrentRSSI();
telemetry.variant.local_stats.num_packets_tx = SimRadio::instance->txGood;
telemetry.variant.local_stats.num_packets_rx = SimRadio::instance->rxGood + SimRadio::instance->rxBad;
telemetry.variant.local_stats.num_packets_rx_bad = SimRadio::instance->rxBad;
@@ -148,10 +157,11 @@ meshtastic_Telemetry DeviceTelemetryModule::getLocalStatsTelemetry()
telemetry.variant.local_stats.num_tx_relay_canceled = router->txRelayCanceled;
}
LOG_INFO("Sending local stats: uptime=%i, channel_utilization=%f, air_util_tx=%f, num_online_nodes=%i, num_total_nodes=%i",
LOG_INFO("Sending local stats: uptime=%i, channel_utilization=%f, air_util_tx=%f, num_online_nodes=%i, num_total_nodes=%i, "
"noise_floor=%d",
telemetry.variant.local_stats.uptime_seconds, telemetry.variant.local_stats.channel_utilization,
telemetry.variant.local_stats.air_util_tx, telemetry.variant.local_stats.num_online_nodes,
telemetry.variant.local_stats.num_total_nodes);
telemetry.variant.local_stats.num_total_nodes, telemetry.variant.local_stats.noise_floor);
LOG_INFO("num_packets_tx=%i, num_packets_rx=%i, num_packets_rx_bad=%i", telemetry.variant.local_stats.num_packets_tx,
telemetry.variant.local_stats.num_packets_rx, telemetry.variant.local_stats.num_packets_rx_bad);
@@ -194,4 +204,4 @@ bool DeviceTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
service->sendToMesh(p, RX_SRC_LOCAL, true);
}
return true;
}
}

View File

@@ -15,6 +15,7 @@
#endif
#include "BMM150Sensor.h"
#include "BMX160Sensor.h"
#include "ICM42607PSensor.h"
#include "ICM20948Sensor.h"
#include "LIS3DHSensor.h"
#include "LSM6DS3Sensor.h"
@@ -111,6 +112,9 @@ class AccelerometerThread : public concurrency::OSThread
case ScanI2C::DeviceType::ICM20948:
sensor = new ICM20948Sensor(device);
break;
case ScanI2C::DeviceType::ICM42607P:
sensor = new ICM42607PSensor(device);
break;
case ScanI2C::DeviceType::BMM150:
sensor = new BMM150Sensor(device);
break;

View File

@@ -0,0 +1,98 @@
#include "ICM42607PSensor.h"
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && __has_include(<ICM42670P.h>)
#include "detect/ScanI2CTwoWire.h"
#include <ICM42670P.h>
static constexpr uint16_t ICM42607P_ACCEL_ODR_HZ = 50;
static constexpr uint16_t ICM42607P_ACCEL_FSR_G = 2;
static constexpr float ICM42607P_COUNTS_PER_G = 32768.0f / ICM42607P_ACCEL_FSR_G;
#ifdef ICM_42607P_INT_PIN
volatile static bool ICM42607P_IRQ = false;
void ICM42607PSetInterrupt()
{
ICM42607P_IRQ = true;
}
#endif
ICM42607PSensor::ICM42607PSensor(ScanI2C::FoundDevice foundDevice) : MotionSensor::MotionSensor(foundDevice)
{
wire = ScanI2CTwoWire::fetchI2CBus(foundDevice.address);
}
ICM42607PSensor::~ICM42607PSensor() = default;
bool ICM42607PSensor::init()
{
bool addressLsb = deviceAddress() == ICM42607P_ADDR_ALT;
LOG_DEBUG("ICM-42607-P begin on addr 0x%02X (port=%d)", deviceAddress(), devicePort());
sensor.reset();
auto newSensor = std::make_unique<ICM42670>(*wire, addressLsb);
int status = newSensor->begin();
// ICM42670P library returns -3 for ICM42607P because WHO_AM_I differs; the register map is compatible.
if (status != 0 && status != -3) {
LOG_DEBUG("ICM-42607-P init error %d", status);
return false;
}
status = newSensor->startAccel(ICM42607P_ACCEL_ODR_HZ, ICM42607P_ACCEL_FSR_G);
if (status != 0) {
LOG_DEBUG("ICM-42607-P accel start error %d", status);
return false;
}
#ifdef ICM_42607P_INT_PIN
ICM42607P_IRQ = false;
status = newSensor->startWakeOnMotion(ICM_42607P_INT_PIN, ICM42607PSetInterrupt);
if (status != 0) {
LOG_DEBUG("ICM-42607-P wake-on-motion start error %d", status);
return false;
}
LOG_DEBUG("ICM-42607-P wake-on-motion interrupt ok pin=%d", ICM_42607P_INT_PIN);
#endif
sensor = std::move(newSensor);
LOG_DEBUG("ICM-42607-P init ok");
return true;
}
int32_t ICM42607PSensor::runOnce()
{
#ifdef ICM_42607P_INT_PIN
if (ICM42607P_IRQ) {
ICM42607P_IRQ = false;
LOG_DEBUG("ICM-42607-P motion interrupt");
wakeScreen();
}
return MOTION_SENSOR_CHECK_INTERVAL_MS;
#else
int16_t x = 0;
int16_t y = 0;
int16_t z = 0;
inv_imu_sensor_event_t event = {};
if (sensor == nullptr || sensor->getDataFromRegisters(event) != 0) {
return MOTION_SENSOR_CHECK_INTERVAL_MS;
}
// getDataFromRegisters() fills accel[] but does not set sensor_mask in this library version.
if (event.accel[0] == 0 && event.accel[1] == 0 && event.accel[2] == 0) {
return MOTION_SENSOR_CHECK_INTERVAL_MS;
}
x = event.accel[0];
y = event.accel[1];
z = event.accel[2];
// LOG_DEBUG("ICM-42607-P accel read x=%.3fg y=%.3fg z=%.3fg", (float)x / ICM42607P_COUNTS_PER_G,
// (float)y / ICM42607P_COUNTS_PER_G, (float)z / ICM42607P_COUNTS_PER_G);
return MOTION_SENSOR_CHECK_INTERVAL_MS;
#endif
}
#endif

View File

@@ -0,0 +1,28 @@
#pragma once
#ifndef _ICM42607P_SENSOR_H_
#define _ICM42607P_SENSOR_H_
#include "MotionSensor.h"
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && __has_include(<ICM42670P.h>)
#include <memory>
class ICM42670;
class ICM42607PSensor : public MotionSensor
{
private:
std::unique_ptr<ICM42670> sensor;
TwoWire *wire = nullptr;
public:
explicit ICM42607PSensor(ScanI2C::FoundDevice foundDevice);
~ICM42607PSensor() override;
virtual bool init() override;
virtual int32_t runOnce() override;
};
#endif
#endif

View File

@@ -0,0 +1,115 @@
#include "MMC5983MASensor.h"
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && __has_include(<SparkFun_MMC5983MA_Arduino_Library.h>)
#include "detect/ScanI2CTwoWire.h"
#if !defined(MESHTASTIC_EXCLUDE_SCREEN)
extern graphics::Screen *screen;
#endif
static constexpr float MMC5983MA_ZERO_FIELD = 131072.0f;
static constexpr float MMC5983MA_COUNTS_PER_GAUSS = 16384.0f;
static constexpr uint16_t MMC5983MA_CONTINUOUS_FREQUENCY_HZ = 10;
static constexpr float MMC5983MA_HEADING_OFFSET_DEG = 180.0f;
MMC5983MASensor::MMC5983MASensor(ScanI2C::FoundDevice foundDevice) : MotionSensor::MotionSensor(foundDevice) {}
bool MMC5983MASensor::init()
{
LOG_DEBUG("MMC5983MA begin on addr 0x%02X (port=%d)", device.address.address, device.address.port);
TwoWire *wire = ScanI2CTwoWire::fetchI2CBus(device.address);
if (!sensor.begin(*wire)) {
LOG_DEBUG("MMC5983MA init error");
return false;
}
sensor.softReset();
sensor.setFilterBandwidth(100);
sensor.performSetOperation();
sensor.enableAutomaticSetReset();
continuousMode = sensor.setContinuousModeFrequency(MMC5983MA_CONTINUOUS_FREQUENCY_HZ);
continuousMode &= sensor.enableContinuousMode();
if (!continuousMode) {
LOG_DEBUG("MMC5983MA continuous mode failed, using single-shot reads");
sensor.disableContinuousMode();
}
loadMagnetometerCalibration(compassCalibrationFileName, highestX, lowestX, highestY, lowestY, highestZ, lowestZ);
return true;
}
bool MMC5983MASensor::readMagnetometer(float &xGauss, float &yGauss, float &zGauss)
{
uint32_t rawX = 0;
uint32_t rawY = 0;
uint32_t rawZ = 0;
if (!(continuousMode ? sensor.readFieldsXYZ(&rawX, &rawY, &rawZ) : sensor.getMeasurementXYZ(&rawX, &rawY, &rawZ))) {
LOG_DEBUG("MMC5983MA read failed");
return false;
}
xGauss = ((float)rawX - MMC5983MA_ZERO_FIELD) / MMC5983MA_COUNTS_PER_GAUSS;
yGauss = ((float)rawY - MMC5983MA_ZERO_FIELD) / MMC5983MA_COUNTS_PER_GAUSS;
zGauss = ((float)rawZ - MMC5983MA_ZERO_FIELD) / MMC5983MA_COUNTS_PER_GAUSS;
return true;
}
int32_t MMC5983MASensor::runOnce()
{
float magX = 0, magY = 0, magZ = 0;
if (!readMagnetometer(magX, magY, magZ)) {
return MOTION_SENSOR_CHECK_INTERVAL_MS;
}
#if !defined(MESHTASTIC_EXCLUDE_SCREEN)
if (doCalibration) {
beginCalibrationDisplay(showingScreen);
updateCalibrationExtrema(magX, magY, magZ, highestX, lowestX, highestY, lowestY, highestZ, lowestZ);
finishCalibrationIfExpired(showingScreen, compassCalibrationFileName, highestX, lowestX, highestY, lowestY, highestZ,
lowestZ);
}
#endif
magX -= (highestX + lowestX) / 2;
magY -= (highestY + lowestY) / 2;
magZ -= (highestZ + lowestZ) / 2;
#if !defined(MESHTASTIC_EXCLUDE_SCREEN) && HAS_SCREEN
float heading = atan2f(magY, magX) * RAD_TO_DEG + MMC5983MA_HEADING_OFFSET_DEG;
if (heading < 0.0f) {
heading += 360.0f;
} else if (heading >= 360.0f) {
heading -= 360.0f;
}
heading = applyCompassOrientation(heading);
if (screen) {
screen->setHeading(heading);
}
#endif
return MOTION_SENSOR_CHECK_INTERVAL_MS;
}
void MMC5983MASensor::calibrate(uint16_t forSeconds)
{
#if !defined(MESHTASTIC_EXCLUDE_SCREEN)
float xGauss = 0.0f;
float yGauss = 0.0f;
float zGauss = 0.0f;
LOG_DEBUG("MMC5983MA calibration started for %is", forSeconds);
if (readMagnetometer(xGauss, yGauss, zGauss)) {
seedCalibrationExtrema(xGauss, yGauss, zGauss, highestX, lowestX, highestY, lowestY, highestZ, lowestZ);
} else {
seedCalibrationExtrema(0.0f, 0.0f, 0.0f, highestX, lowestX, highestY, lowestY, highestZ, lowestZ);
}
startCalibrationWindow(forSeconds);
#endif
}
#endif

View File

@@ -0,0 +1,31 @@
#pragma once
#ifndef _MMC5983MA_SENSOR_H_
#define _MMC5983MA_SENSOR_H_
#include "MotionSensor.h"
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && __has_include(<SparkFun_MMC5983MA_Arduino_Library.h>)
#include <SparkFun_MMC5983MA_Arduino_Library.h>
class MMC5983MASensor : public MotionSensor
{
private:
SFE_MMC5983MA sensor;
bool continuousMode = false;
bool showingScreen = false;
static constexpr const char *compassCalibrationFileName = "/prefs/compass_mmc5983ma.dat";
float highestX = 0, lowestX = 0, highestY = 0, lowestY = 0, highestZ = 0, lowestZ = 0;
bool readMagnetometer(float &xGauss, float &yGauss, float &zGauss);
public:
explicit MMC5983MASensor(ScanI2C::FoundDevice foundDevice);
virtual bool init() override;
virtual int32_t runOnce() override;
virtual void calibrate(uint16_t forSeconds) override;
};
#endif
#endif

View File

@@ -0,0 +1,115 @@
#pragma once
#ifndef _MAGNETOMETER_THREAD_H_
#define _MAGNETOMETER_THREAD_H_
#include "configuration.h"
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && !MESHTASTIC_EXCLUDE_MAGNETOMETER
#include "../concurrency/OSThread.h"
#include "MMC5983MASensor.h"
#include "MotionSensor.h"
extern ScanI2C::DeviceAddress magnetometer_found;
class MagnetometerThread : public concurrency::OSThread
{
private:
MotionSensor *sensor = nullptr;
ScanI2C::FoundDevice device;
bool isInitialised = false;
public:
explicit MagnetometerThread(ScanI2C::FoundDevice foundDevice) : OSThread("Magnetometer")
{
device = foundDevice;
init();
}
explicit MagnetometerThread(ScanI2C::DeviceType type) : MagnetometerThread(ScanI2C::FoundDevice{type, magnetometer_found}) {}
void start()
{
init();
setIntervalFromNow(0);
};
void calibrate(uint16_t forSeconds)
{
if (sensor) {
sensor->calibrate(forSeconds);
setIntervalFromNow(0);
}
}
protected:
int32_t runOnce() override
{
canSleep = true;
if (isInitialised) {
return sensor->runOnce();
}
return MOTION_SENSOR_CHECK_INTERVAL_MS;
}
private:
void init()
{
if (isInitialised) {
return;
}
if (device.address.port == ScanI2C::I2CPort::NO_I2C || device.address.address == 0 || device.type == ScanI2C::NONE) {
LOG_DEBUG("MagnetometerThread Disable due to no sensors found");
disable();
return;
}
switch (device.type) {
case ScanI2C::DeviceType::MMC5983MA:
sensor = new MMC5983MASensor(device);
break;
default:
disable();
return;
}
isInitialised = sensor->init();
if (!isInitialised) {
clean();
}
LOG_DEBUG("MagnetometerThread::init %s", isInitialised ? "ok" : "failed");
}
MagnetometerThread(const MagnetometerThread &other) : OSThread::OSThread("Magnetometer") { this->copy(other); }
virtual ~MagnetometerThread() { clean(); }
MagnetometerThread &operator=(const MagnetometerThread &other)
{
this->copy(other);
return *this;
}
void copy(const MagnetometerThread &other)
{
if (this != &other) {
clean();
this->device = ScanI2C::FoundDevice(other.device.type,
ScanI2C::DeviceAddress(other.device.address.port, other.device.address.address));
}
}
void clean()
{
isInitialised = false;
delete sensor;
sensor = nullptr;
}
};
#endif
#endif

View File

@@ -187,11 +187,9 @@ class BluetoothPhoneAPI : public PhoneAPI, public concurrency::OSThread
LOG_INFO("BLE onConfigStart");
// Prefer high throughput during config/setup, at the cost of high power consumption (for a few seconds)
if (bleServer && isConnected()) {
uint16_t conn_handle = nimbleBluetoothConnHandle.load();
if (conn_handle != BLE_HS_CONN_HANDLE_NONE) {
requestHighThroughputConnection(conn_handle);
}
uint16_t conn_handle = nimbleBluetoothConnHandle.load();
if (conn_handle != BLE_HS_CONN_HANDLE_NONE) {
requestHighThroughputConnection(conn_handle);
}
}
@@ -200,11 +198,9 @@ class BluetoothPhoneAPI : public PhoneAPI, public concurrency::OSThread
LOG_INFO("BLE onConfigComplete");
// Switch to lower power consumption BLE connection params for steady-state use after config/setup is complete
if (bleServer && isConnected()) {
uint16_t conn_handle = nimbleBluetoothConnHandle.load();
if (conn_handle != BLE_HS_CONN_HANDLE_NONE) {
requestLowerPowerConnection(conn_handle);
}
uint16_t conn_handle = nimbleBluetoothConnHandle.load();
if (conn_handle != BLE_HS_CONN_HANDLE_NONE) {
requestLowerPowerConnection(conn_handle);
}
}
@@ -337,7 +333,7 @@ class BluetoothPhoneAPI : public PhoneAPI, public concurrency::OSThread
}
/// Check the current underlying physical link to see if the client is currently connected
virtual bool checkIsConnected() override { return bleServer && bleServer->getConnectedCount() > 0; }
virtual bool checkIsConnected() override { return nimbleBluetoothConnHandle.load() != BLE_HS_CONN_HANDLE_NONE; }
void requestHighThroughputConnection(uint16_t conn_handle)
{
@@ -732,32 +728,19 @@ bool NimbleBluetooth::isActive()
bool NimbleBluetooth::isConnected()
{
return bleServer && bleServer->getConnectedCount() > 0;
return nimbleBluetoothConnHandle.load() != BLE_HS_CONN_HANDLE_NONE;
}
int NimbleBluetooth::getRssi()
{
#if defined(CONFIG_IDF_TARGET_ESP32S3) || defined(CONFIG_IDF_TARGET_ESP32C6)
if (!bleServer || !isConnected()) {
uint16_t conn_handle = nimbleBluetoothConnHandle.load();
if (conn_handle != BLE_HS_CONN_HANDLE_NONE) {
return 0; // No active BLE connection
}
uint16_t connHandle = nimbleBluetoothConnHandle.load();
if (connHandle == BLE_HS_CONN_HANDLE_NONE) {
const auto peers = bleServer->getPeerDevices(true);
if (!peers.empty()) {
connHandle = peers.begin()->first;
nimbleBluetoothConnHandle = connHandle;
}
}
if (connHandle == BLE_HS_CONN_HANDLE_NONE) {
return 0; // Connection handle not available yet
}
int8_t rssi = 0;
const int rc = ble_gap_conn_rssi(connHandle, &rssi);
const int rc = ble_gap_conn_rssi(conn_handle, &rssi);
if (rc == 0) {
return rssi;
@@ -879,7 +862,7 @@ void NimbleBluetooth::setupService()
/// Given a level between 0-100, update the BLE attribute
void updateBatteryLevel(uint8_t level)
{
if ((config.bluetooth.enabled == true) && bleServer && nimbleBluetooth->isConnected()) {
if ((config.bluetooth.enabled == true) && nimbleBluetooth && nimbleBluetooth->isConnected()) {
BatteryCharacteristic->setValue(&level, 1);
BatteryCharacteristic->notify();
}
@@ -894,7 +877,7 @@ void NimbleBluetooth::clearBonds()
void NimbleBluetooth::sendLog(const uint8_t *logMessage, size_t length)
{
if (!bleServer || !isConnected() || length > 512) {
if (!isConnected() || length > 512) {
return;
}
logRadioCharacteristic->setValue(logMessage, length);

View File

@@ -0,0 +1,7 @@
#pragma once
#if __has_include_next("esp_eth_driver.h")
#include_next "esp_eth_driver.h"
#elif __has_include("esp_eth.h")
#include "esp_eth.h"
#endif

View File

@@ -117,6 +117,8 @@
#define HW_VENDOR meshtastic_HardwareModel_PRIVATE_HW
#elif defined(HELTEC_T114)
#define HW_VENDOR meshtastic_HardwareModel_HELTEC_MESH_NODE_T114
#elif defined(HELTEC_MESH_NODE_T1)
#define HW_VENDOR meshtastic_HardwareModel_HELTEC_MESH_NODE_T1
#elif defined(MESHLINK)
#define HW_VENDOR meshtastic_HardwareModel_MESHLINK
#elif defined(SEEED_XIAO_NRF52840_KIT)

View File

@@ -362,4 +362,10 @@ uint32_t SimRadio::getPacketTime(uint32_t pl, bool received)
uint32_t msecs = tPacket * 1000;
return msecs;
}
int16_t SimRadio::getCurrentRSSI()
{
// Simulated radio - return a reasonable default noise floor
return -120;
}

View File

@@ -48,6 +48,8 @@ class SimRadio : public RadioInterface, protected concurrency::NotifiedWorkerThr
// Convert Compressed_msg to normal msg and receive it
void unpackAndReceive(meshtastic_MeshPacket &p);
int16_t getCurrentRSSI() override;
/**
* Debugging counts
*/
@@ -93,4 +95,4 @@ class SimRadio : public RadioInterface, protected concurrency::NotifiedWorkerThr
virtual uint32_t getPacketTime(uint32_t pl, bool received = false) override;
};
extern SimRadio *simRadio;
extern SimRadio *simRadio;

View File

@@ -138,7 +138,6 @@ static const RegionProfile TEST_PROFILE_SPACED = {
/* textThrottle */ 0,
/* positionThrottle */ 0,
/* telemetryThrottle */ 0,
/* overrideSlot */ 0,
};
// A licensed-only profile for testing access control
@@ -151,7 +150,6 @@ static const RegionProfile TEST_PROFILE_LICENSED = {
/* textThrottle */ 5,
/* positionThrottle */ 10,
/* telemetryThrottle */ 10,
/* overrideSlot */ 3,
};
// Turbo-only profile
@@ -164,7 +162,6 @@ static const RegionProfile TEST_PROFILE_TURBO = {
/* textThrottle */ 0,
/* positionThrottle */ 0,
/* telemetryThrottle */ 0,
/* overrideSlot */ 0,
};
// A preset list for the preset-hash override slot test (LONG_FAST + MEDIUM_FAST)
@@ -185,7 +182,6 @@ static const RegionProfile TEST_PROFILE_PRESET_HASH = {
/* textThrottle */ 0,
/* positionThrottle */ 0,
/* telemetryThrottle */ 0,
/* overrideSlot */ OVERRIDE_SLOT_PRESET_HASH,
};
// Standalone test region using US frequencies (26 MHz span → 104 slots at 250 kHz BW)
@@ -200,25 +196,26 @@ static const RegionInfo TEST_REGION_PRESET_HASH = {
false,
&TEST_PROFILE_PRESET_HASH,
meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST,
OVERRIDE_SLOT_PRESET_HASH,
"TEST_PRESET_HASH",
};
static const RegionInfo testRegions[] = {
// A wide US-like region with spacing + padding
{meshtastic_Config_LoRaConfig_RegionCode_US, 902.0f, 928.0f, 100, 30, false, false, &TEST_PROFILE_SPACED,
meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST, "TEST_US_SPACED"},
meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST, 0, "TEST_US_SPACED"},
// A narrow band simulating tight EU regulation
{meshtastic_Config_LoRaConfig_RegionCode_EU_868, 869.4f, 869.65f, 10, 14, false, false, &TEST_PROFILE_LICENSED,
meshtastic_Config_LoRaConfig_ModemPreset_LONG_SLOW, "TEST_EU_LICENSED"},
meshtastic_Config_LoRaConfig_ModemPreset_LONG_SLOW, 3, "TEST_EU_LICENSED"},
// A wide-LoRa region with turbo-only presets
{meshtastic_Config_LoRaConfig_RegionCode_LORA_24, 2400.0f, 2483.5f, 100, 10, false, true, &TEST_PROFILE_TURBO,
meshtastic_Config_LoRaConfig_ModemPreset_SHORT_TURBO, "TEST_LORA24_TURBO"},
meshtastic_Config_LoRaConfig_ModemPreset_SHORT_TURBO, 0, "TEST_LORA24_TURBO"},
// Sentinel — must be last
{meshtastic_Config_LoRaConfig_RegionCode_UNSET, 902.0f, 928.0f, 100, 30, false, false, &TEST_PROFILE_SPACED,
meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST, "TEST_UNSET"},
meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST, 0, "TEST_UNSET"},
};
static const RegionInfo *getTestRegion(meshtastic_Config_LoRaConfig_RegionCode code)
@@ -256,7 +253,7 @@ static void test_shadowTable_licensedProfileFlagsCorrect()
const RegionInfo *r = getTestRegion(meshtastic_Config_LoRaConfig_RegionCode_EU_868);
TEST_ASSERT_TRUE(r->profile->licensedOnly);
TEST_ASSERT_FALSE(r->profile->audioPermitted);
TEST_ASSERT_EQUAL(3, r->profile->overrideSlot);
TEST_ASSERT_EQUAL(3, r->overrideSlot);
}
static void test_shadowTable_presetCountMatchesExpected()
@@ -319,8 +316,8 @@ static void test_shadowTable_unknownCodeFallsToSentinel()
static void test_shadowTable_presetHashProfileHasCorrectOverrideSlot()
{
TEST_ASSERT_EQUAL(OVERRIDE_SLOT_PRESET_HASH, TEST_PROFILE_PRESET_HASH.overrideSlot);
TEST_ASSERT_EQUAL(-1, TEST_PROFILE_PRESET_HASH.overrideSlot);
TEST_ASSERT_EQUAL(OVERRIDE_SLOT_PRESET_HASH, TEST_REGION_PRESET_HASH.overrideSlot);
TEST_ASSERT_EQUAL(-1, TEST_REGION_PRESET_HASH.overrideSlot);
TEST_ASSERT_EQUAL(2, TEST_REGION_PRESET_HASH.getNumPresets());
}

View File

@@ -33,7 +33,12 @@ class TestableRadioInterface : public RadioInterface
static void test_bwCodeToKHz_specialMappings()
{
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 7.8f, bwCodeToKHz(8));
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 10.4f, bwCodeToKHz(10));
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 15.6f, bwCodeToKHz(16));
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 20.8f, bwCodeToKHz(21));
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 31.25f, bwCodeToKHz(31));
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 41.7f, bwCodeToKHz(42));
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 62.5f, bwCodeToKHz(62));
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 203.125f, bwCodeToKHz(200));
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 406.25f, bwCodeToKHz(400));
@@ -47,6 +52,18 @@ static void test_bwCodeToKHz_passthrough()
TEST_ASSERT_FLOAT_WITHIN(0.0001f, 250.0f, bwCodeToKHz(250));
}
static void test_bwCodeToKHz_roundTrip()
{
// Round-trip: bwKHzToCode(bwCodeToKHz(code)) should return the original code
uint16_t codes[] = {8, 10, 16, 21, 31, 42, 62, 200, 400, 800, 1600};
for (size_t i = 0; i < sizeof(codes) / sizeof(codes[0]); i++) {
uint16_t code = codes[i];
float khz = bwCodeToKHz(code);
uint16_t result = bwKHzToCode(khz);
TEST_ASSERT_EQUAL_UINT16(code, result);
}
}
static void test_validateConfigLora_noopWhenUsePresetFalse()
{
meshtastic_Config_LoRaConfig cfg = meshtastic_Config_LoRaConfig_init_zero;
@@ -213,6 +230,7 @@ void setup()
UNITY_BEGIN();
RUN_TEST(test_bwCodeToKHz_specialMappings);
RUN_TEST(test_bwCodeToKHz_passthrough);
RUN_TEST(test_bwCodeToKHz_roundTrip);
RUN_TEST(test_validateConfigLora_noopWhenUsePresetFalse);
RUN_TEST(test_validateConfigLora_validPreset_nonWideRegion);
RUN_TEST(test_validateConfigLora_validPreset_wideRegion);

View File

@@ -195,7 +195,7 @@ custom_sdkconfig =
;
; MBEDTLS
;
CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=8192
CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=16384 ; do not change, affects buffer allocation (PR10535)
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=n
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN=y
; Switch to custom CA bundle (for Meshtastic MQTT/etc) in the future
@@ -205,10 +205,15 @@ custom_sdkconfig =
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=1
; #shame
CONFIG_MBEDTLS_ALLOW_WEAK_CERTIFICATE_VERIFICATION=y
CONFIG_MBEDTLS_SSL_RENEGOTIATION=n
CONFIG_MBEDTLS_SSL_PROTO_DTLS=n
CONFIG_MBEDTLS_CLIENT_SSL_SESSION_TICKETS=n
CONFIG_MBEDTLS_SERVER_SSL_SESSION_TICKETS=n
; These six options must match the precompiled framework-arduinoespressif32-libs
; which was built with all six enabled. Disabling them changes mbedtls_ssl_context
; struct layout, causing an ABI mismatch and a crash in mbedtls_ssl_set_hostname.
CONFIG_MBEDTLS_SSL_RENEGOTIATION=y
CONFIG_MBEDTLS_SSL_PROTO_DTLS=y
CONFIG_MBEDTLS_CLIENT_SSL_SESSION_TICKETS=y
CONFIG_MBEDTLS_SERVER_SSL_SESSION_TICKETS=y
CONFIG_MBEDTLS_SSL_KEEP_PEER_CERTIFICATE=y
CONFIG_MBEDTLS_SSL_ALPN=y
CONFIG_MBEDTLS_PKCS7_C=n
CONFIG_MBEDTLS_CAMELLIA_C=n
CONFIG_MBEDTLS_CCM_C=n

View File

@@ -11,7 +11,7 @@ build_flags = -fno-strict-aliasing
-D USE_EINK
-D USE_EINK_PARALLELDISPLAY
-D PRIVATE_HW
-D TOUCH_THRESHOLD_X=60
-D TOUCH_THRESHOLD_X=40
-D TOUCH_THRESHOLD_Y=40
-D TIME_LONG_PRESS=500
; -D EINK_LIMIT_GHOSTING_PX=5000

View File

@@ -15,7 +15,6 @@ board = promicro-nrf52840
build_flags = ${nrf52840_base.build_flags}
-I variants/nrf52840/diy/nrf52_promicro_diy_tcxo
-D NRF52_PROMICRO_DIY
; -D RADIOLIB_GODMODE=1 ; needed for some LR2021 items, but not enabled by default.
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/nrf52840/diy/nrf52_promicro_diy_tcxo>
debug_tool = jlink

View File

@@ -0,0 +1,35 @@
; Heltec Mesh Node T1 nRF52840/SX1262 device
[env:heltec-mesh-node-t1]
custom_meshtastic_hw_model = 133
custom_meshtastic_hw_model_slug = HELTEC_MESH_NODE_T1
custom_meshtastic_architecture = nrf52840
custom_meshtastic_actively_supported = true
custom_meshtastic_support_level = 1
custom_meshtastic_display_name = Heltec Mesh Node T1
custom_meshtastic_images = heltec-mesh-node-t1.svg
custom_meshtastic_tags = Heltec
extends = nrf52840_base
board = heltec_mesh_node_t1
board_level = pr
debug_tool = jlink
build_flags = ${nrf52840_base.build_flags}
-Ivariants/nrf52840/heltec_mesh_node_t1
-DHELTEC_MESH_NODE_T1
-DUSE_TFTDISPLAY
-DUSER_SETUP_LOADED
-DST7735_DRIVER
-DST7735_REDTAB160x80
-D TFT_SPI_PORT=SPI1
-D TFT_CS=ST7735_CS
-D TFT_DC=ST7735_RS
-D TFT_RST=ST7735_RESET
-D TFT_BL=ST7735_BL
-D TFT_BACKLIGHT_ON=LOW
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/nrf52840/heltec_mesh_node_t1>
lib_deps =
${nrf52840_base.lib_deps}
lewisxhe/PCF8563_Library@^1.0.1
bodmer/TFT_eSPI@2.5.43

View File

@@ -0,0 +1,85 @@
/*
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 - pins 0 and 1 are hardwired for xtal and should never be enabled
0xff, 0xff, 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()
{
pinMode(PIN_BUZZER_VOLTAGE_MULTIPLIER_1, OUTPUT);
pinMode(PIN_BUZZER_VOLTAGE_MULTIPLIER_2, OUTPUT);
digitalWrite(PIN_BUZZER_VOLTAGE_MULTIPLIER_1, HIGH);
digitalWrite(PIN_BUZZER_VOLTAGE_MULTIPLIER_2, HIGH);
}
void variant_shutdown()
{
nrf_gpio_cfg_default(ST7735_CS);
nrf_gpio_cfg_default(ST7735_RS);
nrf_gpio_cfg_default(ST7735_SDA);
nrf_gpio_cfg_default(ST7735_SCK);
nrf_gpio_cfg_default(ST7735_RESET);
nrf_gpio_cfg_default(ST7735_BL);
nrf_gpio_cfg_default(VTFT_CTRL);
nrf_gpio_cfg_default(PIN_WIRE_SDA);
nrf_gpio_cfg_default(PIN_WIRE_SCL);
nrf_gpio_cfg_default(SX126X_CS);
nrf_gpio_cfg_default(SX126X_DIO1);
nrf_gpio_cfg_default(SX126X_BUSY);
nrf_gpio_cfg_default(SX126X_RESET);
nrf_gpio_cfg_default(PIN_SPI_MISO);
nrf_gpio_cfg_default(PIN_SPI_MOSI);
nrf_gpio_cfg_default(PIN_SPI_SCK);
// nrf_gpio_cfg_default(PIN_SPI1_MISO);// ST7735 doesn't support MISO, so we don't configure it at all
nrf_gpio_cfg_default(PIN_SPI1_MOSI);
nrf_gpio_cfg_default(PIN_SPI1_SCK);
nrf_gpio_cfg_default(PIN_GPS_RESET);
nrf_gpio_cfg_default(PIN_GPS_EN);
nrf_gpio_cfg_default(PIN_GPS_PPS);
nrf_gpio_cfg_default(GPS_TX_PIN);
nrf_gpio_cfg_default(GPS_RX_PIN);
nrf_gpio_cfg_default(PIN_BUZZER_VOLTAGE_MULTIPLIER_1);
nrf_gpio_cfg_default(PIN_BUZZER_VOLTAGE_MULTIPLIER_2);
pinMode(PIN_BUZZER, OUTPUT);
digitalWrite(PIN_BUZZER, LOW);
pinMode(PIN_SENSOR_EN, OUTPUT);
digitalWrite(PIN_SENSOR_EN, !PIN_SENSOR_EN_ACTIVE); // Turn off sensor power
pinMode(PIN_LED1, OUTPUT);
digitalWrite(PIN_LED1, HIGH);
}

View File

@@ -0,0 +1,177 @@
/*
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_HELTEC_MESH_NODE_T1_
#define _VARIANT_HELTEC_MESH_NODE_T1_
/** Master clock frequency */
#define VARIANT_MCK (64000000ul)
#define USE_LFXO // Board uses 32khz crystal for LF
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "WVariant.h"
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
#define ST7735_CS (0 + 12)
#define ST7735_RS (0 + 22) // DC
#define ST7735_SDA (0 + 24)
#define ST7735_SCK (32 + 0)
#define ST7735_RESET (0 + 20)
#define ST7735_MISO -1
#define ST7735_BUSY -1
#define ST7735_BL (0 + 15)
#define VTFT_CTRL (0 + 13) // Active HIGH, powers the ST7735 display
#define SPI_FREQUENCY 80000000
#define SPI_READ_FREQUENCY 16000000
#define SCREEN_ROTATE
#define TFT_HEIGHT 160
#define TFT_WIDTH 80
#define TFT_OFFSET_X 24
#define TFT_OFFSET_Y 0
#define TFT_INVERT false
#define SCREEN_TRANSITION_FRAMERATE 3 // fps
#define DISPLAY_FORCE_SMALL_FONTS
// Number of pins defined in PinDescription array
#define PINS_COUNT (48)
#define NUM_DIGITAL_PINS (48)
#define NUM_ANALOG_INPUTS (1)
#define NUM_ANALOG_OUTPUTS (0)
// LEDs
#define PIN_LED1 (0 + 16)
#define LED_BLUE PIN_LED1 // fake for bluefruit library
#define LED_GREEN PIN_LED1
#define LED_STATE_ON 0 // State when LED is lit
/*
* Buttons
*/
#define PIN_BUTTON1 (32 + 10)
#define PIN_BUTTON2 (0 + 14)
/*
No longer populated on PCB
*/
#define PIN_SERIAL2_RX (-1)
#define PIN_SERIAL2_TX (-1)
/*
* I2C
*/
#define WIRE_INTERFACES_COUNT 1
// I2C bus 1
#define PIN_WIRE_SDA (32 + 3)
#define PIN_WIRE_SCL (0 + 10)
#define PIN_SENSOR_EN (32 + 6) // Power control pin for sensors
#define PIN_SENSOR_EN_ACTIVE LOW // Power control active state
// #define ICM_42607P_INT_PIN (32 + 1) // ICM42607P INT1, Arduino pin 33 / nRF P1.01
// #define ICM_42607P_INT2_PIN (32 + 7) // ICM42607P INT2, Arduino pin 39 / nRF P1.07
/*
* Lora radio
*/
#define USE_SX1262
#define SX126X_CS (32 + 11) // FIXME - we really should define LORA_CS instead
#define LORA_CS SX126X_CS
#define SX126X_DIO1 (0 + 31)
#define SX126X_BUSY (0 + 29)
#define SX126X_RESET (0 + 2)
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
/*
* SPI Interfaces
*/
#define SPI_INTERFACES_COUNT 2
// For LORA, spi 0
#define PIN_SPI_MISO (0 + 3)
#define PIN_SPI_MOSI (32 + 14)
#define PIN_SPI_SCK (32 + 13)
#define PIN_SPI1_MISO ST7735_MISO
#define PIN_SPI1_MOSI ST7735_SDA
#define PIN_SPI1_SCK ST7735_SCK
/*
* GPS pins
*/
#define GPS_UC6580
#define GPS_BAUDRATE 115200
#define PIN_GPS_RESET (0 + 26)
#define GPS_RESET_MODE LOW
#define PIN_GPS_EN (0 + 4)
#define GPS_EN_ACTIVE LOW
#define PERIPHERAL_WARMUP_MS 1000 // Make sure I2C QuickLink has stable power before continuing
#define PIN_GPS_PPS (32 + 9) // Pulse per second input from the GPS
#define GPS_TX_PIN (0 + 7)
#define GPS_RX_PIN (0 + 8)
#define GPS_THREAD_INTERVAL 50
#define PIN_SERIAL1_RX GPS_RX_PIN
#define PIN_SERIAL1_TX GPS_TX_PIN
#define PIN_BUZZER (0 + 9)
#define PIN_BUZZER_VOLTAGE_MULTIPLIER_1 (32 + 2)
#define PIN_BUZZER_VOLTAGE_MULTIPLIER_2 (32 + 5)
#define ADC_CTRL 11
#define ADC_CTRL_ENABLED HIGH
#define BATTERY_PIN 5
#define ADC_RESOLUTION 14
#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 (4.916F)
// nrf52840 AIN3 = Pin 5
// commented out due to power leakage of 2.9mA in shutdown state see reported issue #8801
#define BATTERY_LPCOMP_INPUT NRF_LPCOMP_INPUT_3
// We have AIN3 with a VBAT divider so AIN3 = VBAT * (100/490)
// We have the device going deep sleep under 3.1V, which is AIN3 = 0.63V
// So we can wake up when VBAT>=VDD is restored to 3.3V, where AIN3 = 0.67V
// Ratio 0.67/3.3 = 0.20, so we can pick a bit higher, 2/8 VDD, which means
// VBAT=4.04V
#define BATTERY_LPCOMP_THRESHOLD NRF_LPCOMP_REF_SUPPLY_2_8
#define HAS_RTC 0
#ifdef __cplusplus
}
#endif
/*----------------------------------------------------------------------------
* Arduino objects - C++ only
*----------------------------------------------------------------------------*/
#endif

View File

@@ -0,0 +1,16 @@
[env:seeed_xiao_rp2040]
extends = rp2040_base
board = seeed_xiao_rp2040
board_level = pr
upload_protocol = picotool
# add our variants files to the include and src paths
build_src_filter = ${rp2040_base.build_src_filter} +<../variants/rp2040/seeed_xiao_rp2040/>
build_flags =
${rp2040_base.build_flags}
-D PRIVATE_HW
-D SEEED_XIAO_RP2040
-I variants/rp2040/seeed_xiao_rp2040
-D DEBUG_RP2040_PORT=Serial
;-D HW_SPI1_DEVICE
debug_build_flags = ${rp2040_base.build_flags}, -g
debug_tool = cmsis-dap ; for e.g. Picotool

View File

@@ -0,0 +1,10 @@
#include <Arduino.h>
// Turn off the green and blue LEDs, which are on by default.
void initVariant()
{
pinMode(PIN_LED_G, OUTPUT);
pinMode(PIN_LED_B, OUTPUT);
digitalWrite(PIN_LED_G, HIGH);
digitalWrite(PIN_LED_B, HIGH);
}

View File

@@ -0,0 +1,27 @@
#define ARDUINO_ARCH_AVR
// #define BUTTON_PIN -1
#define LED_POWER PIN_LED_R
// active low RGB led
#define LED_POWER_ON 0
// no ADC by default
#define BATTERY_PIN -1
// ratio of voltage divider = 3.0 (R1=200k, R2=100k)
#define ADC_MULTIPLIER 3
#define BATTERY_SENSE_RESOLUTION_BITS ADC_RESOLUTION
#define USE_SX1262
#define LORA_SCK 2
#define LORA_MISO 4
#define LORA_MOSI 3
#define SX126X_CS 6
#define SX126X_DIO1 27
#define SX126X_BUSY 29
#define SX126X_RESET 28
#define SX126X_RXEN 7
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8

View File

@@ -0,0 +1,150 @@
# Raspberry Pi Pico 2 + W5500 + E22-900M30S — Meshtastic Variant
Meshtastic support for a **Raspberry Pi Pico 2** (RP2350, 4 MB flash) with an external **W5500** Ethernet module and an **EBYTE E22-900M30S** LoRa module.
---
## Required Hardware
| Component | Model | Notes |
| --------- | ------------------- | ---------------------------------------- |
| MCU | Raspberry Pi Pico 2 | RP2350 @ 150 MHz, 512 KB RAM, 4 MB flash |
| Ethernet | W5500 module | Any WIZnet W5500 breakout board |
| LoRa | EBYTE E22-900M30S | SX1262 + 30 dBm PA, 868/915 MHz |
---
## Pinout
### System pins (Pico 2, fixed)
| GPIO | Function |
| ---- | --------------------------------------- |
| GP24 | VBUS sense — HIGH when USB is connected |
| GP25 | User LED (heartbeat) |
| GP29 | ADC3 — VSYS/3, measures supply voltage |
### W5500 Ethernet (SPI0)
| W5500 signal | Pico 2 GPIO |
| ------------ | ----------- |
| MISO | GP16 |
| CS / SCS | GP17 |
| SCK | GP18 |
| MOSI | GP19 |
| RST | GP20 |
| INT | — (nc) |
| VCC | 3.3V |
| GND | GND |
> SPI0 is reserved for the W5500.
### E22-900M30S LoRa (SPI1)
| E22 signal | Pico 2 GPIO | Notes |
| ---------- | ----------- | ------------------------------------------ |
| SCK | GP10 | SPI1 clock |
| MOSI | GP11 | SPI1 TX |
| MISO | GP12 | SPI1 RX |
| NSS / CS | GP13 | Chip select |
| RESET | GP15 | Active LOW reset |
| DIO1 | GP14 | IRQ interrupt |
| BUSY | GP2 | Module busy indicator |
| RXEN | GP3 | LNA enable — held HIGH permanently |
| TXEN | ← DIO2 | See wiring note below |
| VCC | 3.3V | Add a 100 µF capacitor close to the module |
| GND | GND | — |
> See `wiring.svg` in this directory for the full connection diagram.
---
## Special wiring: DIO2 → TXEN bridge on the E22 module
The E22-900M30S does **not** connect DIO2 to the TXEN pin of its PA internally. They must be bridged with a short wire or solder bridge **on the module itself**:
```text
E22 DIO2 pin ──┐
├── wire / solder bridge on the module
E22 TXEN pin ──┘
```
With this bridge in place, `SX126X_DIO2_AS_RF_SWITCH` causes the SX1262 to drive DIO2 HIGH automatically during TX, enabling the PA without needing an RP2350 GPIO for TXEN.
**Without this bridge the module will not transmit.**
---
## Build
```bash
pio run -e pico2_w5500_e22
```
### Flash — BOOTSEL mode
1. Hold the **BOOTSEL** button on the Pico 2.
2. Connect USB to the PC — it appears as a `RPI-RP2` storage drive.
3. Copy the `.uf2` file:
```text
.pio/build/pico2_w5500_e22/firmware-pico2_w5500_e22-*.uf2
```
Or directly with picotool:
```bash
pio run -e pico2_w5500_e22 -t upload
```
---
## Network usage
This board uses Ethernet (no Wi-Fi). From the Meshtastic app:
- **Enable Ethernet** under `Config → Network → Ethernet Enabled`
- **DHCP** by default; static IP can also be configured
Services available once connected:
| Service | Details |
| ------- | --------------------------- |
| NTP | Time synchronization |
| MQTT | Messages to external broker |
| API | TCP socket on port 4403 |
| Syslog | Remote logging (optional) |
---
## Technical notes
### LoRa — RF control
| Define | Effect |
| ------------------------------ | ----------------------------------------------------------- |
| `SX126X_ANT_SW 3` | GP3 (RXEN) driven HIGH at init and never toggled again |
| `SX126X_DIO2_AS_RF_SWITCH` | SX1262 drives DIO2 HIGH during TX → enables TXEN via bridge |
| `SX126X_DIO3_TCXO_VOLTAGE 1.8` | E22 TCXO controlled by DIO3 |
| `-D EBYTE_E22_900M30S` | Sets `TX_GAIN_LORA=7`, max power 22 dBm |
> RXEN and TXEN may both be HIGH simultaneously during TX — this is safe for the E22 RF switch.
### Ethernet
- Library: `arduino-libraries/Ethernet@^2.0.2` (supports W5100/W5200/W5500 auto-detection).
- SPI0 is explicitly initialized with pins GP16/18/19 before `Ethernet.init()`.
- DHCP timeout is set to 10 s (instead of the default 60 s) to avoid blocking LoRa startup.
### HW_VENDOR
Mapped to `meshtastic_HardwareModel_PRIVATE_HW` — no dedicated model exists in the Meshtastic protobuf for this hardware combination yet.
---
## Memory usage (reference build)
| Resource | Used | Total | % |
| -------- | ------ | ------- | ----- |
| RAM | 94 KB | 512 KB | 18% |
| Flash | 964 KB | 3.58 MB | 26.3% |

View File

@@ -0,0 +1,25 @@
[env:pico2_w5500_e22]
extends = rp2350_base
board = rpipico2
board_level = community
upload_protocol = picotool
build_flags =
${rp2350_base.build_flags}
-ULED_BUILTIN # avoid "LED_BUILTIN redefined" warnings from framework common.h
-I variants/rp2350/diy/pico2_w5500_e22
-D HW_SPI1_DEVICE
-D EBYTE_E22_900M30S # selects the EBYTE E22-900M30S module config, including TCXO voltage support and TX gain / max power settings
# Re-enable Ethernet and API source paths excluded in rp2350_base
build_src_filter = ${rp2350_base.build_src_filter} +<mesh/eth/> +<mesh/api/> +<mqtt/>
lib_deps =
${rp2350_base.lib_deps}
${networking_base.lib_deps}
${networking_extra.lib_deps}
# Standard WIZnet Ethernet library — supports W5100/W5200/W5500 auto-detect
arduino-libraries/Ethernet@^2.0.2
debug_build_flags = ${rp2350_base.build_flags}, -g
debug_tool = cmsis-dap

View File

@@ -0,0 +1,88 @@
// Raspberry Pi Pico 2 + external W5500 Ethernet module + EBYTE E22-900M30S
// RP2350 (4 MB flash) — wire modules to the GPIO pins listed below
//
// LoRa (SX1262 / E22-900M30S) on SPI1:
// SCK=GP10 MOSI=GP11 MISO=GP12 CS=GP13
// RST=GP15 DIO1/IRQ=GP14 BUSY=GP2 RXEN=GP3
// TXEN: bridge E22_DIO2 → E22_TXEN on the module (no RP2350 GPIO needed)
//
// W5500 Ethernet on SPI0:
// MISO=GP16 CS=GP17 SCK=GP18 MOSI=GP19 RST=GP20
//
// See wiring.svg in this directory for a complete connection diagram.
// Community/DIY board — no dedicated Meshtastic HardwareModel
#define PRIVATE_HW
#define ARDUINO_ARCH_AVR
// Onboard LED (GP25 on Pico 2)
#define LED_POWER PIN_LED
// Power monitoring
// GP24: VBUS sense HIGH when USB is present (digital read)
// GP29: ADC3 measures VSYS/3 (200 kΩ / 100 kΩ divider, same as standard Pico 2)
#define EXT_PWR_DETECT 24
#define BATTERY_PIN 29
#define ADC_MULTIPLIER 3.0
#define BATTERY_SENSE_RESOLUTION_BITS 12
// No real battery — suppress false "battery at 100%" while USB powers VSYS
#define NO_BATTERY_LEVEL_ON_CHARGE
// Optional user button — connect a button between GP6 and GND
// #define BUTTON_PIN 6
// #define BUTTON_NEED_PULLUP
// GPS on UART1 (Serial2) — GP8 TX, GP9 RX
// GP8/GP9 belong to UART1, so we must use Serial2 (not the default Serial1/UART0).
// GP0/GP1 (UART0 defaults) are free but the firmware treats pin 0 as "not configured".
// GP4/GP5 occupied by I2C (SCL/SDA for BMP-280).
#define HAS_GPS 1
#define GPS_TX_PIN 8
#define GPS_RX_PIN 9
#define GPS_BAUDRATE 38400
#define GPS_SERIAL_PORT Serial2
// ---- EBYTE E22-900M30S on SPI1 -----------------------------------------
#define USE_SX1262
#undef LORA_SCK
#undef LORA_MISO
#undef LORA_MOSI
#undef LORA_CS
#define LORA_SCK 10
#define LORA_MOSI 11
#define LORA_MISO 12
#define LORA_CS 13
#define LORA_DIO0 RADIOLIB_NC
#define LORA_RESET 15
#define LORA_DIO1 14 // IRQ
#define LORA_DIO2 2 // BUSY
#define LORA_DIO3 RADIOLIB_NC
#ifdef USE_SX1262
#define SX126X_CS LORA_CS
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_DIO2
#define SX126X_RESET LORA_RESET
// GP3 = RXEN: driven HIGH at init and held there (LNA always enabled).
// SX1262 drives DIO2 HIGH during TX → TXEN via bridge on E22 module.
#define SX126X_ANT_SW 3
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#endif
// ---- W5500 Ethernet on SPI0 --------------------------------------------
#define HAS_ETHERNET 1
// Use the arduino-libraries/Ethernet stack (W5500) instead of RAK13800_W5100S
#define USE_ARDUINO_ETHERNET 1
#define ETH_SPI0_MISO 16
#define ETH_SPI0_SCK 18
#define ETH_SPI0_MOSI 19
#define PIN_ETHERNET_RESET 20
#define PIN_ETHERNET_SS 17
#define ETH_SPI_PORT SPI

View File

@@ -0,0 +1,15 @@
[env:seeed_xiao_rp2350]
extends = rp2350_base
board = seeed_xiao_rp2350
board_level = pr
upload_protocol = picotool
# add our variants files to the include and src paths
build_flags =
${rp2350_base.build_flags}
-D PRIVATE_HW
-I variants/rp2350/seeed_xiao_rp2350
-D DEBUG_RP2040_PORT=Serial
;-D HW_SPI1_DEVICE
debug_build_flags = ${rp2350_base.build_flags}, -g
debug_tool = cmsis-dap ; for e.g. Picotool

View File

@@ -0,0 +1,26 @@
#define ARDUINO_ARCH_AVR
// #define BUTTON_PIN -1
#define LED_POWER PIN_LED
// no ADC by default
#define BATTERY_PIN -1
// ratio of voltage divider = 3.0 (R1=200k, R2=100k)
#define ADC_MULTIPLIER 3
// ADC_RESOLUTION is missing upstream, hardcode it here.
#define BATTERY_SENSE_RESOLUTION_BITS 12
#define USE_SX1262
#define LORA_SCK 2
#define LORA_MISO 4
#define LORA_MOSI 3
#define SX126X_CS 6
#define SX126X_DIO1 27
#define SX126X_BUSY 5
#define SX126X_RESET 28
#define SX126X_RXEN 7
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8