Signed-off-by: 吴文峰 <kevin@lmve.net>

This commit is contained in:
2026-03-06 16:14:00 +08:00
parent 47d5814325
commit 1ad2934389
1451 changed files with 242614 additions and 0 deletions
@@ -0,0 +1,462 @@
#include "Channels.h"
#include "CryptoEngine.h"
#include "Default.h"
#include "DisplayFormatters.h"
#include "NodeDB.h"
#include "RadioInterface.h"
#include "configuration.h"
#include <assert.h>
#if !MESHTASTIC_EXCLUDE_MQTT
#include "mqtt/MQTT.h"
#endif
Channels channels;
const char *Channels::adminChannel = "admin";
const char *Channels::gpioChannel = "gpio";
const char *Channels::serialChannel = "serial";
#if !MESHTASTIC_EXCLUDE_MQTT
const char *Channels::mqttChannel = "mqtt";
#endif
uint8_t xorHash(const uint8_t *p, size_t len)
{
uint8_t code = 0;
for (size_t i = 0; i < len; i++)
code ^= p[i];
return code;
}
/** Given a channel number, return the (0 to 255) hash for that channel.
* The hash is just an xor of the channel name followed by the channel PSK being used for encryption
* If no suitable channel could be found, return -1
*/
int16_t Channels::generateHash(ChannelIndex channelNum)
{
auto k = getKey(channelNum);
if (k.length < 0)
return -1; // invalid
else {
const char *name = getName(channelNum);
uint8_t h = xorHash((const uint8_t *)name, strlen(name));
h ^= xorHash(k.bytes, k.length);
return h;
}
}
/**
* Validate a channel, fixing any errors as needed
*/
meshtastic_Channel &Channels::fixupChannel(ChannelIndex chIndex)
{
meshtastic_Channel &ch = getByIndex(chIndex);
ch.index = chIndex; // Preinit the index so it be ready to share with the phone (we'll never change it later)
if (!ch.has_settings) {
// No settings! Must disable and skip
ch.role = meshtastic_Channel_Role_DISABLED;
memset(&ch.settings, 0, sizeof(ch.settings));
ch.has_settings = true;
} else {
meshtastic_ChannelSettings &meshtastic_channelSettings = ch.settings;
// Convert the old string "Default" to our new short representation
if (strcmp(meshtastic_channelSettings.name, "Default") == 0)
*meshtastic_channelSettings.name = '\0';
}
hashes[chIndex] = generateHash(chIndex);
return ch;
}
void Channels::initDefaultLoraConfig()
{
meshtastic_Config_LoRaConfig &loraConfig = config.lora;
loraConfig.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST; // Default to Long Range & Fast
loraConfig.use_preset = true;
loraConfig.tx_power = 0; // default
loraConfig.channel_num = 0;
#ifdef USERPREFS_LORACONFIG_MODEM_PRESET
loraConfig.modem_preset = USERPREFS_LORACONFIG_MODEM_PRESET;
#endif
#ifdef USERPREFS_LORACONFIG_CHANNEL_NUM
loraConfig.channel_num = USERPREFS_LORACONFIG_CHANNEL_NUM;
#endif
}
bool Channels::ensureLicensedOperation()
{
if (!owner.is_licensed) {
return false;
}
bool hasEncryptionOrAdmin = false;
for (uint8_t i = 0; i < MAX_NUM_CHANNELS; i++) {
auto channel = channels.getByIndex(i);
if (!channel.has_settings) {
continue;
}
auto &channelSettings = channel.settings;
if (strcasecmp(channelSettings.name, Channels::adminChannel) == 0) {
channel.role = meshtastic_Channel_Role_DISABLED;
channelSettings.psk.bytes[0] = 0;
channelSettings.psk.size = 0;
hasEncryptionOrAdmin = true;
channels.setChannel(channel);
} else if (channelSettings.psk.size > 0) {
channelSettings.psk.bytes[0] = 0;
channelSettings.psk.size = 0;
hasEncryptionOrAdmin = true;
channels.setChannel(channel);
}
}
return hasEncryptionOrAdmin;
}
/**
* Write a default channel to the specified channel index
*/
void Channels::initDefaultChannel(ChannelIndex chIndex)
{
meshtastic_Channel &ch = getByIndex(chIndex);
meshtastic_ChannelSettings &channelSettings = ch.settings;
uint8_t defaultpskIndex = 1;
channelSettings.psk.bytes[0] = defaultpskIndex;
channelSettings.psk.size = 1;
strncpy(channelSettings.name, "", sizeof(channelSettings.name));
channelSettings.module_settings.position_precision = 13; // default to sending location on the primary channel
channelSettings.has_module_settings = true;
ch.has_settings = true;
ch.role = chIndex == 0 ? meshtastic_Channel_Role_PRIMARY : meshtastic_Channel_Role_SECONDARY;
switch (chIndex) {
case 0:
#ifdef USERPREFS_CHANNEL_0_PSK
static const uint8_t defaultpsk0[] = USERPREFS_CHANNEL_0_PSK;
memcpy(channelSettings.psk.bytes, defaultpsk0, sizeof(defaultpsk0));
channelSettings.psk.size = sizeof(defaultpsk0);
#endif
#ifdef USERPREFS_CHANNEL_0_NAME
strcpy(channelSettings.name, (const char *)USERPREFS_CHANNEL_0_NAME);
#endif
#ifdef USERPREFS_CHANNEL_0_PRECISION
channelSettings.module_settings.position_precision = USERPREFS_CHANNEL_0_PRECISION;
#endif
#ifdef USERPREFS_CHANNEL_0_UPLINK_ENABLED
channelSettings.uplink_enabled = USERPREFS_CHANNEL_0_UPLINK_ENABLED;
#endif
#ifdef USERPREFS_CHANNEL_0_DOWNLINK_ENABLED
channelSettings.downlink_enabled = USERPREFS_CHANNEL_0_DOWNLINK_ENABLED;
#endif
break;
case 1:
#ifdef USERPREFS_CHANNEL_1_PSK
static const uint8_t defaultpsk1[] = USERPREFS_CHANNEL_1_PSK;
memcpy(channelSettings.psk.bytes, defaultpsk1, sizeof(defaultpsk1));
channelSettings.psk.size = sizeof(defaultpsk1);
#endif
#ifdef USERPREFS_CHANNEL_1_NAME
strcpy(channelSettings.name, (const char *)USERPREFS_CHANNEL_1_NAME);
#endif
#ifdef USERPREFS_CHANNEL_1_PRECISION
channelSettings.module_settings.position_precision = USERPREFS_CHANNEL_1_PRECISION;
#endif
#ifdef USERPREFS_CHANNEL_1_UPLINK_ENABLED
channelSettings.uplink_enabled = USERPREFS_CHANNEL_1_UPLINK_ENABLED;
#endif
#ifdef USERPREFS_CHANNEL_1_DOWNLINK_ENABLED
channelSettings.downlink_enabled = USERPREFS_CHANNEL_1_DOWNLINK_ENABLED;
#endif
break;
case 2:
#ifdef USERPREFS_CHANNEL_2_PSK
static const uint8_t defaultpsk2[] = USERPREFS_CHANNEL_2_PSK;
memcpy(channelSettings.psk.bytes, defaultpsk2, sizeof(defaultpsk2));
channelSettings.psk.size = sizeof(defaultpsk2);
#endif
#ifdef USERPREFS_CHANNEL_2_NAME
strcpy(channelSettings.name, (const char *)USERPREFS_CHANNEL_2_NAME);
#endif
#ifdef USERPREFS_CHANNEL_2_PRECISION
channelSettings.module_settings.position_precision = USERPREFS_CHANNEL_2_PRECISION;
#endif
#ifdef USERPREFS_CHANNEL_2_UPLINK_ENABLED
channelSettings.uplink_enabled = USERPREFS_CHANNEL_2_UPLINK_ENABLED;
#endif
#ifdef USERPREFS_CHANNEL_2_DOWNLINK_ENABLED
channelSettings.downlink_enabled = USERPREFS_CHANNEL_2_DOWNLINK_ENABLED;
#endif
break;
default:
break;
}
}
CryptoKey Channels::getKey(ChannelIndex chIndex)
{
meshtastic_Channel &ch = getByIndex(chIndex);
const meshtastic_ChannelSettings &channelSettings = ch.settings;
CryptoKey k;
memset(k.bytes, 0, sizeof(k.bytes)); // In case the user provided a short key, we want to pad the rest with zeros
if (!ch.has_settings || ch.role == meshtastic_Channel_Role_DISABLED) {
k.length = -1; // invalid
} else {
memcpy(k.bytes, channelSettings.psk.bytes, channelSettings.psk.size);
k.length = channelSettings.psk.size;
if (k.length == 0) {
if (ch.role == meshtastic_Channel_Role_SECONDARY) {
LOG_DEBUG("Unset PSK for secondary channel %s. use primary key", ch.settings.name);
k = getKey(primaryIndex);
} else {
LOG_WARN("User disabled encryption");
}
} else if (k.length == 1) {
// Convert the short single byte variants of psk into variant that can be used more generally
uint8_t pskIndex = k.bytes[0];
LOG_DEBUG("Expand short PSK #%d", pskIndex);
if (pskIndex == 0)
k.length = 0; // Turn off encryption
else {
memcpy(k.bytes, defaultpsk, sizeof(defaultpsk));
k.length = sizeof(defaultpsk);
// Bump up the last byte of PSK as needed
uint8_t *last = k.bytes + sizeof(defaultpsk) - 1;
*last = *last + pskIndex - 1; // index of 1 means no change vs defaultPSK
}
} else if (k.length < 16) {
// Error! The user specified only the first few bits of an AES128 key. So by convention we just pad the rest of the
// key with zeros
LOG_WARN("User provided a too short AES128 key - padding");
k.length = 16;
} else if (k.length < 32 && k.length != 16) {
// Error! The user specified only the first few bits of an AES256 key. So by convention we just pad the rest of the
// key with zeros
LOG_WARN("User provided a too short AES256 key - padding");
k.length = 32;
}
}
return k;
}
/** Given a channel index, change to use the crypto key specified by that index
*/
int16_t Channels::setCrypto(ChannelIndex chIndex)
{
CryptoKey k = getKey(chIndex);
if (k.length < 0)
return -1;
else {
// Tell our crypto engine about the psk
crypto->setKey(k);
return getHash(chIndex);
}
}
void Channels::initDefaults()
{
channelFile.channels_count = MAX_NUM_CHANNELS;
for (int i = 0; i < channelFile.channels_count; i++)
fixupChannel(i);
initDefaultLoraConfig();
#ifdef USERPREFS_CHANNELS_TO_WRITE
for (int i = 0; i < USERPREFS_CHANNELS_TO_WRITE; i++) {
initDefaultChannel(i);
}
#else
initDefaultChannel(0);
#endif
}
void Channels::onConfigChanged()
{
// Make sure the phone hasn't mucked anything up
for (int i = 0; i < channelFile.channels_count; i++) {
const meshtastic_Channel &ch = fixupChannel(i);
if (ch.role == meshtastic_Channel_Role_PRIMARY)
primaryIndex = i;
}
#if !MESHTASTIC_EXCLUDE_MQTT
if (channels.anyMqttEnabled() && mqtt && !mqtt->isEnabled()) {
LOG_DEBUG("MQTT is enabled on at least one channel, so set MQTT thread to run immediately");
mqtt->start();
}
#endif
}
meshtastic_Channel &Channels::getByIndex(ChannelIndex chIndex)
{
// remove this assert cause malformed packets can make our firmware reboot here.
if (chIndex < channelFile.channels_count) { // This should be equal to MAX_NUM_CHANNELS
meshtastic_Channel *ch = channelFile.channels + chIndex;
return *ch;
} else {
LOG_ERROR("Invalid channel index %d > %d, malformed packet received?", chIndex, channelFile.channels_count);
static meshtastic_Channel *ch = (meshtastic_Channel *)malloc(sizeof(meshtastic_Channel));
memset(ch, 0, sizeof(meshtastic_Channel));
// ch.index -1 means we don't know the channel locally and need to look it up by settings.name
// not sure this is handled right everywhere
ch->index = -1;
return *ch;
}
}
meshtastic_Channel &Channels::getByName(const char *chName)
{
for (ChannelIndex i = 0; i < getNumChannels(); i++) {
if (strcasecmp(getGlobalId(i), chName) == 0) {
return channelFile.channels[i];
}
}
return getByIndex(getPrimaryIndex());
}
void Channels::setChannel(const meshtastic_Channel &c)
{
meshtastic_Channel &old = getByIndex(c.index);
// if this is the new primary, demote any existing roles
if (c.role == meshtastic_Channel_Role_PRIMARY)
for (int i = 0; i < getNumChannels(); i++)
if (channelFile.channels[i].role == meshtastic_Channel_Role_PRIMARY)
channelFile.channels[i].role = meshtastic_Channel_Role_SECONDARY;
old = c; // slam in the new settings/role
}
bool Channels::anyMqttEnabled()
{
#if USERPREFS_EVENT_MODE && !MESHTASTIC_EXCLUDE_MQTT
// Don't publish messages on the public MQTT broker if we are in event mode
if (mqtt && mqtt->isUsingDefaultServer() && mqtt->isUsingDefaultRootTopic()) {
return false;
}
#endif
for (int i = 0; i < getNumChannels(); i++)
if (channelFile.channels[i].role != meshtastic_Channel_Role_DISABLED && channelFile.channels[i].has_settings &&
(channelFile.channels[i].settings.downlink_enabled || channelFile.channels[i].settings.uplink_enabled))
return true;
return false;
}
const char *Channels::getName(size_t chIndex)
{
// Convert the short "" representation for Default into a usable string
const meshtastic_ChannelSettings &channelSettings = getByIndex(chIndex).settings;
const char *channelName = channelSettings.name;
if (!*channelName) { // emptystring
// Per mesh.proto spec, if bandwidth is specified we must ignore modemPreset enum, we assume that in that case
// the app effed up and forgot to set channelSettings.name
if (config.lora.use_preset) {
channelName = DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false, config.lora.use_preset);
} else {
channelName = "Custom";
}
}
return channelName;
}
bool Channels::isDefaultChannel(ChannelIndex chIndex)
{
const auto &ch = getByIndex(chIndex);
if (ch.settings.psk.size == 1 && ch.settings.psk.bytes[0] == 1) {
const char *name = getName(chIndex);
const char *presetName =
DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false, config.lora.use_preset);
// Check if the name is the default derived from the modem preset
if (strcmp(name, presetName) == 0)
return true;
}
return false;
}
bool Channels::hasDefaultChannel()
{
// If we don't use a preset or the default frequency slot, or we override the frequency, we don't have a default channel
if (!config.lora.use_preset || !RadioInterface::uses_default_frequency_slot || config.lora.override_frequency)
return false;
// Check if any of the channels are using the default name and PSK
for (size_t i = 0; i < getNumChannels(); i++) {
if (isDefaultChannel(i))
return true;
}
return false;
}
/** Given a channel hash setup crypto for decoding that channel (or the primary channel if that channel is unsecured)
*
* This method is called before decoding inbound packets
*
* @return false if the channel hash or channel is invalid
*/
bool Channels::decryptForHash(ChannelIndex chIndex, ChannelHash channelHash)
{
if (chIndex > getNumChannels() || getHash(chIndex) != channelHash) {
// LOG_DEBUG("Skip channel %d (hash %x) due to invalid hash/index, want=%x", chIndex, getHash(chIndex),
// channelHash);
return false;
} else {
LOG_DEBUG("Use channel %d (hash 0x%x)", chIndex, channelHash);
setCrypto(chIndex);
return true;
}
}
bool Channels::setDefaultPresetCryptoForHash(ChannelHash channelHash)
{
// Iterate all known presets
for (int preset = _meshtastic_Config_LoRaConfig_ModemPreset_MIN; preset <= _meshtastic_Config_LoRaConfig_ModemPreset_MAX;
++preset) {
const char *name = DisplayFormatters::getModemPresetDisplayName((meshtastic_Config_LoRaConfig_ModemPreset)preset, false,
config.lora.use_preset);
if (!name)
continue;
if (strcmp(name, "Invalid") == 0)
continue; // skip invalid placeholder
uint8_t h = xorHash((const uint8_t *)name, strlen(name));
// Expand default PSK alias 1 to actual bytes and xor into hash
uint8_t tmp = h ^ xorHash(defaultpsk, sizeof(defaultpsk));
if (tmp == channelHash) {
// Set crypto to defaultpsk and report success
CryptoKey k;
memcpy(k.bytes, defaultpsk, sizeof(defaultpsk));
k.length = sizeof(defaultpsk);
crypto->setKey(k);
LOG_INFO("Matched default preset '%s' for hash 0x%x; set default PSK", name, channelHash);
return true;
}
}
return false;
}
/** Given a channel index setup crypto for encoding that channel (or the primary channel if that channel is unsecured)
*
* This method is called before encoding outbound packets
*
* @return the (0 to 255) hash for that channel - if no suitable channel could be found, return -1
*/
int16_t Channels::setActiveByIndex(ChannelIndex channelIndex)
{
return setCrypto(channelIndex);
}
@@ -0,0 +1,149 @@
#pragma once
#include "CryptoEngine.h"
#include "NodeDB.h"
#include "mesh-pb-constants.h"
#include <Arduino.h>
/** A channel number (index into the channel table)
*/
typedef uint8_t ChannelIndex;
/** A low quality hash of the channel PSK and the channel name. created by generateHash(chIndex)
* Used as a hint to limit which PSKs are considered for packet decoding.
*/
typedef uint8_t ChannelHash;
/** The container/on device API for working with channels */
class Channels
{
/// The index of the primary channel
ChannelIndex primaryIndex = 0;
/** The channel index that was requested for sending/receiving. Note: if this channel is a secondary
channel and does not have a PSK, we will use the PSK from the primary channel. If this channel is disabled
no sending or receiving will be allowed */
ChannelIndex activeChannelIndex = 0;
/// the precomputed hashes for each of our channels, or -1 for invalid
int16_t hashes[MAX_NUM_CHANNELS] = {};
public:
Channels() {}
/// Well known channel names
static const char *adminChannel, *gpioChannel, *serialChannel, *mqttChannel;
const meshtastic_ChannelSettings &getPrimary() { return getByIndex(getPrimaryIndex()).settings; }
/** Return the Channel for a specified index */
meshtastic_Channel &getByIndex(ChannelIndex chIndex);
/** Return the Channel for a specified name, return primary if not found. */
meshtastic_Channel &getByName(const char *chName);
/** Using the index inside the channel, update the specified channel's settings and role. If this channel is being promoted
* to be primary, force all other channels to be secondary.
*/
void setChannel(const meshtastic_Channel &c);
/** Return a human friendly name for this channel (and expand any short strings as needed)
*/
const char *getName(size_t chIndex);
/**
* Return a globally unique channel ID usable with MQTT.
*/
const char *getGlobalId(size_t chIndex) { return getName(chIndex); } // FIXME, not correct
/** The index of the primary channel */
ChannelIndex getPrimaryIndex() const { return primaryIndex; }
ChannelIndex getNumChannels() { return channelFile.channels_count; }
/// Called by NodeDB on initial boot when the radio config settings are unset. Set a default single channel config.
void initDefaults();
/// called when the user has just changed our radio config and we might need to change channel keys
void onConfigChanged();
/** Given a channel hash setup crypto for decoding that channel (or the primary channel if that channel is unsecured)
*
* This method is called before decoding inbound packets
*
* @return false if the channel hash or channel is invalid
*/
bool decryptForHash(ChannelIndex chIndex, ChannelHash channelHash);
/** Given a channel index setup crypto for encoding that channel (or the primary channel if that channel is unsecured)
*
* This method is called before encoding outbound packets
*
* @eturn the (0 to 255) hash for that channel - if no suitable channel could be found, return -1
*/
int16_t setActiveByIndex(ChannelIndex channelIndex);
// Returns true if the channel has the default name and PSK
bool isDefaultChannel(ChannelIndex chIndex);
// Returns true if we can be reached via a channel with the default settings given a region and modem preset
bool hasDefaultChannel();
// Returns true if any of our channels have enabled MQTT uplink or downlink
bool anyMqttEnabled();
bool ensureLicensedOperation();
bool setDefaultPresetCryptoForHash(ChannelHash channelHash);
private:
/** Given a channel index, change to use the crypto key specified by that index
*
* @eturn the (0 to 255) hash for that channel - if no suitable channel could be found, return -1
*/
int16_t setCrypto(ChannelIndex chIndex);
/** Return the channel index for the specified channel hash, or -1 for not found */
int8_t getIndexByHash(ChannelHash channelHash);
/** Given a channel number, return the (0 to 255) hash for that channel
* If no suitable channel could be found, return -1
*
* called by fixupChannel when a new channel is set
*/
int16_t generateHash(ChannelIndex channelNum);
int16_t getHash(ChannelIndex i) { return hashes[i]; }
/**
* Validate a channel, fixing any errors as needed
*/
meshtastic_Channel &fixupChannel(ChannelIndex chIndex);
/**
* Writes the default lora config
*/
void initDefaultLoraConfig();
/**
* Write default channels defined in UserPrefs
*/
void initDefaultChannel(ChannelIndex chIndex);
/**
* Return the key used for encrypting this channel (if channel is secondary and no key provided, use the primary channel's
* PSK)
*/
CryptoKey getKey(ChannelIndex chIndex);
};
/// Singleton channel table
extern Channels channels;
/// 16 bytes of random PSK for our _public_ default channel that all devices power up on (AES128)
static const uint8_t defaultpsk[] = {0xd4, 0xf1, 0xbb, 0x3a, 0x20, 0x29, 0x07, 0x59,
0xf0, 0xbc, 0xff, 0xab, 0xcf, 0x4e, 0x69, 0x01};
static const uint8_t eventpsk[] = {0x38, 0x4b, 0xbc, 0xc0, 0x1d, 0xc0, 0x22, 0xd1, 0x81, 0xbf, 0x36,
0xb8, 0x61, 0x21, 0xe1, 0xfb, 0x96, 0xb7, 0x2e, 0x55, 0xbf, 0x74,
0x22, 0x7e, 0x9d, 0x6a, 0xfb, 0x48, 0xd6, 0x4c, 0xb1, 0xa1};
@@ -0,0 +1,271 @@
#include "CryptoEngine.h"
// #include "NodeDB.h"
#include "architecture.h"
#if !(MESHTASTIC_EXCLUDE_PKI)
#include "NodeDB.h"
#include "aes-ccm.h"
#include "meshUtils.h"
#include <Crypto.h>
#include <Curve25519.h>
#include <RNG.h>
#include <SHA256.h>
#if !(MESHTASTIC_EXCLUDE_PKI_KEYGEN)
#if !defined(ARCH_STM32WL)
#define CryptRNG RNG
#endif
/**
* Create a public/private key pair with Curve25519.
*
* @param pubKey The destination for the public key.
* @param privKey The destination for the private key.
*/
void CryptoEngine::generateKeyPair(uint8_t *pubKey, uint8_t *privKey)
{
// Mix in any randomness we can, to make key generation stronger.
CryptRNG.begin(optstr(APP_VERSION));
if (myNodeInfo.device_id.size == 16) {
CryptRNG.stir(myNodeInfo.device_id.bytes, myNodeInfo.device_id.size);
}
auto noise = random();
CryptRNG.stir((uint8_t *)&noise, sizeof(noise));
LOG_DEBUG("Generate Curve25519 keypair");
Curve25519::dh1(public_key, private_key);
memcpy(pubKey, public_key, sizeof(public_key));
memcpy(privKey, private_key, sizeof(private_key));
}
/**
* regenerate a public key with Curve25519.
*
* @param pubKey The destination for the public key.
* @param privKey The source for the private key.
*/
bool CryptoEngine::regeneratePublicKey(uint8_t *pubKey, uint8_t *privKey)
{
if (!memfll(privKey, 0, sizeof(private_key))) {
Curve25519::eval(pubKey, privKey, 0);
if (Curve25519::isWeakPoint(pubKey)) {
LOG_ERROR("PKI key generation failed. Specified private key results in a weak");
memset(pubKey, 0, 32);
return false;
}
memcpy(private_key, privKey, sizeof(private_key));
memcpy(public_key, pubKey, sizeof(public_key));
} else {
LOG_WARN("X25519 key generation failed due to blank private key");
return false;
}
return true;
}
#endif
void CryptoEngine::clearKeys()
{
memset(public_key, 0, sizeof(public_key));
memset(private_key, 0, sizeof(private_key));
}
/**
* Encrypt a packet's payload using a key generated with Curve25519 and SHA256
* for a specific node.
*
* @param toNode The MeshPacket `to` field.
* @param fromNode The MeshPacket `from` field.
* @param remotePublic The remote node's Curve25519 public key.
* @param packetId The MeshPacket `id` field.
* @param numBytes Number of bytes of plaintext in the bytes buffer.
* @param bytes Buffer containing plaintext input.
* @param bytesOut Output buffer to be populated with encrypted ciphertext.
*/
bool CryptoEngine::encryptCurve25519(uint32_t toNode, uint32_t fromNode, meshtastic_UserLite_public_key_t remotePublic,
uint64_t packetNum, size_t numBytes, const uint8_t *bytes, uint8_t *bytesOut)
{
uint8_t *auth;
long extraNonceTmp = random();
auth = bytesOut + numBytes;
memcpy((uint8_t *)(auth + 8), &extraNonceTmp,
sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : *extraNonce = extraNonceTmp;
LOG_DEBUG("Random nonce value: %d", extraNonceTmp);
if (remotePublic.size == 0) {
LOG_DEBUG("Node %d or their public_key not found", toNode);
return false;
}
if (!setDHPublicKey(remotePublic.bytes)) {
return false;
}
hash(shared_key, 32);
initNonce(fromNode, packetNum, extraNonceTmp);
// Calculate the shared secret with the destination node and encrypt
printBytes("Attempt encrypt with nonce: ", nonce, 13);
printBytes("Attempt encrypt with shared_key starting with: ", shared_key, 8);
aes_ccm_ae(shared_key, 32, nonce, 8, bytes, numBytes, nullptr, 0, bytesOut,
auth); // this can write up to 15 bytes longer than numbytes past bytesOut
memcpy((uint8_t *)(auth + 8), &extraNonceTmp,
sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : *extraNonce = extraNonceTmp;
return true;
}
/**
* Decrypt a packet's payload using a key generated with Curve25519 and SHA256
* for a specific node.
*
* @param fromNode The MeshPacket `from` field.
* @param remotePublic The remote node's Curve25519 public key.
* @param packetId The MeshPacket `id` field.
* @param numBytes Number of bytes of ciphertext in the bytes buffer.
* @param bytes Buffer containing ciphertext input.
* @param bytesOut Output buffer to be populated with decrypted plaintext.
*/
bool CryptoEngine::decryptCurve25519(uint32_t fromNode, meshtastic_UserLite_public_key_t remotePublic, uint64_t packetNum,
size_t numBytes, const uint8_t *bytes, uint8_t *bytesOut)
{
const uint8_t *auth = bytes + numBytes - 12; // set to last 8 bytes of text?
uint32_t extraNonce; // pointer was not really used
memcpy(&extraNonce, auth + 8,
sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : (uint32_t *)(auth + 8);
LOG_INFO("Random nonce value: %d", extraNonce);
if (remotePublic.size == 0) {
LOG_DEBUG("Node or its public key not found in database");
return false;
}
// Calculate the shared secret with the sending node and decrypt
if (!setDHPublicKey(remotePublic.bytes)) {
return false;
}
hash(shared_key, 32);
initNonce(fromNode, packetNum, extraNonce);
printBytes("Attempt decrypt with nonce: ", nonce, 13);
printBytes("Attempt decrypt with shared_key starting with: ", shared_key, 8);
return aes_ccm_ad(shared_key, 32, nonce, 8, bytes, numBytes - 12, nullptr, 0, auth, bytesOut);
}
void CryptoEngine::setDHPrivateKey(uint8_t *_private_key)
{
memcpy(private_key, _private_key, 32);
}
/**
* Hash arbitrary data using SHA256.
*
* @param bytes
* @param numBytes
*/
void CryptoEngine::hash(uint8_t *bytes, size_t numBytes)
{
SHA256 hash;
size_t posn;
uint8_t size = numBytes;
uint8_t inc = 16;
hash.reset();
for (posn = 0; posn < size; posn += inc) {
size_t len = size - posn;
if (len > inc)
len = inc;
hash.update(bytes + posn, len);
}
hash.finalize(bytes, 32);
}
void CryptoEngine::aesSetKey(const uint8_t *key_bytes, size_t key_len)
{
delete aes;
aes = nullptr;
if (key_len != 0) {
aes = new AESSmall256();
aes->setKey(key_bytes, key_len);
}
}
void CryptoEngine::aesEncrypt(uint8_t *in, uint8_t *out)
{
aes->encryptBlock(out, in);
}
bool CryptoEngine::setDHPublicKey(uint8_t *pubKey)
{
uint8_t local_priv[32];
memcpy(shared_key, pubKey, 32);
memcpy(local_priv, private_key, 32);
// Calculate the shared secret with the specified node's public key and our private key
// This includes an internal weak key check, which among other things looks for an all 0 public key and shared key.
if (!Curve25519::dh2(shared_key, local_priv)) {
LOG_WARN("Curve25519DH step 2 failed!");
return false;
}
return true;
}
#endif
concurrency::Lock *cryptLock;
void CryptoEngine::setKey(const CryptoKey &k)
{
LOG_DEBUG("Use AES%d key!", k.length * 8);
key = k;
}
/**
* Encrypt a packet
*
* @param bytes is updated in place
*/
void CryptoEngine::encryptPacket(uint32_t fromNode, uint64_t packetId, size_t numBytes, uint8_t *bytes)
{
if (key.length > 0) {
initNonce(fromNode, packetId);
if (numBytes <= MAX_BLOCKSIZE) {
encryptAESCtr(key, nonce, numBytes, bytes);
} else {
LOG_ERROR("Packet too large for crypto engine: %d. noop encryption!", numBytes);
}
}
}
void CryptoEngine::decrypt(uint32_t fromNode, uint64_t packetId, size_t numBytes, uint8_t *bytes)
{
// For CTR, the implementation is the same
encryptPacket(fromNode, packetId, numBytes, bytes);
}
// Generic implementation of AES-CTR encryption.
void CryptoEngine::encryptAESCtr(CryptoKey _key, uint8_t *_nonce, size_t numBytes, uint8_t *bytes)
{
delete ctr;
ctr = nullptr;
if (_key.length == 16)
ctr = new CTR<AES128>();
else
ctr = new CTR<AES256>();
ctr->setKey(_key.bytes, _key.length);
static uint8_t scratch[MAX_BLOCKSIZE];
memcpy(scratch, bytes, numBytes);
memset(scratch + numBytes, 0,
sizeof(scratch) - numBytes); // Fill rest of buffer with zero (in case cypher looks at it)
ctr->setIV(_nonce, 16);
ctr->setCounterSize(4);
ctr->encrypt(bytes, scratch, numBytes);
}
/**
* Init our 128 bit nonce for a new packet
*/
void CryptoEngine::initNonce(uint32_t fromNode, uint64_t packetId, uint32_t extraNonce)
{
memset(nonce, 0, sizeof(nonce));
// use memcpy to avoid breaking strict-aliasing
memcpy(nonce, &packetId, sizeof(uint64_t));
memcpy(nonce + sizeof(uint64_t), &fromNode, sizeof(uint32_t));
if (extraNonce)
memcpy(nonce + sizeof(uint32_t), &extraNonce, sizeof(uint32_t));
}
#ifndef HAS_CUSTOM_CRYPTO_ENGINE
CryptoEngine *crypto = new CryptoEngine;
#endif
@@ -0,0 +1,97 @@
#pragma once
#include "AES.h"
#include "CTR.h"
#include "concurrency/LockGuard.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
#include <Arduino.h>
extern concurrency::Lock *cryptLock;
struct CryptoKey {
uint8_t bytes[32];
/// # of bytes, or -1 to mean "invalid key - do not use"
int8_t length;
};
/**
* see docs/software/crypto.md for details.
*
*/
#define MAX_BLOCKSIZE 256
#define TEST_CURVE25519_FIELD_OPS // Exposes Curve25519::isWeakPoint() for testing keys
class CryptoEngine
{
public:
#if !(MESHTASTIC_EXCLUDE_PKI)
uint8_t public_key[32] = {0};
#endif
virtual ~CryptoEngine() {}
#if !(MESHTASTIC_EXCLUDE_PKI)
#if !(MESHTASTIC_EXCLUDE_PKI_KEYGEN)
virtual void generateKeyPair(uint8_t *pubKey, uint8_t *privKey);
virtual bool regeneratePublicKey(uint8_t *pubKey, uint8_t *privKey);
#endif
void clearKeys();
void setDHPrivateKey(uint8_t *_private_key);
virtual bool encryptCurve25519(uint32_t toNode, uint32_t fromNode, meshtastic_UserLite_public_key_t remotePublic,
uint64_t packetNum, size_t numBytes, const uint8_t *bytes, uint8_t *bytesOut);
virtual bool decryptCurve25519(uint32_t fromNode, meshtastic_UserLite_public_key_t remotePublic, uint64_t packetNum,
size_t numBytes, const uint8_t *bytes, uint8_t *bytesOut);
virtual bool setDHPublicKey(uint8_t *publicKey);
virtual void hash(uint8_t *bytes, size_t numBytes);
virtual void aesSetKey(const uint8_t *key, size_t key_len);
virtual void aesEncrypt(uint8_t *in, uint8_t *out);
AESSmall256 *aes = NULL;
#endif
/**
* Set the key used for encrypt, decrypt.
*
* As a special case: If all bytes are zero, we assume _no encryption_ and send all data in cleartext.
*
* @param numBytes must be 16 (AES128), 32 (AES256) or 0 (no crypt)
* @param bytes a _static_ buffer that will remain valid for the life of this crypto instance (i.e. this class will cache the
* provided pointer)
*/
virtual void setKey(const CryptoKey &k);
/**
* Encrypt a packet
*
* @param bytes is updated in place
*/
virtual void encryptPacket(uint32_t fromNode, uint64_t packetId, size_t numBytes, uint8_t *bytes);
virtual void decrypt(uint32_t fromNode, uint64_t packetId, size_t numBytes, uint8_t *bytes);
virtual void encryptAESCtr(CryptoKey key, uint8_t *nonce, size_t numBytes, uint8_t *bytes);
#ifndef PIO_UNIT_TESTING
protected:
#endif
/** Our per packet nonce */
uint8_t nonce[16] = {0};
CryptoKey key = {};
CTRCommon *ctr = NULL;
#if !(MESHTASTIC_EXCLUDE_PKI)
uint8_t shared_key[32] = {0};
uint8_t private_key[32] = {0};
#endif
/**
* Init our 128 bit nonce for a new packet
*
* The NONCE is constructed by concatenating (from MSB to LSB):
* a 64 bit packet number (stored in little endian order)
* a 32 bit sending node number (stored in little endian order)
* a 32 bit block counter (starts at zero)
*/
void initNonce(uint32_t fromNode, uint64_t packetId, uint32_t extraNonce = 0);
};
extern CryptoEngine *crypto;
@@ -0,0 +1,67 @@
#include "Default.h"
#include "meshUtils.h"
uint32_t Default::getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval)
{
if (configuredInterval > 0)
return configuredInterval * 1000;
return defaultInterval * 1000;
}
uint32_t Default::getConfiguredOrDefaultMs(uint32_t configuredInterval)
{
if (configuredInterval > 0)
return configuredInterval * 1000;
return default_broadcast_interval_secs * 1000;
}
uint32_t Default::getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue)
{
if (configured > 0)
return configured;
return defaultValue;
}
/**
* Calculates the scaled value of the configured or default value in ms based on the number of online nodes.
*
* For example a default of 30 minutes (1800 seconds * 1000) would yield:
* 45 nodes = 2475 * 1000
* 60 nodes = 4500 * 1000
* 75 nodes = 6525 * 1000
* 90 nodes = 8550 * 1000
* @param configured The configured value.
* @param defaultValue The default value.
* @param numOnlineNodes The number of online nodes.
* @return The scaled value of the configured or default value.
*/
uint32_t Default::getConfiguredOrDefaultMsScaled(uint32_t configured, uint32_t defaultValue, uint32_t numOnlineNodes)
{
// If we are a router, we don't scale the value. It's already significantly higher.
if (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER)
return getConfiguredOrDefaultMs(configured, defaultValue);
// Additionally if we're a tracker or sensor, we want priority to send position and telemetry
if (IS_ONE_OF(config.device.role, meshtastic_Config_DeviceConfig_Role_SENSOR, meshtastic_Config_DeviceConfig_Role_TRACKER))
return getConfiguredOrDefaultMs(configured, defaultValue);
return getConfiguredOrDefaultMs(configured, defaultValue) * congestionScalingCoefficient(numOnlineNodes);
}
uint32_t Default::getConfiguredOrMinimumValue(uint32_t configured, uint32_t minValue)
{
// If zero, intervals should be coalesced later by getConfiguredOrDefault... methods
if (configured == 0)
return configured;
return configured < minValue ? minValue : configured;
}
uint8_t Default::getConfiguredOrDefaultHopLimit(uint8_t configured)
{
#if USERPREFS_EVENT_MODE
return (configured > HOP_RELIABLE) ? HOP_RELIABLE : config.lora.hop_limit;
#else
return (configured >= HOP_MAX) ? HOP_MAX : config.lora.hop_limit;
#endif
}
@@ -0,0 +1,91 @@
#pragma once
#include <NodeDB.h>
#include <cstdint>
#include <meshUtils.h>
#define ONE_DAY 24 * 60 * 60
#define ONE_MINUTE_MS 60 * 1000
#define THIRTY_SECONDS_MS 30 * 1000
#define TWO_SECONDS_MS 2 * 1000
#define FIVE_SECONDS_MS 5 * 1000
#define TEN_SECONDS_MS 10 * 1000
#define MAX_INTERVAL INT32_MAX // FIXME: INT32_MAX to avoid overflow issues with Apple clients but should be UINT32_MAX
#define min_default_telemetry_interval_secs 30 * 60
#define default_gps_update_interval IF_ROUTER(ONE_DAY, 2 * 60)
#define default_telemetry_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 60 * 60)
#define default_broadcast_interval_secs IF_ROUTER(ONE_DAY / 2, 15 * 60)
#define default_wait_bluetooth_secs IF_ROUTER(1, 60)
#define default_sds_secs IF_ROUTER(ONE_DAY, UINT32_MAX) // Default to forever super deep sleep
#define default_ls_secs IF_ROUTER(ONE_DAY, 5 * 60)
#define default_min_wake_secs 10
#define default_screen_on_secs IF_ROUTER(1, 60 * 10)
#define default_node_info_broadcast_secs 3 * 60 * 60
#define default_neighbor_info_broadcast_secs 6 * 60 * 60
#define min_node_info_broadcast_secs 60 * 60 // No regular broadcasts of more than once an hour
#define min_neighbor_info_broadcast_secs 4 * 60 * 60
#define default_map_publish_interval_secs 60 * 60
#ifdef USERPREFS_RINGTONE_NAG_SECS
#define default_ringtone_nag_secs USERPREFS_RINGTONE_NAG_SECS
#else
#define default_ringtone_nag_secs 15
#endif
#define default_network_ipv6_enabled false
#define default_mqtt_address "mqtt.meshtastic.org"
#define default_mqtt_username "meshdev"
#define default_mqtt_password "large4cats"
#define default_mqtt_root "msh"
#define default_mqtt_encryption_enabled true
#define default_mqtt_tls_enabled false
#define IF_ROUTER(routerVal, normalVal) \
((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) ? (routerVal) : (normalVal))
class Default
{
public:
static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval);
static uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t defaultInterval);
static uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue);
// Note: numOnlineNodes uses uint32_t to match the public API and allow flexibility,
// even though internal node counts use uint16_t (max 65535 nodes)
static uint32_t getConfiguredOrDefaultMsScaled(uint32_t configured, uint32_t defaultValue, uint32_t numOnlineNodes);
static uint8_t getConfiguredOrDefaultHopLimit(uint8_t configured);
static uint32_t getConfiguredOrMinimumValue(uint32_t configured, uint32_t minValue);
private:
// Note: Kept as uint32_t to match the public API parameter type
static float congestionScalingCoefficient(uint32_t numOnlineNodes)
{
// Increase frequency of broadcasts for small networks regardless of preset
if (numOnlineNodes <= 10) {
return 0.6;
} else if (numOnlineNodes <= 20) {
return 0.7;
} else if (numOnlineNodes <= 30) {
return 0.8;
} else if (numOnlineNodes <= 40) {
return 1.0;
} else {
float throttlingFactor = 0.075;
if (config.lora.use_preset && config.lora.modem_preset == meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_SLOW)
throttlingFactor = 0.04;
else if (config.lora.use_preset && config.lora.modem_preset == meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_FAST)
throttlingFactor = 0.02;
else if (config.lora.use_preset &&
IS_ONE_OF(config.lora.modem_preset, meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST,
meshtastic_Config_LoRaConfig_ModemPreset_SHORT_TURBO,
meshtastic_Config_LoRaConfig_ModemPreset_SHORT_SLOW))
throttlingFactor = 0.01;
#if USERPREFS_EVENT_MODE
// If we are in event mode, scale down the throttling factor
throttlingFactor = 0.04;
#endif
// Scaling up traffic based on number of nodes over 40
int nodesOverForty = (numOnlineNodes - 40);
return 1.0 + (nodesOverForty * throttlingFactor); // Each number of online node scales by 0.075 (default)
}
}
};
@@ -0,0 +1,149 @@
#include "FloodingRouter.h"
#include "MeshTypes.h"
#include "NodeDB.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
#include "meshUtils.h"
#if !MESHTASTIC_EXCLUDE_TRACEROUTE
#include "modules/TraceRouteModule.h"
#endif
FloodingRouter::FloodingRouter() {}
/**
* Send a packet on a suitable interface. This routine will
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*/
ErrorCode FloodingRouter::send(meshtastic_MeshPacket *p)
{
// Add any messages _we_ send to the seen message list (so we will ignore all retransmissions we see)
p->relay_node = nodeDB->getLastByteOfNodeNum(getNodeNum()); // First set the relayer to us
wasSeenRecently(p); // FIXME, move this to a sniffSent method
return Router::send(p);
}
bool FloodingRouter::shouldFilterReceived(const meshtastic_MeshPacket *p)
{
bool wasUpgraded = false;
bool seenRecently =
wasSeenRecently(p, true, nullptr, nullptr, &wasUpgraded); // Updates history; returns false when an upgrade is detected
// Handle hop_limit upgrade scenario for rebroadcasters
if (wasUpgraded && perhapsHandleUpgradedPacket(p)) {
return true; // we handled it, so stop processing
}
if (seenRecently) {
printPacket("Ignore dupe incoming msg", p);
rxDupe++;
/* If the original transmitter is doing retransmissions (hopStart equals hopLimit) for a reliable transmission, e.g., when
the ACK got lost, we will handle the packet again to make sure it gets an implicit ACK. */
bool isRepeated = p->hop_start > 0 && p->hop_start == p->hop_limit;
if (isRepeated) {
LOG_DEBUG("Repeated reliable tx");
// Check if it's still in the Tx queue, if not, we have to relay it again
if (!findInTxQueue(p->from, p->id)) {
reprocessPacket(p);
perhapsRebroadcast(p);
}
} else {
perhapsCancelDupe(p);
}
return true;
}
return Router::shouldFilterReceived(p);
}
bool FloodingRouter::perhapsHandleUpgradedPacket(const meshtastic_MeshPacket *p)
{
// isRebroadcaster() is duplicated in perhapsRebroadcast(), but this avoids confusing log messages
if (isRebroadcaster() && iface && p->hop_limit > 0) {
// If we overhear a duplicate copy of the packet with more hops left than the one we are waiting to
// rebroadcast, then remove the packet currently sitting in the TX queue and use this one instead.
uint8_t dropThreshold = p->hop_limit; // remove queued packets that have fewer hops remaining
if (iface->removePendingTXPacket(getFrom(p), p->id, dropThreshold)) {
LOG_DEBUG("Processing upgraded packet 0x%08x for rebroadcast with hop limit %d (dropping queued < %d)", p->id,
p->hop_limit, dropThreshold);
reprocessPacket(p);
perhapsRebroadcast(p);
rxDupe++;
// We already enqueued the improved copy, so make sure the incoming packet stops here.
return true;
}
}
return false;
}
void FloodingRouter::reprocessPacket(const meshtastic_MeshPacket *p)
{
if (nodeDB)
nodeDB->updateFrom(*p);
#if !MESHTASTIC_EXCLUDE_TRACEROUTE
if (traceRouteModule && p->which_payload_variant == meshtastic_MeshPacket_decoded_tag &&
p->decoded.portnum == meshtastic_PortNum_TRACEROUTE_APP)
traceRouteModule->processUpgradedPacket(*p);
#endif
}
bool FloodingRouter::roleAllowsCancelingDupe(const meshtastic_MeshPacket *p)
{
if (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER ||
config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER_LATE) {
// ROUTER, ROUTER_LATE should never cancel relaying a packet (i.e. we should always rebroadcast),
// even if we've heard another station rebroadcast it already.
return false;
}
if (config.device.role == meshtastic_Config_DeviceConfig_Role_CLIENT_BASE) {
// CLIENT_BASE: if the packet is from or to a favorited node,
// we should act like a ROUTER and should never cancel a rebroadcast (i.e. we should always rebroadcast),
// even if we've heard another station rebroadcast it already.
return !nodeDB->isFromOrToFavoritedNode(*p);
}
// All other roles (such as CLIENT) should cancel a rebroadcast if they hear another station's rebroadcast.
return true;
}
void FloodingRouter::perhapsCancelDupe(const meshtastic_MeshPacket *p)
{
if (p->transport_mechanism == meshtastic_MeshPacket_TransportMechanism_TRANSPORT_LORA && roleAllowsCancelingDupe(p)) {
// cancel rebroadcast of this message *if* there was already one, unless we're a router!
// But only LoRa packets should be able to trigger this.
if (Router::cancelSending(p->from, p->id))
txRelayCanceled++;
}
if (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER_LATE && iface) {
iface->clampToLateRebroadcastWindow(getFrom(p), p->id);
}
}
bool FloodingRouter::isRebroadcaster()
{
return config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_MUTE &&
config.device.rebroadcast_mode != meshtastic_Config_DeviceConfig_RebroadcastMode_NONE;
}
void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c)
{
bool isAckorReply = (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) &&
(p->decoded.request_id != 0 || p->decoded.reply_id != 0);
if (isAckorReply && !isToUs(p) && !isBroadcast(p->to)) {
// do not flood direct message that is ACKed or replied to
LOG_DEBUG("Rxd an ACK/reply not for me, cancel rebroadcast");
Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM
}
perhapsRebroadcast(p);
// handle the packet as normal
Router::sniffReceived(p, c);
}
@@ -0,0 +1,78 @@
#pragma once
#include "Router.h"
/**
* This is a mixin that extends Router with the ability to do Naive Flooding (in the standard mesh protocol sense)
*
* Rules for broadcasting (listing here for now, will move elsewhere eventually):
If to==BROADCAST and id==0, this is a simple broadcast (0 hops). It will be
sent only by the current node and other nodes will not attempt to rebroadcast
it.
If to==BROADCAST and id!=0, this is a "naive flooding" broadcast. The initial
node will send it on all local interfaces.
When other nodes receive this message, they will
first check if their recentBroadcasts table contains the (from, id) pair that
indicates this message. If so, we've already seen it - so we discard it. If
not, we add it to the table and then resend this message on all interfaces.
When resending we are careful to use the "from" ID of the original sender. Not
our own ID. When resending we pick a random delay between 0 and 10 seconds to
decrease the chance of collisions with transmitters we can not even hear.
Any entries in recentBroadcasts that are older than X seconds (longer than the
max time a flood can take) will be discarded.
*/
class FloodingRouter : public Router
{
public:
/**
* Constructor
*
*/
FloodingRouter();
/**
* Send a packet on a suitable interface. This routine will
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*/
virtual ErrorCode send(meshtastic_MeshPacket *p) override;
protected:
/**
* Should this incoming filter be dropped?
*
* Called immediately on reception, before any further processing.
* @return true to abandon the packet
*/
virtual bool shouldFilterReceived(const meshtastic_MeshPacket *p) override;
/**
* Look for broadcasts we need to rebroadcast
*/
virtual void sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c) override;
/* Check if we should rebroadcast this packet, and do so if needed */
virtual bool perhapsRebroadcast(const meshtastic_MeshPacket *p) = 0;
/* Check if we should handle an upgraded packet (with higher hop_limit)
* @return true if we handled it (so stop processing)
*/
bool perhapsHandleUpgradedPacket(const meshtastic_MeshPacket *p);
/* Call when we receive a packet that needs some reprocessing, but afterwards should be filtered */
void reprocessPacket(const meshtastic_MeshPacket *p);
// Return false for roles like ROUTER which should always rebroadcast even when we've heard another rebroadcast of
// the same packet
bool roleAllowsCancelingDupe(const meshtastic_MeshPacket *p);
/* Call when receiving a duplicate packet to check whether we should cancel a packet in the Tx queue */
void perhapsCancelDupe(const meshtastic_MeshPacket *p);
// Return true if we are a rebroadcaster
bool isRebroadcaster();
};
@@ -0,0 +1,38 @@
#include "LR11x0Interface.cpp"
#include "LR11x0Interface.h"
#include "SX126xInterface.cpp"
#include "SX126xInterface.h"
#include "SX128xInterface.cpp"
#include "SX128xInterface.h"
#include "api/ServerAPI.cpp"
#include "api/ServerAPI.h"
// We need this declaration for proper linking in derived classes
#if RADIOLIB_EXCLUDE_SX126X != 1
template class SX126xInterface<SX1262>;
template class SX126xInterface<SX1268>;
template class SX126xInterface<LLCC68>;
#endif
#if RADIOLIB_EXCLUDE_SX128X != 1
template class SX128xInterface<SX1280>;
#endif
#if RADIOLIB_EXCLUDE_LR11X0 != 1
template class LR11x0Interface<LR1110>;
template class LR11x0Interface<LR1120>;
template class LR11x0Interface<LR1121>;
#endif
#ifdef ARCH_STM32WL
template class SX126xInterface<STM32WLx>;
#endif
#if HAS_ETHERNET && !defined(USE_WS5500)
#include "api/ethServerAPI.h"
template class ServerAPI<EthernetClient>;
template class APIServerPort<ethServerAPI, EthernetServer>;
#endif
#if HAS_WIFI
#include "api/WiFiServerAPI.h"
template class ServerAPI<WiFiClient>;
template class APIServerPort<WiFiServerAPI, WiFiServer>;
#endif
@@ -0,0 +1,11 @@
#if RADIOLIB_EXCLUDE_SX126X != 1
#include "LLCC68Interface.h"
#include "configuration.h"
#include "error.h"
LLCC68Interface::LLCC68Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: SX126xInterface(hal, cs, irq, rst, busy)
{
}
#endif
@@ -0,0 +1,19 @@
#pragma once
#if RADIOLIB_EXCLUDE_SX126X != 1
#include "SX126xInterface.h"
/**
* Our adapter for LLCC68 radios
* https://www.semtech.com/products/wireless-rf/lora-core/llcc68
* ⚠️⚠️⚠️
* Be aware that LLCC68 does not support Spreading Factor 12 (SF12) and will not work on the "LongSlow" and "VLongSlow" channels.
* You must change the channel if you get `Critical Error #3` with this module.
* ⚠️⚠️⚠️
*/
class LLCC68Interface : public SX126xInterface<LLCC68>
{
public:
LLCC68Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
};
#endif
@@ -0,0 +1,12 @@
#if RADIOLIB_EXCLUDE_LR11X0 != 1
#include "LR1110Interface.h"
#include "configuration.h"
#include "error.h"
LR1110Interface::LR1110Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: LR11x0Interface(hal, cs, irq, rst, busy)
{
}
#endif
@@ -0,0 +1,14 @@
#pragma once
#if RADIOLIB_EXCLUDE_LR11X0 != 1
#include "LR11x0Interface.h"
/**
* Our adapter for LR1110 radios
*/
class LR1110Interface : public LR11x0Interface<LR1110>
{
public:
LR1110Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
};
#endif
@@ -0,0 +1,17 @@
#if RADIOLIB_EXCLUDE_LR11X0 != 1
#include "LR1120Interface.h"
#include "configuration.h"
#include "error.h"
LR1120Interface::LR1120Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: LR11x0Interface(hal, cs, irq, rst, busy)
{
}
bool LR1120Interface::wideLora()
{
return true;
}
#endif
@@ -0,0 +1,15 @@
#pragma once
#if RADIOLIB_EXCLUDE_LR11X0 != 1
#include "LR11x0Interface.h"
/**
* Our adapter for LR1120 wideband radios
*/
class LR1120Interface : public LR11x0Interface<LR1120>
{
public:
LR1120Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
bool wideLora() override;
};
#endif
@@ -0,0 +1,16 @@
#if RADIOLIB_EXCLUDE_LR11X0 != 1
#include "LR1121Interface.h"
#include "configuration.h"
#include "error.h"
LR1121Interface::LR1121Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: LR11x0Interface(hal, cs, irq, rst, busy)
{
}
bool LR1121Interface::wideLora()
{
return true;
}
#endif
@@ -0,0 +1,16 @@
#pragma once
#if RADIOLIB_EXCLUDE_LR11X0 != 1
#include "LR11x0Interface.h"
/**
* Our adapter for LR1121 wideband radios
*/
class LR1121Interface : public LR11x0Interface<LR1121>
{
public:
LR1121Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
bool wideLora() override;
};
#endif
@@ -0,0 +1,307 @@
#if RADIOLIB_EXCLUDE_LR11X0 != 1
#include "LR11x0Interface.h"
#include "Throttle.h"
#include "configuration.h"
#include "error.h"
#include "mesh/NodeDB.h"
#ifdef LR11X0_DIO_AS_RF_SWITCH
#include "rfswitch.h"
#elif ARCH_PORTDUINO
#include "PortduinoGlue.h"
#define rfswitch_dio_pins portduino_config.rfswitch_dio_pins
#define rfswitch_table portduino_config.rfswitch_table
#else
static const uint32_t rfswitch_dio_pins[] = {RADIOLIB_NC, RADIOLIB_NC, RADIOLIB_NC, RADIOLIB_NC, RADIOLIB_NC};
static const Module::RfSwitchMode_t rfswitch_table[] = {
{LR11x0::MODE_STBY, {}}, {LR11x0::MODE_RX, {}}, {LR11x0::MODE_TX, {}}, {LR11x0::MODE_TX_HP, {}},
{LR11x0::MODE_TX_HF, {}}, {LR11x0::MODE_GNSS, {}}, {LR11x0::MODE_WIFI, {}}, END_OF_MODE_TABLE,
};
#endif
// Particular boards might define a different max power based on what their hardware can do, default to max power output if not
// specified (may be dangerous if using external PA and LR11x0 power config forgotten)
#if ARCH_PORTDUINO
#define LR1110_MAX_POWER portduino_config.lr1110_max_power
#endif
#ifndef LR1110_MAX_POWER
#define LR1110_MAX_POWER 22
#endif
// the 2.4G part maxes at 13dBm
#if ARCH_PORTDUINO
#define LR1120_MAX_POWER portduino_config.lr1120_max_power
#endif
#ifndef LR1120_MAX_POWER
#define LR1120_MAX_POWER 13
#endif
template <typename T>
LR11x0Interface<T>::LR11x0Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: RadioLibInterface(hal, cs, irq, rst, busy, &lora), lora(&module)
{
LOG_WARN("LR11x0Interface(cs=%d, irq=%d, rst=%d, busy=%d)", cs, irq, rst, busy);
}
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
template <typename T> bool LR11x0Interface<T>::init()
{
#ifdef LR11X0_POWER_EN
pinMode(LR11X0_POWER_EN, OUTPUT);
digitalWrite(LR11X0_POWER_EN, HIGH);
#endif
#if ARCH_PORTDUINO
float tcxoVoltage = (float)portduino_config.dio3_tcxo_voltage / 1000;
// FIXME: correct logic to default to not using TCXO if no voltage is specified for LR11x0_DIO3_TCXO_VOLTAGE
#elif !defined(LR11X0_DIO3_TCXO_VOLTAGE)
float tcxoVoltage =
0; // "TCXO reference voltage to be set on DIO3. Defaults to 1.6 V, set to 0 to skip." per
// https://github.com/jgromes/RadioLib/blob/690a050ebb46e6097c5d00c371e961c1caa3b52e/src/modules/LR11x0/LR11x0.h#L471C26-L471C104
// (DIO3 is free to be used as an IRQ)
LOG_DEBUG("LR11X0_DIO3_TCXO_VOLTAGE not defined, not using DIO3 as TCXO reference voltage");
#else
float tcxoVoltage = LR11X0_DIO3_TCXO_VOLTAGE;
LOG_DEBUG("LR11X0_DIO3_TCXO_VOLTAGE defined, using DIO3 as TCXO reference voltage at %f V", LR11X0_DIO3_TCXO_VOLTAGE);
// (DIO3 is not free to be used as an IRQ)
#endif
RadioLibInterface::init();
limitPower(LR1110_MAX_POWER);
if ((power > LR1120_MAX_POWER) &&
(config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) { // clamp again if wide freq range
power = LR1120_MAX_POWER;
preambleLength = 12; // 12 is the default for operation above 2GHz
}
#ifdef LR11X0_RF_SWITCH_SUBGHZ
pinMode(LR11X0_RF_SWITCH_SUBGHZ, OUTPUT);
digitalWrite(LR11X0_RF_SWITCH_SUBGHZ, getFreq() < 1e9 ? HIGH : LOW);
LOG_DEBUG("Set RF0 switch to %s", getFreq() < 1e9 ? "SubGHz" : "2.4GHz");
#endif
#ifdef LR11X0_RF_SWITCH_2_4GHZ
pinMode(LR11X0_RF_SWITCH_2_4GHZ, OUTPUT);
digitalWrite(LR11X0_RF_SWITCH_2_4GHZ, getFreq() < 1e9 ? LOW : HIGH);
LOG_DEBUG("Set RF1 switch to %s", getFreq() < 1e9 ? "SubGHz" : "2.4GHz");
#endif
int res = lora.begin(getFreq(), bw, sf, cr, syncWord, power, preambleLength, tcxoVoltage);
// \todo Display actual typename of the adapter, not just `LR11x0`
LOG_INFO("LR11x0 init result %d", res);
if (res == RADIOLIB_ERR_CHIP_NOT_FOUND)
return false;
LR11x0VersionInfo_t version;
res = lora.getVersionInfo(&version);
if (res == RADIOLIB_ERR_NONE)
LOG_DEBUG("LR11x0 Device %d, HW %d, FW %d.%d, WiFi %d.%d, GNSS %d.%d", version.device, version.hardware, version.fwMajor,
version.fwMinor, version.fwMajorWiFi, version.fwMinorWiFi, version.fwGNSS, version.almanacGNSS);
LOG_INFO("Frequency set to %f", getFreq());
LOG_INFO("Bandwidth set to %f", bw);
LOG_INFO("Power output set to %d", power);
if (res == RADIOLIB_ERR_NONE)
res = lora.setCRC(2);
// FIXME: May want to set depending on a definition, currently all LR1110 variant files use the DC-DC regulator option
if (res == RADIOLIB_ERR_NONE)
res = lora.setRegulatorDCDC();
#ifdef LR11X0_DIO_AS_RF_SWITCH
bool dioAsRfSwitch = true;
#elif defined(ARCH_PORTDUINO)
bool dioAsRfSwitch = portduino_config.has_rfswitch_table;
#else
bool dioAsRfSwitch = false;
#endif
if (dioAsRfSwitch) {
lora.setRfSwitchTable(rfswitch_dio_pins, rfswitch_table);
LOG_DEBUG("Set DIO RF switch");
}
if (res == RADIOLIB_ERR_NONE) {
if (config.lora.sx126x_rx_boosted_gain) { // the name is unfortunate but historically accurate
res = lora.setRxBoostedGainMode(true);
LOG_INFO("Set RX gain to boosted mode; result: %d", res);
} else {
res = lora.setRxBoostedGainMode(false);
LOG_INFO("Set RX gain to power saving mode (boosted mode off); result: %d", res);
}
}
if (res == RADIOLIB_ERR_NONE)
startReceive(); // start receiving
return res == RADIOLIB_ERR_NONE;
}
template <typename T> bool LR11x0Interface<T>::reconfigure()
{
RadioLibInterface::reconfigure();
// set mode to standby
setStandby();
// configure publicly accessible settings
int err = lora.setSpreadingFactor(sf);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setBandwidth(bw, wideLora() && (getFreq() > 1000.0f));
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setCodingRate(cr);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setSyncWord(syncWord);
assert(err == RADIOLIB_ERR_NONE);
err = lora.setPreambleLength(preambleLength);
assert(err == RADIOLIB_ERR_NONE);
err = lora.setFrequency(getFreq());
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
if (power > LR1110_MAX_POWER) // This chip has lower power limits than some
power = LR1110_MAX_POWER;
if ((power > LR1120_MAX_POWER) && (config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) // 2.4G power limit
power = LR1120_MAX_POWER;
err = lora.setOutputPower(power);
assert(err == RADIOLIB_ERR_NONE);
startReceive(); // restart receiving
return RADIOLIB_ERR_NONE;
}
template <typename T> void INTERRUPT_ATTR LR11x0Interface<T>::disableInterrupt()
{
lora.clearIrqAction();
}
template <typename T> void LR11x0Interface<T>::setStandby()
{
checkNotification(); // handle any pending interrupts before we force standby
int err = lora.standby();
if (err != RADIOLIB_ERR_NONE) {
LOG_DEBUG("LR11x0 standby failed with error %d", err);
}
assert(err == RADIOLIB_ERR_NONE);
isReceiving = false; // If we were receiving, not any more
activeReceiveStart = 0;
disableInterrupt();
completeSending(); // If we were sending, not anymore
RadioLibInterface::setStandby();
}
/**
* Add SNR data to received messages
*/
template <typename T> void LR11x0Interface<T>::addReceiveMetadata(meshtastic_MeshPacket *mp)
{
// LOG_DEBUG("PacketStatus %x", lora.getPacketStatus());
mp->rx_snr = lora.getSNR();
mp->rx_rssi = lround(lora.getRSSI());
LOG_DEBUG("Corrected frequency offset: %f", lora.getFrequencyError());
}
/** We override to turn on transmitter power as needed.
*/
template <typename T> void LR11x0Interface<T>::configHardwareForSend()
{
RadioLibInterface::configHardwareForSend();
}
// For power draw measurements, helpful to force radio to stay sleeping
// #define SLEEP_ONLY
template <typename T> void LR11x0Interface<T>::startReceive()
{
#ifdef SLEEP_ONLY
sleep();
#else
setStandby();
lora.setPreambleLength(preambleLength); // Solve RX ack fail after direct message sent. Not sure why this is needed.
// We use a 16 bit preamble so this should save some power by letting radio sit in standby mostly.
int err =
lora.startReceive(RADIOLIB_LR11X0_RX_TIMEOUT_INF, MESHTASTIC_RADIOLIB_IRQ_RX_FLAGS, RADIOLIB_IRQ_RX_DEFAULT_MASK, 0);
assert(err == RADIOLIB_ERR_NONE);
RadioLibInterface::startReceive();
// Must be done AFTER, starting transmit, because startTransmit clears (possibly stale) interrupt pending register bits
enableInterrupt(isrRxLevel0);
#endif
}
/** Is the channel currently active? */
template <typename T> bool LR11x0Interface<T>::isChannelActive()
{
// check if we can detect a LoRa preamble on the current channel
ChannelScanConfig_t cfg = {.cad = {.symNum = NUM_SYM_CAD,
.detPeak = RADIOLIB_LR11X0_CAD_PARAM_DEFAULT,
.detMin = RADIOLIB_LR11X0_CAD_PARAM_DEFAULT,
.exitMode = RADIOLIB_LR11X0_CAD_PARAM_DEFAULT,
.timeout = 0,
.irqFlags = RADIOLIB_IRQ_CAD_DEFAULT_FLAGS,
.irqMask = RADIOLIB_IRQ_CAD_DEFAULT_MASK}};
int16_t result;
setStandby();
result = lora.scanChannel(cfg);
if (result == RADIOLIB_LORA_DETECTED)
return true;
assert(result != RADIOLIB_ERR_WRONG_MODEM);
return false;
}
/** Could we send right now (i.e. either not actively receiving or transmitting)? */
template <typename T> bool LR11x0Interface<T>::isActivelyReceiving()
{
// The IRQ status will be cleared when we start our read operation. Check if we've started a header, but haven't yet
// received and handled the interrupt for reading the packet/handling errors.
return receiveDetected(lora.getIrqStatus(), RADIOLIB_LR11X0_IRQ_SYNC_WORD_HEADER_VALID,
RADIOLIB_LR11X0_IRQ_PREAMBLE_DETECTED);
}
template <typename T> bool LR11x0Interface<T>::sleep()
{
// \todo Display actual typename of the adapter, not just `LR11x0`
LOG_DEBUG("LR11x0 entering sleep mode");
setStandby(); // Stop any pending operations
// turn off TCXO if it was powered
lora.setTCXO(0);
// put chipset into sleep mode (we've already disabled interrupts by now)
bool keepConfig = false;
lora.sleep(keepConfig, 0); // Note: we do not keep the config, full reinit will be needed
#ifdef LR11X0_POWER_EN
digitalWrite(LR11X0_POWER_EN, LOW);
#endif
return true;
}
#endif
@@ -0,0 +1,71 @@
#pragma once
#if RADIOLIB_EXCLUDE_LR11X0 != 1
#include "RadioLibInterface.h"
/**
* \brief Adapter for LR11x0 radio family. Implements common logic for child classes.
* \tparam T RadioLib module type for LR11x0: SX1262, SX1268.
*/
template <class T> class LR11x0Interface : public RadioLibInterface
{
public:
LR11x0Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool init() override;
/// Apply any radio provisioning changes
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool reconfigure() override;
/// Prepare hardware for sleep. Call this _only_ for deep sleep, not needed for light sleep.
virtual bool sleep() override;
bool isIRQPending() override { return lora.getIrqFlags() != 0; }
protected:
/**
* Specific module instance
*/
T lora;
/**
* Glue functions called from ISR land
*/
virtual void disableInterrupt() override;
/**
* Enable a particular ISR callback glue function
*/
virtual void enableInterrupt(void (*callback)()) { lora.setIrqAction(callback); }
/** can we detect a LoRa preamble on the current channel? */
virtual bool isChannelActive() override;
/** are we actively receiving a packet (only called during receiving state) */
virtual bool isActivelyReceiving() override;
/**
* Start waiting to receive a message
*/
virtual void startReceive() override;
/**
* We override to turn on transmitter power as needed.
*/
virtual void configHardwareForSend() override;
/**
* Add SNR data to received messages
*/
virtual void addReceiveMetadata(meshtastic_MeshPacket *mp) override;
virtual void setStandby() override;
uint32_t getPacketTime(uint32_t pl, bool received) override { return computePacketTime(lora, pl, received); }
};
#endif
@@ -0,0 +1,161 @@
#pragma once
#include <Arduino.h>
#include <assert.h>
#include <functional>
#include <memory>
#include "PointerQueue.h"
#include "configuration.h" // For LOG_WARN, LOG_DEBUG, LOG_HEAP
template <class T> class Allocator
{
public:
Allocator() : deleter([this](T *p) { this->release(p); }) {}
virtual ~Allocator() {}
/// Return a queable object which has been prefilled with zeros. Return nullptr if no buffer is available
/// Note: this method is safe to call from regular OR ISR code
T *allocZeroed()
{
T *p = allocZeroed(0);
if (!p) {
LOG_WARN("Failed to allocate zeroed memory");
}
return p;
}
/// Return a queable object which has been prefilled with zeros - allow timeout to wait for available buffers (you probably
/// don't want this version).
T *allocZeroed(TickType_t maxWait)
{
T *p = alloc(maxWait);
if (p)
memset(p, 0, sizeof(T));
return p;
}
/// Return a queable object which is a copy of some other object
T *allocCopy(const T &src, TickType_t maxWait = portMAX_DELAY)
{
T *p = alloc(maxWait);
if (!p) {
LOG_WARN("Failed to allocate memory for copy");
return nullptr;
}
*p = src;
return p;
}
/// Variations of the above methods that return std::unique_ptr instead of raw pointers.
using UniqueAllocation = std::unique_ptr<T, const std::function<void(T *)> &>;
/// Return a queable object which has been prefilled with zeros.
/// std::unique_ptr wrapped variant of allocZeroed().
UniqueAllocation allocUniqueZeroed() { return UniqueAllocation(allocZeroed(), deleter); }
/// Return a queable object which has been prefilled with zeros - allow timeout to wait for available buffers (you probably
/// don't want this version).
/// std::unique_ptr wrapped variant of allocZeroed(TickType_t maxWait).
UniqueAllocation allocUniqueZeroed(TickType_t maxWait) { return UniqueAllocation(allocZeroed(maxWait), deleter); }
/// Return a queable object which is a copy of some other object
/// std::unique_ptr wrapped variant of allocCopy(const T &src, TickType_t maxWait).
UniqueAllocation allocUniqueCopy(const T &src, TickType_t maxWait = portMAX_DELAY)
{
return UniqueAllocation(allocCopy(src, maxWait), deleter);
}
/// Return a buffer for use by others
virtual void release(T *p) = 0;
protected:
// Alloc some storage
virtual T *alloc(TickType_t maxWait) = 0;
private:
// std::unique_ptr Deleter function; calls release().
const std::function<void(T *)> deleter;
};
/**
* An allocator that just uses regular free/malloc
*/
template <class T> class MemoryDynamic : public Allocator<T>
{
public:
/// Return a buffer for use by others
virtual void release(T *p) override
{
if (p == nullptr)
return;
LOG_HEAP("Freeing 0x%x", p);
free(p);
}
protected:
// Alloc some storage
virtual T *alloc(TickType_t maxWait) override
{
T *p = (T *)malloc(sizeof(T));
assert(p);
return p;
}
};
/**
* A static memory pool that uses a fixed buffer instead of heap allocation
*/
template <class T, int MaxSize> class MemoryPool : public Allocator<T>
{
private:
T pool[MaxSize];
bool used[MaxSize];
public:
MemoryPool() : pool{}, used{}
{
// Arrays are now zero-initialized by member initializer list
// pool array: all elements are default-constructed (zero for POD types)
// used array: all elements are false (zero-initialized)
}
/// Return a buffer for use by others
virtual void release(T *p) override
{
if (!p) {
LOG_DEBUG("Failed to release memory, pointer is null");
return;
}
// Find the index of this pointer in our pool
int index = p - pool;
if (index >= 0 && index < MaxSize) {
assert(used[index]); // Should be marked as used
used[index] = false;
LOG_HEAP("Released static pool item %d at 0x%x", index, p);
} else {
LOG_WARN("Pointer 0x%x not from our pool!", p);
}
}
protected:
// Alloc some storage from our static pool
virtual T *alloc(TickType_t maxWait) override
{
// Find first free slot
for (int i = 0; i < MaxSize; i++) {
if (!used[i]) {
used[i] = true;
LOG_HEAP("Allocated static pool item %d at 0x%x", i, &pool[i]);
return &pool[i];
}
}
// No free slots available - return nullptr instead of asserting
LOG_WARN("No free slots available in static memory pool!");
return nullptr;
}
};
@@ -0,0 +1,314 @@
#include "MeshModule.h"
#include "Channels.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "configuration.h"
#include "modules/RoutingModule.h"
#include <algorithm>
#include <assert.h>
std::vector<MeshModule *> *MeshModule::modules;
const meshtastic_MeshPacket *MeshModule::currentRequest;
uint8_t MeshModule::numPeriodicModules = 0;
/**
* If any of the current chain of modules has already sent a reply, it will be here. This is useful to allow
* the RoutingModule to avoid sending redundant acks
*/
meshtastic_MeshPacket *MeshModule::currentReply;
MeshModule::MeshModule(const char *_name) : name(_name)
{
// Can't trust static initializer order, so we check each time
if (!modules)
modules = new std::vector<MeshModule *>();
modules->push_back(this);
}
void MeshModule::setup() {}
MeshModule::~MeshModule()
{
auto it = std::find(modules->begin(), modules->end(), this);
assert(it != modules->end());
modules->erase(it);
}
// ⚠️ **Only call once** to set the initial delay before a module starts broadcasting periodically
int32_t MeshModule::setStartDelay()
{
int32_t startDelay = MESHMODULE_MIN_BROADCAST_DELAY_MS + numPeriodicModules * MESHMODULE_BROADCAST_SPACING_MS;
numPeriodicModules++;
return startDelay;
}
meshtastic_MeshPacket *MeshModule::allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex,
uint8_t hopLimit)
{
meshtastic_Routing c = meshtastic_Routing_init_default;
c.error_reason = err;
c.which_variant = meshtastic_Routing_error_reason_tag;
// Now that we have moded sendAckNak up one level into the class hierarchy we can no longer assume we are a RoutingModule
// So we manually call pb_encode_to_bytes and specify routing port number
// auto p = allocDataProtobuf(c);
meshtastic_MeshPacket *p = router->allocForSending();
p->decoded.portnum = meshtastic_PortNum_ROUTING_APP;
p->decoded.payload.size =
pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), &meshtastic_Routing_msg, &c);
p->priority = meshtastic_MeshPacket_Priority_ACK;
p->hop_limit = hopLimit; // Flood ACK back to original sender
p->to = to;
p->decoded.request_id = idFrom;
p->channel = chIndex;
if (err != meshtastic_Routing_Error_NONE)
LOG_WARN("Alloc an err=%d,to=0x%x,idFrom=0x%x,id=0x%x", err, to, idFrom, p->id);
return p;
}
meshtastic_MeshPacket *MeshModule::allocErrorResponse(meshtastic_Routing_Error err, const meshtastic_MeshPacket *p)
{
// If the original packet couldn't be decoded, use the primary channel
uint8_t channelIndex =
p->which_payload_variant == meshtastic_MeshPacket_decoded_tag ? p->channel : channels.getPrimaryIndex();
auto r = allocAckNak(err, getFrom(p), p->id, channelIndex);
setReplyTo(r, *p);
return r;
}
void MeshModule::callModules(meshtastic_MeshPacket &mp, RxSource src)
{
// LOG_DEBUG("In call modules");
bool moduleFound = false;
// We now allow **encrypted** packets to pass through the modules
bool isDecoded = mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag;
currentReply = NULL; // No reply yet
bool ignoreRequest = false; // No module asked to ignore the request yet
// Was this message directed to us specifically? Will be false if we are sniffing someone elses packets
auto ourNodeNum = nodeDB->getNodeNum();
bool toUs = isBroadcast(mp.to) || isToUs(&mp);
for (auto i = modules->begin(); i != modules->end(); ++i) {
auto &pi = **i;
pi.currentRequest = &mp;
/// We only call modules that are interested in the packet (and the message is destined to us or we are promiscious)
bool wantsPacket = (isDecoded || pi.encryptedOk) && (pi.isPromiscuous || toUs) && pi.wantPacket(&mp);
if ((src == RX_SRC_LOCAL) && !(pi.loopbackOk)) {
// new case, monitor separately for now, then FIXME merge above
wantsPacket = false;
}
assert(!pi.myReply); // If it is !null it means we have a bug, because it should have been sent the previous time
if (wantsPacket) {
LOG_DEBUG("Module '%s' wantsPacket=%d", pi.name, wantsPacket);
moduleFound = true;
/// received channel (or NULL if not decoded)
meshtastic_Channel *ch = isDecoded ? &channels.getByIndex(mp.channel) : NULL;
/// Is the channel this packet arrived on acceptable? (security check)
/// Note: we can't know channel names for encrypted packets, so those are NEVER sent to boundChannel modules
/// Also: if a packet comes in on the local PC interface, we don't check for bound channels, because it is TRUSTED and
/// it needs to to be able to fetch the initial admin packets without yet knowing any channels.
bool rxChannelOk = !pi.boundChannel || (mp.from == 0) || (ch && strcasecmp(ch->settings.name, pi.boundChannel) == 0);
if (!rxChannelOk) {
// no one should have already replied!
assert(!currentReply);
if (isDecoded && mp.decoded.want_response) {
printPacket("packet on wrong channel, returning error", &mp);
currentReply = pi.allocErrorResponse(meshtastic_Routing_Error_NOT_AUTHORIZED, &mp);
} else
printPacket("packet on wrong channel, but can't respond", &mp);
} else {
ProcessMessage handled = pi.handleReceived(mp);
pi.alterReceived(mp);
// Possibly send replies (but only if the message was directed to us specifically, i.e. not for promiscious
// sniffing) also: we only let the one module send a reply, once that happens, remaining modules are not
// considered
// NOTE: we send a reply *even if the (non broadcast) request was from us* which is unfortunate but necessary
// because currently when the phone sends things, it sends things using the local node ID as the from address. A
// better solution (FIXME) would be to let phones have their own distinct addresses and we 'route' to them like
// any other node.
if (isDecoded && mp.decoded.want_response && toUs && (!isFromUs(&mp) || isToUs(&mp)) && !currentReply) {
pi.sendResponse(mp);
ignoreRequest = ignoreRequest || pi.ignoreRequest; // If at least one module asks it, we may ignore a request
LOG_INFO("Asked module '%s' to send a response", pi.name);
} else {
LOG_DEBUG("Module '%s' considered", pi.name);
}
// If the requester didn't ask for a response we might need to discard unused replies to prevent memory leaks
if (pi.myReply) {
LOG_DEBUG("Discard an unneeded response");
packetPool.release(pi.myReply);
pi.myReply = NULL;
}
if (handled == ProcessMessage::STOP) {
LOG_DEBUG("Module '%s' handled and skipped other processing", pi.name);
break;
}
}
}
pi.currentRequest = NULL;
}
if (isDecoded && mp.decoded.want_response && toUs) {
if (currentReply) {
printPacket("Send response", currentReply);
service->sendToMesh(currentReply);
currentReply = NULL;
} else if (mp.from != ourNodeNum && !ignoreRequest) {
// Note: if the message started with the local node or a module asked to ignore the request, we don't want to send a
// no response reply
// No one wanted to reply to this request, tell the requster that happened
LOG_DEBUG("No one responded, send a nak");
// SECURITY NOTE! I considered sending back a different error code if we didn't find the psk (i.e. !isDecoded)
// but opted NOT TO. Because it is not a good idea to let remote nodes 'probe' to find out which PSKs were "good" vs
// bad.
routingModule->sendAckNak(meshtastic_Routing_Error_NO_RESPONSE, getFrom(&mp), mp.id, mp.channel,
routingModule->getHopLimitForResponse(mp.hop_start, mp.hop_limit));
}
}
if (!moduleFound && isDecoded) {
LOG_DEBUG("No modules interested in portnum=%d, src=%s", mp.decoded.portnum, (src == RX_SRC_LOCAL) ? "LOCAL" : "REMOTE");
}
}
meshtastic_MeshPacket *MeshModule::allocReply()
{
auto r = myReply;
myReply = NULL; // Only use each reply once
return r;
}
/** Messages can be received that have the want_response bit set. If set, this callback will be invoked
* so that subclasses can (optionally) send a response back to the original sender. Implementing this method
* is optional
*/
void MeshModule::sendResponse(const meshtastic_MeshPacket &req)
{
auto r = allocReply();
if (r) {
setReplyTo(r, req);
currentReply = r;
} else {
// Ignore - this is now expected behavior for routing module (because it ignores some replies)
// LOG_WARN("Client requested response but this module did not provide");
}
}
/** set the destination and packet parameters of packet p intended as a reply to a particular "to" packet
* This ensures that if the request packet was sent reliably, the reply is sent that way as well.
*/
void setReplyTo(meshtastic_MeshPacket *p, const meshtastic_MeshPacket &to)
{
assert(p->which_payload_variant == meshtastic_MeshPacket_decoded_tag); // Should already be set by now
p->to = getFrom(&to); // Make sure that if we are sending to the local node, we use our local node addr, not 0
p->channel = to.channel; // Use the same channel that the request came in on
p->hop_limit = routingModule->getHopLimitForResponse(to.hop_start, to.hop_limit);
// No need for an ack if we are just delivering locally (it just generates an ignored ack)
p->want_ack = (to.from != 0) ? to.want_ack : false;
if (p->priority == meshtastic_MeshPacket_Priority_UNSET)
p->priority = meshtastic_MeshPacket_Priority_RELIABLE;
p->decoded.request_id = to.id;
}
std::vector<MeshModule *> MeshModule::GetMeshModulesWithUIFrames(int startIndex)
{
std::vector<MeshModule *> modulesWithUIFrames;
// Fill with nullptr up to startIndex
modulesWithUIFrames.resize(startIndex, nullptr);
if (modules) {
for (auto i = modules->begin(); i != modules->end(); ++i) {
auto &pi = **i;
if (pi.wantUIFrame()) {
LOG_DEBUG("%s wants a UI Frame", pi.name);
modulesWithUIFrames.push_back(&pi);
}
}
}
return modulesWithUIFrames;
}
void MeshModule::observeUIEvents(Observer<const UIFrameEvent *> *observer)
{
if (modules) {
for (auto i = modules->begin(); i != modules->end(); ++i) {
auto &pi = **i;
Observable<const UIFrameEvent *> *observable = pi.getUIFrameObservable();
if (observable != NULL) {
LOG_DEBUG("%s wants a UI Frame", pi.name);
observer->observe(observable);
}
}
}
}
AdminMessageHandleResult MeshModule::handleAdminMessageForAllModules(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response)
{
AdminMessageHandleResult handled = AdminMessageHandleResult::NOT_HANDLED;
if (modules) {
for (auto i = modules->begin(); i != modules->end(); ++i) {
auto &pi = **i;
AdminMessageHandleResult h = pi.handleAdminMessageForModule(mp, request, response);
if (h == AdminMessageHandleResult::HANDLED_WITH_RESPONSE) {
// In case we have a response it always has priority.
LOG_DEBUG("Reply prepared by module '%s' of variant: %d", pi.name, response->which_payload_variant);
handled = h;
} else if ((handled != AdminMessageHandleResult::HANDLED_WITH_RESPONSE) && (h == AdminMessageHandleResult::HANDLED)) {
// In case the message is handled it should be populated, but will not overwrite
// a result with response.
handled = h;
}
}
}
return handled;
}
#if HAS_SCREEN
// Would our module like its frame to be focused after Screen::setFrames has regenerated the list of frames?
// Only considered if setFrames is triggered by a UIFrameEvent
bool MeshModule::isRequestingFocus()
{
if (_requestingFocus) {
_requestingFocus = false; // Consume the request
return true;
} else
return false;
}
#endif
@@ -0,0 +1,228 @@
#pragma once
#include "mesh/Channels.h"
#include "mesh/MeshTypes.h"
#include <vector>
#if HAS_SCREEN
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
#endif
#define MESHMODULE_MIN_BROADCAST_DELAY_MS 30 * 1000 // Min. delay after boot before sending first broadcast by any module
#define MESHMODULE_BROADCAST_SPACING_MS 15 * 1000 // Initial spacing between broadcasts of different modules
/** handleReceived return enumeration
*
* Use ProcessMessage::CONTINUE to allows other modules to process a message.
*
* Use ProcessMessage::STOP to stop further message processing.
*/
enum class ProcessMessage {
CONTINUE = 0,
STOP = 1,
};
/**
* Used by modules to return the result of the AdminMessage handling.
* If request is handled, then module should return HANDLED,
* If response is also prepared for the request, then HANDLED_WITH_RESPONSE
* should be returned.
*/
enum class AdminMessageHandleResult {
NOT_HANDLED = 0,
HANDLED = 1,
HANDLED_WITH_RESPONSE = 2,
};
/*
* This struct is used by Screen to figure out whether screen frame should be updated.
*/
struct UIFrameEvent {
// What do we actually want to happen?
enum Action {
REDRAW_ONLY, // Don't change which frames are show, just redraw, asap
REGENERATE_FRAMESET, // Regenerate (change? add? remove?) screen frames, honoring requestFocus()
REGENERATE_FRAMESET_BACKGROUND, // Regenerate screen frames, Attempt to remain on the same frame throughout
} action = REDRAW_ONLY;
// We might want to pass additional data inside this struct at some point
};
/** A baseclass for any mesh "module".
*
* A module allows you to add new features to meshtastic device code, without needing to know messaging details.
*
* A key concept for this is that your module should use a particular "portnum" for each message type you want to receive
* and handle.
*
* Internally we use modules to implement the core meshtastic text messaging and gps position sharing features. You
* can use these classes as examples for how to write your own custom module. See here: (FIXME)
*/
class MeshModule
{
static std::vector<MeshModule *> *modules;
public:
/** Constructor
* name is for debugging output
*/
MeshModule(const char *_name);
virtual ~MeshModule();
/** For use only by MeshService
*/
static void callModules(meshtastic_MeshPacket &mp, RxSource src = RX_SRC_RADIO);
static std::vector<MeshModule *> GetMeshModulesWithUIFrames(int startIndex);
static void observeUIEvents(Observer<const UIFrameEvent *> *observer);
static AdminMessageHandleResult handleAdminMessageForAllModules(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response);
#if HAS_SCREEN
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { return; }
virtual bool isRequestingFocus(); // Checked by screen, when regenerating frameset
virtual bool interceptingKeyboardInput() { return false; } // Can screen use keyboard for nav, or is module handling input?
#endif
protected:
const char *name;
/** Most modules only care about packets that are destined for their node (i.e. broadcasts or has their node as the specific
recipient) But some plugs might want to 'sniff' packets that are merely being routed (passing through the current node). Those
modules can set this to true and their handleReceived() will be called for every packet.
*/
bool isPromiscuous = false;
/** Also receive a copy of LOCALLY GENERATED messages - most modules should leave
* this setting disabled - see issue #877 */
bool loopbackOk = false;
/** Most modules only understand decrypted packets. For modules that also want to see encrypted packets, they should set this
* flag */
bool encryptedOk = false;
/* We allow modules to ignore a request without sending an error if they have a specific reason for it. */
bool ignoreRequest = false;
/** If a bound channel name is set, we will only accept received packets that come in on that channel.
* A special exception (FIXME, not sure if this is a good idea) - packets that arrive on the local interface
* are allowed on any channel (this lets the local user do anything).
*
* We will send responses on the same channel that the request arrived on.
*/
const char *boundChannel = NULL;
/**
* If this module is currently handling a request currentRequest will be preset
* to the packet with the request. This is mostly useful for reply handlers.
*
* Note: this can be static because we are guaranteed to be processing only one
* plumodulegin at a time.
*/
static const meshtastic_MeshPacket *currentRequest;
// We keep track of the number of modules that send a periodic broadcast to schedule them spaced out over time
static uint8_t numPeriodicModules;
// Set the start delay for module that broadcasts periodically
int32_t setStartDelay();
/**
* If your handler wants to send a response, simply set currentReply and it will be sent at the end of response handling.
*/
meshtastic_MeshPacket *myReply = NULL;
/**
* Initialize your module. This setup function is called once after all hardware and mesh protocol layers have
* been initialized
*/
virtual void setup();
/**
* @return true if you want to receive the specified portnum
*/
virtual bool wantPacket(const meshtastic_MeshPacket *p) = 0;
/** Called to handle a particular incoming message
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for
it
*/
virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp) { return ProcessMessage::CONTINUE; }
/** Called to change a particular incoming message
This allows the module to change the message before it is passed through the rest of the call-chain.
*/
virtual void alterReceived(meshtastic_MeshPacket &mp) {}
/** Messages can be received that have the want_response bit set. If set, this callback will be invoked
* so that subclasses can (optionally) send a response back to the original sender.
*
* Note: most implementers don't need to override this, instead: If while handling a request you have a reply, just set
* the protected reply field in this instance.
* */
virtual meshtastic_MeshPacket *allocReply();
/***
* @return true if you want to be alloced a UI screen frame
*/
virtual bool wantUIFrame() { return false; }
virtual Observable<const UIFrameEvent *> *getUIFrameObservable() { return NULL; }
meshtastic_MeshPacket *allocAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex,
uint8_t hopLimit = 0);
/// Send an error response for the specified packet.
meshtastic_MeshPacket *allocErrorResponse(meshtastic_Routing_Error err, const meshtastic_MeshPacket *p);
/**
* @brief An admin message arrived to AdminModule. Module was asked whether it want to handle the request.
*
* @param mp The mesh packet arrived.
* @param request The AdminMessage request extracted from the packet.
* @param response The prepared response
* @return AdminMessageHandleResult
* HANDLED if message was handled
* HANDLED_WITH_RESPONSE if a response is also prepared and to be sent.
*/
virtual AdminMessageHandleResult handleAdminMessageForModule(const meshtastic_MeshPacket &mp,
meshtastic_AdminMessage *request,
meshtastic_AdminMessage *response)
{
return AdminMessageHandleResult::NOT_HANDLED;
};
#if HAS_SCREEN
/** Request that our module's screen frame be focused when Screen::setFrames runs
* Only considered if Screen::setFrames is triggered via a UIFrameEvent
*
* Having this as a separate call, instead of part of the UIFrameEvent, allows the module to delay decision
* until drawFrame() is called. This required less restructuring.
*/
bool _requestingFocus = false;
void requestFocus() { _requestingFocus = true; }
#else
void requestFocus(){}; // No-op
#endif
private:
/**
* If any of the current chain of modules has already sent a reply, it will be here. This is useful to allow
* the RoutingModule to avoid sending redundant acks
*/
static meshtastic_MeshPacket *currentReply;
friend class ReliableRouter;
/** Messages can be received that have the want_response bit set. If set, this callback will be invoked
* so that subclasses can (optionally) send a response back to the original sender. This method calls allocReply()
* to generate the reply message, and if !NULL that message will be delivered to whoever sent req
*/
void sendResponse(const meshtastic_MeshPacket &req);
};
/** set the destination and packet parameters of packet p intended as a reply to a particular "to" packet
* This ensures that if the request packet was sent reliably, the reply is sent that way as well.
*/
void setReplyTo(meshtastic_MeshPacket *p, const meshtastic_MeshPacket &to);
@@ -0,0 +1,189 @@
#include "MeshPacketQueue.h"
#include "NodeDB.h"
#include "configuration.h"
#include <assert.h>
#include <algorithm>
/// @return the priority of the specified packet
inline uint32_t getPriority(const meshtastic_MeshPacket *p)
{
auto pri = p->priority;
return pri;
}
/// @return "true" if "p1" is ordered before "p2"
bool CompareMeshPacketFunc(const meshtastic_MeshPacket *p1, const meshtastic_MeshPacket *p2)
{
assert(p1 && p2);
// If one packet is in the late transmit window, prefer the other one
if ((bool)p1->tx_after != (bool)p2->tx_after) {
return !p1->tx_after;
}
auto p1p = getPriority(p1), p2p = getPriority(p2);
// If priorities differ, use that
// for equal priorities, prefer packets already on mesh.
return (p1p != p2p) ? (p1p > p2p) : (!isFromUs(p1) && isFromUs(p2));
}
MeshPacketQueue::MeshPacketQueue(size_t _maxLen) : maxLen(_maxLen) {}
bool MeshPacketQueue::empty()
{
return queue.empty();
}
/**
* Some clients might not properly set priority, therefore we fix it here.
*/
void fixPriority(meshtastic_MeshPacket *p)
{
// We might receive acks from other nodes (and since generated remotely, they won't have priority assigned. Check for that
// and fix it
if (p->priority == meshtastic_MeshPacket_Priority_UNSET) {
// if a reliable message give a bit higher default priority
p->priority = (p->want_ack ? meshtastic_MeshPacket_Priority_RELIABLE : meshtastic_MeshPacket_Priority_DEFAULT);
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
// if acks/naks give very high priority
if (p->decoded.portnum == meshtastic_PortNum_ROUTING_APP) {
p->priority = meshtastic_MeshPacket_Priority_ACK;
// if text or admin, give high priority
} else if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP ||
p->decoded.portnum == meshtastic_PortNum_ADMIN_APP) {
p->priority = meshtastic_MeshPacket_Priority_HIGH;
// if it is a response, give higher priority to let it arrive early and stop the request being relayed
} else if (p->decoded.request_id != 0) {
p->priority = meshtastic_MeshPacket_Priority_RESPONSE;
// Also if we want a response, give a bit higher priority
} else if (p->decoded.want_response) {
p->priority = meshtastic_MeshPacket_Priority_RELIABLE;
}
}
}
}
/** enqueue a packet, return false if full */
bool MeshPacketQueue::enqueue(meshtastic_MeshPacket *p, bool *dropped)
{
// no space - try to replace a lower priority packet in the queue
if (queue.size() >= maxLen) {
bool replaced = replaceLowerPriorityPacket(p);
if (!replaced) {
LOG_WARN("TX queue is full, and there is no lower-priority packet available to evict in favour of 0x%08x", p->id);
}
if (dropped) {
*dropped = true;
}
return replaced;
}
if (dropped) {
*dropped = false;
}
// Find the correct position using upper_bound to maintain a stable order
auto it = std::upper_bound(queue.begin(), queue.end(), p, CompareMeshPacketFunc);
queue.insert(it, p); // Insert packet at the found position
return true;
}
meshtastic_MeshPacket *MeshPacketQueue::dequeue()
{
if (empty()) {
return NULL;
}
auto *p = queue.front();
queue.erase(queue.begin()); // Remove the highest-priority packet
return p;
}
meshtastic_MeshPacket *MeshPacketQueue::getFront()
{
if (empty()) {
return NULL;
}
auto *p = queue.front();
return p;
}
/** Get a packet from this queue. Returns a pointer to the packet, or NULL if not found. */
meshtastic_MeshPacket *MeshPacketQueue::getPacketFromQueue(NodeNum from, PacketId id)
{
for (auto it = queue.begin(); it != queue.end(); it++) {
auto p = (*it);
if (getFrom(p) == from && p->id == id) {
return p;
}
}
return NULL;
}
/** Attempt to find and remove a packet from this queue. Returns a pointer to the removed packet, or NULL if not found */
meshtastic_MeshPacket *MeshPacketQueue::remove(NodeNum from, PacketId id, bool tx_normal, bool tx_late, uint8_t hop_limit_lt)
{
for (auto it = queue.begin(); it != queue.end(); it++) {
auto p = (*it);
if (getFrom(p) == from && p->id == id && ((tx_normal && !p->tx_after) || (tx_late && p->tx_after)) &&
(!hop_limit_lt || p->hop_limit < hop_limit_lt)) {
queue.erase(it);
return p;
}
}
return NULL;
}
/* Attempt to find a packet from this queue. Return true if it was found. */
bool MeshPacketQueue::find(const NodeNum from, const PacketId id)
{
return getPacketFromQueue(from, id) != NULL;
}
/**
* Attempt to find a lower-priority packet in the queue and replace it with the provided one.
* @return True if the replacement succeeded, false otherwise
*/
bool MeshPacketQueue::replaceLowerPriorityPacket(meshtastic_MeshPacket *p)
{
if (queue.empty()) {
return false; // No packets to replace
}
// Check if the packet at the back has a lower priority than the new packet
auto *backPacket = queue.back();
if (!backPacket->tx_after && backPacket->priority < p->priority) {
LOG_WARN("Dropping packet 0x%08x to make room in the TX queue for higher-priority packet 0x%08x", backPacket->id, p->id);
// Remove the back packet
queue.pop_back();
packetPool.release(backPacket);
// Insert the new packet in the correct order
enqueue(p);
return true;
}
if (backPacket->tx_after) {
// Check if there's a non-late packet with lower priority
auto it = queue.end();
auto refPacket = *--it;
for (; refPacket->tx_after && it != queue.begin(); refPacket = *--it)
;
if (!refPacket->tx_after && refPacket->priority < p->priority) {
LOG_WARN("Dropping non-late packet 0x%08x to make room in the TX queue for higher-priority packet 0x%08x",
refPacket->id, p->id);
queue.erase(it);
packetPool.release(refPacket);
// Insert the new packet in the correct order
enqueue(p);
return true;
}
}
// If the back packet's priority is not lower, no replacement occurs
return false;
}
@@ -0,0 +1,49 @@
#pragma once
#include "MeshTypes.h"
#include <queue>
/**
* A priority queue of packets
*/
class MeshPacketQueue
{
size_t maxLen;
std::vector<meshtastic_MeshPacket *> queue;
/** Replace a lower priority package in the queue with 'mp' (provided there are lower pri packages). Return true if replaced.
*/
bool replaceLowerPriorityPacket(meshtastic_MeshPacket *mp);
public:
explicit MeshPacketQueue(size_t _maxLen);
/** enqueue a packet, return false if full
* @param dropped Optional pointer to a bool that will be set to true if a packet was dropped
*/
bool enqueue(meshtastic_MeshPacket *p, bool *dropped = nullptr);
/** return true if the queue is empty */
bool empty();
/** return amount of free packets in Queue */
size_t getFree() { return maxLen - queue.size(); }
/** return total size of the Queue */
size_t getMaxLen() { return maxLen; }
meshtastic_MeshPacket *dequeue();
meshtastic_MeshPacket *getFront();
/** Get a packet from this queue. Returns a pointer to the packet, or NULL if not found. */
meshtastic_MeshPacket *getPacketFromQueue(NodeNum from, PacketId id);
/** Attempt to find and remove a packet from this queue. Returns the packet which was removed from the queue */
meshtastic_MeshPacket *remove(NodeNum from, PacketId id, bool tx_normal = true, bool tx_late = true,
uint8_t hop_limit_lt = 0);
/* Attempt to find a packet from this queue. Return true if it was found. */
bool find(const NodeNum from, const PacketId id);
};
@@ -0,0 +1,25 @@
#pragma once
#include "MemoryPool.h"
#include "MeshTypes.h"
#include "PointerQueue.h"
#include "configuration.h"
// Map from old region names to new region enums
struct RegionInfo {
meshtastic_Config_LoRaConfig_RegionCode code;
float freqStart;
float freqEnd;
float dutyCycle;
float spacing;
uint8_t powerLimit; // Or zero for not set
bool audioPermitted;
bool freqSwitching;
bool wideLora;
const char *name; // EU433 etc
};
extern const RegionInfo regions[];
extern const RegionInfo *myRegion;
extern void initRegion();
@@ -0,0 +1,455 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_GPS
#include "GPS.h"
#endif
#include "../concurrency/Periodic.h"
#include "BluetoothCommon.h" // needed for updateBatteryLevel, FIXME, eventually when we pull mesh out into a lib we shouldn't be whacking bluetooth from here
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "RTC.h"
#include "TypeConversions.h"
#include "main.h"
#include "mesh-pb-constants.h"
#include "meshUtils.h"
#include "modules/NodeInfoModule.h"
#include "modules/PositionModule.h"
#include "modules/RoutingModule.h"
#include "power.h"
#include <assert.h>
#include <string>
#if ARCH_PORTDUINO
#include "PortduinoGlue.h"
#endif
/*
receivedPacketQueue - this is a queue of messages we've received from the mesh, which we are keeping to deliver to the phone.
It is implemented with a FreeRTos queue (wrapped with a little RTQueue class) of pointers to MeshPacket protobufs (which were
alloced with new). After a packet ptr is removed from the queue and processed it should be deleted. (eventually we should move
sent packets into a 'sentToPhone' queue of packets we can delete just as soon as we are sure the phone has acked those packets -
when the phone writes to FromNum)
mesh - an instance of Mesh class. Which manages the interface to the mesh radio library, reception of packets from other nodes,
arbitrating to select a node number and keeping the current nodedb.
*/
/* Broadcast when a newly powered mesh node wants to find a node num it can use
The algorithm is as follows:
* when a node starts up, it broadcasts their user and the normal flow is for all other nodes to reply with their User as well (so
the new node can build its node db)
*/
MeshService *service;
#define MAX_MQTT_PROXY_MESSAGES 16
static MemoryPool<meshtastic_MqttClientProxyMessage, MAX_MQTT_PROXY_MESSAGES> staticMqttClientProxyMessagePool;
#define MAX_QUEUE_STATUS 4
static MemoryPool<meshtastic_QueueStatus, MAX_QUEUE_STATUS> staticQueueStatusPool;
#define MAX_CLIENT_NOTIFICATIONS 4
static MemoryPool<meshtastic_ClientNotification, MAX_CLIENT_NOTIFICATIONS> staticClientNotificationPool;
Allocator<meshtastic_MqttClientProxyMessage> &mqttClientProxyMessagePool = staticMqttClientProxyMessagePool;
Allocator<meshtastic_ClientNotification> &clientNotificationPool = staticClientNotificationPool;
Allocator<meshtastic_QueueStatus> &queueStatusPool = staticQueueStatusPool;
#include "Router.h"
MeshService::MeshService()
#ifdef ARCH_PORTDUINO
: toPhoneQueue(MAX_RX_TOPHONE), toPhoneQueueStatusQueue(MAX_RX_QUEUESTATUS_TOPHONE),
toPhoneMqttProxyQueue(MAX_RX_MQTTPROXY_TOPHONE), toPhoneClientNotificationQueue(MAX_RX_NOTIFICATION_TOPHONE)
#endif
{
lastQueueStatus = {0, 0, 16, 0};
}
void MeshService::init()
{
#if HAS_GPS
if (gps)
gpsObserver.observe(&gps->newStatus);
#endif
}
int MeshService::handleFromRadio(const meshtastic_MeshPacket *mp)
{
powerFSM.trigger(EVENT_PACKET_FOR_PHONE); // Possibly keep the node from sleeping
nodeDB->updateFrom(*mp); // update our DB state based off sniffing every RX packet from the radio
bool isPreferredRebroadcaster = config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER;
if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag &&
mp->decoded.portnum == meshtastic_PortNum_TELEMETRY_APP && mp->decoded.request_id > 0) {
LOG_DEBUG("Received telemetry response. Skip sending our NodeInfo");
// ignore our request for its NodeInfo
} else if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag && !nodeDB->getMeshNode(mp->from)->has_user &&
nodeInfoModule && !isPreferredRebroadcaster && !nodeDB->isFull()) {
if (airTime->isTxAllowedChannelUtil(true)) {
// Hops used by the request. If somebody in between running modified firmware modified it, ignore it
auto hopStart = mp->hop_start;
auto hopLimit = mp->hop_limit;
uint8_t hopsUsed = hopStart < hopLimit ? config.lora.hop_limit : hopStart - hopLimit;
if (hopsUsed > config.lora.hop_limit + 2) {
LOG_DEBUG("Skip send NodeInfo: %d hops away is too far away", hopsUsed);
} else {
LOG_INFO("Heard new node on ch. %d, send NodeInfo and ask for response", mp->channel);
nodeInfoModule->sendOurNodeInfo(mp->from, true, mp->channel);
}
} else {
LOG_DEBUG("Skip sending NodeInfo > 25%% ch. util");
}
}
printPacket("Forwarding to phone", mp);
sendToPhone(packetPool.allocCopy(*mp));
return 0;
}
/// Do idle processing (mostly processing messages which have been queued from the radio)
void MeshService::loop()
{
if (lastQueueStatus.free == 0) { // check if there is now free space in TX queue
meshtastic_QueueStatus qs = router->getQueueStatus();
if (qs.free != lastQueueStatus.free)
(void)sendQueueStatusToPhone(qs, 0, 0);
}
if (oldFromNum != fromNum) { // We don't want to generate extra notifies for multiple new packets
int result = fromNumChanged.notifyObservers(fromNum);
if (result == 0) // If any observer returns non-zero, we will try again
oldFromNum = fromNum;
}
}
/// The radioConfig object just changed, call this to force the hw to change to the new settings
void MeshService::reloadConfig(int saveWhat)
{
// If we can successfully set this radio to these settings, save them to disk
// This will also update the region as needed
nodeDB->resetRadioConfig(); // Don't let the phone send us fatally bad settings
configChanged.notifyObservers(NULL); // This will cause radio hardware to change freqs etc
nodeDB->saveToDisk(saveWhat);
}
/// The owner User record just got updated, update our node DB and broadcast the info into the mesh
void MeshService::reloadOwner(bool shouldSave)
{
// LOG_DEBUG("reloadOwner()");
// update our local data directly
nodeDB->updateUser(nodeDB->getNodeNum(), owner);
assert(nodeInfoModule);
// update everyone else and save to disk
if (nodeInfoModule && shouldSave) {
nodeInfoModule->sendOurNodeInfo();
}
}
// search the queue for a request id and return the matching nodenum
NodeNum MeshService::getNodenumFromRequestId(uint32_t request_id)
{
NodeNum nodenum = 0;
for (int i = 0; i < toPhoneQueue.numUsed(); i++) {
meshtastic_MeshPacket *p = toPhoneQueue.dequeuePtr(0);
if (p->id == request_id) {
nodenum = p->to;
// make sure to continue this to make one full loop
}
// put it right back on the queue
toPhoneQueue.enqueue(p, 0);
}
return nodenum;
}
/**
* Given a ToRadio buffer parse it and properly handle it (setup radio, owner or send packet into the mesh)
* Called by PhoneAPI.handleToRadio. Note: p is a scratch buffer, this function is allowed to write to it but it can not keep a
* reference
*/
void MeshService::handleToRadio(meshtastic_MeshPacket &p)
{
#if defined(ARCH_PORTDUINO)
if (SimRadio::instance && p.decoded.portnum == meshtastic_PortNum_SIMULATOR_APP) {
// Simulates device received a packet via the LoRa chip
SimRadio::instance->unpackAndReceive(p);
return;
}
#endif
p.from = 0; // We don't let clients assign nodenums to their sent messages
p.next_hop = NO_NEXT_HOP_PREFERENCE; // We don't let clients assign next_hop to their sent messages
p.relay_node = NO_RELAY_NODE; // We don't let clients assign relay_node to their sent messages
if (p.id == 0)
p.id = generatePacketId(); // If the phone didn't supply one, then pick one
p.rx_time = getValidTime(RTCQualityFromNet); // Record the time the packet arrived from the phone
// (so we update our nodedb for the local node)
// Send the packet into the mesh
DEBUG_HEAP_BEFORE;
auto a = packetPool.allocCopy(p);
DEBUG_HEAP_AFTER("MeshService::handleToRadio", a);
sendToMesh(a, RX_SRC_USER);
bool loopback = false; // if true send any packet the phone sends back itself (for testing)
if (loopback) {
// no need to copy anymore because handle from radio assumes it should _not_ delete
// packetPool.allocCopy(r.variant.packet);
handleFromRadio(&p);
// handleFromRadio will tell the phone a new packet arrived
}
}
/** Attempt to cancel a previously sent packet from this _local_ node. Returns true if a packet was found we could cancel */
bool MeshService::cancelSending(PacketId id)
{
return router->cancelSending(nodeDB->getNodeNum(), id);
}
ErrorCode MeshService::sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id)
{
meshtastic_QueueStatus *copied = queueStatusPool.allocCopy(qs);
copied->res = res;
copied->mesh_packet_id = mesh_packet_id;
if (toPhoneQueueStatusQueue.numFree() == 0) {
LOG_INFO("tophone queue status queue is full, discard oldest");
meshtastic_QueueStatus *d = toPhoneQueueStatusQueue.dequeuePtr(0);
if (d)
releaseQueueStatusToPool(d);
}
lastQueueStatus = *copied;
res = toPhoneQueueStatusQueue.enqueue(copied, 0);
fromNum++;
return res ? ERRNO_OK : ERRNO_UNKNOWN;
}
void MeshService::sendToMesh(meshtastic_MeshPacket *p, RxSource src, bool ccToPhone)
{
uint32_t mesh_packet_id = p->id;
nodeDB->updateFrom(*p); // update our local DB for this packet (because phone might have sent position packets etc...)
// Note: We might return !OK if our fifo was full, at that point the only option we have is to drop it
ErrorCode res = router->sendLocal(p, src);
/* NOTE(pboldin): Prepare and send QueueStatus message to the phone as a
* high-priority message. */
meshtastic_QueueStatus qs = router->getQueueStatus();
ErrorCode r = sendQueueStatusToPhone(qs, res, mesh_packet_id);
if (r != ERRNO_OK) {
LOG_DEBUG("Can't send status to phone");
}
if ((res == ERRNO_OK || res == ERRNO_SHOULD_RELEASE) && ccToPhone) { // Check if p is not released in case it couldn't be sent
DEBUG_HEAP_BEFORE;
auto a = packetPool.allocCopy(*p);
DEBUG_HEAP_AFTER("MeshService::sendToMesh", a);
sendToPhone(a);
}
// Router may ask us to release the packet if it wasn't sent
if (res == ERRNO_SHOULD_RELEASE) {
releaseToPool(p);
}
}
bool MeshService::trySendPosition(NodeNum dest, bool wantReplies)
{
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum());
assert(node);
if (nodeDB->hasValidPosition(node)) {
#if HAS_GPS && !MESHTASTIC_EXCLUDE_GPS
if (positionModule) {
LOG_INFO("Send position ping to 0x%x, wantReplies=%d, channel=%d", dest, wantReplies, node->channel);
positionModule->sendOurPosition(dest, wantReplies, node->channel);
return true;
}
} else {
#endif
if (nodeInfoModule) {
LOG_INFO("Send nodeinfo ping to 0x%x, wantReplies=%d, channel=%d", dest, wantReplies, node->channel);
nodeInfoModule->sendOurNodeInfo(dest, wantReplies, node->channel);
}
}
return false;
}
void MeshService::sendToPhone(meshtastic_MeshPacket *p)
{
perhapsDecode(p);
#ifdef ARCH_ESP32
#if !MESHTASTIC_EXCLUDE_STOREFORWARD
if (moduleConfig.store_forward.enabled && storeForwardModule->isServer() &&
p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP) {
releaseToPool(p); // Copy is already stored in StoreForward history
fromNum++; // Notify observers for packet from radio
return;
}
#endif
#endif
if (toPhoneQueue.numFree() == 0) {
if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP ||
p->decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP) {
LOG_WARN("ToPhone queue is full, discard oldest");
meshtastic_MeshPacket *d = toPhoneQueue.dequeuePtr(0);
if (d)
releaseToPool(d);
} else {
LOG_WARN("ToPhone queue is full, drop packet");
releaseToPool(p);
fromNum++; // Make sure to notify observers in case they are reconnected so they can get the packets
return;
}
}
if (toPhoneQueue.enqueue(p, 0) == false) {
LOG_CRIT("Failed to queue a packet into toPhoneQueue!");
abort();
}
fromNum++;
}
void MeshService::sendMqttMessageToClientProxy(meshtastic_MqttClientProxyMessage *m)
{
LOG_DEBUG("Send mqtt message on topic '%s' to client for proxy", m->topic);
if (toPhoneMqttProxyQueue.numFree() == 0) {
LOG_WARN("MqttClientProxyMessagePool queue is full, discard oldest");
meshtastic_MqttClientProxyMessage *d = toPhoneMqttProxyQueue.dequeuePtr(0);
if (d)
releaseMqttClientProxyMessageToPool(d);
}
if (toPhoneMqttProxyQueue.enqueue(m, 0) == false) {
LOG_CRIT("Failed to queue a packet into toPhoneMqttProxyQueue!");
abort();
}
fromNum++;
}
void MeshService::sendRoutingErrorResponse(meshtastic_Routing_Error error, const meshtastic_MeshPacket *mp)
{
if (!mp) {
LOG_WARN("Cannot send routing error response: null packet");
return;
}
// Use the routing module to send the error response
if (routingModule) {
routingModule->sendAckNak(error, mp->from, mp->id, mp->channel);
} else {
LOG_ERROR("Cannot send routing error response: no routing module");
}
}
void MeshService::sendClientNotification(meshtastic_ClientNotification *n)
{
LOG_DEBUG("Send client notification to phone");
if (toPhoneClientNotificationQueue.numFree() == 0) {
LOG_WARN("ClientNotification queue is full, discard oldest");
meshtastic_ClientNotification *d = toPhoneClientNotificationQueue.dequeuePtr(0);
if (d)
releaseClientNotificationToPool(d);
}
if (toPhoneClientNotificationQueue.enqueue(n, 0) == false) {
LOG_CRIT("Failed to queue a notification into toPhoneClientNotificationQueue!");
abort();
}
fromNum++;
}
meshtastic_NodeInfoLite *MeshService::refreshLocalMeshNode()
{
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(nodeDB->getNodeNum());
assert(node);
// We might not have a position yet for our local node, in that case, at least try to send the time
if (!node->has_position) {
memset(&node->position, 0, sizeof(node->position));
node->has_position = true;
}
meshtastic_PositionLite &position = node->position;
// Update our local node info with our time (even if we don't decide to update anyone else)
node->last_heard =
getValidTime(RTCQualityFromNet); // This nodedb timestamp might be stale, so update it if our clock is kinda valid
position.time = getValidTime(RTCQualityFromNet);
if (powerStatus->getHasBattery() == 1) {
updateBatteryLevel(powerStatus->getBatteryChargePercent());
}
return node;
}
#if HAS_GPS
int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
{
// Update our local node info with our position (even if we don't decide to update anyone else)
const meshtastic_NodeInfoLite *node = refreshLocalMeshNode();
meshtastic_Position pos = meshtastic_Position_init_default;
if (newStatus->getHasLock()) {
// load data from GPS object, will add timestamp + battery further down
pos = gps->p;
} else {
// The GPS has lost lock
#ifdef GPS_DEBUG
LOG_DEBUG("onGPSchanged() - lost validLocation");
#endif
}
// Used fixed position if configured regardless of GPS lock
if (config.position.fixed_position) {
LOG_WARN("Use fixed position");
pos = TypeConversions::ConvertToPosition(node->position);
}
// Add a fresh timestamp
pos.time = getValidTime(RTCQualityFromNet);
// In debug logs, identify position by @timestamp:stage (stage 4 = nodeDB)
LOG_DEBUG("onGPSChanged() pos@%x time=%u lat=%d lon=%d alt=%d", pos.timestamp, pos.time, pos.latitude_i, pos.longitude_i,
pos.altitude);
// Update our current position in the local DB
nodeDB->updatePosition(nodeDB->getNodeNum(), pos, RX_SRC_LOCAL);
return 0;
}
#endif
bool MeshService::isToPhoneQueueEmpty()
{
return toPhoneQueue.isEmpty();
}
uint32_t MeshService::GetTimeSinceMeshPacket(const meshtastic_MeshPacket *mp)
{
uint32_t now = getTime();
uint32_t last_seen = mp->rx_time;
int delta = (int)(now - last_seen);
if (delta < 0) // our clock must be slightly off still - not set from GPS yet
delta = 0;
return delta;
}
@@ -0,0 +1,205 @@
#pragma once
#include <Arduino.h>
#include <assert.h>
#include <string>
#include "GPSStatus.h"
#include "MemoryPool.h"
#include "MeshRadio.h"
#include "MeshTypes.h"
#include "Observer.h"
#ifdef ARCH_PORTDUINO
#include "PointerQueue.h"
#else
#include "StaticPointerQueue.h"
#endif
#include "mesh-pb-constants.h"
#if defined(ARCH_PORTDUINO)
#include "../platform/portduino/SimRadio.h"
#endif
#if defined(ARCH_ESP32) || defined(ARCH_PORTDUINO)
#if !MESHTASTIC_EXCLUDE_STOREFORWARD
#include "modules/StoreForwardModule.h"
#endif
#endif
extern Allocator<meshtastic_QueueStatus> &queueStatusPool;
extern Allocator<meshtastic_MqttClientProxyMessage> &mqttClientProxyMessagePool;
extern Allocator<meshtastic_ClientNotification> &clientNotificationPool;
/**
* Top level app for this service. keeps the mesh, the radio config and the queue of received packets.
*
*/
class MeshService
{
#if HAS_GPS
CallbackObserver<MeshService, const meshtastic::GPSStatus *> gpsObserver =
CallbackObserver<MeshService, const meshtastic::GPSStatus *>(this, &MeshService::onGPSChanged);
#endif
/// received packets waiting for the phone to process them
/// FIXME, change to a DropOldestQueue and keep a count of the number of dropped packets to ensure
/// we never hang because android hasn't been there in a while
/// FIXME - save this to flash on deep sleep
#ifdef ARCH_PORTDUINO
PointerQueue<meshtastic_MeshPacket> toPhoneQueue;
#else
StaticPointerQueue<meshtastic_MeshPacket, MAX_RX_TOPHONE> toPhoneQueue;
#endif
// keep list of QueueStatus packets to be send to the phone
#ifdef ARCH_PORTDUINO
PointerQueue<meshtastic_QueueStatus> toPhoneQueueStatusQueue;
#else
StaticPointerQueue<meshtastic_QueueStatus, MAX_RX_QUEUESTATUS_TOPHONE> toPhoneQueueStatusQueue;
#endif
// keep list of MqttClientProxyMessages to be send to the client for delivery
#ifdef ARCH_PORTDUINO
PointerQueue<meshtastic_MqttClientProxyMessage> toPhoneMqttProxyQueue;
#else
StaticPointerQueue<meshtastic_MqttClientProxyMessage, MAX_RX_MQTTPROXY_TOPHONE> toPhoneMqttProxyQueue;
#endif
// keep list of ClientNotifications to be send to the client (phone)
#ifdef ARCH_PORTDUINO
PointerQueue<meshtastic_ClientNotification> toPhoneClientNotificationQueue;
#else
StaticPointerQueue<meshtastic_ClientNotification, MAX_RX_NOTIFICATION_TOPHONE> toPhoneClientNotificationQueue;
#endif
// This holds the last QueueStatus send
meshtastic_QueueStatus lastQueueStatus;
/// The current nonce for the newest packet which has been queued for the phone
uint32_t fromNum = 0;
/// Updated in loop() to detect when fromNum changes
uint32_t oldFromNum = 0;
public:
enum APIState {
STATE_DISCONNECTED, // Initial state, no API is connected
STATE_BLE,
STATE_WIFI,
STATE_SERIAL,
STATE_PACKET,
STATE_HTTP,
STATE_ETH
};
APIState api_state = STATE_DISCONNECTED;
static bool isTextPayload(const meshtastic_MeshPacket *p)
{
if (moduleConfig.range_test.enabled && p->decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP) {
return true;
}
return p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP ||
p->decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP ||
p->decoded.portnum == meshtastic_PortNum_ALERT_APP;
}
/// Called when some new packets have arrived from one of the radios
Observable<uint32_t> fromNumChanged;
/// Called when radio config has changed (radios should observe this and set their hardware as required)
Observable<void *> configChanged;
MeshService();
void init();
/// Do idle processing (mostly processing messages which have been queued from the radio)
void loop();
/// Return the next packet destined to the phone. FIXME, somehow use fromNum to allow the phone to retry the
/// last few packets if needs to.
meshtastic_MeshPacket *getForPhone() { return toPhoneQueue.dequeuePtr(0); }
/// Allows the bluetooth handler to free packets after they have been sent
void releaseToPool(meshtastic_MeshPacket *p) { packetPool.release(p); }
/// Return the next QueueStatus packet destined to the phone.
meshtastic_QueueStatus *getQueueStatusForPhone() { return toPhoneQueueStatusQueue.dequeuePtr(0); }
/// Return the next MqttClientProxyMessage packet destined to the phone.
meshtastic_MqttClientProxyMessage *getMqttClientProxyMessageForPhone() { return toPhoneMqttProxyQueue.dequeuePtr(0); }
/// Return the next ClientNotification packet destined to the phone.
meshtastic_ClientNotification *getClientNotificationForPhone() { return toPhoneClientNotificationQueue.dequeuePtr(0); }
// search the queue for a request id and return the matching nodenum
NodeNum getNodenumFromRequestId(uint32_t request_id);
// Release QueueStatus packet to pool
void releaseQueueStatusToPool(meshtastic_QueueStatus *p) { queueStatusPool.release(p); }
// Release MqttClientProxyMessage packet to pool
void releaseMqttClientProxyMessageToPool(meshtastic_MqttClientProxyMessage *p) { mqttClientProxyMessagePool.release(p); }
/// Release the next ClientNotification packet to pool.
void releaseClientNotificationToPool(meshtastic_ClientNotification *p) { clientNotificationPool.release(p); }
/**
* Given a ToRadio buffer parse it and properly handle it (setup radio, owner or send packet into the mesh)
* Called by PhoneAPI.handleToRadio. Note: p is a scratch buffer, this function is allowed to write to it but it can not keep
* a reference
*/
void handleToRadio(meshtastic_MeshPacket &p);
/** The radioConfig object just changed, call this to force the hw to change to the new settings
* @return true if client devices should be sent a new set of radio configs
*/
void reloadConfig(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS);
/// The owner User record just got updated, update our node DB and broadcast the info into the mesh
void reloadOwner(bool shouldSave = true);
/// Called when the user wakes up our GUI, normally sends our latest location to the mesh (if we have it), otherwise at least
/// sends our nodeinfo
/// returns true if we sent a position
bool trySendPosition(NodeNum dest, bool wantReplies = false);
/// Send a packet into the mesh - note p must have been allocated from packetPool. We will return it to that pool after
/// sending. This is the ONLY function you should use for sending messages into the mesh, because it also updates the nodedb
/// cache
void sendToMesh(meshtastic_MeshPacket *p, RxSource src = RX_SRC_LOCAL, bool ccToPhone = false);
/** Attempt to cancel a previously sent packet from this _local_ node. Returns true if a packet was found we could cancel */
bool cancelSending(PacketId id);
/// Pull the latest power and time info into my nodeinfo
meshtastic_NodeInfoLite *refreshLocalMeshNode();
/// Send a packet to the phone
void sendToPhone(meshtastic_MeshPacket *p);
/// Send an MQTT message to the phone for client proxying
virtual void sendMqttMessageToClientProxy(meshtastic_MqttClientProxyMessage *m);
/// Send a ClientNotification to the phone
virtual void sendClientNotification(meshtastic_ClientNotification *cn);
/// Send an error response to the phone
void sendRoutingErrorResponse(meshtastic_Routing_Error error, const meshtastic_MeshPacket *mp);
bool isToPhoneQueueEmpty();
ErrorCode sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id);
uint32_t GetTimeSinceMeshPacket(const meshtastic_MeshPacket *mp);
private:
#if HAS_GPS
/// Called when our gps position has changed - updates nodedb and sends Location message out into the mesh
/// returns 0 to allow further processing
int onGPSChanged(const meshtastic::GPSStatus *arg);
#endif
/// Handle a packet that just arrived from the radio. This method does _not_ free the provided packet. If it
/// needs to keep the packet around it makes a copy
int handleFromRadio(const meshtastic_MeshPacket *p);
friend class RoutingModule;
};
extern MeshService *service;
@@ -0,0 +1,69 @@
#pragma once
// low level types
#include "MemoryPool.h"
#include "mesh/mesh-pb-constants.h"
#include <Arduino.h>
typedef uint32_t NodeNum;
typedef uint32_t PacketId; // A packet sequence number
#define NODENUM_BROADCAST UINT32_MAX
#define NODENUM_BROADCAST_NO_LORA \
1 // Reserved to only deliver packets over high speed (non-lora) transports, such as MQTT or BLE mesh (not yet implemented)
#define ERRNO_OK 0
#define ERRNO_NO_INTERFACES 33
#define ERRNO_UNKNOWN 32 // pick something that doesn't conflict with RH_ROUTER_ERROR_UNABLE_TO_DELIVER
#define ERRNO_DISABLED 34 // the interface is disabled
#define ERRNO_SHOULD_RELEASE 35 // no error, but the packet should still be released
#define ID_COUNTER_MASK (UINT32_MAX >> 22) // mask to select the counter portion of the ID
/*
* Source of a received message
*/
enum RxSource {
RX_SRC_LOCAL, // message was generated locally
RX_SRC_RADIO, // message was received from radio mesh
RX_SRC_USER // message was received from end-user device
};
/**
* the max number of hops a message can pass through, used as the default max for hop_limit in MeshPacket.
*
* We reserve 3 bits in the header so this could be up to 7, but given the high range of lora and typical usecases, keeping
* maxhops to 3 should be fine for a while. This also serves to prevent routing/flooding attempts to be attempted for
* too long.
**/
#define HOP_MAX 7
/// We normally just use max 3 hops for sending reliable messages
#define HOP_RELIABLE 3
// For old firmware or when falling back to flooding, there is no next-hop preference
#define NO_NEXT_HOP_PREFERENCE 0
// For old firmware there is no relay node set
#define NO_RELAY_NODE 0
typedef int ErrorCode;
/// Alloc and free packets to our global, ISR safe pool
extern Allocator<meshtastic_MeshPacket> &packetPool;
using UniquePacketPoolPacket = Allocator<meshtastic_MeshPacket>::UniqueAllocation;
/**
* Most (but not always) of the time we want to treat packets 'from' the local phone (where from == 0), as if they originated on
* the local node. If from is zero this function returns our node number instead
*/
NodeNum getFrom(const meshtastic_MeshPacket *p);
// Returns true if the packet originated from the local node
bool isFromUs(const meshtastic_MeshPacket *p);
// Returns true if the packet is destined to us
bool isToUs(const meshtastic_MeshPacket *p);
/* Some clients might not properly set priority, therefore we fix it here. */
void fixPriority(meshtastic_MeshPacket *p);
bool isBroadcast(uint32_t dest);
@@ -0,0 +1,339 @@
#include "NextHopRouter.h"
#include "MeshTypes.h"
#include "meshUtils.h"
#if !MESHTASTIC_EXCLUDE_TRACEROUTE
#include "modules/TraceRouteModule.h"
#endif
#include "NodeDB.h"
NextHopRouter::NextHopRouter() {}
PendingPacket::PendingPacket(meshtastic_MeshPacket *p, uint8_t numRetransmissions)
{
packet = p;
this->numRetransmissions = numRetransmissions - 1; // We subtract one, because we assume the user just did the first send
}
/**
* Send a packet
*/
ErrorCode NextHopRouter::send(meshtastic_MeshPacket *p)
{
// Add any messages _we_ send to the seen message list (so we will ignore all retransmissions we see)
p->relay_node = nodeDB->getLastByteOfNodeNum(getNodeNum()); // First set the relayer to us
wasSeenRecently(p); // FIXME, move this to a sniffSent method
p->next_hop = getNextHop(p->to, p->relay_node); // set the next hop
LOG_DEBUG("Setting next hop for packet with dest %x to %x", p->to, p->next_hop);
// If it's from us, ReliableRouter already handles retransmissions if want_ack is set. If a next hop is set and hop limit is
// not 0 or want_ack is set, start retransmissions
if ((!isFromUs(p) || !p->want_ack) && p->next_hop != NO_NEXT_HOP_PREFERENCE && (p->hop_limit > 0 || p->want_ack))
startRetransmission(packetPool.allocCopy(*p)); // start retransmission for relayed packet
return Router::send(p);
}
bool NextHopRouter::shouldFilterReceived(const meshtastic_MeshPacket *p)
{
bool wasFallback = false;
bool weWereNextHop = false;
bool wasUpgraded = false;
bool seenRecently = wasSeenRecently(p, true, &wasFallback, &weWereNextHop,
&wasUpgraded); // Updates history; returns false when an upgrade is detected
// Handle hop_limit upgrade scenario for rebroadcasters
if (wasUpgraded && perhapsHandleUpgradedPacket(p)) {
return true; // we handled it, so stop processing
}
if (seenRecently) {
printPacket("Ignore dupe incoming msg", p);
if (p->transport_mechanism == meshtastic_MeshPacket_TransportMechanism_TRANSPORT_LORA) {
rxDupe++;
stopRetransmission(p->from, p->id);
}
// If it was a fallback to flooding, try to relay again
if (wasFallback) {
LOG_INFO("Fallback to flooding from relay_node=0x%x", p->relay_node);
// Check if it's still in the Tx queue, if not, we have to relay it again
if (!findInTxQueue(p->from, p->id)) {
reprocessPacket(p);
perhapsRebroadcast(p);
}
} else {
bool isRepeated = p->hop_start > 0 && p->hop_start == p->hop_limit;
// If repeated and not in Tx queue anymore, try relaying again, or if we are the destination, send the ACK again
if (isRepeated) {
if (!findInTxQueue(p->from, p->id)) {
reprocessPacket(p);
if (!perhapsRebroadcast(p) && isToUs(p) && p->want_ack) {
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel, 0);
}
}
} else if (!weWereNextHop) {
perhapsCancelDupe(p); // If it's a dupe, cancel relay if we were not explicitly asked to relay
}
}
return true;
}
return Router::shouldFilterReceived(p);
}
void NextHopRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c)
{
NodeNum ourNodeNum = getNodeNum();
uint8_t ourRelayID = nodeDB->getLastByteOfNodeNum(ourNodeNum);
bool isAckorReply = (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) &&
(p->decoded.request_id != 0 || p->decoded.reply_id != 0);
if (isAckorReply) {
// Update next-hop for the original transmitter of this successful transmission to the relay node, but ONLY if "from"
// is not 0 (means implicit ACK) and original packet was also relayed by this node, or we sent it directly to the
// destination
if (p->from != 0) {
meshtastic_NodeInfoLite *origTx = nodeDB->getMeshNode(p->from);
if (origTx) {
// Either relayer of ACK was also a relayer of the packet, or we were the *only* relayer and the ACK came
// directly from the destination
bool wasAlreadyRelayer = wasRelayer(p->relay_node, p->decoded.request_id, p->to);
bool weWereSoleRelayer = false;
bool weWereRelayer = wasRelayer(ourRelayID, p->decoded.request_id, p->to, &weWereSoleRelayer);
if ((weWereRelayer && wasAlreadyRelayer) ||
(p->hop_start != 0 && p->hop_start == p->hop_limit && weWereSoleRelayer)) {
if (origTx->next_hop != p->relay_node) { // Not already set
LOG_INFO("Update next hop of 0x%x to 0x%x based on ACK/reply (was relayer %d we were sole %d)", p->from,
p->relay_node, wasAlreadyRelayer, weWereSoleRelayer);
origTx->next_hop = p->relay_node;
}
}
}
}
if (!isToUs(p)) {
Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM
// stop retransmission for the original packet
stopRetransmission(p->to, p->decoded.request_id); // for original packet, from = to and id = request_id
}
}
perhapsRebroadcast(p);
// handle the packet as normal
Router::sniffReceived(p, c);
}
/* Check if we should be rebroadcasting this packet if so, do so. */
bool NextHopRouter::perhapsRebroadcast(const meshtastic_MeshPacket *p)
{
if (!isToUs(p) && !isFromUs(p) && p->hop_limit > 0) {
if (p->id != 0) {
if (isRebroadcaster()) {
if (p->next_hop == NO_NEXT_HOP_PREFERENCE || p->next_hop == nodeDB->getLastByteOfNodeNum(getNodeNum())) {
meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p); // keep a copy because we will be sending it
LOG_INFO("Rebroadcast received message coming from %x", p->relay_node);
// Use shared logic to determine if hop_limit should be decremented
if (shouldDecrementHopLimit(p)) {
tosend->hop_limit--; // bump down the hop count
} else {
LOG_INFO("favorite-ROUTER/CLIENT_BASE-to-ROUTER/CLIENT_BASE rebroadcast: preserving hop_limit");
}
#if USERPREFS_EVENT_MODE
if (tosend->hop_limit > 2) {
// if we are "correcting" the hop_limit, "correct" the hop_start by the same amount to preserve hops away.
tosend->hop_start -= (tosend->hop_limit - 2);
tosend->hop_limit = 2;
}
#endif
if (p->next_hop == NO_NEXT_HOP_PREFERENCE) {
FloodingRouter::send(tosend);
} else {
NextHopRouter::send(tosend);
}
return true;
}
} else {
LOG_DEBUG("No rebroadcast: Role = CLIENT_MUTE or Rebroadcast Mode = NONE");
}
} else {
LOG_DEBUG("Ignore 0 id broadcast");
}
}
return false;
}
/**
* Get the next hop for a destination, given the relay node
* @return the node number of the next hop, 0 if no preference (fallback to FloodingRouter)
*/
uint8_t NextHopRouter::getNextHop(NodeNum to, uint8_t relay_node)
{
if (isBroadcast(to))
return NO_NEXT_HOP_PREFERENCE;
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(to);
if (node && node->next_hop) {
// We are careful not to return the relay node as the next hop
if (node->next_hop != relay_node) {
// LOG_DEBUG("Next hop for 0x%x is 0x%x", to, node->next_hop);
return node->next_hop;
} else
LOG_WARN("Next hop for 0x%x is 0x%x, same as relayer; set no pref", to, node->next_hop);
}
return NO_NEXT_HOP_PREFERENCE;
}
PendingPacket *NextHopRouter::findPendingPacket(GlobalPacketId key)
{
auto old = pending.find(key); // If we have an old record, someone messed up because id got reused
if (old != pending.end()) {
return &old->second;
} else
return NULL;
}
/**
* Stop any retransmissions we are doing of the specified node/packet ID pair
*/
bool NextHopRouter::stopRetransmission(NodeNum from, PacketId id)
{
auto key = GlobalPacketId(from, id);
return stopRetransmission(key);
}
bool NextHopRouter::roleAllowsCancelingFromTxQueue(const meshtastic_MeshPacket *p)
{
// Return true if we're allowed to cancel a packet in the txQueue (so we may never transmit it even once)
// Return false for roles like ROUTER, ROUTER_LATE which should always transmit the packet at least once.
return roleAllowsCancelingDupe(p); // same logic as FloodingRouter::roleAllowsCancelingDupe
}
bool NextHopRouter::stopRetransmission(GlobalPacketId key)
{
auto old = findPendingPacket(key);
if (old) {
auto p = old->packet;
/* Only when we already transmitted a packet via LoRa, we will cancel the packet in the Tx queue
to avoid canceling a transmission if it was ACKed super fast via MQTT */
if (old->numRetransmissions < NUM_RELIABLE_RETX - 1) {
// We only cancel it if we are the original sender or if we're not a router(_late)
if (isFromUs(p) || roleAllowsCancelingFromTxQueue(p)) {
// remove the 'original' (identified by originator and packet->id) from the txqueue and free it
cancelSending(getFrom(p), p->id);
}
}
// Regardless of whether or not we canceled this packet from the txQueue, remove it from our pending list so it
// doesn't get scheduled again. (This is the core of stopRetransmission.)
auto numErased = pending.erase(key);
assert(numErased == 1);
// When we remove an entry from pending, always be sure to release the copy of the packet that was allocated in the
// call to startRetransmission.
packetPool.release(p);
return true;
} else
return false;
}
/**
* Add p to the list of packets to retransmit occasionally. We will free it once we stop retransmitting.
*/
PendingPacket *NextHopRouter::startRetransmission(meshtastic_MeshPacket *p, uint8_t numReTx)
{
auto id = GlobalPacketId(p);
auto rec = PendingPacket(p, numReTx);
stopRetransmission(getFrom(p), p->id);
setNextTx(&rec);
pending[id] = rec;
return &pending[id];
}
/**
* Do any retransmissions that are scheduled (FIXME - for the time being called from loop)
*/
int32_t NextHopRouter::doRetransmissions()
{
uint32_t now = millis();
int32_t d = INT32_MAX;
// FIXME, we should use a better datastructure rather than walking through this map.
// for(auto el: pending) {
for (auto it = pending.begin(), nextIt = it; it != pending.end(); it = nextIt) {
++nextIt; // we use this odd pattern because we might be deleting it...
auto &p = it->second;
bool stillValid = true; // assume we'll keep this record around
// FIXME, handle 51 day rolloever here!!!
if (p.nextTxMsec <= now) {
if (p.numRetransmissions == 0) {
if (isFromUs(p.packet)) {
LOG_DEBUG("Reliable send failed, returning a nak for fr=0x%x,to=0x%x,id=0x%x", p.packet->from, p.packet->to,
p.packet->id);
sendAckNak(meshtastic_Routing_Error_MAX_RETRANSMIT, getFrom(p.packet), p.packet->id, p.packet->channel);
}
// Note: we don't stop retransmission here, instead the Nak packet gets processed in sniffReceived
stopRetransmission(it->first);
stillValid = false; // just deleted it
} else {
LOG_DEBUG("Sending retransmission fr=0x%x,to=0x%x,id=0x%x, tries left=%d", p.packet->from, p.packet->to,
p.packet->id, p.numRetransmissions);
if (!isBroadcast(p.packet->to)) {
if (p.numRetransmissions == 1) {
// Last retransmission, reset next_hop (fallback to FloodingRouter)
p.packet->next_hop = NO_NEXT_HOP_PREFERENCE;
// Also reset it in the nodeDB
meshtastic_NodeInfoLite *sentTo = nodeDB->getMeshNode(p.packet->to);
if (sentTo) {
LOG_INFO("Resetting next hop for packet with dest 0x%x\n", p.packet->to);
sentTo->next_hop = NO_NEXT_HOP_PREFERENCE;
}
FloodingRouter::send(packetPool.allocCopy(*p.packet));
} else {
NextHopRouter::send(packetPool.allocCopy(*p.packet));
}
} else {
// Note: we call the superclass version because we don't want to have our version of send() add a new
// retransmission record
FloodingRouter::send(packetPool.allocCopy(*p.packet));
}
// Queue again
--p.numRetransmissions;
setNextTx(&p);
}
}
if (stillValid) {
// Update our desired sleep delay
int32_t t = p.nextTxMsec - now;
d = min(t, d);
}
}
return d;
}
void NextHopRouter::setNextTx(PendingPacket *pending)
{
assert(iface);
auto d = iface->getRetransmissionMsec(pending->packet);
pending->nextTxMsec = millis() + d;
LOG_DEBUG("Setting next retransmission in %u msecs: ", d);
printPacket("", pending->packet);
setReceivedMessage(); // Run ASAP, so we can figure out our correct sleep time
}
@@ -0,0 +1,154 @@
#pragma once
#include "FloodingRouter.h"
#include <unordered_map>
/**
* An identifier for a globally unique message - a pair of the sending nodenum and the packet id assigned
* to that message
*/
struct GlobalPacketId {
NodeNum node;
PacketId id;
bool operator==(const GlobalPacketId &p) const { return node == p.node && id == p.id; }
explicit GlobalPacketId(const meshtastic_MeshPacket *p)
{
node = getFrom(p);
id = p->id;
}
GlobalPacketId(NodeNum _from, PacketId _id)
{
node = _from;
id = _id;
}
};
/**
* A packet queued for retransmission
*/
struct PendingPacket {
meshtastic_MeshPacket *packet;
/** The next time we should try to retransmit this packet */
uint32_t nextTxMsec = 0;
/** Starts at NUM_RETRANSMISSIONS -1 and counts down. Once zero it will be removed from the list */
uint8_t numRetransmissions = 0;
PendingPacket() {}
explicit PendingPacket(meshtastic_MeshPacket *p, uint8_t numRetransmissions);
};
class GlobalPacketIdHashFunction
{
public:
size_t operator()(const GlobalPacketId &p) const { return (std::hash<NodeNum>()(p.node)) ^ (std::hash<PacketId>()(p.id)); }
};
/*
Router for direct messages, which only relays if it is the next hop for a packet. The next hop is set by the current
relayer of a packet, which bases this on information from a previous successful delivery to the destination via flooding.
Namely, in the PacketHistory, we keep track of (up to 3) relayers of a packet. When the ACK is delivered back to us via a node
that also relayed the original packet, we use that node as next hop for the destination from then on. This makes sure that only
when theres a two-way connection, we assign a next hop. Both the ReliableRouter and NextHopRouter will do retransmissions (the
NextHopRouter only 1 time). For the final retry, if no one actually relayed the packet, it will reset the next hop in order to
fall back to the FloodingRouter again. Note that thus also intermediate hops will do a single retransmission if the intended
next-hop didnt relay, in order to fix changes in the middle of the route.
*/
class NextHopRouter : public FloodingRouter
{
public:
/**
* Constructor
*
*/
NextHopRouter();
/**
* Send a packet
* @return an error code
*/
virtual ErrorCode send(meshtastic_MeshPacket *p) override;
/** Do our retransmission handling */
virtual int32_t runOnce() override
{
// Note: We must doRetransmissions FIRST, because it might queue up work for the base class runOnce implementation
doRetransmissions();
int32_t r = FloodingRouter::runOnce();
// Also after calling runOnce there might be new packets to retransmit
auto d = doRetransmissions();
return min(d, r);
}
// The number of retransmissions intermediate nodes will do (actually 1 less than this)
constexpr static uint8_t NUM_INTERMEDIATE_RETX = 2;
// The number of retransmissions the original sender will do
constexpr static uint8_t NUM_RELIABLE_RETX = 3;
protected:
/**
* Pending retransmissions
*/
std::unordered_map<GlobalPacketId, PendingPacket, GlobalPacketIdHashFunction> pending;
/**
* Should this incoming filter be dropped?
*
* Called immediately on reception, before any further processing.
* @return true to abandon the packet
*/
virtual bool shouldFilterReceived(const meshtastic_MeshPacket *p) override;
/**
* Look for packets we need to relay
*/
virtual void sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c) override;
/**
* Try to find the pending packet record for this ID (or NULL if not found)
*/
PendingPacket *findPendingPacket(NodeNum from, PacketId id) { return findPendingPacket(GlobalPacketId(from, id)); }
PendingPacket *findPendingPacket(GlobalPacketId p);
/**
* Add p to the list of packets to retransmit occasionally. We will free it once we stop retransmitting.
*/
PendingPacket *startRetransmission(meshtastic_MeshPacket *p, uint8_t numReTx = NUM_INTERMEDIATE_RETX);
// Return true if we're allowed to cancel a packet in the txQueue (so we may never transmit it even once)
bool roleAllowsCancelingFromTxQueue(const meshtastic_MeshPacket *p);
/**
* Stop any retransmissions we are doing of the specified node/packet ID pair
*
* @return true if we found and removed a transmission with this ID
*/
bool stopRetransmission(NodeNum from, PacketId id);
bool stopRetransmission(GlobalPacketId p);
/**
* Do any retransmissions that are scheduled (FIXME - for the time being called from loop)
*
* @return the number of msecs until our next retransmission or MAXINT if none scheduled
*/
int32_t doRetransmissions();
void setNextTx(PendingPacket *pending);
private:
/**
* Get the next hop for a destination, given the relay node
* @return the node number of the next hop, 0 if no preference (fallback to FloodingRouter)
*/
uint8_t getNextHop(NodeNum to, uint8_t relay_node);
/** Check if we should be rebroadcasting this packet if so, do so.
* @return true if we did rebroadcast */
bool perhapsRebroadcast(const meshtastic_MeshPacket *p) override;
};
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,376 @@
#pragma once
#include "Observer.h"
#include <Arduino.h>
#include <algorithm>
#include <assert.h>
#include <pb_encode.h>
#include <string>
#include <vector>
#include "MeshTypes.h"
#include "NodeStatus.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
#include "mesh/generated/meshtastic/mesh.pb.h" // For CriticalErrorCode
#if ARCH_PORTDUINO
#include "PortduinoGlue.h"
#endif
#if !defined(MESHTASTIC_EXCLUDE_PKI)
// E3B0C442 is the blank hash
static const uint8_t LOW_ENTROPY_HASHES[][32] = {
{0xf4, 0x7e, 0xcc, 0x17, 0xe6, 0xb4, 0xa3, 0x22, 0xec, 0xee, 0xd9, 0x08, 0x4f, 0x39, 0x63, 0xea,
0x80, 0x75, 0xe1, 0x24, 0xce, 0x05, 0x36, 0x69, 0x63, 0xb2, 0xcb, 0xc0, 0x28, 0xd3, 0x34, 0x8b},
{0x5a, 0x9e, 0xa2, 0xa6, 0x8a, 0xa6, 0x66, 0xc1, 0x5f, 0x55, 0x00, 0x64, 0xa3, 0xa6, 0xfe, 0x71,
0xc0, 0xbb, 0x82, 0xc3, 0x32, 0x3d, 0x7a, 0x7a, 0xe3, 0x6e, 0xfd, 0xdd, 0xad, 0x3a, 0x66, 0xb9},
{0xb3, 0xdf, 0x3b, 0x2e, 0x67, 0xb6, 0xd5, 0xf8, 0xdf, 0x76, 0x2c, 0x45, 0x5e, 0x2e, 0xbd, 0x16,
0xc5, 0xf8, 0x67, 0xaa, 0x15, 0xf8, 0x92, 0x0b, 0xdf, 0x5a, 0x66, 0x50, 0xac, 0x0d, 0xbb, 0x2f},
{0x3b, 0x8f, 0x86, 0x3a, 0x38, 0x1f, 0x77, 0x39, 0xa9, 0x4e, 0xef, 0x91, 0x18, 0x5a, 0x62, 0xe1,
0xaa, 0x9d, 0x36, 0xea, 0xce, 0x60, 0x35, 0x8d, 0x9d, 0x1f, 0xf4, 0xb8, 0xc9, 0x13, 0x6a, 0x5d},
{0x36, 0x7e, 0x2d, 0xe1, 0x84, 0x5f, 0x42, 0x52, 0x29, 0x11, 0x0a, 0x25, 0x64, 0x54, 0x6a, 0x6b,
0xfd, 0xb6, 0x65, 0xff, 0x15, 0x1a, 0x51, 0x71, 0x22, 0x40, 0x57, 0xf6, 0x91, 0x9b, 0x64, 0x58},
{0x16, 0x77, 0xeb, 0xa4, 0x52, 0x91, 0xfb, 0x26, 0xcf, 0x8f, 0xd7, 0xd9, 0xd1, 0x5d, 0xc4, 0x68,
0x73, 0x75, 0xed, 0xc5, 0x95, 0x58, 0xee, 0x90, 0x56, 0xd4, 0x2f, 0x31, 0x29, 0xf7, 0x8c, 0x1f},
{0x31, 0x8c, 0xa9, 0x5e, 0xed, 0x3c, 0x12, 0xbf, 0x97, 0x9c, 0x47, 0x8e, 0x98, 0x9d, 0xc2, 0x3e,
0x86, 0x23, 0x90, 0x29, 0xc8, 0xb0, 0x20, 0xf8, 0xb1, 0xb0, 0xaa, 0x19, 0x2a, 0xcf, 0x0a, 0x54},
{0xa4, 0x8a, 0x99, 0x0e, 0x51, 0xdc, 0x12, 0x20, 0xf3, 0x13, 0xf5, 0x2b, 0x3a, 0xe2, 0x43, 0x42,
0xc6, 0x52, 0x98, 0xcd, 0xbb, 0xca, 0xb1, 0x31, 0xa0, 0xd4, 0xd6, 0x30, 0xf3, 0x27, 0xfb, 0x49},
{0xd2, 0x3f, 0x13, 0x8d, 0x22, 0x04, 0x8d, 0x07, 0x59, 0x58, 0xa0, 0xf9, 0x55, 0xcf, 0x30, 0xa0,
0x2e, 0x2f, 0xca, 0x80, 0x20, 0xe4, 0xde, 0xa1, 0xad, 0xd9, 0x58, 0xb3, 0x43, 0x2b, 0x22, 0x70},
{0x40, 0x41, 0xec, 0x6a, 0xd2, 0xd6, 0x03, 0xe4, 0x9a, 0x9e, 0xbd, 0x6c, 0x0a, 0x9b, 0x75, 0xa4,
0xbc, 0xab, 0x6f, 0xa7, 0x95, 0xff, 0x2d, 0xf6, 0xe9, 0xb9, 0xab, 0x4c, 0x0c, 0x1c, 0xd0, 0x3b},
{0x22, 0x49, 0x32, 0x2b, 0x00, 0xf9, 0x22, 0xfa, 0x17, 0x02, 0xe9, 0x64, 0x82, 0xf0, 0x4d, 0x1b,
0xc7, 0x04, 0xfc, 0xdc, 0x8c, 0x5e, 0xb6, 0xd9, 0x16, 0xd6, 0x37, 0xce, 0x59, 0xaa, 0x09, 0x49},
{0x48, 0x6f, 0x1e, 0x48, 0x97, 0x88, 0x64, 0xac, 0xe8, 0xeb, 0x30, 0xa3, 0xc3, 0xe1, 0xcf, 0x97,
0x39, 0xa6, 0x55, 0x5b, 0x5f, 0xbf, 0x18, 0xb7, 0x3a, 0xdf, 0xa8, 0x75, 0xe7, 0x9d, 0xe0, 0x1e},
{0x09, 0xb4, 0xe2, 0x6d, 0x28, 0x98, 0xc9, 0x47, 0x66, 0x46, 0xbf, 0xff, 0x58, 0x17, 0x91, 0xaa,
0xc3, 0xbf, 0x4a, 0x9d, 0x0b, 0x88, 0xb1, 0xf1, 0x03, 0xdd, 0x61, 0xd7, 0xba, 0x9e, 0x64, 0x98},
{0x39, 0x39, 0x84, 0xe0, 0x22, 0x2f, 0x7d, 0x78, 0x45, 0x18, 0x72, 0xb4, 0x13, 0xd2, 0x01, 0x2f,
0x3c, 0xa1, 0xb0, 0xfe, 0x39, 0xd0, 0xf1, 0x3c, 0x72, 0xd6, 0xef, 0x54, 0xd5, 0x77, 0x22, 0xa0},
{0x0a, 0xda, 0x5f, 0xec, 0xff, 0x5c, 0xc0, 0x2e, 0x5f, 0xc4, 0x8d, 0x03, 0xe5, 0x80, 0x59, 0xd3,
0x5d, 0x49, 0x86, 0xe9, 0x8d, 0xf6, 0xf6, 0x16, 0x35, 0x3d, 0xf9, 0x9b, 0x29, 0x55, 0x9e, 0x64},
{0x08, 0x56, 0xF0, 0xD7, 0xEF, 0x77, 0xD6, 0x11, 0x1C, 0x8F, 0x95, 0x2D, 0x3C, 0xDF, 0xB1, 0x22,
0xBF, 0x60, 0x9B, 0xE5, 0xA9, 0xC0, 0x6E, 0x4B, 0x01, 0xDC, 0xD1, 0x57, 0x44, 0xB2, 0xA5, 0xCF},
{0x2C, 0xB2, 0x77, 0x85, 0xD6, 0xB7, 0x48, 0x9C, 0xFE, 0xBC, 0x80, 0x26, 0x60, 0xF4, 0x6D, 0xCE,
0x11, 0x31, 0xA2, 0x1E, 0x33, 0x0A, 0x6D, 0x2B, 0x00, 0xFA, 0x0C, 0x90, 0x95, 0x8F, 0x5C, 0x6B},
{0xFA, 0x59, 0xC8, 0x6E, 0x94, 0xEE, 0x75, 0xC9, 0x9A, 0xB0, 0xFE, 0x89, 0x36, 0x40, 0xC9, 0x99,
0x4A, 0x3B, 0xF4, 0xAA, 0x12, 0x24, 0xA2, 0x0F, 0xF9, 0xD1, 0x08, 0xCB, 0x78, 0x19, 0xAA, 0xE5},
{0x6E, 0x42, 0x7A, 0x4A, 0x8C, 0x61, 0x62, 0x22, 0xA1, 0x89, 0xD3, 0xA4, 0xC2, 0x19, 0xA3, 0x83,
0x53, 0xA7, 0x7A, 0x0A, 0x89, 0xE2, 0x54, 0x52, 0x62, 0x3D, 0xE7, 0xCA, 0x8C, 0xF6, 0x6A, 0x60},
{0x20, 0x27, 0x2F, 0xBA, 0x0C, 0x99, 0xD7, 0x29, 0xF3, 0x11, 0x35, 0x89, 0x9D, 0x0E, 0x24, 0xA1,
0xC3, 0xCB, 0xDF, 0x8A, 0xF1, 0xC6, 0xFE, 0xD0, 0xD7, 0x9F, 0x92, 0xD6, 0x8F, 0x59, 0xBF, 0xE4},
{0x91, 0x70, 0xb4, 0x7c, 0xfb, 0xff, 0xa0, 0x59, 0x6a, 0x25, 0x1c, 0xa9, 0x9e, 0xe9, 0x43, 0x81,
0x5d, 0x74, 0xb1, 0xb1, 0x09, 0x28, 0x00, 0x4a, 0xaf, 0xe3, 0xfc, 0xa9, 0x4e, 0x27, 0x76, 0x4c},
{0x85, 0xfe, 0x7c, 0xec, 0xb6, 0x78, 0x74, 0xc3, 0xec, 0xe1, 0x32, 0x7f, 0xb0, 0xb7, 0x02, 0x74,
0xf9, 0x23, 0xd8, 0xe7, 0xfa, 0x14, 0xe6, 0xee, 0x66, 0x44, 0xb1, 0x8c, 0xa5, 0x2f, 0x7e, 0xd2},
{0x8e, 0x66, 0x65, 0x7b, 0x3b, 0x6f, 0x7e, 0xcc, 0x57, 0xb4, 0x57, 0xea, 0xcc, 0x83, 0xf5, 0xaa,
0xf7, 0x65, 0xa3, 0xce, 0x93, 0x72, 0x13, 0xc1, 0xb6, 0x46, 0x7b, 0x29, 0x45, 0xb5, 0xc8, 0x93},
{0xcc, 0x11, 0xfb, 0x1a, 0xab, 0xa1, 0x31, 0x87, 0x6a, 0xc6, 0xde, 0x88, 0x87, 0xa9, 0xb9, 0x59,
0x37, 0x82, 0x8d, 0xb2, 0xcc, 0xd8, 0x97, 0x40, 0x9a, 0x5c, 0x8f, 0x40, 0x55, 0xcb, 0x4c, 0x3e}};
static const char LOW_ENTROPY_WARNING[] = "Compromised keys were detected and regenerated.";
#endif
/*
DeviceState versions used to be defined in the .proto file but really only this function cares. So changed to a
#define here.
*/
#define SEGMENT_CONFIG 1
#define SEGMENT_MODULECONFIG 2
#define SEGMENT_DEVICESTATE 4
#define SEGMENT_CHANNELS 8
#define SEGMENT_NODEDATABASE 16
#define DEVICESTATE_CUR_VER 24
#define DEVICESTATE_MIN_VER 24
extern meshtastic_DeviceState devicestate;
extern meshtastic_NodeDatabase nodeDatabase;
extern meshtastic_ChannelFile channelFile;
extern meshtastic_MyNodeInfo &myNodeInfo;
extern meshtastic_LocalConfig config;
extern meshtastic_DeviceUIConfig uiconfig;
extern meshtastic_LocalModuleConfig moduleConfig;
extern meshtastic_User &owner;
extern meshtastic_Position localPosition;
static constexpr const char *deviceStateFileName = "/prefs/device.proto";
static constexpr const char *legacyPrefFileName = "/prefs/db.proto";
static constexpr const char *nodeDatabaseFileName = "/prefs/nodes.proto";
static constexpr const char *configFileName = "/prefs/config.proto";
static constexpr const char *uiconfigFileName = "/prefs/uiconfig.proto";
static constexpr const char *moduleConfigFileName = "/prefs/module.proto";
static constexpr const char *channelFileName = "/prefs/channels.proto";
static constexpr const char *backupFileName = "/backups/backup.proto";
/// Given a node, return how many seconds in the past (vs now) that we last heard from it
uint32_t sinceLastSeen(const meshtastic_NodeInfoLite *n);
/// Given a packet, return how many seconds in the past (vs now) it was received
uint32_t sinceReceived(const meshtastic_MeshPacket *p);
enum LoadFileResult {
// Successfully opened the file
LOAD_SUCCESS = 1,
// File does not exist
NOT_FOUND = 2,
// Device does not have a filesystem
NO_FILESYSTEM = 3,
// File exists, but could not decode protobufs
DECODE_FAILED = 4,
// File exists, but open failed for some reason
OTHER_FAILURE = 5
};
enum UserLicenseStatus { NotKnown, NotLicensed, Licensed };
class NodeDB
{
// NodeNum provisionalNodeNum; // if we are trying to find a node num this is our current attempt
// A NodeInfo for every node we've seen
// Eventually use a smarter datastructure
// HashMap<NodeNum, NodeInfo> nodes;
// Note: these two references just point into our static array we serialize to/from disk
public:
std::vector<meshtastic_NodeInfoLite> *meshNodes;
bool updateGUI = false; // we think the gui should definitely be redrawn, screen will clear this once handled
meshtastic_NodeInfoLite *updateGUIforNode = NULL; // if currently showing this node, we think you should update the GUI
Observable<const meshtastic::NodeStatus *> newStatus;
pb_size_t numMeshNodes;
bool keyIsLowEntropy = false;
bool hasWarned = false;
/// don't do mesh based algorithm for node id assignment (initially)
/// instead just store in flash - possibly even in the initial alpha release do this hack
NodeDB();
/// write to flash
/// @return true if the save was successful
bool saveToDisk(int saveWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS |
SEGMENT_NODEDATABASE);
/** Reinit radio config if needed, because either:
* a) sometimes a buggy android app might send us bogus settings or
* b) the client set factory_reset
*
* @param factory_reset if true, reset all settings to factory defaults
* @param is_fresh_install set to true after a fresh install, to trigger NodeInfo/Position requests
* @return true if the config was completely reset, in that case, we should send it back to the client
*/
void resetRadioConfig(bool is_fresh_install = false);
/// given a subpacket sniffed from the network, update our DB state
/// we updateGUI and updateGUIforNode if we think our this change is big enough for a redraw
void updateFrom(const meshtastic_MeshPacket &p);
void addFromContact(const meshtastic_SharedContact);
/** Update position info for this node based on received position data
*/
void updatePosition(uint32_t nodeId, const meshtastic_Position &p, RxSource src = RX_SRC_RADIO);
/** Update telemetry info for this node based on received metrics
*/
void updateTelemetry(uint32_t nodeId, const meshtastic_Telemetry &t, RxSource src = RX_SRC_RADIO);
/** Update user info and channel for this node based on received user data
*/
bool updateUser(uint32_t nodeId, meshtastic_User &p, uint8_t channelIndex = 0);
/*
* Sets a node either favorite or unfavorite
*/
void set_favorite(bool is_favorite, uint32_t nodeId);
/*
* Returns true if the node is in the NodeDB and marked as favorite
*/
bool isFavorite(uint32_t nodeId);
/*
* Returns true if p->from or p->to is a favorited node
*/
bool isFromOrToFavoritedNode(const meshtastic_MeshPacket &p);
/**
* Other functions like the node picker can request a pause in the node sorting
*/
void pause_sort(bool paused);
/// @return our node number
NodeNum getNodeNum() { return myNodeInfo.my_node_num; }
/// @return our node ID as a string in the format "!xxxxxxxx"
std::string getNodeId() const;
// @return last byte of a NodeNum, 0xFF if it ended at 0x00
uint8_t getLastByteOfNodeNum(NodeNum num) { return (uint8_t)((num & 0xFF) ? (num & 0xFF) : 0xFF); }
/// if returns false, that means our node should send a DenyNodeNum response. If true, we think the number is okay for use
// bool handleWantNodeNum(NodeNum n);
/* void handleDenyNodeNum(NodeNum FIXME read mesh proto docs, perhaps picking a random node num is not a great idea
and instead we should use a special 'im unconfigured node number' and include our desired node number in the wantnum message.
the unconfigured node num would only be used while initially joining the mesh so low odds of conflicting (especially if we
randomly select from a small number of nodenums which can be used temporarily for this operation). figure out what the lower
level mesh sw does if it does conflict? would it be better for people who are replying with denynode num to just broadcast
their denial?)
*/
// get channel channel index we heard a nodeNum on, defaults to 0 if not found
uint8_t getMeshNodeChannel(NodeNum n);
/* Return the number of nodes we've heard from recently (within the last 2 hrs?)
* @param localOnly if true, ignore nodes heard via MQTT
*/
size_t getNumOnlineMeshNodes(bool localOnly = false);
void initConfigIntervals(), initModuleConfigIntervals(), resetNodes(bool keepFavorites = false),
removeNodeByNum(NodeNum nodeNum);
bool factoryReset(bool eraseBleBonds = false);
LoadFileResult loadProto(const char *filename, size_t protoSize, size_t objSize, const pb_msgdesc_t *fields,
void *dest_struct);
bool saveProto(const char *filename, size_t protoSize, const pb_msgdesc_t *fields, const void *dest_struct,
bool fullAtomic = true);
void installRoleDefaults(meshtastic_Config_DeviceConfig_Role role);
const meshtastic_NodeInfoLite *readNextMeshNode(uint32_t &readIndex);
meshtastic_NodeInfoLite *getMeshNodeByIndex(size_t x)
{
assert(x < numMeshNodes);
return &meshNodes->at(x);
}
virtual meshtastic_NodeInfoLite *getMeshNode(NodeNum n);
size_t getNumMeshNodes() { return numMeshNodes; }
UserLicenseStatus getLicenseStatus(uint32_t nodeNum);
size_t getMaxNodesAllocatedSize()
{
meshtastic_NodeDatabase emptyNodeDatabase;
emptyNodeDatabase.version = DEVICESTATE_CUR_VER;
size_t nodeDatabaseSize;
pb_get_encoded_size(&nodeDatabaseSize, meshtastic_NodeDatabase_fields, &emptyNodeDatabase);
return nodeDatabaseSize + (MAX_NUM_NODES * meshtastic_NodeInfoLite_size);
}
// returns true if the maximum number of nodes is reached or we are running low on memory
bool isFull();
void clearLocalPosition();
void setLocalPosition(meshtastic_Position position, bool timeOnly = false)
{
if (timeOnly) {
LOG_DEBUG("Set local position time only: time=%u timestamp=%u", position.time, position.timestamp);
localPosition.time = position.time;
localPosition.timestamp = position.timestamp > 0 ? position.timestamp : position.time;
return;
}
LOG_DEBUG("Set local position: lat=%i lon=%i time=%u timestamp=%u", position.latitude_i, position.longitude_i,
position.time, position.timestamp);
localPosition = position;
}
bool hasValidPosition(const meshtastic_NodeInfoLite *n);
bool checkLowEntropyPublicKey(const meshtastic_Config_SecurityConfig_public_key_t &keyToTest);
bool backupPreferences(meshtastic_AdminMessage_BackupLocation location);
bool restorePreferences(meshtastic_AdminMessage_BackupLocation location,
int restoreWhat = SEGMENT_CONFIG | SEGMENT_MODULECONFIG | SEGMENT_DEVICESTATE | SEGMENT_CHANNELS);
/// Notify observers of changes to the DB
void notifyObservers(bool forceUpdate = false)
{
// Notify observers of the current node state
const meshtastic::NodeStatus status = meshtastic::NodeStatus(getNumOnlineMeshNodes(), getNumMeshNodes(), forceUpdate);
newStatus.notifyObservers(&status);
}
private:
bool duplicateWarned = false;
uint32_t lastNodeDbSave = 0; // when we last saved our db to flash
uint32_t lastBackupAttempt = 0; // when we last tried a backup automatically or manually
uint32_t lastSort = 0; // When last sorted the nodeDB
/// Find a node in our DB, create an empty NodeInfoLite if missing
meshtastic_NodeInfoLite *getOrCreateMeshNode(NodeNum n);
/*
* Internal boolean to track sorting paused
*/
bool sortingIsPaused = false;
/// pick a provisional nodenum we hope no one is using
void pickNewNodeNum();
/// read our db from flash
void loadFromDisk();
/// purge db entries without user info
void cleanupMeshDB();
/// Reinit device state from scratch (not loading from disk)
void installDefaultDeviceState(), installDefaultNodeDatabase(), installDefaultChannels(),
installDefaultConfig(bool preserveKey), installDefaultModuleConfig();
/// write to flash
/// @return true if the save was successful
bool saveToDiskNoRetry(int saveWhat);
bool saveChannelsToDisk();
bool saveDeviceStateToDisk();
bool saveNodeDatabaseToDisk();
void sortMeshDB();
};
extern NodeDB *nodeDB;
/*
If is_router is set, we use a number of different default values
# FIXME - after tuning, move these params into the on-device defaults based on is_router and is_power_saving
# prefs.position_broadcast_secs = FIXME possibly broadcast only once an hr
prefs.wait_bluetooth_secs = 1 # Don't stay in bluetooth mode
# try to stay in light sleep one full day, then briefly wake and sleep again
prefs.ls_secs = oneday
prefs.position_broadcast_secs = 12 hours # send either position or owner every 12hrs
# get a new GPS position once per day
prefs.gps_update_interval = oneday
prefs.is_power_saving = True
*/
/** The current change # for radio settings. Starts at 0 on boot and any time the radio settings
* might have changed is incremented. Allows others to detect they might now be on a new channel.
*/
extern uint32_t radioGeneration;
extern meshtastic_CriticalErrorCode error_code;
/*
* A numeric error address (nonzero if available)
*/
extern uint32_t error_address;
#define NODEINFO_BITFIELD_IS_KEY_MANUALLY_VERIFIED_SHIFT 0
#define NODEINFO_BITFIELD_IS_KEY_MANUALLY_VERIFIED_MASK (1 << NODEINFO_BITFIELD_IS_KEY_MANUALLY_VERIFIED_SHIFT)
#define Module_Config_size \
(ModuleConfig_CannedMessageConfig_size + ModuleConfig_ExternalNotificationConfig_size + ModuleConfig_MQTTConfig_size + \
ModuleConfig_RangeTestConfig_size + ModuleConfig_SerialConfig_size + ModuleConfig_StoreForwardConfig_size + \
ModuleConfig_TelemetryConfig_size + ModuleConfig_size)
// Please do not remove this comment, it makes trunk and compiler happy at the same time.
@@ -0,0 +1,253 @@
#include "PacketCache.h"
#include "Router.h"
PacketCache packetCache{};
/**
* Allocate a new cache entry and copy the packet header and payload into it
*/
PacketCacheEntry *PacketCache::cache(const meshtastic_MeshPacket *p, bool preserveMetadata)
{
size_t payload_size =
(p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag) ? p->encrypted.size : p->decoded.payload.size;
PacketCacheEntry *e = (PacketCacheEntry *)malloc(sizeof(PacketCacheEntry) + payload_size +
(preserveMetadata ? sizeof(PacketCacheMetadata) : 0));
if (!e) {
LOG_ERROR("Unable to allocate memory for packet cache entry");
return NULL;
}
*e = {};
e->header.from = p->from;
e->header.to = p->to;
e->header.id = p->id;
e->header.channel = p->channel;
e->header.next_hop = p->next_hop;
e->header.relay_node = p->relay_node;
e->header.flags = (p->hop_limit & PACKET_FLAGS_HOP_LIMIT_MASK) | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) |
(p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0) |
((p->hop_start << PACKET_FLAGS_HOP_START_SHIFT) & PACKET_FLAGS_HOP_START_MASK);
PacketCacheMetadata m{};
if (preserveMetadata) {
e->has_metadata = true;
m.rx_rssi = (uint8_t)(p->rx_rssi + 200);
m.rx_snr = (uint8_t)((p->rx_snr + 30.0f) / 0.25f);
m.rx_time = p->rx_time;
m.transport_mechanism = p->transport_mechanism;
m.priority = p->priority;
}
if (p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag) {
e->encrypted = true;
e->payload_len = p->encrypted.size;
memcpy(((unsigned char *)e) + sizeof(PacketCacheEntry), p->encrypted.bytes, p->encrypted.size);
} else if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
e->encrypted = false;
if (preserveMetadata) {
m.portnum = p->decoded.portnum;
m.want_response = p->decoded.want_response;
m.emoji = p->decoded.emoji;
m.bitfield = p->decoded.bitfield;
if (p->decoded.reply_id)
m.reply_id = p->decoded.reply_id;
else if (p->decoded.request_id)
m.request_id = p->decoded.request_id;
}
e->payload_len = p->decoded.payload.size;
memcpy(((unsigned char *)e) + sizeof(PacketCacheEntry), p->decoded.payload.bytes, p->decoded.payload.size);
} else {
LOG_ERROR("Unable to cache packet with unknown payload type %d", p->which_payload_variant);
free(e);
return NULL;
}
if (preserveMetadata)
memcpy(((unsigned char *)e) + sizeof(PacketCacheEntry) + e->payload_len, &m, sizeof(m));
size += sizeof(PacketCacheEntry) + e->payload_len + (e->has_metadata ? sizeof(PacketCacheMetadata) : 0);
insert(e);
return e;
};
/**
* Dump a list of packets into the provided buffer
*/
void PacketCache::dump(void *dest, const PacketCacheEntry **entries, size_t num_entries)
{
unsigned char *pos = (unsigned char *)dest;
for (size_t i = 0; i < num_entries; i++) {
size_t entry_len =
sizeof(PacketCacheEntry) + entries[i]->payload_len + (entries[i]->has_metadata ? sizeof(PacketCacheMetadata) : 0);
memcpy(pos, entries[i], entry_len);
pos += entry_len;
}
}
/**
* Calculate the length of buffer needed to dump the specified entries
*/
size_t PacketCache::dumpSize(const PacketCacheEntry **entries, size_t num_entries)
{
size_t total_size = 0;
for (size_t i = 0; i < num_entries; i++) {
total_size += sizeof(PacketCacheEntry) + entries[i]->payload_len;
if (entries[i]->has_metadata)
total_size += sizeof(PacketCacheMetadata);
}
return total_size;
}
/**
* Find a packet in the cache
*/
PacketCacheEntry *PacketCache::find(NodeNum from, PacketId id)
{
uint16_t h = PACKET_HASH(from, id);
PacketCacheEntry *e = buckets[PACKET_CACHE_BUCKET(h)];
while (e) {
if (e->header.from == from && e->header.id == id)
return e;
e = e->next;
}
return NULL;
}
/**
* Find a packet in the cache by its hash
*/
PacketCacheEntry *PacketCache::find(PacketHash h)
{
PacketCacheEntry *e = buckets[PACKET_CACHE_BUCKET(h)];
while (e) {
if (PACKET_HASH(e->header.from, e->header.id) == h)
return e;
e = e->next;
}
return NULL;
}
/**
* Load a list of packets from the provided buffer
*/
bool PacketCache::load(void *src, PacketCacheEntry **entries, size_t num_entries)
{
memset(entries, 0, sizeof(PacketCacheEntry *) * num_entries);
unsigned char *pos = (unsigned char *)src;
for (size_t i = 0; i < num_entries; i++) {
PacketCacheEntry e{};
memcpy(&e, pos, sizeof(PacketCacheEntry));
size_t entry_len = sizeof(PacketCacheEntry) + e.payload_len + (e.has_metadata ? sizeof(PacketCacheMetadata) : 0);
entries[i] = (PacketCacheEntry *)malloc(entry_len);
size += entry_len;
if (!entries[i]) {
LOG_ERROR("Unable to allocate memory for packet cache entry");
for (size_t j = 0; j < i; j++) {
size -= sizeof(PacketCacheEntry) + entries[j]->payload_len +
(entries[j]->has_metadata ? sizeof(PacketCacheMetadata) : 0);
free(entries[j]);
entries[j] = NULL;
}
return false;
}
memcpy(entries[i], pos, entry_len);
pos += entry_len;
}
for (size_t i = 0; i < num_entries; i++)
insert(entries[i]);
return true;
}
/**
* Copy the cached packet into the provided MeshPacket structure
*/
void PacketCache::rehydrate(const PacketCacheEntry *e, meshtastic_MeshPacket *p)
{
if (!e || !p)
return;
*p = {};
p->from = e->header.from;
p->to = e->header.to;
p->id = e->header.id;
p->channel = e->header.channel;
p->next_hop = e->header.next_hop;
p->relay_node = e->header.relay_node;
p->hop_limit = e->header.flags & PACKET_FLAGS_HOP_LIMIT_MASK;
p->want_ack = !!(e->header.flags & PACKET_FLAGS_WANT_ACK_MASK);
p->via_mqtt = !!(e->header.flags & PACKET_FLAGS_VIA_MQTT_MASK);
p->hop_start = (e->header.flags & PACKET_FLAGS_HOP_START_MASK) >> PACKET_FLAGS_HOP_START_SHIFT;
p->which_payload_variant = e->encrypted ? meshtastic_MeshPacket_encrypted_tag : meshtastic_MeshPacket_decoded_tag;
unsigned char *payload = ((unsigned char *)e) + sizeof(PacketCacheEntry);
PacketCacheMetadata m{};
if (e->has_metadata) {
memcpy(&m, (payload + e->payload_len), sizeof(m));
p->rx_rssi = ((int)m.rx_rssi) - 200;
p->rx_snr = ((float)m.rx_snr * 0.25f) - 30.0f;
p->rx_time = m.rx_time;
p->transport_mechanism = (meshtastic_MeshPacket_TransportMechanism)m.transport_mechanism;
p->priority = (meshtastic_MeshPacket_Priority)m.priority;
}
if (e->encrypted) {
memcpy(p->encrypted.bytes, payload, e->payload_len);
p->encrypted.size = e->payload_len;
} else {
memcpy(p->decoded.payload.bytes, payload, e->payload_len);
p->decoded.payload.size = e->payload_len;
if (e->has_metadata) {
// Decrypted-only metadata
p->decoded.portnum = (meshtastic_PortNum)m.portnum;
p->decoded.want_response = m.want_response;
p->decoded.emoji = m.emoji;
p->decoded.bitfield = m.bitfield;
if (m.reply_id)
p->decoded.reply_id = m.reply_id;
else if (m.request_id)
p->decoded.request_id = m.request_id;
}
}
}
/**
* Release a cache entry
*/
void PacketCache::release(PacketCacheEntry *e)
{
if (!e)
return;
remove(e);
size -= sizeof(PacketCacheEntry) + e->payload_len + (e->has_metadata ? sizeof(PacketCacheMetadata) : 0);
free(e);
}
/**
* Insert a new entry into the hash table
*/
void PacketCache::insert(PacketCacheEntry *e)
{
assert(e);
PacketHash h = PACKET_HASH(e->header.from, e->header.id);
PacketCacheEntry **target = &buckets[PACKET_CACHE_BUCKET(h)];
e->next = *target;
*target = e;
num_entries++;
}
/**
* Remove an entry from the hash table
*/
void PacketCache::remove(PacketCacheEntry *e)
{
assert(e);
PacketHash h = PACKET_HASH(e->header.from, e->header.id);
PacketCacheEntry **target = &buckets[PACKET_CACHE_BUCKET(h)];
while (*target) {
if (*target == e) {
*target = e->next;
e->next = NULL;
num_entries--;
break;
} else {
target = &(*target)->next;
}
}
}
@@ -0,0 +1,75 @@
#pragma once
#include "RadioInterface.h"
#define PACKET_HASH(a, b) ((((a ^ b) >> 16) ^ (a ^ b)) & 0xFFFF) // 16 bit fold of packet (from, id) tuple
typedef uint16_t PacketHash;
#define PACKET_CACHE_BUCKETS 64 // Number of hash table buckets
#define PACKET_CACHE_BUCKET(h) (((h >> 12) ^ (h >> 6) ^ h) & 0x3F) // Fold hash down to 6-bit bucket index
typedef struct PacketCacheEntry {
PacketCacheEntry *next;
PacketHeader header;
uint16_t payload_len = 0;
union {
uint16_t bitfield;
struct {
uint8_t encrypted : 1; // Payload is encrypted
uint8_t has_metadata : 1; // Payload includes PacketCacheMetadata
uint8_t : 6; // Reserved for future use
uint8_t : 8; // Reserved for future use
};
};
} PacketCacheEntry;
typedef struct PacketCacheMetadata {
PacketCacheMetadata() : _bitfield(0), reply_id(0), _bitfield2(0) {}
union {
uint32_t _bitfield;
struct {
uint16_t portnum : 9; // meshtastic_MeshPacket::decoded::portnum
uint16_t want_response : 1; // meshtastic_MeshPacket::decoded::want_response
uint16_t emoji : 1; // meshtastic_MeshPacket::decoded::emoji
uint16_t bitfield : 5; // meshtastic_MeshPacket::decoded::bitfield (truncated)
uint8_t rx_rssi : 8; // meshtastic_MeshPacket::rx_rssi (map via actual RSSI + 200)
uint8_t rx_snr : 8; // meshtastic_MeshPacket::rx_snr (map via (p->rx_snr + 30.0f) / 0.25f)
};
};
union {
uint32_t reply_id; // meshtastic_MeshPacket::decoded.reply_id
uint32_t request_id; // meshtastic_MeshPacket::decoded.request_id
};
uint32_t rx_time = 0; // meshtastic_MeshPacket::rx_time
uint8_t transport_mechanism = 0; // meshtastic_MeshPacket::transport_mechanism
struct {
uint8_t _bitfield2;
union {
uint8_t priority : 7; // meshtastic_MeshPacket::priority
uint8_t reserved : 1; // Reserved for future use
};
};
} PacketCacheMetadata;
class PacketCache
{
public:
PacketCacheEntry *cache(const meshtastic_MeshPacket *p, bool preserveMetadata);
static void dump(void *dest, const PacketCacheEntry **entries, size_t num_entries);
size_t dumpSize(const PacketCacheEntry **entries, size_t num_entries);
PacketCacheEntry *find(NodeNum from, PacketId id);
PacketCacheEntry *find(PacketHash h);
bool load(void *src, PacketCacheEntry **entries, size_t num_entries);
size_t getNumEntries() { return num_entries; }
size_t getSize() { return size; }
void rehydrate(const PacketCacheEntry *e, meshtastic_MeshPacket *p);
void release(PacketCacheEntry *e);
private:
PacketCacheEntry *buckets[PACKET_CACHE_BUCKETS]{};
size_t num_entries = 0;
size_t size = 0;
void insert(PacketCacheEntry *e);
void remove(PacketCacheEntry *e);
};
extern PacketCache packetCache;
@@ -0,0 +1,460 @@
#include "PacketHistory.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
#ifdef ARCH_PORTDUINO
#include "platform/portduino/PortduinoGlue.h"
#endif
#include "Throttle.h"
#define PACKETHISTORY_MAX \
max((u_int32_t)(MAX_NUM_NODES * 2.0), \
(u_int32_t)100) // x2..3 Should suffice. Empirical setup. 16B per record malloc'ed, but no less than 100
#define RECENT_WARN_AGE (10 * 60 * 1000L) // Warn if the packet that gets removed was more recent than 10 min
#define VERBOSE_PACKET_HISTORY 0 // Set to 1 for verbose logging, 2 for heavy debugging
#define PACKET_HISTORY_TRACE_AGING 1 // Set to 1 to enable logging of the age of re/used history slots
PacketHistory::PacketHistory(uint32_t size) : recentPacketsCapacity(0), recentPackets(NULL) // Initialize members
{
if (size < 4 || size > PACKETHISTORY_MAX) { // Copilot suggested - makes sense
LOG_WARN("Packet History - Invalid size %d, using default %d", size, PACKETHISTORY_MAX);
size = PACKETHISTORY_MAX; // Use default size if invalid
}
// Allocate memory for the recent packets array
recentPacketsCapacity = size;
recentPackets = new PacketRecord[recentPacketsCapacity];
if (!recentPackets) { // No logging here, console/log probably uninitialized yet.
LOG_ERROR("Packet History - Memory allocation failed for size=%d entries / %d Bytes", size,
sizeof(PacketRecord) * recentPacketsCapacity);
recentPacketsCapacity = 0; // mark allocation fail
return; // return early
}
// Initialize the recent packets array to zero
memset(recentPackets, 0, sizeof(PacketRecord) * recentPacketsCapacity);
}
PacketHistory::~PacketHistory()
{
recentPacketsCapacity = 0;
delete[] recentPackets;
recentPackets = NULL;
}
/** Update recentPackets and return true if we have already seen this packet */
bool PacketHistory::wasSeenRecently(const meshtastic_MeshPacket *p, bool withUpdate, bool *wasFallback, bool *weWereNextHop,
bool *wasUpgraded)
{
if (!initOk()) {
LOG_ERROR("Packet History - Was Seen Recently: NOT INITIALIZED!");
return false;
}
if (p->id == 0) {
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - Was Seen Recently: ID is 0, not a floodable message");
#endif
return false; // Not a floodable message ID, so we don't care
}
PacketRecord r;
memset(&r, 0, sizeof(PacketRecord)); // Initialize the record to zero
// Save basic info from checked packet
r.id = p->id;
r.sender = getFrom(p); // If 0 then use our ID
r.next_hop = p->next_hop;
setHighestHopLimit(r, p->hop_limit);
bool weWillRelay = false;
uint8_t ourRelayID = nodeDB->getLastByteOfNodeNum(nodeDB->getNodeNum());
if (p->relay_node == ourRelayID) { // If the relay_node is us, store it
weWillRelay = true;
setOurTxHopLimit(r, p->hop_limit);
r.relayed_by[0] = p->relay_node;
}
r.rxTimeMsec = millis(); //
if (r.rxTimeMsec == 0) // =0 every 49.7 days? 0 is special
r.rxTimeMsec = 1;
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - Was Seen Recently: @start s=%08x id=%08x / to=%08x nh=%02x rn=%02x / wUpd=%s / wasFb?%d wWNH?%d",
r.sender, r.id, p->to, p->next_hop, p->relay_node, withUpdate ? "YES" : "NO", wasFallback ? *wasFallback : -1,
weWereNextHop ? *weWereNextHop : -1);
#endif
PacketRecord *found = find(r.sender, r.id); // Find the packet record in the recentPackets array
bool seenRecently = (found != NULL); // If found -> the packet was seen recently
// Check for hop_limit upgrade scenario
if (seenRecently && wasUpgraded && found->hop_limit < p->hop_limit) {
LOG_DEBUG("Packet History - Hop limit upgrade: packet 0x%08x from hop_limit=%d to hop_limit=%d", p->id, found->hop_limit,
p->hop_limit);
*wasUpgraded = true;
} else if (wasUpgraded) {
*wasUpgraded = false; // Initialize to false if not an upgrade
}
if (seenRecently) {
if (wasFallback) {
// If it was seen with a next-hop not set to us and now it's NO_NEXT_HOP_PREFERENCE, and the relayer relayed already
// before, it's a fallback to flooding. If we didn't already relay and the next-hop neither, we might need to handle
// it now.
if (found->sender != nodeDB->getNodeNum() && found->next_hop != NO_NEXT_HOP_PREFERENCE &&
found->next_hop != ourRelayID && p->next_hop == NO_NEXT_HOP_PREFERENCE && wasRelayer(p->relay_node, *found) &&
!wasRelayer(ourRelayID, *found) &&
!wasRelayer(
found->next_hop,
*found)) { // If we were not the next hop and the next hop is not us, and we are not relaying this packet
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - Was Seen Recently: f=%08x id=%08x nh=%02x rn=%02x oID=%02x, wasFbk=%d-set TRUE",
p->from, p->id, p->next_hop, p->relay_node, ourRelayID, wasFallback ? *wasFallback : -1);
#endif
*wasFallback = true;
} else {
// debug log only
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - Was Seen Recently: f=%08x id=%08x nh=%02x rn=%02x oID=%02x, wasFbk=%d-no change",
p->from, p->id, p->next_hop, p->relay_node, ourRelayID, wasFallback ? *wasFallback : -1);
#endif
}
}
// Check if we were the next hop for this packet
if (weWereNextHop) {
*weWereNextHop = (found->next_hop == ourRelayID);
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - Was Seen Recently: f=%08x id=%08x nh=%02x rn=%02x foundnh=%02x oID=%02x -> wWNH=%s",
p->from, p->id, p->next_hop, p->relay_node, found->next_hop, ourRelayID, (*weWereNextHop) ? "YES" : "NO");
#endif
}
}
if (withUpdate) {
if (found != NULL) {
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - Was Seen Recently: s=%08x id=%08x nh=%02x rby=%02x %02x %02x age=%d wUpd BEFORE",
found->sender, found->id, found->next_hop, found->relayed_by[0], found->relayed_by[1], found->relayed_by[2],
millis() - found->rxTimeMsec);
#endif
// Only update the relayer if it heard us directly (meaning hopLimit is decreased by 1)
uint8_t startIdx = weWillRelay ? 1 : 0;
if (!weWillRelay) {
bool weWereRelayer = wasRelayer(ourRelayID, *found);
// We were a relayer and the packet came in with a hop limit that is one less than when we sent it out
if (weWereRelayer && (p->hop_limit == getOurTxHopLimit(*found) || p->hop_limit == getOurTxHopLimit(*found) - 1)) {
r.relayed_by[0] = p->relay_node;
startIdx = 1; // Start copying existing relayers from index 1
}
// keep the original ourTxHopLimit
setOurTxHopLimit(r, getOurTxHopLimit(*found));
}
// Preserve the highest hop_limit we've ever seen for this packet so upgrades aren't lost when a later copy has
// fewer hops remaining.
if (getHighestHopLimit(*found) > getHighestHopLimit(r))
setHighestHopLimit(r, getHighestHopLimit(*found));
// Add the existing relayed_by to the new record, avoiding duplicates
for (uint8_t i = 0; i < (NUM_RELAYERS - startIdx); i++) {
if (found->relayed_by[i] == 0)
continue;
bool exists = false;
for (uint8_t j = 0; j < NUM_RELAYERS; j++) {
if (r.relayed_by[j] == found->relayed_by[i]) {
exists = true;
break;
}
}
if (!exists) {
r.relayed_by[i + startIdx] = found->relayed_by[i];
}
}
r.next_hop = found->next_hop; // keep the original next_hop (such that we check whether we were originally asked)
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - Was Seen Recently: s=%08x id=%08x nh=%02x rby=%02x %02x %02x age=%d wUpd AFTER", r.sender,
r.id, r.next_hop, r.relayed_by[0], r.relayed_by[1], r.relayed_by[2], millis() - r.rxTimeMsec);
#endif
// TODO: have direct *found entry - can modify directly without local copy _vs_ not convolute the code by this
}
insert(r); // Insert or update the packet record in the history
}
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - Was Seen Recently: @exit s=%08x id=%08x (to=%08x) relby=%02x %02x %02x nxthop=%02x rxT=%d "
"found?%s seenRecently?%s wUpd?%s",
r.sender, r.id, p->to, r.relayed_by[0], r.relayed_by[1], r.relayed_by[2], r.next_hop, r.rxTimeMsec,
found ? "YES" : "NO ", seenRecently ? "YES" : "NO ", withUpdate ? "YES" : "NO ");
#endif
return seenRecently;
}
/** Find a packet record in history.
* @return pointer to PacketRecord if found, NULL if not found */
PacketHistory::PacketRecord *PacketHistory::find(NodeNum sender, PacketId id)
{
if (sender == 0 || id == 0) {
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - find: s=%08x id=%08x sender/id=0->NOT FOUND", sender, id);
#endif
return NULL;
}
PacketRecord *it = NULL;
for (it = recentPackets; it < (recentPackets + recentPacketsCapacity); ++it) {
if (it->id == id && it->sender == sender) {
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - find: s=%08x id=%08x FOUND nh=%02x rby=%02x %02x %02x age=%d slot=%d/%d", it->sender,
it->id, it->next_hop, it->relayed_by[0], it->relayed_by[1], it->relayed_by[2], millis() - (it->rxTimeMsec),
it - recentPackets, recentPacketsCapacity);
#endif
// only the first match is returned, so be careful not to create duplicate entries
return it; // Return pointer to the found record
}
}
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - find: s=%08x id=%08x NOT FOUND", sender, id);
#endif
return NULL; // Not found
}
/** Insert/Replace oldest PacketRecord in recentPackets. */
void PacketHistory::insert(const PacketRecord &r)
{
uint32_t now_millis = millis(); // Should not jump with time changes
uint32_t OldtrxTimeMsec = 0;
PacketRecord *tu = NULL; // Will insert here.
PacketRecord *it = NULL;
// Find a free, matching or oldest used slot in the recentPackets array
for (it = recentPackets; it < (recentPackets + recentPacketsCapacity); ++it) {
if (it->id == 0 && it->sender == 0 /*&& rxTimeMsec == 0*/) { // Record is empty
tu = it; // Remember the free slot
#if VERBOSE_PACKET_HISTORY >= 2
LOG_DEBUG("Packet History - insert: Free slot@ %d/%d", tu - recentPackets, recentPacketsCapacity);
#endif
// We have that, Exit the loop
it = (recentPackets + recentPacketsCapacity);
} else if (it->id == r.id && it->sender == r.sender) { // Record matches the packet we want to insert
tu = it; // Remember the matching slot
OldtrxTimeMsec = now_millis - it->rxTimeMsec; // ..and save current entry's age
#if VERBOSE_PACKET_HISTORY >= 2
LOG_DEBUG("Packet History - insert: Matched slot@ %d/%d age=%d", tu - recentPackets, recentPacketsCapacity,
OldtrxTimeMsec);
#endif
// We have that, Exit the loop
it = (recentPackets + recentPacketsCapacity);
} else {
if (it->rxTimeMsec == 0) {
LOG_WARN(
"Packet History - insert: Found packet s=%08x id=%08x with rxTimeMsec = 0, slot %d/%d. Should never happen!",
it->sender, it->id, it - recentPackets, recentPacketsCapacity);
}
if ((now_millis - it->rxTimeMsec) > OldtrxTimeMsec) { // 49.7 days rollover friendly
OldtrxTimeMsec = now_millis - it->rxTimeMsec;
tu = it; // remember the oldest packet
#if VERBOSE_PACKET_HISTORY >= 2
LOG_DEBUG("Packet History - insert: Older slot@ %d/%d age=%d", tu - recentPackets, recentPacketsCapacity,
OldtrxTimeMsec);
#endif
}
// keep looking for oldest till entire array is checked
}
}
if (tu == NULL) {
LOG_ERROR("Packet History - insert: No free slot, no matched packet, no oldest to reuse. Something leaked."); // mx
// assert(false); // This should never happen, we should always have at least one packet to clear
return; // Return early if we can't update the history
}
#if VERBOSE_PACKET_HISTORY
if (tu->id == 0 && tu->sender == 0) {
LOG_DEBUG("Packet History - insert: slot@ %d/%d is NEW", tu - recentPackets, recentPacketsCapacity);
} else if (tu->id == r.id && tu->sender == r.sender) {
LOG_DEBUG("Packet History - insert: slot@ %d/%d MATCHED, age=%d", tu - recentPackets, recentPacketsCapacity,
OldtrxTimeMsec);
} else {
LOG_DEBUG("Packet History - insert: slot@ %d/%d REUSE OLDEST, age=%d", tu - recentPackets, recentPacketsCapacity,
OldtrxTimeMsec);
}
#endif
// If we are reusing a slot, we should warn if the packet is too recent
#if RECENT_WARN_AGE > 0
if (tu->rxTimeMsec && (OldtrxTimeMsec < RECENT_WARN_AGE)) {
if (!(tu->id == r.id && tu->sender == r.sender)) {
#if VERBOSE_PACKET_HISTORY
LOG_WARN("Packet History - insert: Reusing slot aged %ds < %ds RECENT_WARN_AGE", OldtrxTimeMsec / 1000,
RECENT_WARN_AGE / 1000);
#endif
} else {
// debug only
#if VERBOSE_PACKET_HISTORY
LOG_WARN("Packet History - insert: Reusing slot aged %.3fs < %ds with MATCHED PACKET - this is normal",
OldtrxTimeMsec / 1000., RECENT_WARN_AGE / 1000);
#endif
}
}
#if PACKET_HISTORY_TRACE_AGING
if (tu->rxTimeMsec != 0) {
LOG_INFO("Packet History - insert: Reusing slot aged %.3fs TRACE %s", OldtrxTimeMsec / 1000.,
(tu->id == r.id && tu->sender == r.sender) ? "MATCHED PACKET" : "OLDEST SLOT");
} else {
LOG_INFO("Packet History - insert: Using new slot @uptime %.3fs TRACE NEW", millis() / 1000.);
}
#endif
#endif
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - insert: Store slot@ %d/%d s=%08x id=%08x nh=%02x rby=%02x %02x %02x rxT=%d BEFORE",
tu - recentPackets, recentPacketsCapacity, tu->sender, tu->id, tu->next_hop, tu->relayed_by[0], tu->relayed_by[1],
tu->relayed_by[2], tu->rxTimeMsec);
#endif
if (r.rxTimeMsec == 0) {
#if VERBOSE_PACKET_HISTORY
LOG_WARN("Packet History - insert: I will not store packet with rxTimeMsec = 0.");
#endif
return; // Return early if we can't update the history
}
*tu = r; // store the packet
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - insert: Store slot@ %d/%d s=%08x id=%08x nh=%02x rby=%02x %02x %02x rxT=%d AFTER",
tu - recentPackets, recentPacketsCapacity, tu->sender, tu->id, tu->next_hop, tu->relayed_by[0], tu->relayed_by[1],
tu->relayed_by[2], tu->rxTimeMsec);
#endif
}
/* Check if a certain node was a relayer of a packet in the history given an ID and sender
* @return true if node was indeed a relayer, false if not */
bool PacketHistory::wasRelayer(const uint8_t relayer, const uint32_t id, const NodeNum sender, bool *wasSole)
{
if (!initOk()) {
LOG_ERROR("PacketHistory - wasRelayer: NOT INITIALIZED!");
return false;
}
if (relayer == 0) {
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - was relayer: s=%08x id=%08x / rl=%02x=zero. NO", sender, id, relayer);
#endif
return false;
}
const PacketRecord *found = find(sender, id);
if (found == NULL) {
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - was relayer: s=%08x id=%08x / rl=%02x / PR not found. NO", sender, id, relayer);
#endif
return false;
}
#if VERBOSE_PACKET_HISTORY >= 2
LOG_DEBUG("Packet History - was relayer: s=%08x id=%08x nh=%02x age=%d rls=%02x %02x %02x InHistory,check:%02x",
found->sender, found->id, found->next_hop, millis() - found->rxTimeMsec, found->relayed_by[0], found->relayed_by[1],
found->relayed_by[2], relayer);
#endif
return wasRelayer(relayer, *found, wasSole);
}
/* Check if a certain node was a relayer of a packet in the history given iterator
* @return true if node was indeed a relayer, false if not */
bool PacketHistory::wasRelayer(const uint8_t relayer, const PacketRecord &r, bool *wasSole)
{
bool found = false;
bool other_present = false;
for (uint8_t i = 0; i < NUM_RELAYERS; ++i) {
if (r.relayed_by[i] == relayer) {
found = true;
} else if (r.relayed_by[i] != 0) {
other_present = true;
}
}
if (wasSole) {
*wasSole = (found && !other_present);
}
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - was rel.PR.: s=%08x id=%08x rls=%02x %02x %02x / rl=%02x? NO", r.sender, r.id, r.relayed_by[0],
r.relayed_by[1], r.relayed_by[2], relayer);
#endif
return found;
}
// Remove a relayer from the list of relayers of a packet in the history given an ID and sender
void PacketHistory::removeRelayer(const uint8_t relayer, const uint32_t id, const NodeNum sender)
{
if (!initOk()) {
LOG_ERROR("Packet History - remove Relayer: NOT INITIALIZED!");
return;
}
PacketRecord *found = find(sender, id);
if (found == NULL) {
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - remove Relayer s=%08x id=%08x (rl=%02x) NOT FOUND", sender, id, relayer);
#endif
return; // Nothing to remove
}
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - remove Relayer s=%08x id=%08x rby=%02x %02x %02x, rl:%02x BEFORE", found->sender, found->id,
found->relayed_by[0], found->relayed_by[1], found->relayed_by[2], relayer);
#endif
// nexthop and rxTimeMsec too stay in found entry
uint8_t j = 0;
uint8_t i = 0;
for (; i < NUM_RELAYERS; i++) {
if (found->relayed_by[i] != relayer) {
found->relayed_by[j] = found->relayed_by[i];
j++;
} else
found->relayed_by[i] = 0;
}
for (; j < NUM_RELAYERS; j++) { // Clear the rest of the relayed_by array
found->relayed_by[j] = 0;
}
#if VERBOSE_PACKET_HISTORY
LOG_DEBUG("Packet History - remove Relayer s=%08x id=%08x rby=%02x %02x %02x rl:%02x AFTER - removed?%d", found->sender,
found->id, found->relayed_by[0], found->relayed_by[1], found->relayed_by[2], relayer, i != j);
#endif
}
// Getters and setters for hop limit fields packed in hop_limit
inline uint8_t PacketHistory::getHighestHopLimit(PacketRecord &r)
{
return r.hop_limit & HOP_LIMIT_HIGHEST_MASK;
}
inline void PacketHistory::setHighestHopLimit(PacketRecord &r, uint8_t hopLimit)
{
r.hop_limit = (r.hop_limit & ~HOP_LIMIT_HIGHEST_MASK) | (hopLimit & HOP_LIMIT_HIGHEST_MASK);
}
inline uint8_t PacketHistory::getOurTxHopLimit(PacketRecord &r)
{
return (r.hop_limit & HOP_LIMIT_OUR_TX_MASK) >> HOP_LIMIT_OUR_TX_SHIFT;
}
inline void PacketHistory::setOurTxHopLimit(PacketRecord &r, uint8_t hopLimit)
{
r.hop_limit = (r.hop_limit & ~HOP_LIMIT_OUR_TX_MASK) | ((hopLimit << HOP_LIMIT_OUR_TX_SHIFT) & HOP_LIMIT_OUR_TX_MASK);
}
@@ -0,0 +1,78 @@
#pragma once
#include "NodeDB.h"
// Number of relayers we keep track of. Use 6 to be efficient with memory alignment of PacketRecord to 20 bytes
#define NUM_RELAYERS 6
#define HOP_LIMIT_HIGHEST_MASK 0x07 // Bits 0-2
#define HOP_LIMIT_OUR_TX_MASK 0x38 // Bits 3-5
#define HOP_LIMIT_OUR_TX_SHIFT 3 // Bits 3-5
/**
* This is a mixin that adds a record of past packets we have seen
*/
class PacketHistory
{
private:
struct PacketRecord { // A record of a recent message broadcast, no need to be visible outside this class.
NodeNum sender;
PacketId id;
uint32_t rxTimeMsec; // Unix time in msecs - the time we received it, 0 means empty
uint8_t next_hop; // The next hop asked for this packet
uint8_t hop_limit; // bit 0-2: Highest hop limit observed for this packet,
// bit 3-5: our hop limit when we first transmitted it
uint8_t relayed_by[NUM_RELAYERS]; // Array of nodes that relayed this packet
}; // 4B + 4B + 4B + 1B + 1B + 6B = 20B
uint32_t recentPacketsCapacity =
0; // Can be set in constructor, no need to recompile. Used to allocate memory for mx_recentPackets.
PacketRecord *recentPackets = NULL; // Simple and fixed in size. Debloat.
/** Find a packet record in history.
* @param sender NodeNum
* @param id PacketId
* @return pointer to PacketRecord if found, NULL if not found */
PacketRecord *find(NodeNum sender, PacketId id);
/** Insert/Replace oldest PacketRecord in mx_recentPackets.
* @param r PacketRecord to insert or replace */
void insert(const PacketRecord &r); // Insert or replace a packet record in the history
/* Check if a certain node was a relayer of a packet in the history given iterator
* If wasSole is not nullptr, it will be set to true if the relayer was the only relayer of that packet
* @return true if node was indeed a relayer, false if not */
bool wasRelayer(const uint8_t relayer, const PacketRecord &r, bool *wasSole = nullptr);
uint8_t getHighestHopLimit(PacketRecord &r);
void setHighestHopLimit(PacketRecord &r, uint8_t hopLimit);
uint8_t getOurTxHopLimit(PacketRecord &r);
void setOurTxHopLimit(PacketRecord &r, uint8_t hopLimit);
PacketHistory(const PacketHistory &); // non construction-copyable
PacketHistory &operator=(const PacketHistory &); // non copyable
public:
explicit PacketHistory(uint32_t size = -1); // Constructor with size parameter, default is PACKETHISTORY_MAX
~PacketHistory();
/**
* Update recentBroadcasts and return true if we have already seen this packet
*
* @param withUpdate if true and not found we add an entry to recentPackets
* @param wasFallback if not nullptr, packet will be checked for fallback to flooding and value will be set to true if so
* @param weWereNextHop if not nullptr, packet will be checked for us being the next hop and value will be set to true if so
* @param wasUpgraded if not nullptr, will be set to true if this packet has better hop_limit than previously seen
*/
bool wasSeenRecently(const meshtastic_MeshPacket *p, bool withUpdate = true, bool *wasFallback = nullptr,
bool *weWereNextHop = nullptr, bool *wasUpgraded = nullptr);
/* Check if a certain node was a relayer of a packet in the history given an ID and sender
* If wasSole is not nullptr, it will be set to true if the relayer was the only relayer of that packet
* @return true if node was indeed a relayer, false if not */
bool wasRelayer(const uint8_t relayer, const uint32_t id, const NodeNum sender, bool *wasSole = nullptr);
// Remove a relayer from the list of relayers of a packet in the history given an ID and sender
void removeRelayer(const uint8_t relayer, const uint32_t id, const NodeNum sender);
// To check if the PacketHistory was initialized correctly by constructor
bool initOk(void) { return recentPackets != NULL && recentPacketsCapacity != 0; }
};
@@ -0,0 +1,844 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_GPS
#include "GPS.h"
#endif
#include "Channels.h"
#include "Default.h"
#include "FSCommon.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PacketHistory.h"
#include "PhoneAPI.h"
#include "PowerFSM.h"
#include "RadioInterface.h"
#include "Router.h"
#include "SPILock.h"
#include "TypeConversions.h"
#include "concurrency/LockGuard.h"
#include "main.h"
#include "xmodem.h"
#if FromRadio_size > MAX_TO_FROM_RADIO_SIZE
#error FromRadio is too big
#endif
#if ToRadio_size > MAX_TO_FROM_RADIO_SIZE
#error ToRadio is too big
#endif
#if !MESHTASTIC_EXCLUDE_MQTT
#include "mqtt/MQTT.h"
#endif
#include "Throttle.h"
#include <RTC.h>
// Flag to indicate a heartbeat was received and we should send queue status
bool heartbeatReceived = false;
PhoneAPI::PhoneAPI()
{
lastContactMsec = millis();
std::fill(std::begin(recentToRadioPacketIds), std::end(recentToRadioPacketIds), 0);
}
PhoneAPI::~PhoneAPI()
{
close();
}
void PhoneAPI::handleStartConfig()
{
// Must be before setting state (because state is how we know !connected)
if (!isConnected()) {
onConnectionChanged(true);
observe(&service->fromNumChanged);
#ifdef FSCom
observe(&xModem.packetReady);
#endif
}
// Allow subclasses to prepare for high-throughput config traffic
onConfigStart();
// even if we were already connected - restart our state machine
if (config_nonce == SPECIAL_NONCE_ONLY_NODES) {
// If client only wants node info, jump directly to sending nodes
state = STATE_SEND_OWN_NODEINFO;
LOG_INFO("Client only wants node info, skipping other config");
} else {
state = STATE_SEND_MY_INFO;
}
pauseBluetoothLogging = true;
spiLock->lock();
filesManifest = getFiles("/", 10);
spiLock->unlock();
LOG_DEBUG("Got %d files in manifest", filesManifest.size());
LOG_INFO("Start API client config millis=%u", millis());
// Protect against concurrent BLE callbacks: they run in NimBLE's FreeRTOS task and also touch nodeInfoQueue.
{
concurrency::LockGuard guard(&nodeInfoMutex);
nodeInfoForPhone = {};
nodeInfoQueue.clear();
}
resetReadIndex();
}
void PhoneAPI::close()
{
LOG_DEBUG("PhoneAPI::close()");
if (service->api_state == service->STATE_BLE && api_type == TYPE_BLE)
service->api_state = service->STATE_DISCONNECTED;
else if (service->api_state == service->STATE_WIFI && api_type == TYPE_WIFI)
service->api_state = service->STATE_DISCONNECTED;
else if (service->api_state == service->STATE_SERIAL && api_type == TYPE_SERIAL)
service->api_state = service->STATE_DISCONNECTED;
else if (service->api_state == service->STATE_PACKET && api_type == TYPE_PACKET)
service->api_state = service->STATE_DISCONNECTED;
else if (service->api_state == service->STATE_HTTP && api_type == TYPE_HTTP)
service->api_state = service->STATE_DISCONNECTED;
else if (service->api_state == service->STATE_ETH && api_type == TYPE_ETH)
service->api_state = service->STATE_DISCONNECTED;
if (state != STATE_SEND_NOTHING) {
state = STATE_SEND_NOTHING;
resetReadIndex();
unobserve(&service->fromNumChanged);
#ifdef FSCom
unobserve(&xModem.packetReady);
#endif
releasePhonePacket(); // Don't leak phone packets on shutdown
releaseQueueStatusPhonePacket();
releaseMqttClientProxyPhonePacket();
releaseClientNotification();
onConnectionChanged(false);
fromRadioScratch = {};
toRadioScratch = {};
// Clear cached node info under lock because NimBLE callbacks can still be draining it.
{
concurrency::LockGuard guard(&nodeInfoMutex);
nodeInfoForPhone = {};
nodeInfoQueue.clear();
}
packetForPhone = NULL;
filesManifest.clear();
fromRadioNum = 0;
config_nonce = 0;
config_state = 0;
pauseBluetoothLogging = false;
heartbeatReceived = false;
}
}
bool PhoneAPI::checkConnectionTimeout()
{
if (isConnected()) {
bool newContact = checkIsConnected();
if (!newContact) {
LOG_INFO("Lost phone connection");
close();
return true;
}
}
return false;
}
/**
* Handle a ToRadio protobuf
*/
bool PhoneAPI::handleToRadio(const uint8_t *buf, size_t bufLength)
{
powerFSM.trigger(EVENT_CONTACT_FROM_PHONE); // As long as the phone keeps talking to us, don't let the radio go to sleep
lastContactMsec = millis();
memset(&toRadioScratch, 0, sizeof(toRadioScratch));
if (pb_decode_from_bytes(buf, bufLength, &meshtastic_ToRadio_msg, &toRadioScratch)) {
switch (toRadioScratch.which_payload_variant) {
case meshtastic_ToRadio_packet_tag:
return handleToRadioPacket(toRadioScratch.packet);
case meshtastic_ToRadio_want_config_id_tag:
config_nonce = toRadioScratch.want_config_id;
LOG_INFO("Client wants config, nonce=%u", config_nonce);
handleStartConfig();
break;
case meshtastic_ToRadio_disconnect_tag:
LOG_INFO("Disconnect from phone");
close();
break;
case meshtastic_ToRadio_xmodemPacket_tag:
LOG_INFO("Got xmodem packet");
#ifdef FSCom
xModem.handlePacket(toRadioScratch.xmodemPacket);
#endif
break;
#if !MESHTASTIC_EXCLUDE_MQTT
case meshtastic_ToRadio_mqttClientProxyMessage_tag:
LOG_DEBUG("Got MqttClientProxy message");
if (state != STATE_SEND_PACKETS) {
LOG_WARN("Ignore MqttClientProxy message while completing config handshake");
break;
}
if (mqtt && moduleConfig.mqtt.proxy_to_client_enabled && moduleConfig.mqtt.enabled &&
(channels.anyMqttEnabled() || moduleConfig.mqtt.map_reporting_enabled)) {
mqtt->onClientProxyReceive(toRadioScratch.mqttClientProxyMessage);
} else {
LOG_WARN("MqttClientProxy received but proxy is not enabled, no channels have up/downlink, or map reporting "
"not enabled");
}
break;
#endif
case meshtastic_ToRadio_heartbeat_tag:
LOG_DEBUG("Got client heartbeat");
heartbeatReceived = true;
break;
default:
// Ignore nop messages
break;
}
} else {
LOG_ERROR("Error: ignore malformed toradio");
}
return false;
}
/**
* Get the next packet we want to send to the phone, or NULL if no such packet is available.
*
* We assume buf is at least FromRadio_size bytes long.
*
* Our sending states progress in the following sequence (the client apps ASSUME THIS SEQUENCE, DO NOT CHANGE IT):
STATE_SEND_MY_INFO, // send our my info record
STATE_SEND_UIDATA,
STATE_SEND_OWN_NODEINFO,
STATE_SEND_METADATA,
STATE_SEND_CHANNELS
STATE_SEND_CONFIG,
STATE_SEND_MODULE_CONFIG,
STATE_SEND_OTHER_NODEINFOS, // states progress in this order as the device sends to the client
STATE_SEND_FILEMANIFEST,
STATE_SEND_COMPLETE_ID,
STATE_SEND_PACKETS // send packets or debug strings
*/
size_t PhoneAPI::getFromRadio(uint8_t *buf)
{
// Respond to heartbeat by sending queue status
if (heartbeatReceived) {
memset(&fromRadioScratch, 0, sizeof(fromRadioScratch));
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_queueStatus_tag;
fromRadioScratch.queueStatus = router->getQueueStatus();
heartbeatReceived = false;
size_t numbytes = pb_encode_to_bytes(buf, meshtastic_FromRadio_size, &meshtastic_FromRadio_msg, &fromRadioScratch);
LOG_DEBUG("FromRadio=STATE_SEND_QUEUE_STATUS, numbytes=%u", numbytes);
return numbytes;
}
if (!available()) {
return 0;
}
// In case we send a FromRadio packet
memset(&fromRadioScratch, 0, sizeof(fromRadioScratch));
// Advance states as needed
switch (state) {
case STATE_SEND_NOTHING:
LOG_DEBUG("FromRadio=STATE_SEND_NOTHING");
break;
case STATE_SEND_MY_INFO:
LOG_DEBUG("FromRadio=STATE_SEND_MY_INFO");
// If the user has specified they don't want our node to share its location, make sure to tell the phone
// app not to send locations on our behalf.
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_my_info_tag;
strncpy(myNodeInfo.pio_env, optstr(APP_ENV), sizeof(myNodeInfo.pio_env));
myNodeInfo.nodedb_count = static_cast<uint16_t>(nodeDB->getNumMeshNodes());
fromRadioScratch.my_info = myNodeInfo;
state = STATE_SEND_UIDATA;
service->refreshLocalMeshNode(); // Update my NodeInfo because the client will be asking for it soon.
break;
case STATE_SEND_UIDATA:
LOG_INFO("getFromRadio=STATE_SEND_UIDATA");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_deviceuiConfig_tag;
fromRadioScratch.deviceuiConfig = uiconfig;
state = STATE_SEND_OWN_NODEINFO;
break;
case STATE_SEND_OWN_NODEINFO: {
LOG_DEBUG("Send My NodeInfo");
auto us = nodeDB->readNextMeshNode(readIndex);
if (us) {
auto info = TypeConversions::ConvertToNodeInfo(us);
info.has_hops_away = false;
info.is_favorite = true;
{
concurrency::LockGuard guard(&nodeInfoMutex);
nodeInfoForPhone = info;
}
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_node_info_tag;
fromRadioScratch.node_info = info;
// Should allow us to resume sending NodeInfo in STATE_SEND_OTHER_NODEINFOS
{
concurrency::LockGuard guard(&nodeInfoMutex);
nodeInfoForPhone.num = 0;
}
}
if (config_nonce == SPECIAL_NONCE_ONLY_NODES) {
// If client only wants node info, jump directly to sending nodes
state = STATE_SEND_OTHER_NODEINFOS;
onNowHasData(0);
} else {
state = STATE_SEND_METADATA;
}
break;
}
case STATE_SEND_METADATA:
LOG_DEBUG("Send device metadata");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_metadata_tag;
fromRadioScratch.metadata = getDeviceMetadata();
state = STATE_SEND_CHANNELS;
break;
case STATE_SEND_CHANNELS:
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_channel_tag;
fromRadioScratch.channel = channels.getByIndex(config_state);
config_state++;
// Advance when we have sent all of our Channels
if (config_state >= MAX_NUM_CHANNELS) {
LOG_DEBUG("Send channels %d", config_state);
state = STATE_SEND_CONFIG;
config_state = _meshtastic_AdminMessage_ConfigType_MIN + 1;
}
break;
case STATE_SEND_CONFIG:
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_tag;
switch (config_state) {
case meshtastic_Config_device_tag:
LOG_DEBUG("Send config: device");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_device_tag;
fromRadioScratch.config.payload_variant.device = config.device;
break;
case meshtastic_Config_position_tag:
LOG_DEBUG("Send config: position");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_position_tag;
fromRadioScratch.config.payload_variant.position = config.position;
break;
case meshtastic_Config_power_tag:
LOG_DEBUG("Send config: power");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_power_tag;
fromRadioScratch.config.payload_variant.power = config.power;
fromRadioScratch.config.payload_variant.power.ls_secs = default_ls_secs;
break;
case meshtastic_Config_network_tag:
LOG_DEBUG("Send config: network");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_network_tag;
fromRadioScratch.config.payload_variant.network = config.network;
break;
case meshtastic_Config_display_tag:
LOG_DEBUG("Send config: display");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_display_tag;
fromRadioScratch.config.payload_variant.display = config.display;
break;
case meshtastic_Config_lora_tag:
LOG_DEBUG("Send config: lora");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_lora_tag;
fromRadioScratch.config.payload_variant.lora = config.lora;
break;
case meshtastic_Config_bluetooth_tag:
LOG_DEBUG("Send config: bluetooth");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_bluetooth_tag;
fromRadioScratch.config.payload_variant.bluetooth = config.bluetooth;
break;
case meshtastic_Config_security_tag:
LOG_DEBUG("Send config: security");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_security_tag;
fromRadioScratch.config.payload_variant.security = config.security;
break;
case meshtastic_Config_sessionkey_tag:
LOG_DEBUG("Send config: sessionkey");
fromRadioScratch.config.which_payload_variant = meshtastic_Config_sessionkey_tag;
break;
case meshtastic_Config_device_ui_tag: // NOOP!
fromRadioScratch.config.which_payload_variant = meshtastic_Config_device_ui_tag;
break;
default:
LOG_ERROR("Unknown config type %d", config_state);
}
// NOTE: The phone app needs to know the ls_secs value so it can properly expect sleep behavior.
// So even if we internally use 0 to represent 'use default' we still need to send the value we are
// using to the app (so that even old phone apps work with new device loads).
config_state++;
// Advance when we have sent all of our config objects
if (config_state > (_meshtastic_AdminMessage_ConfigType_MAX + 1)) {
state = STATE_SEND_MODULECONFIG;
config_state = _meshtastic_AdminMessage_ModuleConfigType_MIN + 1;
}
break;
case STATE_SEND_MODULECONFIG:
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_moduleConfig_tag;
switch (config_state) {
case meshtastic_ModuleConfig_mqtt_tag:
LOG_DEBUG("Send module config: mqtt");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_mqtt_tag;
fromRadioScratch.moduleConfig.payload_variant.mqtt = moduleConfig.mqtt;
break;
case meshtastic_ModuleConfig_serial_tag:
LOG_DEBUG("Send module config: serial");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_serial_tag;
fromRadioScratch.moduleConfig.payload_variant.serial = moduleConfig.serial;
break;
case meshtastic_ModuleConfig_external_notification_tag:
LOG_DEBUG("Send module config: ext notification");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_external_notification_tag;
fromRadioScratch.moduleConfig.payload_variant.external_notification = moduleConfig.external_notification;
break;
case meshtastic_ModuleConfig_store_forward_tag:
LOG_DEBUG("Send module config: store forward");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_store_forward_tag;
fromRadioScratch.moduleConfig.payload_variant.store_forward = moduleConfig.store_forward;
break;
case meshtastic_ModuleConfig_range_test_tag:
LOG_DEBUG("Send module config: range test");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_range_test_tag;
fromRadioScratch.moduleConfig.payload_variant.range_test = moduleConfig.range_test;
break;
case meshtastic_ModuleConfig_telemetry_tag:
LOG_DEBUG("Send module config: telemetry");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_telemetry_tag;
fromRadioScratch.moduleConfig.payload_variant.telemetry = moduleConfig.telemetry;
break;
case meshtastic_ModuleConfig_canned_message_tag:
LOG_DEBUG("Send module config: canned message");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_canned_message_tag;
fromRadioScratch.moduleConfig.payload_variant.canned_message = moduleConfig.canned_message;
break;
case meshtastic_ModuleConfig_audio_tag:
LOG_DEBUG("Send module config: audio");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_audio_tag;
fromRadioScratch.moduleConfig.payload_variant.audio = moduleConfig.audio;
break;
case meshtastic_ModuleConfig_remote_hardware_tag:
LOG_DEBUG("Send module config: remote hardware");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_remote_hardware_tag;
fromRadioScratch.moduleConfig.payload_variant.remote_hardware = moduleConfig.remote_hardware;
break;
case meshtastic_ModuleConfig_neighbor_info_tag:
LOG_DEBUG("Send module config: neighbor info");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_neighbor_info_tag;
fromRadioScratch.moduleConfig.payload_variant.neighbor_info = moduleConfig.neighbor_info;
break;
case meshtastic_ModuleConfig_detection_sensor_tag:
LOG_DEBUG("Send module config: detection sensor");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_detection_sensor_tag;
fromRadioScratch.moduleConfig.payload_variant.detection_sensor = moduleConfig.detection_sensor;
break;
case meshtastic_ModuleConfig_ambient_lighting_tag:
LOG_DEBUG("Send module config: ambient lighting");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_ambient_lighting_tag;
fromRadioScratch.moduleConfig.payload_variant.ambient_lighting = moduleConfig.ambient_lighting;
break;
case meshtastic_ModuleConfig_paxcounter_tag:
LOG_DEBUG("Send module config: paxcounter");
fromRadioScratch.moduleConfig.which_payload_variant = meshtastic_ModuleConfig_paxcounter_tag;
fromRadioScratch.moduleConfig.payload_variant.paxcounter = moduleConfig.paxcounter;
break;
default:
LOG_ERROR("Unknown module config type %d", config_state);
}
config_state++;
// Advance when we have sent all of our ModuleConfig objects
if (config_state > (_meshtastic_AdminMessage_ModuleConfigType_MAX + 1)) {
// Handle special nonce behaviors:
// - SPECIAL_NONCE_ONLY_CONFIG: Skip node info, go directly to file manifest
// - SPECIAL_NONCE_ONLY_NODES: After sending nodes, skip to complete
if (config_nonce == SPECIAL_NONCE_ONLY_CONFIG) {
state = STATE_SEND_FILEMANIFEST;
} else {
state = STATE_SEND_OTHER_NODEINFOS;
onNowHasData(0);
}
config_state = 0;
}
break;
case STATE_SEND_OTHER_NODEINFOS: {
if (readIndex == 2) { // readIndex==2 will be true for the first non-us node
LOG_INFO("Start sending nodeinfos millis=%u", millis());
}
meshtastic_NodeInfo infoToSend = {};
{
concurrency::LockGuard guard(&nodeInfoMutex);
if (nodeInfoForPhone.num == 0 && !nodeInfoQueue.empty()) {
// Serve the next cached node without re-reading from the DB iterator.
nodeInfoForPhone = nodeInfoQueue.front();
nodeInfoQueue.pop_front();
}
infoToSend = nodeInfoForPhone;
if (infoToSend.num != 0)
nodeInfoForPhone = {};
}
if (infoToSend.num != 0) {
// Just in case we stored a different user.id in the past, but should never happen going forward
sprintf(infoToSend.user.id, "!%08x", infoToSend.num);
// Logging this really slows down sending nodes on initial connection because the serial console is so slow, so only
// uncomment if you really need to:
// LOG_INFO("nodeinfo: num=0x%x, lastseen=%u, id=%s, name=%s", nodeInfoForPhone.num, nodeInfoForPhone.last_heard,
// nodeInfoForPhone.user.id, nodeInfoForPhone.user.long_name);
// Occasional progress logging. (readIndex==2 will be true for the first non-us node)
if (readIndex == 2 || readIndex % 20 == 0) {
LOG_DEBUG("nodeinfo: %d/%d", readIndex, nodeDB->getNumMeshNodes());
}
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_node_info_tag;
fromRadioScratch.node_info = infoToSend;
prefetchNodeInfos();
} else {
LOG_DEBUG("Done sending %d of %d nodeinfos millis=%u", readIndex, nodeDB->getNumMeshNodes(), millis());
concurrency::LockGuard guard(&nodeInfoMutex);
nodeInfoQueue.clear();
state = STATE_SEND_FILEMANIFEST;
// Go ahead and send that ID right now
return getFromRadio(buf);
}
break;
}
case STATE_SEND_FILEMANIFEST: {
LOG_DEBUG("FromRadio=STATE_SEND_FILEMANIFEST");
// last element
if (config_state == filesManifest.size() ||
config_nonce == SPECIAL_NONCE_ONLY_NODES) { // also handles an empty filesManifest
config_state = 0;
filesManifest.clear();
// Skip to complete packet
sendConfigComplete();
} else {
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_fileInfo_tag;
fromRadioScratch.fileInfo = filesManifest.at(config_state);
LOG_DEBUG("File: %s (%d) bytes", fromRadioScratch.fileInfo.file_name, fromRadioScratch.fileInfo.size_bytes);
config_state++;
}
break;
}
case STATE_SEND_COMPLETE_ID:
sendConfigComplete();
break;
case STATE_SEND_PACKETS:
pauseBluetoothLogging = false;
// Do we have a message from the mesh or packet from the local device?
LOG_DEBUG("FromRadio=STATE_SEND_PACKETS");
if (queueStatusPacketForPhone) {
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_queueStatus_tag;
fromRadioScratch.queueStatus = *queueStatusPacketForPhone;
releaseQueueStatusPhonePacket();
} else if (mqttClientProxyMessageForPhone) {
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_mqttClientProxyMessage_tag;
fromRadioScratch.mqttClientProxyMessage = *mqttClientProxyMessageForPhone;
releaseMqttClientProxyPhonePacket();
} else if (xmodemPacketForPhone.control != meshtastic_XModem_Control_NUL) {
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_xmodemPacket_tag;
fromRadioScratch.xmodemPacket = xmodemPacketForPhone;
xmodemPacketForPhone = meshtastic_XModem_init_zero;
} else if (clientNotification) {
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_clientNotification_tag;
fromRadioScratch.clientNotification = *clientNotification;
releaseClientNotification();
} else if (packetForPhone) {
printPacket("phone downloaded packet", packetForPhone);
// Encapsulate as a FromRadio packet
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_packet_tag;
fromRadioScratch.packet = *packetForPhone;
releasePhonePacket();
}
break;
default:
LOG_ERROR("getFromRadio unexpected state %d", state);
}
// Do we have a message from the mesh?
if (fromRadioScratch.which_payload_variant != 0) {
// Encapsulate as a FromRadio packet
size_t numbytes = pb_encode_to_bytes(buf, meshtastic_FromRadio_size, &meshtastic_FromRadio_msg, &fromRadioScratch);
// VERY IMPORTANT to not print debug messages while writing to fromRadioScratch - because we use that same buffer
// for logging (when we are encapsulating with protobufs)
return numbytes;
}
LOG_DEBUG("No FromRadio packet available");
return 0;
}
void PhoneAPI::sendConfigComplete()
{
LOG_INFO("Config Send Complete millis=%u", millis());
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_complete_id_tag;
fromRadioScratch.config_complete_id = config_nonce;
config_nonce = 0;
state = STATE_SEND_PACKETS;
if (api_type == TYPE_BLE) {
service->api_state = service->STATE_BLE;
} else if (api_type == TYPE_WIFI) {
service->api_state = service->STATE_WIFI;
} else if (api_type == TYPE_SERIAL) {
service->api_state = service->STATE_SERIAL;
} else if (api_type == TYPE_PACKET) {
service->api_state = service->STATE_PACKET;
} else if (api_type == TYPE_HTTP) {
service->api_state = service->STATE_HTTP;
} else if (api_type == TYPE_ETH) {
service->api_state = service->STATE_ETH;
}
// Allow subclasses to know we've entered steady-state so they can lower power consumption
onConfigComplete();
pauseBluetoothLogging = false;
}
void PhoneAPI::releasePhonePacket()
{
if (packetForPhone) {
service->releaseToPool(packetForPhone); // we just copied the bytes, so don't need this buffer anymore
packetForPhone = NULL;
}
}
void PhoneAPI::releaseQueueStatusPhonePacket()
{
if (queueStatusPacketForPhone) {
service->releaseQueueStatusToPool(queueStatusPacketForPhone);
queueStatusPacketForPhone = NULL;
}
}
void PhoneAPI::prefetchNodeInfos()
{
bool added = false;
// Keep the queue topped up so BLE reads stay responsive even if DB fetches take a moment.
{
concurrency::LockGuard guard(&nodeInfoMutex);
while (nodeInfoQueue.size() < kNodePrefetchDepth) {
auto nextNode = nodeDB->readNextMeshNode(readIndex);
if (!nextNode)
break;
auto info = TypeConversions::ConvertToNodeInfo(nextNode);
bool isUs = info.num == nodeDB->getNodeNum();
info.hops_away = isUs ? 0 : info.hops_away;
info.last_heard = isUs ? getValidTime(RTCQualityFromNet) : info.last_heard;
info.snr = isUs ? 0 : info.snr;
info.via_mqtt = isUs ? false : info.via_mqtt;
info.is_favorite = info.is_favorite || isUs;
nodeInfoQueue.push_back(info);
added = true;
}
}
if (added)
onNowHasData(0);
}
void PhoneAPI::releaseMqttClientProxyPhonePacket()
{
if (mqttClientProxyMessageForPhone) {
service->releaseMqttClientProxyMessageToPool(mqttClientProxyMessageForPhone);
mqttClientProxyMessageForPhone = NULL;
}
}
void PhoneAPI::releaseClientNotification()
{
if (clientNotification) {
service->releaseClientNotificationToPool(clientNotification);
clientNotification = NULL;
}
}
/**
* Return true if we have data available to send to the phone
*/
bool PhoneAPI::available()
{
switch (state) {
case STATE_SEND_NOTHING:
return false;
case STATE_SEND_MY_INFO:
case STATE_SEND_UIDATA:
case STATE_SEND_CHANNELS:
case STATE_SEND_CONFIG:
case STATE_SEND_MODULECONFIG:
case STATE_SEND_METADATA:
case STATE_SEND_OWN_NODEINFO:
case STATE_SEND_FILEMANIFEST:
case STATE_SEND_COMPLETE_ID:
return true;
case STATE_SEND_OTHER_NODEINFOS: {
concurrency::LockGuard guard(&nodeInfoMutex);
if (nodeInfoQueue.empty()) {
// Drop the lock before prefetching; prefetchNodeInfos() will re-acquire it.
goto PREFETCH_NODEINFO;
}
}
return true; // Always say we have something, because we might need to advance our state machine
PREFETCH_NODEINFO:
prefetchNodeInfos();
return true;
case STATE_SEND_PACKETS: {
if (!queueStatusPacketForPhone)
queueStatusPacketForPhone = service->getQueueStatusForPhone();
if (!mqttClientProxyMessageForPhone)
mqttClientProxyMessageForPhone = service->getMqttClientProxyMessageForPhone();
if (!clientNotification)
clientNotification = service->getClientNotificationForPhone();
bool hasPacket = !!queueStatusPacketForPhone || !!mqttClientProxyMessageForPhone || !!clientNotification;
if (hasPacket)
return true;
#ifdef FSCom
if (xmodemPacketForPhone.control == meshtastic_XModem_Control_NUL)
xmodemPacketForPhone = xModem.getForPhone();
if (xmodemPacketForPhone.control != meshtastic_XModem_Control_NUL) {
xModem.resetForPhone();
return true;
}
#endif
#ifdef ARCH_ESP32
#if !MESHTASTIC_EXCLUDE_STOREFORWARD
// Check if StoreForward has packets stored for us.
if (!packetForPhone && storeForwardModule)
packetForPhone = storeForwardModule->getForPhone();
#endif
#endif
if (!packetForPhone)
packetForPhone = service->getForPhone();
hasPacket = !!packetForPhone;
return hasPacket;
}
default:
LOG_ERROR("PhoneAPI::available unexpected state %d", state);
}
return false;
}
void PhoneAPI::sendNotification(meshtastic_LogRecord_Level level, uint32_t replyId, const char *message)
{
meshtastic_ClientNotification *cn = clientNotificationPool.allocZeroed();
cn->has_reply_id = true;
cn->reply_id = replyId;
cn->level = meshtastic_LogRecord_Level_WARNING;
cn->time = getValidTime(RTCQualityFromNet);
strncpy(cn->message, message, sizeof(cn->message));
service->sendClientNotification(cn);
}
bool PhoneAPI::wasSeenRecently(uint32_t id)
{
for (int i = 0; i < 20; i++) {
if (recentToRadioPacketIds[i] == id) {
return true;
}
if (recentToRadioPacketIds[i] == 0) {
recentToRadioPacketIds[i] = id;
return false;
}
}
// If the array is full, shift all elements to the left and add the new id at the end
memmove(recentToRadioPacketIds, recentToRadioPacketIds + 1, (19) * sizeof(uint32_t));
recentToRadioPacketIds[19] = id;
return false;
}
/**
* Handle a packet that the phone wants us to send. It is our responsibility to free the packet to the pool
*/
bool PhoneAPI::handleToRadioPacket(meshtastic_MeshPacket &p)
{
printPacket("PACKET FROM PHONE", &p);
#if defined(ARCH_PORTDUINO)
// For use with the simulator, we should not ignore duplicate packets from the phone
if (SimRadio::instance == nullptr)
#endif
if (p.id > 0 && wasSeenRecently(p.id)) {
LOG_DEBUG("Ignore packet from phone, already seen recently");
return false;
}
if (p.decoded.portnum == meshtastic_PortNum_TRACEROUTE_APP && lastPortNumToRadio[p.decoded.portnum] &&
Throttle::isWithinTimespanMs(lastPortNumToRadio[p.decoded.portnum], THIRTY_SECONDS_MS)) {
LOG_WARN("Rate limit portnum %d", p.decoded.portnum);
sendNotification(meshtastic_LogRecord_Level_WARNING, p.id, "TraceRoute can only be sent once every 30 seconds");
meshtastic_QueueStatus qs = router->getQueueStatus();
service->sendQueueStatusToPhone(qs, 0, p.id);
return false;
} else if (p.decoded.portnum == meshtastic_PortNum_TRACEROUTE_APP && isBroadcast(p.to) && p.hop_limit > 0) {
sendNotification(meshtastic_LogRecord_Level_WARNING, p.id, "Multi-hop traceroute to broadcast address is not allowed");
meshtastic_QueueStatus qs = router->getQueueStatus();
service->sendQueueStatusToPhone(qs, 0, p.id);
return false;
} else if (IS_ONE_OF(p.decoded.portnum, meshtastic_PortNum_POSITION_APP, meshtastic_PortNum_WAYPOINT_APP,
meshtastic_PortNum_ALERT_APP, meshtastic_PortNum_TELEMETRY_APP) &&
lastPortNumToRadio[p.decoded.portnum] &&
Throttle::isWithinTimespanMs(lastPortNumToRadio[p.decoded.portnum], TEN_SECONDS_MS)) {
// TODO: [Issue #6700] Make this rate limit throttling scale up / down with the preset
LOG_WARN("Rate limit portnum %d", p.decoded.portnum);
meshtastic_QueueStatus qs = router->getQueueStatus();
service->sendQueueStatusToPhone(qs, 0, p.id);
// FIXME: Figure out why this continues to happen
// sendNotification(meshtastic_LogRecord_Level_WARNING, p.id, "Position can only be sent once every 5 seconds");
return false;
} else if (p.decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP && lastPortNumToRadio[p.decoded.portnum] &&
Throttle::isWithinTimespanMs(lastPortNumToRadio[p.decoded.portnum], TWO_SECONDS_MS)) {
LOG_WARN("Rate limit portnum %d", p.decoded.portnum);
meshtastic_QueueStatus qs = router->getQueueStatus();
service->sendQueueStatusToPhone(qs, 0, p.id);
service->sendRoutingErrorResponse(meshtastic_Routing_Error_RATE_LIMIT_EXCEEDED, &p);
// sendNotification(meshtastic_LogRecord_Level_WARNING, p.id, "Text messages can only be sent once every 2 seconds");
return false;
}
// Upgrade traceroute requests from phone to use reliable delivery, matching TraceRouteModule
if (p.decoded.portnum == meshtastic_PortNum_TRACEROUTE_APP && !isBroadcast(p.to)) {
// Use reliable delivery for traceroute requests (which will be copied to traceroute responses by setReplyTo)
p.want_ack = true;
}
lastPortNumToRadio[p.decoded.portnum] = millis();
service->handleToRadio(p);
return true;
}
/// If the mesh service tells us fromNum has changed, tell the phone
int PhoneAPI::onNotify(uint32_t newValue)
{
bool timeout = checkConnectionTimeout(); // a handy place to check if we've heard from the phone (since the BLE version
// doesn't call this from idle)
if (state == STATE_SEND_PACKETS) {
LOG_INFO("Tell client we have new packets %u", newValue);
onNowHasData(newValue);
} else {
LOG_DEBUG("Client not yet interested in packets (state=%d)", state);
}
return timeout ? -1 : 0; // If we timed out, MeshService should stop iterating through observers as we just removed one
}
@@ -0,0 +1,203 @@
#pragma once
#include "Observer.h"
#include "concurrency/Lock.h"
#include "mesh-pb-constants.h"
#include "meshtastic/portnums.pb.h"
#include <deque>
#include <iterator>
#include <string>
#include <unordered_map>
#include <vector>
// Make sure that we never let our packets grow too large for one BLE packet
#define MAX_TO_FROM_RADIO_SIZE 512
#if meshtastic_FromRadio_size > MAX_TO_FROM_RADIO_SIZE
#error "meshtastic_FromRadio_size is too large for our BLE packets"
#endif
#if meshtastic_ToRadio_size > MAX_TO_FROM_RADIO_SIZE
#error "meshtastic_ToRadio_size is too large for our BLE packets"
#endif
#define SPECIAL_NONCE_ONLY_CONFIG 69420
#define SPECIAL_NONCE_ONLY_NODES 69421 // ( ͡° ͜ʖ ͡°)
/**
* Provides our protobuf based API which phone/PC clients can use to talk to our device
* over UDP, bluetooth or serial.
*
* Subclass to customize behavior for particular type of transport (BLE, UDP, TCP, serial)
*
* Eventually there should be once instance of this class for each live connection (because it has a bit of state
* for that connection)
*/
class PhoneAPI
: public Observer<uint32_t> // FIXME, we shouldn't be inheriting from Observer, instead use CallbackObserver as a member
{
enum State {
STATE_SEND_NOTHING, // Initial state, don't send anything until the client starts asking for config
STATE_SEND_UIDATA, // send stored data for device-ui
STATE_SEND_MY_INFO, // send our my info record
STATE_SEND_OWN_NODEINFO,
STATE_SEND_METADATA,
STATE_SEND_CHANNELS, // Send all channels
STATE_SEND_CONFIG, // Replacement for the old Radioconfig
STATE_SEND_MODULECONFIG, // Send Module specific config
STATE_SEND_OTHER_NODEINFOS, // states progress in this order as the device sends to to the client
STATE_SEND_FILEMANIFEST, // Send file manifest
STATE_SEND_COMPLETE_ID,
STATE_SEND_PACKETS // send packets or debug strings
};
State state = STATE_SEND_NOTHING;
uint8_t config_state = 0;
// Hashmap of timestamps for last time we received a packet on the API per portnum
std::unordered_map<meshtastic_PortNum, uint32_t> lastPortNumToRadio;
uint32_t recentToRadioPacketIds[20]; // Last 20 ToRadio MeshPacket IDs we have seen
/**
* Each packet sent to the phone has an incrementing count
*/
uint32_t fromRadioNum = 0;
/// We temporarily keep the packet here between the call to available and getFromRadio. We will free it after the phone
/// downloads it
meshtastic_MeshPacket *packetForPhone = NULL;
// file transfer packets destined for phone. Push it to the queue then free it.
meshtastic_XModem xmodemPacketForPhone = meshtastic_XModem_init_zero;
// Keep QueueStatus packet just as packetForPhone
meshtastic_QueueStatus *queueStatusPacketForPhone = NULL;
// Keep MqttClientProxyMessage packet just as packetForPhone
meshtastic_MqttClientProxyMessage *mqttClientProxyMessageForPhone = NULL;
// Keep ClientNotification packet just as packetForPhone
meshtastic_ClientNotification *clientNotification = NULL;
/// We temporarily keep the nodeInfo here between the call to available and getFromRadio
meshtastic_NodeInfo nodeInfoForPhone = meshtastic_NodeInfo_init_default;
// Prefetched node info entries ready for immediate transmission to the phone.
std::deque<meshtastic_NodeInfo> nodeInfoQueue;
// Tunable size of the node info cache so we can keep BLE reads non-blocking.
static constexpr size_t kNodePrefetchDepth = 4;
// Protect nodeInfoForPhone + nodeInfoQueue because NimBLE callbacks run in a separate FreeRTOS task.
concurrency::Lock nodeInfoMutex;
meshtastic_ToRadio toRadioScratch = {
0}; // this is a static scratch object, any data must be copied elsewhere before returning
/// Use to ensure that clients don't get confused about old messages from the radio
uint32_t config_nonce = 0;
uint32_t readIndex = 0;
std::vector<meshtastic_FileInfo> filesManifest = {};
void resetReadIndex() { readIndex = 0; }
public:
PhoneAPI();
/// Destructor - calls close()
virtual ~PhoneAPI();
// Call this when the client drops the connection, resets the state to STATE_SEND_NOTHING
// Unregisters our observer. A closed connection **can** be reopened by calling init again.
virtual void close();
/**
* Handle a ToRadio protobuf
* @return true true if a packet was queued for sending (so that caller can yield)
*/
virtual bool handleToRadio(const uint8_t *buf, size_t len);
/**
* Send a (client)notification to the phone
*/
virtual void sendNotification(meshtastic_LogRecord_Level level, uint32_t replyId, const char *message);
/**
* Get the next packet we want to send to the phone
*
* We assume buf is at least FromRadio_size bytes long.
* Returns number of bytes in the FromRadio packet (or 0 if no packet available)
*/
size_t getFromRadio(uint8_t *buf);
void sendConfigComplete();
/**
* Return true if we have data available to send to the phone
*/
bool available();
bool isConnected() { return state != STATE_SEND_NOTHING; }
bool isSendingPackets() { return state == STATE_SEND_PACKETS; }
protected:
/// Our fromradio packet while it is being assembled
meshtastic_FromRadio fromRadioScratch = {};
/** the last msec we heard from the client on the other side of this link */
uint32_t lastContactMsec = 0;
/// Hookable to find out when connection changes
virtual void onConnectionChanged(bool connected) {}
/// If we haven't heard from the other side in a while then say not connected. Returns true if timeout occurred
bool checkConnectionTimeout();
/// Check the current underlying physical link to see if the client is currently connected
virtual bool checkIsConnected() = 0;
/**
* Subclasses can use this as a hook to provide custom notifications for their transport (i.e. bluetooth notifies)
*/
virtual void onNowHasData(uint32_t fromRadioNum) {}
/// Subclasses can use these lifecycle hooks for transport-specific behavior around config/steady-state
/// (i.e. BLE connection params)
virtual void onConfigStart() {}
virtual void onConfigComplete() {}
/// begin a new connection
void handleStartConfig();
enum APIType {
TYPE_NONE, // Initial state, don't send anything until the client starts asking for config
TYPE_BLE,
TYPE_WIFI,
TYPE_SERIAL,
TYPE_PACKET,
TYPE_HTTP,
TYPE_ETH
};
APIType api_type = TYPE_NONE;
private:
void releasePhonePacket();
void releaseQueueStatusPhonePacket();
void prefetchNodeInfos();
void releaseMqttClientProxyPhonePacket();
void releaseClientNotification();
bool wasSeenRecently(uint32_t packetId);
/**
* Handle a packet that the phone wants us to send. We can write to it but can not keep a reference to it
* @return true true if a packet was queued for sending
*/
bool handleToRadioPacket(meshtastic_MeshPacket &p);
/// If the mesh service tells us fromNum has changed, tell the phone
virtual int onNotify(uint32_t newValue) override;
};
@@ -0,0 +1,30 @@
#pragma once
#include "TypedQueue.h"
/**
* A wrapper for freertos queues that assumes each element is a pointer
*/
template <class T> class PointerQueue : public TypedQueue<T *>
{
public:
explicit PointerQueue(int maxElements) : TypedQueue<T *>(maxElements) {}
// returns a ptr or null if the queue was empty
T *dequeuePtr(TickType_t maxWait = portMAX_DELAY)
{
T *p;
return this->dequeue(&p, maxWait) ? p : nullptr;
}
#ifdef HAS_FREE_RTOS
// returns a ptr or null if the queue was empty
T *dequeuePtrFromISR(BaseType_t *higherPriWoken)
{
T *p;
return this->dequeueFromISR(&p, higherPriWoken) ? p : nullptr;
}
#endif
};
@@ -0,0 +1,2 @@
#include "ProtobufModule.h"
#include "configuration.h"
@@ -0,0 +1,123 @@
#pragma once
#include "SinglePortModule.h"
/**
* A base class for mesh modules that assume that they are sending/receiving one particular protobuf based
* payload. Using one particular app ID.
*
* If you are using protobufs to encode your packets (recommended) you can use this as a baseclass for your module
* and avoid a bunch of boilerplate code.
*/
template <class T> class ProtobufModule : protected SinglePortModule
{
const pb_msgdesc_t *fields;
public:
uint16_t numOnlineNodes = 0;
/** Constructor
* name is for debugging output
*/
ProtobufModule(const char *_name, meshtastic_PortNum _ourPortNum, const pb_msgdesc_t *_fields)
: SinglePortModule(_name, _ourPortNum), fields(_fields)
{
}
protected:
/**
* Handle a received message, the data field in the message is already decoded and is provided
*
* In general decoded will always be !NULL. But in some special applications (where you have handling packets
* for multiple port numbers, decoding will ONLY be attempted for packets where the portnum matches our expected ourPortNum.
*/
virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, T *decoded) = 0;
/** Called to make changes to a particular incoming message
*/
virtual void alterReceivedProtobuf(meshtastic_MeshPacket &mp, T *decoded){};
/**
* Return a mesh packet which has been preinited with a particular protobuf data payload and port number.
* You can then send this packet (after customizing any of the payload fields you might need) with
* service->sendToMesh()
*/
meshtastic_MeshPacket *allocDataProtobuf(const T &payload)
{
// Update our local node info with our position (even if we don't decide to update anyone else)
meshtastic_MeshPacket *p = allocDataPacket();
p->decoded.payload.size =
pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), fields, &payload);
// LOG_DEBUG("did encode");
return p;
}
/**
* Gets the short name from the sender of the mesh packet
* Returns "???" if unknown sender
*/
const char *getSenderShortName(const meshtastic_MeshPacket &mp)
{
auto node = nodeDB->getMeshNode(getFrom(&mp));
const char *sender = (node) ? node->user.short_name : "???";
return sender;
}
int handleStatusUpdate(const meshtastic::Status *arg)
{
if (arg->getStatusType() == STATUS_TYPE_NODE) {
numOnlineNodes = nodeStatus->getNumOnline();
}
return 0;
}
private:
/** Called to handle a particular incoming message
@return ProcessMessage::STOP if you've guaranteed you've handled this message and no other handlers should be considered for
it
*/
virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp) override
{
// FIXME - we currently update position data in the DB only if the message was a broadcast or destined to us
// it would be better to update even if the message was destined to others.
auto &p = mp.decoded;
LOG_INFO("Received %s from=0x%0x, id=0x%x, portnum=%d, payloadlen=%d", name, mp.from, mp.id, p.portnum, p.payload.size);
T scratch;
T *decoded = NULL;
if (mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp.decoded.portnum == ourPortNum) {
memset(&scratch, 0, sizeof(scratch));
if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, fields, &scratch)) {
decoded = &scratch;
} else {
LOG_ERROR("Error decoding proto module!");
// if we can't decode it, nobody can process it!
return ProcessMessage::STOP;
}
}
return handleReceivedProtobuf(mp, decoded) ? ProcessMessage::STOP : ProcessMessage::CONTINUE;
}
/** Called to alter a particular incoming message
*/
virtual void alterReceived(meshtastic_MeshPacket &mp) override
{
T scratch;
T *decoded = NULL;
if (mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp.decoded.portnum == ourPortNum) {
memset(&scratch, 0, sizeof(scratch));
const meshtastic_Data &p = mp.decoded;
if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, fields, &scratch)) {
decoded = &scratch;
} else {
LOG_ERROR("Error decoding proto module!");
// if we can't decode it, nobody can process it!
return;
}
return alterReceivedProtobuf(mp, decoded);
}
}
};
@@ -0,0 +1,341 @@
#if RADIOLIB_EXCLUDE_SX127X != 1
#include "RF95Interface.h"
#include "MeshRadio.h" // kinda yucky, but we need to know which region we are in
#include "RadioLibRF95.h"
#include "configuration.h"
#include "error.h"
#if ARCH_PORTDUINO
#include "PortduinoGlue.h"
#endif
#if ARCH_PORTDUINO
#define RF95_MAX_POWER portduino_config.rf95_max_power
#endif
#ifndef RF95_MAX_POWER
#define RF95_MAX_POWER 20
#endif
// if we use 20 we are limited to 1% duty cycle or hw might overheat. For continuous operation set a limit of 17
// In theory up to 27 dBm is possible, but the modules installed in most radios can cope with a max of 20. So BIG WARNING
// if you set power to something higher than 17 or 20 you might fry your board.
#if defined(RADIOMASTER_900_BANDIT_NANO) || defined(RADIOMASTER_900_BANDIT)
// Structure to hold DAC and DB values
typedef struct {
uint8_t dac;
uint8_t db;
} DACDB;
// Interpolation function
DACDB interpolate(uint8_t dbm, uint8_t dbm1, uint8_t dbm2, DACDB val1, DACDB val2)
{
DACDB result;
double fraction = (double)(dbm - dbm1) / (dbm2 - dbm1);
result.dac = (uint8_t)(val1.dac + fraction * (val2.dac - val1.dac));
result.db = (uint8_t)(val1.db + fraction * (val2.db - val1.db));
return result;
}
// Function to find the correct DAC and DB values based on dBm using interpolation
DACDB getDACandDB(uint8_t dbm)
{
// Predefined values
static const struct {
uint8_t dbm;
DACDB values;
}
#ifdef RADIOMASTER_900_BANDIT_NANO
dbmToDACDB[] = {
{20, {168, 2}}, // 100mW
{24, {148, 6}}, // 250mW
{27, {128, 9}}, // 500mW
{30, {90, 12}} // 1000mW
};
#endif
#ifdef RADIOMASTER_900_BANDIT
dbmToDACDB[] = {
{20, {165, 2}}, // 100mW
{24, {155, 6}}, // 250mW
{27, {142, 9}}, // 500mW
{30, {110, 10}} // 1000mW
};
#endif
const int numValues = sizeof(dbmToDACDB) / sizeof(dbmToDACDB[0]);
// Find the interval dbm falls within and interpolate
for (int i = 0; i < numValues - 1; i++) {
if (dbm >= dbmToDACDB[i].dbm && dbm <= dbmToDACDB[i + 1].dbm) {
return interpolate(dbm, dbmToDACDB[i].dbm, dbmToDACDB[i + 1].dbm, dbmToDACDB[i].values, dbmToDACDB[i + 1].values);
}
}
// Return a default value if no match is found and default to 100mW
#ifdef RADIOMASTER_900_BANDIT_NANO
DACDB defaultValue = {168, 2};
#endif
#ifdef RADIOMASTER_900_BANDIT
DACDB defaultValue = {165, 2};
#endif
return defaultValue;
}
#endif
RF95Interface::RF95Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: RadioLibInterface(hal, cs, irq, rst, busy)
{
LOG_DEBUG("RF95Interface(cs=%d, irq=%d, rst=%d, busy=%d)", cs, irq, rst, busy);
}
/** Some boards require GPIO control of tx vs rx paths */
void RF95Interface::setTransmitEnable(bool txon)
{
#ifdef RF95_TXEN
digitalWrite(RF95_TXEN, txon ? 1 : 0);
#elif ARCH_PORTDUINO
if (portduino_config.lora_txen_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_txen_pin.pin, txon ? 1 : 0);
}
#endif
#ifdef RF95_RXEN
digitalWrite(RF95_RXEN, txon ? 0 : 1);
#elif ARCH_PORTDUINO
if (portduino_config.lora_rxen_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_rxen_pin.pin, txon ? 0 : 1);
}
#endif
}
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
bool RF95Interface::init()
{
RadioLibInterface::init();
#if defined(RADIOMASTER_900_BANDIT_NANO) || defined(RADIOMASTER_900_BANDIT)
// DAC and DB values based on dBm using interpolation
DACDB dacDbValues = getDACandDB(power);
int8_t powerDAC = dacDbValues.dac;
power = dacDbValues.db;
#endif
limitPower(RF95_MAX_POWER);
iface = lora = new RadioLibRF95(&module);
#ifdef RF95_TCXO
pinMode(RF95_TCXO, OUTPUT);
digitalWrite(RF95_TCXO, 1);
#endif
// enable PA
#ifdef RF95_PA_EN
#if defined(RF95_PA_DAC_EN)
#if defined(RADIOMASTER_900_BANDIT_NANO) || defined(RADIOMASTER_900_BANDIT)
// Use calculated DAC value
dacWrite(RF95_PA_EN, powerDAC);
#else
// Use Value set in /*/variant.h
dacWrite(RF95_PA_EN, RF95_PA_LEVEL);
#endif
#endif
#endif
/*
#define RF95_TXEN (22) // If defined, this pin should be set high prior to transmit (controls an external analog switch)
#define RF95_RXEN (23) // If defined, this pin should be set high prior to receive (controls an external analog switch)
*/
#ifdef RF95_TXEN
pinMode(RF95_TXEN, OUTPUT);
digitalWrite(RF95_TXEN, 0);
#endif
#ifdef RF95_FAN_EN
pinMode(RF95_FAN_EN, OUTPUT);
digitalWrite(RF95_FAN_EN, 1);
#endif
#ifdef RF95_RXEN
pinMode(RF95_RXEN, OUTPUT);
digitalWrite(RF95_RXEN, 1);
#endif
#if ARCH_PORTDUINO
if (portduino_config.lora_txen_pin.pin != RADIOLIB_NC) {
pinMode(portduino_config.lora_txen_pin.pin, OUTPUT);
digitalWrite(portduino_config.lora_txen_pin.pin, 0);
}
if (portduino_config.lora_rxen_pin.pin != RADIOLIB_NC) {
pinMode(portduino_config.lora_rxen_pin.pin, OUTPUT);
digitalWrite(portduino_config.lora_rxen_pin.pin, 0);
}
#endif
setTransmitEnable(false);
int res = lora->begin(getFreq(), bw, sf, cr, syncWord, power, preambleLength);
LOG_INFO("RF95 init result %d", res);
LOG_INFO("Frequency set to %f", getFreq());
LOG_INFO("Bandwidth set to %f", bw);
LOG_INFO("Power output set to %d", power);
#if defined(RADIOMASTER_900_BANDIT_NANO) || defined(RADIOMASTER_900_BANDIT)
LOG_INFO("DAC output set to %d", powerDAC);
#endif
if (res == RADIOLIB_ERR_NONE)
res = lora->setCRC(RADIOLIB_SX126X_LORA_CRC_ON);
if (res == RADIOLIB_ERR_NONE)
startReceive(); // start receiving
return res == RADIOLIB_ERR_NONE;
}
void INTERRUPT_ATTR RF95Interface::disableInterrupt()
{
lora->clearDio0Action();
}
bool RF95Interface::reconfigure()
{
RadioLibInterface::reconfigure();
// set mode to standby
setStandby();
// configure publicly accessible settings
int err = lora->setSpreadingFactor(sf);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora->setBandwidth(bw);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora->setCodingRate(cr);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora->setSyncWord(syncWord);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("RF95 setSyncWord %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
err = lora->setCurrentLimit(currentLimit);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("RF95 setCurrentLimit %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
err = lora->setPreambleLength(preambleLength);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("RF95 setPreambleLength %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
err = lora->setFrequency(getFreq());
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
if (power > RF95_MAX_POWER) // This chip has lower power limits than some
power = RF95_MAX_POWER;
#ifdef USE_RF95_RFO
err = lora->setOutputPower(power, true);
#else
err = lora->setOutputPower(power);
#endif
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
startReceive(); // restart receiving
return RADIOLIB_ERR_NONE;
}
/**
* Add SNR data to received messages
*/
void RF95Interface::addReceiveMetadata(meshtastic_MeshPacket *mp)
{
mp->rx_snr = lora->getSNR();
mp->rx_rssi = lround(lora->getRSSI());
LOG_DEBUG("Corrected frequency offset: %f", lora->getFrequencyError());
}
void RF95Interface::setStandby()
{
int err = lora->standby();
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("RF95 standby %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
isReceiving = false; // If we were receiving, not any more
disableInterrupt();
completeSending(); // If we were sending, not anymore
RadioLibInterface::setStandby();
}
/** We override to turn on transmitter power as needed.
*/
void RF95Interface::configHardwareForSend()
{
setTransmitEnable(true);
RadioLibInterface::configHardwareForSend();
}
void RF95Interface::startReceive()
{
setTransmitEnable(false);
setStandby();
int err = lora->startReceive();
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("RF95 startReceive %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
isReceiving = true;
// Must be done AFTER, starting receive, because startReceive clears (possibly stale) interrupt pending register bits
enableInterrupt(isrRxLevel0);
}
bool RF95Interface::isChannelActive()
{
// check if we can detect a LoRa preamble on the current channel
int16_t result;
setTransmitEnable(false);
setStandby(); // needed for smooth transition
result = lora->scanChannel();
if (result == RADIOLIB_PREAMBLE_DETECTED) {
// LOG_DEBUG("Channel is busy!");
return true;
}
if (result != RADIOLIB_CHANNEL_FREE)
LOG_ERROR("RF95 isChannelActive %s%d", radioLibErr, result);
assert(result != RADIOLIB_ERR_WRONG_MODEM);
// LOG_DEBUG("Channel is free!");
return false;
}
/** Could we send right now (i.e. either not actively receiving or transmitting)? */
bool RF95Interface::isActivelyReceiving()
{
return lora->isReceiving();
}
bool RF95Interface::sleep()
{
// put chipset into sleep mode
setStandby(); // First cancel any active receiving/sending
lora->sleep();
#ifdef RF95_FAN_EN
digitalWrite(RF95_FAN_EN, 0);
#endif
return true;
}
#endif
@@ -0,0 +1,74 @@
#pragma once
#if RADIOLIB_EXCLUDE_SX127X != 1
#include "MeshRadio.h" // kinda yucky, but we need to know which region we are in
#include "RadioLibInterface.h"
#include "RadioLibRF95.h"
/**
* Our new not radiohead adapter for RF95 style radios
*/
class RF95Interface : public RadioLibInterface
{
RadioLibRF95 *lora = NULL; // Either a RFM95 or RFM96 depending on what was stuffed on this board
public:
RF95Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
// TODO: Verify that this irq flag works with RFM95 / SX1276 radios the way it used to
bool isIRQPending() override { return lora->getIRQFlags() & RADIOLIB_SX127X_MASK_IRQ_FLAG_VALID_HEADER; }
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool init() override;
/// Apply any radio provisioning changes
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool reconfigure() override;
/// Prepare hardware for sleep. Call this _only_ for deep sleep, not needed for light sleep.
virtual bool sleep() override;
protected:
/**
* Glue functions called from ISR land
*/
virtual void disableInterrupt() override;
/**
* Enable a particular ISR callback glue function
*/
virtual void enableInterrupt(void (*callback)()) { lora->setDio0Action(callback, RISING); }
/** can we detect a LoRa preamble on the current channel? */
virtual bool isChannelActive() override;
/** are we actively receiving a packet (only called during receiving state) */
virtual bool isActivelyReceiving() override;
/**
* Start waiting to receive a message
*/
virtual void startReceive() override;
/**
* Add SNR data to received messages
*/
virtual void addReceiveMetadata(meshtastic_MeshPacket *mp) override;
virtual void setStandby() override;
/**
* We override to turn on transmitter power as needed.
*/
virtual void configHardwareForSend() override;
uint32_t getPacketTime(uint32_t pl, bool received) override { return computePacketTime(*lora, pl, received); }
private:
/** Some boards require GPIO control of tx vs rx paths */
void setTransmitEnable(bool txon);
};
#endif
@@ -0,0 +1,714 @@
#include "RadioInterface.h"
#include "Channels.h"
#include "DisplayFormatters.h"
#include "MeshRadio.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "Router.h"
#include "configuration.h"
#include "main.h"
#include "sleep.h"
#include <assert.h>
#include <pb_decode.h>
#include <pb_encode.h>
// Calculate 2^n without calling pow()
uint32_t pow_of_2(uint32_t n)
{
return 1 << n;
}
#define RDEF(name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, frequency_switching, wide_lora) \
{ \
meshtastic_Config_LoRaConfig_RegionCode_##name, freq_start, freq_end, duty_cycle, spacing, power_limit, audio_permitted, \
frequency_switching, wide_lora, #name \
}
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, 0, 30, true, false, false),
/*
EN300220 ETSI V3.2.1 [Table B.1, Item H, p. 21]
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, 0, 10, true, false, false),
/*
https://www.thethingsnetwork.org/docs/lorawan/duty-cycle/
https://www.thethingsnetwork.org/docs/lorawan/regional-parameters/
https://www.legislation.gov.uk/uksi/1999/930/schedule/6/part/III/made/data.xht?view=snippet&wrap=true
audio_permitted = false per regulation
Special Note:
The link above describes LoRaWAN's band plan, stating a power limit of 16 dBm. This is their own suggested specification,
we do not need to follow it. The European Union regulations clearly state that the power limit for this frequency range is
500 mW, or 27 dBm. It also states that we can use interference avoidance and spectrum access techniques (such as LBT +
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, 0, 27, false, false, false),
/*
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
*/
RDEF(CN, 470.0f, 510.0f, 100, 0, 19, true, false, false),
/*
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, 0, 13, true, false, false),
/*
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, 0, 30, true, false, false),
/*
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, 0, 14, true, false, false),
/*
https://digital.gov.ru/uploaded/files/prilozhenie-12-k-reshenyu-gkrch-18-46-03-1.pdf
Note:
- We do LBT, so 100% is allowed.
*/
RDEF(RU, 868.7f, 869.2f, 100, 0, 20, true, false, false),
/*
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, 0, 23, true, false, false),
/*
Taiwan, 920-925Mhz, limited to 0.5W indoor or coastal, 1.0W outdoor.
5.8.1 in the Low-power Radio-frequency Devices Technical Regulations
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, 0, 27, true, false, false),
/*
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
*/
RDEF(IN, 865.0f, 867.0f, 100, 0, 30, true, false, false),
/*
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, 0, 36, true, false, false),
/*
https://lora-alliance.org/wp-content/uploads/2020/11/lorawan_regional_parameters_v1.0.3reva_0.pdf
*/
RDEF(TH, 920.0f, 925.0f, 100, 0, 16, true, false, false),
/*
433,05-434,7 Mhz 10 mW
https://nkrzi.gov.ua/images/upload/256/5810/PDF_UUZ_19_01_2016.pdf
*/
RDEF(UA_433, 433.0f, 434.7f, 10, 0, 10, true, false, false),
/*
868,0-868,6 Mhz 25 mW
https://nkrzi.gov.ua/images/upload/256/5810/PDF_UUZ_19_01_2016.pdf
*/
RDEF(UA_868, 868.0f, 868.6f, 1, 0, 14, true, false, false),
/*
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, 0, 20, true, false, false),
/*
Malaysia
919 - 923 Mhz at 500mW, no restrictions.
923 - 924 MHz at 500mW with 1% duty cycle OR frequency hopping.
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, 0, 27, true, true, false),
/*
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, 0, 20, true, false, false),
/*
Philippines
433 - 434.7 MHz <10 mW erp, NTC approved device required
868 - 869.4 MHz <25 mW erp, NTC approved device required
915 - 918 MHz <250 mW EIRP, no external antenna allowed
https://github.com/meshtastic/firmware/issues/4948#issuecomment-2394926135
*/
RDEF(PH_433, 433.0f, 434.7f, 100, 0, 10, true, false, false), RDEF(PH_868, 868.0f, 869.4f, 100, 0, 14, true, false, false),
RDEF(PH_915, 915.0f, 918.0f, 100, 0, 24, true, false, false),
/*
Kazakhstan
433.075 - 434.775 MHz <10 mW EIRP, Low Powered Devices (LPD)
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, 0, 10, true, false, false), RDEF(KZ_863, 863.0f, 868.0f, 100, 0, 30, true, false, true),
/*
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, 0, 30, true, false, false),
/*
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, 0, 30, true, false, false),
/*
2.4 GHZ WLAN Band equivalent. Only for SX128x chips.
*/
RDEF(LORA_24, 2400.0f, 2483.5f, 100, 0, 10, true, false, true),
/*
This needs to be last. Same as US.
*/
RDEF(UNSET, 902.0f, 928.0f, 100, 0, 30, true, false, false)
};
const RegionInfo *myRegion;
bool RadioInterface::uses_default_frequency_slot = true;
static uint8_t bytes[MAX_LORA_PAYLOAD_LEN + 1];
void initRegion()
{
const RegionInfo *r = regions;
#ifdef REGULATORY_LORA_REGIONCODE
for (; r->code != meshtastic_Config_LoRaConfig_RegionCode_UNSET && r->code != REGULATORY_LORA_REGIONCODE; r++)
;
LOG_INFO("Wanted region %d, regulatory override to %s", config.lora.region, r->name);
#else
for (; r->code != meshtastic_Config_LoRaConfig_RegionCode_UNSET && r->code != config.lora.region; r++)
;
LOG_INFO("Wanted region %d, using %s", config.lora.region, r->name);
#endif
myRegion = r;
}
/**
* ## LoRaWAN for North America
LoRaWAN defines 64, 125 kHz channels from 902.3 to 914.9 MHz increments.
The maximum output power for North America is +30 dBM.
The band is from 902 to 928 MHz. It mentions channel number and its respective channel frequency. All the 13 channels are
separated by 2.16 MHz with respect to the adjacent channels. Channel zero starts at 903.08 MHz center frequency.
*/
uint32_t RadioInterface::getPacketTime(const meshtastic_MeshPacket *p, bool received)
{
uint32_t pl = 0;
if (p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag) {
pl = p->encrypted.size + sizeof(PacketHeader);
} else {
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_Data_msg, &p->decoded);
pl = numbytes + sizeof(PacketHeader);
}
return getPacketTime(pl, received);
}
/** The delay to use for retransmitting dropped packets */
uint32_t RadioInterface::getRetransmissionMsec(const meshtastic_MeshPacket *p)
{
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_Data_msg, &p->decoded);
uint32_t packetAirtime = getPacketTime(numbytes + sizeof(PacketHeader));
// Make sure enough time has elapsed for this packet to be sent and an ACK is received.
// LOG_DEBUG("Waiting for flooding message with airtime %d and slotTime is %d", packetAirtime, slotTimeMsec);
float channelUtil = airTime->channelUtilizationPercent();
uint8_t CWsize = map(channelUtil, 0, 100, CWmin, CWmax);
// Assuming we pick max. of CWsize and there will be a client with SNR at half the range
return 2 * packetAirtime + (pow_of_2(CWsize) + 2 * CWmax + pow_of_2(int((CWmax + CWmin) / 2))) * slotTimeMsec +
PROCESSING_TIME_MSEC;
}
/** The delay to use when we want to send something */
uint32_t RadioInterface::getTxDelayMsec()
{
/** We wait a random multiple of 'slotTimes' (see definition in header file) in order to avoid collisions.
The pool to take a random multiple from is the contention window (CW), which size depends on the
current channel utilization. */
float channelUtil = airTime->channelUtilizationPercent();
uint8_t CWsize = map(channelUtil, 0, 100, CWmin, CWmax);
// LOG_DEBUG("Current channel utilization is %f so setting CWsize to %d", channelUtil, CWsize);
return random(0, pow_of_2(CWsize)) * slotTimeMsec;
}
/** The CW size to use when calculating SNR_based delays */
uint8_t RadioInterface::getCWsize(float snr)
{
// The minimum value for a LoRa SNR
const int32_t SNR_MIN = -20;
// The maximum value for a LoRa SNR
const int32_t SNR_MAX = 10;
return map(snr, SNR_MIN, SNR_MAX, CWmin, CWmax);
}
/** The worst-case SNR_based packet delay */
uint32_t RadioInterface::getTxDelayMsecWeightedWorst(float snr)
{
uint8_t CWsize = getCWsize(snr);
// offset the maximum delay for routers: (2 * CWmax * slotTimeMsec)
return (2 * CWmax * slotTimeMsec) + pow_of_2(CWsize) * slotTimeMsec;
}
/** Returns true if we should rebroadcast early like a ROUTER */
bool RadioInterface::shouldRebroadcastEarlyLikeRouter(meshtastic_MeshPacket *p)
{
// If we are a ROUTER, we always rebroadcast early
if (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER) {
return true;
}
// If we are a CLIENT_BASE and the packet is from or to a favorited node, we should rebroadcast early
if (config.device.role == meshtastic_Config_DeviceConfig_Role_CLIENT_BASE) {
return nodeDB->isFromOrToFavoritedNode(*p);
}
return false;
}
/** The delay to use when we want to flood a message */
uint32_t RadioInterface::getTxDelayMsecWeighted(meshtastic_MeshPacket *p)
{
// high SNR = large CW size (Long Delay)
// low SNR = small CW size (Short Delay)
float snr = p->rx_snr;
uint32_t delay = 0;
uint8_t CWsize = getCWsize(snr);
// LOG_DEBUG("rx_snr of %f so setting CWsize to:%d", snr, CWsize);
if (shouldRebroadcastEarlyLikeRouter(p)) {
delay = random(0, 2 * CWsize) * slotTimeMsec;
LOG_DEBUG("rx_snr found in packet. Router: setting tx delay:%d", delay);
} else {
// offset the maximum delay for routers: (2 * CWmax * slotTimeMsec)
delay = (2 * CWmax * slotTimeMsec) + random(0, pow_of_2(CWsize)) * slotTimeMsec;
LOG_DEBUG("rx_snr found in packet. Setting tx delay:%d", delay);
}
return delay;
}
void printPacket(const char *prefix, const meshtastic_MeshPacket *p)
{
#if defined(DEBUG_PORT) && !defined(DEBUG_MUTE)
std::string out =
DEBUG_PORT.mt_sprintf("%s (id=0x%08x fr=0x%08x to=0x%08x, transport = %u, WantAck=%d, HopLim=%d Ch=0x%x", prefix, p->id,
p->from, p->to, p->transport_mechanism, p->want_ack, p->hop_limit, p->channel);
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
auto &s = p->decoded;
out += DEBUG_PORT.mt_sprintf(" Portnum=%d", s.portnum);
if (s.want_response)
out += DEBUG_PORT.mt_sprintf(" WANTRESP");
if (p->pki_encrypted)
out += DEBUG_PORT.mt_sprintf(" PKI");
if (s.source != 0)
out += DEBUG_PORT.mt_sprintf(" source=%08x", s.source);
if (s.dest != 0)
out += DEBUG_PORT.mt_sprintf(" dest=%08x", s.dest);
if (s.request_id)
out += DEBUG_PORT.mt_sprintf(" requestId=%0x", s.request_id);
/* now inside Data and therefore kinda opaque
if (s.which_ackVariant == SubPacket_success_id_tag)
out += DEBUG_PORT.mt_sprintf(" successId=%08x", s.ackVariant.success_id);
else if (s.which_ackVariant == SubPacket_fail_id_tag)
out += DEBUG_PORT.mt_sprintf(" failId=%08x", s.ackVariant.fail_id); */
} else {
out += " encrypted";
out += DEBUG_PORT.mt_sprintf(" len=%d", p->encrypted.size + sizeof(PacketHeader));
}
if (p->rx_time != 0)
out += DEBUG_PORT.mt_sprintf(" rxtime=%u", p->rx_time);
if (p->rx_snr != 0.0)
out += DEBUG_PORT.mt_sprintf(" rxSNR=%g", p->rx_snr);
if (p->rx_rssi != 0)
out += DEBUG_PORT.mt_sprintf(" rxRSSI=%i", p->rx_rssi);
if (p->via_mqtt != 0)
out += DEBUG_PORT.mt_sprintf(" via MQTT");
if (p->hop_start != 0)
out += DEBUG_PORT.mt_sprintf(" hopStart=%d", p->hop_start);
if (p->next_hop != 0)
out += DEBUG_PORT.mt_sprintf(" nextHop=0x%x", p->next_hop);
if (p->relay_node != 0)
out += DEBUG_PORT.mt_sprintf(" relay=0x%x", p->relay_node);
if (p->priority != 0)
out += DEBUG_PORT.mt_sprintf(" priority=%d", p->priority);
out += ")";
LOG_DEBUG("%s", out.c_str());
#endif
}
RadioInterface::RadioInterface()
{
assert(sizeof(PacketHeader) == MESHTASTIC_HEADER_LENGTH); // make sure the compiler did what we expected
}
bool RadioInterface::reconfigure()
{
applyModemConfig();
return true;
}
bool RadioInterface::init()
{
LOG_INFO("Start meshradio init");
configChangedObserver.observe(&service->configChanged);
preflightSleepObserver.observe(&preflightSleep);
notifyDeepSleepObserver.observe(&notifyDeepSleep);
// we now expect interfaces to operate in promiscuous mode
// radioIf.setThisAddress(nodeDB->getNodeNum()); // Note: we must do this here, because the nodenum isn't inited at
// constructor time.
applyModemConfig();
return true;
}
int RadioInterface::notifyDeepSleepCb(void *unused)
{
sleep();
return 0;
}
/** hash a string into an integer
*
* djb2 by Dan Bernstein.
* http://www.cse.yorku.ca/~oz/hash.html
*/
uint32_t hash(const char *str)
{
uint32_t hash = 5381;
int c;
while ((c = *str++) != 0)
hash = ((hash << 5) + hash) + (unsigned char)c; /* hash * 33 + c */
return hash;
}
/**
* Save our frequency for later reuse.
*/
void RadioInterface::saveFreq(float freq)
{
savedFreq = freq;
}
/**
* Save our channel for later reuse.
*/
void RadioInterface::saveChannelNum(uint32_t channel_num)
{
savedChannelNum = channel_num;
}
/**
* Save our frequency for later reuse.
*/
float RadioInterface::getFreq()
{
return savedFreq;
}
/**
* Save our channel for later reuse.
*/
uint32_t RadioInterface::getChannelNum()
{
return savedChannelNum;
}
/**
* Pull our channel settings etc... from protobufs to the dumb interface settings
*/
void RadioInterface::applyModemConfig()
{
// Set up default configuration
// No Sync Words in LORA mode
meshtastic_Config_LoRaConfig &loraConfig = config.lora;
bool validConfig = false; // We need to check for a valid configuration
while (!validConfig) {
if (loraConfig.use_preset) {
switch (loraConfig.modem_preset) {
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_TURBO:
bw = (myRegion->wideLora) ? 1625.0 : 500;
cr = 5;
sf = 7;
break;
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST:
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 5;
sf = 7;
break;
case meshtastic_Config_LoRaConfig_ModemPreset_SHORT_SLOW:
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 5;
sf = 8;
break;
case meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_FAST:
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 5;
sf = 9;
break;
case meshtastic_Config_LoRaConfig_ModemPreset_MEDIUM_SLOW:
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 5;
sf = 10;
break;
default: // Config_LoRaConfig_ModemPreset_LONG_FAST is default. Gracefully use this is preset is something illegal.
bw = (myRegion->wideLora) ? 812.5 : 250;
cr = 5;
sf = 11;
break;
case meshtastic_Config_LoRaConfig_ModemPreset_LONG_MODERATE:
bw = (myRegion->wideLora) ? 406.25 : 125;
cr = 8;
sf = 11;
break;
case meshtastic_Config_LoRaConfig_ModemPreset_LONG_SLOW:
bw = (myRegion->wideLora) ? 406.25 : 125;
cr = 8;
sf = 12;
break;
}
} else {
sf = loraConfig.spread_factor;
cr = loraConfig.coding_rate;
bw = loraConfig.bandwidth;
if (bw == 31) // This parameter is not an integer
bw = 31.25;
if (bw == 62) // Fix for 62.5Khz bandwidth
bw = 62.5;
if (bw == 200)
bw = 203.125;
if (bw == 400)
bw = 406.25;
if (bw == 800)
bw = 812.5;
if (bw == 1600)
bw = 1625.0;
}
if ((myRegion->freqEnd - myRegion->freqStart) < bw / 1000) {
static const char *err_string = "Regional frequency range is smaller than bandwidth. Fall back to default preset";
LOG_ERROR(err_string);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
meshtastic_ClientNotification *cn = clientNotificationPool.allocZeroed();
cn->level = meshtastic_LogRecord_Level_ERROR;
sprintf(cn->message, err_string);
service->sendClientNotification(cn);
// Set to default modem preset
loraConfig.use_preset = true;
loraConfig.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST;
} else {
validConfig = true;
}
}
power = loraConfig.tx_power;
if ((power == 0) || ((power > myRegion->powerLimit) && !devicestate.owner.is_licensed))
power = myRegion->powerLimit;
if (power == 0)
power = 17; // Default to this power level if we don't have a valid regional power limit (powerLimit of myRegion defaults
// to 0, currently no region has an actual power limit of 0 [dBm] so we can assume regions which have this
// variable set to 0 don't have a valid power limit)
// Set final tx_power back onto config
loraConfig.tx_power = (int8_t)power; // cppcheck-suppress assignmentAddressToInteger
// Calculate the number of channels
uint32_t numChannels = floor((myRegion->freqEnd - myRegion->freqStart) / (myRegion->spacing + (bw / 1000)));
// If user has manually specified a channel num, then use that, otherwise generate one by hashing the name
const char *channelName = channels.getName(channels.getPrimaryIndex());
// channel_num is actually (channel_num - 1), since modulus (%) returns values from 0 to (numChannels - 1)
uint32_t channel_num = (loraConfig.channel_num ? loraConfig.channel_num - 1 : hash(channelName)) % numChannels;
// Check if we use the default frequency slot
RadioInterface::uses_default_frequency_slot =
channel_num ==
hash(DisplayFormatters::getModemPresetDisplayName(config.lora.modem_preset, false, config.lora.use_preset)) % numChannels;
// Old frequency selection formula
// float freq = myRegion->freqStart + ((((myRegion->freqEnd - myRegion->freqStart) / numChannels) / 2) * channel_num);
// New frequency selection formula
float freq = myRegion->freqStart + (bw / 2000) + (channel_num * (bw / 1000));
// override if we have a verbatim frequency
if (loraConfig.override_frequency) {
freq = loraConfig.override_frequency;
channel_num = -1;
}
saveChannelNum(channel_num);
saveFreq(freq + loraConfig.frequency_offset);
slotTimeMsec = computeSlotTimeMsec();
preambleTimeMsec = preambleLength * (pow_of_2(sf) / bw);
LOG_INFO("Radio freq=%.3f, config.lora.frequency_offset=%.3f", freq, loraConfig.frequency_offset);
LOG_INFO("Set radio: region=%s, name=%s, config=%u, ch=%d, power=%d", myRegion->name, channelName, loraConfig.modem_preset,
channel_num, power);
LOG_INFO("myRegion->freqStart -> myRegion->freqEnd: %f -> %f (%f MHz)", myRegion->freqStart, myRegion->freqEnd,
myRegion->freqEnd - myRegion->freqStart);
LOG_INFO("numChannels: %d x %.3fkHz", numChannels, bw);
LOG_INFO("channel_num: %d", channel_num + 1);
LOG_INFO("frequency: %f", getFreq());
LOG_INFO("Slot time: %u msec, preamble time: %u msec", slotTimeMsec, preambleTimeMsec);
}
/** Slottime is the time to detect a transmission has started, consisting of:
- CAD duration;
- roundtrip air propagation time (assuming max. 30km between nodes);
- Tx/Rx turnaround time (maximum of SX126x and SX127x);
- MAC processing time (measured on T-beam) */
uint32_t RadioInterface::computeSlotTimeMsec()
{
float sumPropagationTurnaroundMACTime = 0.2 + 0.4 + 7; // in milliseconds
float symbolTime = pow_of_2(sf) / bw; // in milliseconds
if (myRegion->wideLora) {
// CAD duration derived from AN1200.22 of SX1280
return (NUM_SYM_CAD_24GHZ + (2 * sf + 3) / 32) * symbolTime + sumPropagationTurnaroundMACTime;
} else {
// CAD duration for SX127x is max. 2.25 symbols, for SX126x it is number of symbols + 0.5 symbol
return max(2.25, NUM_SYM_CAD + 0.5) * symbolTime + sumPropagationTurnaroundMACTime;
}
}
/**
* Some regulatory regions limit xmit power.
* This function should be called by subclasses after setting their desired power. It might lower it
*/
void RadioInterface::limitPower(int8_t loraMaxPower)
{
uint8_t maxPower = 255; // No limit
if (myRegion->powerLimit)
maxPower = myRegion->powerLimit;
if ((power > maxPower) && !devicestate.owner.is_licensed) {
LOG_INFO("Lower transmit power because of regulatory limits");
power = maxPower;
}
#ifndef NUM_PA_POINTS
if (TX_GAIN_LORA > 0 && !devicestate.owner.is_licensed) {
LOG_INFO("Requested Tx power: %d dBm; Device LoRa Tx gain: %d dB", power, TX_GAIN_LORA);
power -= TX_GAIN_LORA;
}
#else
if (!devicestate.owner.is_licensed) {
// we have an array of PA gain values. Find the highest power setting that works.
const uint16_t tx_gain[NUM_PA_POINTS] = {TX_GAIN_LORA};
for (int radio_dbm = 0; radio_dbm < NUM_PA_POINTS; radio_dbm++) {
if (((radio_dbm + tx_gain[radio_dbm]) > power) ||
((radio_dbm == (NUM_PA_POINTS - 1)) && ((radio_dbm + tx_gain[radio_dbm]) <= power))) {
// we've exceeded the power limit, or hit the max we can do
LOG_INFO("Requested Tx power: %d dBm; Device LoRa Tx gain: %d dB", power, tx_gain[radio_dbm]);
power -= tx_gain[radio_dbm];
break;
}
}
}
#endif
if (power > loraMaxPower) // Clamp power to maximum defined level
power = loraMaxPower;
LOG_INFO("Final Tx power: %d dBm", power);
}
void RadioInterface::deliverToReceiver(meshtastic_MeshPacket *p)
{
if (router) {
p->transport_mechanism = meshtastic_MeshPacket_TransportMechanism_TRANSPORT_LORA;
router->enqueueReceivedMessage(p);
}
}
/***
* given a packet set sendingPacket and decode the protobufs into radiobuf. Returns # of payload bytes to send
*/
size_t RadioInterface::beginSending(meshtastic_MeshPacket *p)
{
assert(!sendingPacket);
// LOG_DEBUG("Send queued packet on mesh (txGood=%d,rxGood=%d,rxBad=%d)", rf95.txGood(), rf95.rxGood(), rf95.rxBad());
assert(p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag); // It should have already been encoded by now
radioBuffer.header.from = p->from;
radioBuffer.header.to = p->to;
radioBuffer.header.id = p->id;
radioBuffer.header.channel = p->channel;
radioBuffer.header.next_hop = p->next_hop;
radioBuffer.header.relay_node = p->relay_node;
if (p->hop_limit > HOP_MAX) {
LOG_WARN("hop limit %d is too high, setting to %d", p->hop_limit, HOP_RELIABLE);
p->hop_limit = HOP_RELIABLE;
}
radioBuffer.header.flags =
p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) | (p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0);
radioBuffer.header.flags |= (p->hop_start << PACKET_FLAGS_HOP_START_SHIFT) & PACKET_FLAGS_HOP_START_MASK;
// if the sender nodenum is zero, that means uninitialized
assert(radioBuffer.header.from);
assert(p->encrypted.size <= sizeof(radioBuffer.payload));
memcpy(radioBuffer.payload, p->encrypted.bytes, p->encrypted.size);
sendingPacket = p;
return p->encrypted.size + sizeof(PacketHeader);
}
@@ -0,0 +1,274 @@
#pragma once
#include "MemoryPool.h"
#include "MeshTypes.h"
#include "Observer.h"
#include "PointerQueue.h"
#include "airtime.h"
#include "error.h"
#define MAX_TX_QUEUE 16 // max number of packets which can be waiting for transmission
#define MAX_LORA_PAYLOAD_LEN 255 // max length of 255 per Semtech's datasheets on SX12xx
#define MESHTASTIC_HEADER_LENGTH 16
#define MESHTASTIC_PKC_OVERHEAD 12
#define PACKET_FLAGS_HOP_LIMIT_MASK 0x07
#define PACKET_FLAGS_WANT_ACK_MASK 0x08
#define PACKET_FLAGS_VIA_MQTT_MASK 0x10
#define PACKET_FLAGS_HOP_START_MASK 0xE0
#define PACKET_FLAGS_HOP_START_SHIFT 5
/**
* This structure has to exactly match the wire layout when sent over the radio link. Used to keep compatibility
* with the old radiohead implementation.
*/
typedef struct {
NodeNum to, from; // can be 1 byte or four bytes
PacketId id; // can be 1 byte or 4 bytes
/**
* Usage of flags:
*
* The bottom three bits of flags are use to store hop_limit when sent over the wire.
**/
uint8_t flags;
/** The channel hash - used as a hint for the decoder to limit which channels we consider */
uint8_t channel;
// Last byte of the NodeNum of the next-hop for this packet
uint8_t next_hop;
// Last byte of the NodeNum of the node that will relay/relayed this packet
uint8_t relay_node;
} PacketHeader;
/**
* This structure represent the structured buffer : a PacketHeader then the payload. The whole is
* MAX_LORA_PAYLOAD_LEN + 1 length
* It makes the use of its data easier, and avoids manipulating pointers (and potential non aligned accesses)
*/
typedef struct {
/** The header, as defined just before */
PacketHeader header;
/** The payload, of maximum length minus the header, aligned just to be sure */
uint8_t payload[MAX_LORA_PAYLOAD_LEN + 1 - sizeof(PacketHeader)] __attribute__((__aligned__));
} RadioBuffer;
/**
* Basic operations all radio chipsets must implement.
*
* This defines the SOLE API for talking to radios (because soon we will have alternate radio implementations)
*/
class RadioInterface
{
friend class MeshRadio; // for debugging we let that class touch pool
CallbackObserver<RadioInterface, void *> configChangedObserver =
CallbackObserver<RadioInterface, void *>(this, &RadioInterface::reloadConfig);
CallbackObserver<RadioInterface, void *> preflightSleepObserver =
CallbackObserver<RadioInterface, void *>(this, &RadioInterface::preflightSleepCb);
CallbackObserver<RadioInterface, void *> notifyDeepSleepObserver =
CallbackObserver<RadioInterface, void *>(this, &RadioInterface::notifyDeepSleepCb);
protected:
bool disabled = false;
float bw = 125;
uint8_t sf = 9;
uint8_t cr = 5;
const uint8_t NUM_SYM_CAD = 2; // Number of symbols used for CAD, 2 is the default since RadioLib 6.3.0 as per AN1200.48
const uint8_t NUM_SYM_CAD_24GHZ = 4; // Number of symbols used for CAD in 2.4 GHz, 4 is recommended in AN1200.22 of SX1280
uint32_t slotTimeMsec = computeSlotTimeMsec();
uint16_t preambleLength = 16; // 8 is default, but we use longer to increase the amount of sleep time when receiving
uint32_t preambleTimeMsec = 165; // calculated on startup, this is the default for LongFast
const uint32_t PROCESSING_TIME_MSEC =
4500; // time to construct, process and construct a packet again (empirically determined)
const uint8_t CWmin = 3; // minimum CWsize
const uint8_t CWmax = 8; // maximum CWsize
meshtastic_MeshPacket *sendingPacket = NULL; // The packet we are currently sending
uint32_t lastTxStart = 0L;
uint32_t computeSlotTimeMsec();
/**
* A temporary buffer used for sending/receiving packets, sized to hold the biggest buffer we might need
* */
RadioBuffer radioBuffer __attribute__((__aligned__));
/**
* Enqueue a received packet for the registered receiver
*/
void deliverToReceiver(meshtastic_MeshPacket *p);
public:
/** pool is the pool we will alloc our rx packets from
*/
RadioInterface();
virtual ~RadioInterface() {}
/**
* Return true if we think the board can go to sleep (i.e. our tx queue is empty, we are not sending or receiving)
*
* This method must be used before putting the CPU into deep or light sleep.
*/
virtual bool canSleep() { return true; }
virtual bool wideLora() { return false; }
/// Prepare hardware for sleep. Call this _only_ for deep sleep, not needed for light sleep.
virtual bool sleep() { return true; }
/// Disable this interface (while disabled, no packets can be sent or received)
void disable()
{
disabled = true;
sleep();
}
/**
* Send a packet (possibly by enquing in a private fifo). This routine will
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*/
virtual ErrorCode send(meshtastic_MeshPacket *p) = 0;
/** Return TX queue status */
virtual meshtastic_QueueStatus getQueueStatus()
{
meshtastic_QueueStatus qs;
qs.res = qs.mesh_packet_id = qs.free = qs.maxlen = 0;
return qs;
}
/** Attempt to cancel a previously sent packet. Returns true if a packet was found we could cancel */
virtual bool cancelSending(NodeNum from, PacketId id) { return false; }
/** Attempt to find a packet in the TxQueue. Returns true if the packet was found. */
virtual bool findInTxQueue(NodeNum from, PacketId id) { return false; }
// methods from radiohead
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool init();
/// Apply any radio provisioning changes
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool reconfigure();
/** The delay to use for retransmitting dropped packets */
uint32_t getRetransmissionMsec(const meshtastic_MeshPacket *p);
/** The delay to use when we want to send something */
uint32_t getTxDelayMsec();
/** The CW to use when calculating SNR_based delays */
uint8_t getCWsize(float snr);
/** The worst-case SNR_based packet delay */
uint32_t getTxDelayMsecWeightedWorst(float snr);
/** Returns true if we should rebroadcast early like a ROUTER */
bool shouldRebroadcastEarlyLikeRouter(meshtastic_MeshPacket *p);
/** The delay to use when we want to flood a message. Use a weighted scale based on SNR */
uint32_t getTxDelayMsecWeighted(meshtastic_MeshPacket *p);
/** If the packet is not already in the late rebroadcast window, move it there */
virtual void clampToLateRebroadcastWindow(NodeNum from, PacketId id) { return; }
/**
* If there is a packet pending TX in the queue with a worse hop limit, remove it pending replacement with a better version
* @return Whether a pending packet was removed
*/
virtual bool removePendingTXPacket(NodeNum from, PacketId id, uint32_t hop_limit_lt) { return false; }
/**
* Calculate airtime per
* https://www.rs-online.com/designspark/rel-assets/ds-assets/uploads/knowledge-items/application-notes-for-the-internet-of-things/LoRa%20Design%20Guide.pdf
* section 4
*
* @return num msecs for the packet
*/
uint32_t getPacketTime(const meshtastic_MeshPacket *p, bool received = false);
virtual uint32_t getPacketTime(uint32_t totalPacketLen, bool received = false) = 0;
/**
* Get the channel we saved.
*/
uint32_t getChannelNum();
/**
* Get the frequency we saved.
*/
virtual float getFreq();
/// Some boards (1st gen Pinetab Lora module) have broken IRQ wires, so we need to poll via i2c registers
virtual bool isIRQPending() { return false; }
// Whether we use the default frequency slot given our LoRa config (region and modem preset)
static bool uses_default_frequency_slot;
protected:
int8_t power = 17; // Set by applyModemConfig()
float savedFreq;
uint32_t savedChannelNum;
/***
* given a packet set sendingPacket and decode the protobufs into radiobuf. Returns # of bytes to send (including the
* PacketHeader & payload).
*
* Used as the first step of
*/
size_t beginSending(meshtastic_MeshPacket *p);
/**
* Some regulatory regions limit xmit power.
* This function should be called by subclasses after setting their desired power. It might lower it
*/
void limitPower(int8_t MAX_POWER);
/**
* Save the frequency we selected for later reuse.
*/
virtual void saveFreq(float savedFreq);
/**
* Save the channel we selected for later reuse.
*/
virtual void saveChannelNum(uint32_t savedChannelNum);
private:
/**
* Convert our modemConfig enum into wf, sf, etc...
*
* These parameters will be pull from the channelSettings global
*/
void applyModemConfig();
/// Return 0 if sleep is okay
int preflightSleepCb(void *unused = NULL) { return canSleep() ? 0 : 1; }
int notifyDeepSleepCb(void *unused = NULL);
int reloadConfig(void *unused)
{
reconfigure();
return 0;
}
};
/// Debug printing for packets
void printPacket(const char *prefix, const meshtastic_MeshPacket *p);
@@ -0,0 +1,566 @@
#include "RadioLibInterface.h"
#include "MeshTypes.h"
#include "NodeDB.h"
#include "PowerMon.h"
#include "SPILock.h"
#include "Throttle.h"
#include "configuration.h"
#include "error.h"
#include "main.h"
#include "mesh-pb-constants.h"
#include <pb_decode.h>
#include <pb_encode.h>
#if ARCH_PORTDUINO
#include "PortduinoGlue.h"
#include "meshUtils.h"
#endif
void LockingArduinoHal::spiBeginTransaction()
{
spiLock->lock();
ArduinoHal::spiBeginTransaction();
}
void LockingArduinoHal::spiEndTransaction()
{
ArduinoHal::spiEndTransaction();
spiLock->unlock();
}
#if ARCH_PORTDUINO
void LockingArduinoHal::spiTransfer(uint8_t *out, size_t len, uint8_t *in)
{
spi->transfer(out, in, len);
}
#endif
RadioLibInterface::RadioLibInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy, PhysicalLayer *_iface)
: NotifiedWorkerThread("RadioIf"), module(hal, cs, irq, rst, busy), iface(_iface)
{
instance = this;
#if defined(ARCH_STM32WL) && defined(USE_SX1262)
module.setCb_digitalWrite(stm32wl_emulate_digitalWrite);
module.setCb_digitalRead(stm32wl_emulate_digitalRead);
#endif
}
#ifdef ARCH_ESP32
// ESP32 doesn't use that flag
#define YIELD_FROM_ISR(x) portYIELD_FROM_ISR()
#else
#define YIELD_FROM_ISR(x) portYIELD_FROM_ISR(x)
#endif
void INTERRUPT_ATTR RadioLibInterface::isrLevel0Common(PendingISR cause)
{
instance->disableInterrupt();
BaseType_t xHigherPriorityTaskWoken;
instance->notifyFromISR(&xHigherPriorityTaskWoken, cause, true);
/* Force a context switch if xHigherPriorityTaskWoken is now set to pdTRUE.
The macro used to do this is dependent on the port and may be called
portEND_SWITCHING_ISR. */
YIELD_FROM_ISR(xHigherPriorityTaskWoken);
}
void INTERRUPT_ATTR RadioLibInterface::isrRxLevel0()
{
isrLevel0Common(ISR_RX);
}
void INTERRUPT_ATTR RadioLibInterface::isrTxLevel0()
{
isrLevel0Common(ISR_TX);
}
/** Our ISR code currently needs this to find our active instance
*/
RadioLibInterface *RadioLibInterface::instance;
/** Could we send right now (i.e. either not actively receiving or transmitting)? */
bool RadioLibInterface::canSendImmediately()
{
// We wait _if_ we are partially though receiving a packet (rather than just merely waiting for one).
// To do otherwise would be doubly bad because not only would we drop the packet that was on the way in,
// we almost certainly guarantee no one outside will like the packet we are sending.
bool busyTx = sendingPacket != NULL;
bool busyRx = isReceiving && isActivelyReceiving();
if (busyTx || busyRx) {
if (busyTx) {
LOG_WARN("Can not send yet, busyTx");
}
// If we've been trying to send the same packet more than one minute and we haven't gotten a
// TX IRQ from the radio, the radio is probably broken.
if (busyTx && !Throttle::isWithinTimespanMs(lastTxStart, 60000)) {
LOG_ERROR("Hardware Failure! busyTx for more than 60s");
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_TRANSMIT_FAILED);
// reboot in 5 seconds when this condition occurs.
rebootAtMsec = lastTxStart + 65000;
}
if (busyRx) {
LOG_WARN("Can not send yet, busyRx");
}
return false;
} else
return true;
}
bool RadioLibInterface::receiveDetected(uint16_t irq, ulong syncWordHeaderValidFlag, ulong preambleDetectedFlag)
{
bool detected = (irq & (syncWordHeaderValidFlag | preambleDetectedFlag));
// Handle false detections
if (detected) {
if (!activeReceiveStart) {
activeReceiveStart = millis();
} else if (!Throttle::isWithinTimespanMs(activeReceiveStart, 2 * preambleTimeMsec)) {
if (!(irq & syncWordHeaderValidFlag)) {
// The HEADER_VALID flag should be set by now if it was really a packet, so ignore PREAMBLE_DETECTED flag
activeReceiveStart = 0;
LOG_DEBUG("Ignore false preamble detection");
return false;
} else {
uint32_t maxPacketTimeMsec = getPacketTime(meshtastic_Constants_DATA_PAYLOAD_LEN + sizeof(PacketHeader));
if (!Throttle::isWithinTimespanMs(activeReceiveStart, maxPacketTimeMsec)) {
// We should have gotten an RX_DONE IRQ by now if it was really a packet, so ignore HEADER_VALID flag
activeReceiveStart = 0;
LOG_DEBUG("Ignore false header detection");
return false;
}
}
}
}
return detected;
}
/// Send a packet (possibly by enquing in a private fifo). This routine will
/// later free() the packet to pool. This routine is not allowed to stall because it is called from
/// bluetooth comms code. If the txmit queue is empty it might return an error
ErrorCode RadioLibInterface::send(meshtastic_MeshPacket *p)
{
#ifndef DISABLE_WELCOME_UNSET
if (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_UNSET) {
if (disabled || !config.lora.tx_enabled) {
LOG_WARN("send - !config.lora.tx_enabled");
packetPool.release(p);
return ERRNO_DISABLED;
}
} else {
LOG_WARN("send - lora tx disabled: Region unset");
packetPool.release(p);
return ERRNO_DISABLED;
}
#else
if (disabled || !config.lora.tx_enabled) {
LOG_WARN("send - !config.lora.tx_enabled");
packetPool.release(p);
return ERRNO_DISABLED;
}
#endif
if (p->to == NODENUM_BROADCAST_NO_LORA) {
LOG_DEBUG("Drop no-LoRa pkt");
return ERRNO_SHOULD_RELEASE;
}
// Sometimes when testing it is useful to be able to never turn on the xmitter
#ifndef LORA_DISABLE_SENDING
printPacket("enqueue for send", p);
LOG_DEBUG("txGood=%d,txRelay=%d,rxGood=%d,rxBad=%d", txGood, txRelay, rxGood, rxBad);
bool dropped = false;
ErrorCode res = txQueue.enqueue(p, &dropped) ? ERRNO_OK : ERRNO_UNKNOWN;
if (dropped) {
txDrop++;
}
if (res != ERRNO_OK) { // we weren't able to queue it, so we must drop it to prevent leaks
packetPool.release(p);
return res;
}
// set (random) transmit delay to let others reconfigure their radio,
// to avoid collisions and implement timing-based flooding
setTransmitDelay();
return res;
#else
packetPool.release(p);
return ERRNO_DISABLED;
#endif
}
meshtastic_QueueStatus RadioLibInterface::getQueueStatus()
{
meshtastic_QueueStatus qs;
qs.res = qs.mesh_packet_id = 0;
qs.free = txQueue.getFree();
qs.maxlen = txQueue.getMaxLen();
return qs;
}
bool RadioLibInterface::canSleep()
{
bool res = txQueue.empty();
if (!res) { // only print debug messages if we are vetoing sleep
LOG_DEBUG("Radio wait to sleep, txEmpty=%d", res);
}
return res;
}
/** Allow other firmware components to ask whether we are currently sending a packet
Initially implemented to protect T-Echo's capacitive touch button from spurious presses during tx
*/
bool RadioLibInterface::isSending()
{
return sendingPacket != NULL;
}
/** Attempt to cancel a previously sent packet. Returns true if a packet was found we could cancel */
bool RadioLibInterface::cancelSending(NodeNum from, PacketId id)
{
auto p = txQueue.remove(from, id);
if (p)
packetPool.release(p); // free the packet we just removed
bool result = (p != NULL);
LOG_DEBUG("cancelSending id=0x%x, removed=%d", id, result);
return result;
}
/** Attempt to find a packet in the TxQueue. Returns true if the packet was found. */
bool RadioLibInterface::findInTxQueue(NodeNum from, PacketId id)
{
return txQueue.find(from, id);
}
/** radio helper thread callback.
We never immediately transmit after any operation (either Rx or Tx). Instead we should wait a random multiple of
'slotTimes' (see definition in RadioInterface.h) taken from a contention window (CW) to lower the chance of collision.
The CW size is determined by setTransmitDelay() and depends either on the current channel utilization or SNR in case
of a flooding message. After this, we perform channel activity detection (CAD) and reset the transmit delay if it is
currently active.
*/
void RadioLibInterface::onNotify(uint32_t notification)
{
switch (notification) {
case ISR_TX:
handleTransmitInterrupt();
startReceive();
setTransmitDelay();
break;
case ISR_RX:
handleReceiveInterrupt();
startReceive();
setTransmitDelay();
break;
case TRANSMIT_DELAY_COMPLETED:
// If we are not currently in receive mode, then restart the random delay (this can happen if the main thread
// has placed the unit into standby) FIXME, how will this work if the chipset is in sleep mode?
if (!txQueue.empty()) {
if (!canSendImmediately()) {
setTransmitDelay(); // currently Rx/Tx-ing: reset random delay
} else {
meshtastic_MeshPacket *txp = txQueue.getFront();
assert(txp);
long delay_remaining = txp->tx_after ? txp->tx_after - millis() : 0;
if (delay_remaining > 0) {
// There's still some delay pending on this packet, so resume waiting for it to elapse
notifyLater(delay_remaining, TRANSMIT_DELAY_COMPLETED, false);
} else {
if (isChannelActive()) { // check if there is currently a LoRa packet on the channel
startReceive(); // try receiving this packet, afterwards we'll be trying to transmit again
setTransmitDelay();
} else {
// Send any outgoing packets we have ready as fast as possible to keep the time between channel scan and
// actual transmission as short as possible
txp = txQueue.dequeue();
assert(txp);
startSend(txp);
LOG_DEBUG("%d packets remain in the TX queue", txQueue.getMaxLen() - txQueue.getFree());
}
}
}
} else {
// Do nothing, because the queue is empty
}
break;
default:
assert(0); // We expected to receive a valid notification from the ISR
}
}
void RadioLibInterface::setTransmitDelay()
{
meshtastic_MeshPacket *p = txQueue.getFront();
if (!p) {
return; // noop if there's nothing in the queue
}
// We want all sending/receiving to be done by our daemon thread.
// We use a delay here because this packet might have been sent in response to a packet we just received.
// So we want to make sure the other side has had a chance to reconfigure its radio.
if (p->tx_after) {
unsigned long add_delay = p->rx_rssi ? getTxDelayMsecWeighted(p) : getTxDelayMsec();
unsigned long now = millis();
p->tx_after = min(max(p->tx_after + add_delay, now + add_delay), now + 2 * getTxDelayMsecWeightedWorst(p->rx_snr));
notifyLater(p->tx_after - now, TRANSMIT_DELAY_COMPLETED, false);
} else if (p->rx_snr == 0 && p->rx_rssi == 0) {
/* We assume if rx_snr = 0 and rx_rssi = 0, the packet was generated locally.
* This assumption is valid because of the offset generated by the radio to account for the noise
* floor.
*/
startTransmitTimer(true);
} else {
// If there is a SNR, start a timer scaled based on that SNR.
LOG_DEBUG("rx_snr found. hop_limit:%d rx_snr:%f", p->hop_limit, p->rx_snr);
startTransmitTimerRebroadcast(p);
}
}
void RadioLibInterface::startTransmitTimer(bool withDelay)
{
// If we have work to do and the timer wasn't already scheduled, schedule it now
if (!txQueue.empty()) {
uint32_t delay = !withDelay ? 1 : getTxDelayMsec();
notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
}
}
void RadioLibInterface::startTransmitTimerRebroadcast(meshtastic_MeshPacket *p)
{
// If we have work to do and the timer wasn't already scheduled, schedule it now
if (!txQueue.empty()) {
uint32_t delay = getTxDelayMsecWeighted(p);
notifyLater(delay, TRANSMIT_DELAY_COMPLETED, false); // This will implicitly enable
}
}
/**
* If the packet is not already in the late rebroadcast window, move it there
*/
void RadioLibInterface::clampToLateRebroadcastWindow(NodeNum from, PacketId id)
{
// Look for non-late packets only, so we don't do this twice!
meshtastic_MeshPacket *p = txQueue.remove(from, id, true, false);
if (p) {
p->tx_after = millis() + getTxDelayMsecWeightedWorst(p->rx_snr);
bool dropped = false;
if (txQueue.enqueue(p, &dropped)) {
LOG_DEBUG("Move existing queued packet to the late rebroadcast window %dms from now", p->tx_after - millis());
} else {
packetPool.release(p);
}
if (dropped) {
txDrop++;
}
}
}
/**
* If there is a packet pending TX in the queue with a worse hop limit, remove it pending replacement with a better version
* @return Whether a pending packet was removed
*/
bool RadioLibInterface::removePendingTXPacket(NodeNum from, PacketId id, uint32_t hop_limit_lt)
{
meshtastic_MeshPacket *p = txQueue.remove(from, id, true, true, hop_limit_lt);
if (p) {
LOG_DEBUG("Dropping pending-TX packet 0x%08x with hop limit %d", p->id, p->hop_limit);
packetPool.release(p);
return true;
}
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
// ignore the transmit interrupt
if (sendingPacket)
completeSending();
powerMon->clearState(meshtastic_PowerMon_State_Lora_TXOn); // But our transmitter is definitely off now
}
void RadioLibInterface::completeSending()
{
// We are careful to clear sending packet before calling printPacket because
// that can take a long time
auto p = sendingPacket;
sendingPacket = NULL;
if (p) {
// Packet has been sent, count it toward our TX airtime utilization.
uint32_t xmitMsec = getPacketTime(p);
airTime->logAirtime(TX_LOG, xmitMsec);
txGood++;
if (!isFromUs(p))
txRelay++;
printPacket("Completed sending", p);
// We are done sending that packet, release it
packetPool.release(p);
}
}
void RadioLibInterface::handleReceiveInterrupt()
{
// when this is called, we should be in receive mode - if we are not, just jump out instead of bombing. Possible Race
// Condition?
if (!isReceiving) {
LOG_ERROR("handleReceiveInterrupt called when not in rx mode, which shouldn't happen");
return;
}
isReceiving = false;
// read the number of actually received bytes
size_t length = iface->getPacketLength();
uint32_t rxMsec = getPacketTime(length, true);
#ifndef DISABLE_WELCOME_UNSET
if (config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_UNSET) {
LOG_WARN("lora rx disabled: Region unset");
airTime->logAirtime(RX_ALL_LOG, rxMsec);
return;
}
#endif
int state = iface->readData((uint8_t *)&radioBuffer, length);
#if ARCH_PORTDUINO
if (portduino_config.logoutputlevel == level_trace) {
printBytes("Raw incoming packet: ", (uint8_t *)&radioBuffer, length);
}
#endif
if (state != RADIOLIB_ERR_NONE) {
LOG_ERROR("Ignore received packet due to error=%d (maybe to=0x%08x, from=0x%08x, flags=0x%02x)", state,
radioBuffer.header.to, radioBuffer.header.from, radioBuffer.header.flags);
rxBad++;
airTime->logAirtime(RX_ALL_LOG, rxMsec);
} else {
// Skip the 4 headers that are at the beginning of the rxBuf
int32_t payloadLen = length - sizeof(PacketHeader);
// check for short packets
if (payloadLen < 0) {
LOG_WARN("Ignore received packet too short");
rxBad++;
airTime->logAirtime(RX_ALL_LOG, rxMsec);
} else {
rxGood++;
// altered packet with "from == 0" can do Remote Node Administration without permission
if (radioBuffer.header.from == 0) {
LOG_WARN("Ignore received packet without sender");
return;
}
// Note: we deliver _all_ packets to our router (i.e. our interface is intentionally promiscuous).
// This allows the router and other apps on our node to sniff packets (usually routing) between other
// nodes.
meshtastic_MeshPacket *mp = packetPool.allocZeroed();
// Keep the assigned fields in sync with src/mqtt/MQTT.cpp:onReceiveProto
mp->from = radioBuffer.header.from;
mp->to = radioBuffer.header.to;
mp->id = radioBuffer.header.id;
mp->channel = radioBuffer.header.channel;
assert(HOP_MAX <= PACKET_FLAGS_HOP_LIMIT_MASK); // If hopmax changes, carefully check this code
mp->hop_limit = radioBuffer.header.flags & PACKET_FLAGS_HOP_LIMIT_MASK;
mp->hop_start = (radioBuffer.header.flags & PACKET_FLAGS_HOP_START_MASK) >> PACKET_FLAGS_HOP_START_SHIFT;
mp->want_ack = !!(radioBuffer.header.flags & PACKET_FLAGS_WANT_ACK_MASK);
mp->via_mqtt = !!(radioBuffer.header.flags & PACKET_FLAGS_VIA_MQTT_MASK);
// If hop_start is not set, next_hop and relay_node are invalid (firmware <2.3)
mp->next_hop = mp->hop_start == 0 ? NO_NEXT_HOP_PREFERENCE : radioBuffer.header.next_hop;
mp->relay_node = mp->hop_start == 0 ? NO_RELAY_NODE : radioBuffer.header.relay_node;
addReceiveMetadata(mp);
mp->which_payload_variant =
meshtastic_MeshPacket_encrypted_tag; // Mark that the payload is still encrypted at this point
assert(((uint32_t)payloadLen) <= sizeof(mp->encrypted.bytes));
memcpy(mp->encrypted.bytes, radioBuffer.payload, payloadLen);
mp->encrypted.size = payloadLen;
printPacket("Lora RX", mp);
airTime->logAirtime(RX_LOG, rxMsec);
deliverToReceiver(mp);
}
}
}
void RadioLibInterface::startReceive()
{
isReceiving = true;
powerMon->setState(meshtastic_PowerMon_State_Lora_RXOn);
}
void RadioLibInterface::configHardwareForSend()
{
powerMon->setState(meshtastic_PowerMon_State_Lora_TXOn);
}
void RadioLibInterface::setStandby()
{
// neither sending nor receiving
powerMon->clearState(meshtastic_PowerMon_State_Lora_RXOn);
powerMon->clearState(meshtastic_PowerMon_State_Lora_TXOn);
}
/** start an immediate transmit */
bool RadioLibInterface::startSend(meshtastic_MeshPacket *txp)
{
/* NOTE: Minimize the actions before startTransmit() to keep the time between
channel scan and actual transmit as low as possible to avoid collisions. */
if (disabled || !config.lora.tx_enabled) {
LOG_WARN("Drop Tx packet because LoRa Tx disabled");
packetPool.release(txp);
return false;
} else {
configHardwareForSend(); // must be after setStandby
size_t numbytes = beginSending(txp);
int res = iface->startTransmit((uint8_t *)&radioBuffer, numbytes);
if (res != RADIOLIB_ERR_NONE) {
LOG_ERROR("startTransmit failed, error=%d", res);
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_RADIO_SPI_BUG);
// This send failed, but make sure to 'complete' it properly
completeSending();
powerMon->clearState(meshtastic_PowerMon_State_Lora_TXOn); // Transmitter off now
startReceive(); // Restart receive mode (because startTransmit failed to put us in xmit mode)
} else {
// Must be done AFTER, starting transmit, because startTransmit clears (possibly stale) interrupt pending register
// bits
enableInterrupt(isrTxLevel0);
lastTxStart = millis();
printPacket("Started Tx", txp);
}
return res == RADIOLIB_ERR_NONE;
}
}
@@ -0,0 +1,267 @@
#pragma once
#include "MeshPacketQueue.h"
#include "RadioInterface.h"
#include "concurrency/NotifiedWorkerThread.h"
#include <RadioLib.h>
#include <sys/types.h>
// ESP32 has special rules about ISR code
#ifdef ARDUINO_ARCH_ESP32
#define INTERRUPT_ATTR IRAM_ATTR
#else
#define INTERRUPT_ATTR
#endif
#define RADIOLIB_PIN_TYPE uint32_t
// In addition to the default Rx flags, we need the PREAMBLE_DETECTED flag to detect whether we are actively receiving
#define MESHTASTIC_RADIOLIB_IRQ_RX_FLAGS (RADIOLIB_IRQ_RX_DEFAULT_FLAGS | (1 << RADIOLIB_IRQ_PREAMBLE_DETECTED))
/**
* We need to override the RadioLib ArduinoHal class to add mutex protection for SPI bus access
*/
class LockingArduinoHal : public ArduinoHal
{
public:
LockingArduinoHal(SPIClass &spi, SPISettings spiSettings) : ArduinoHal(spi, spiSettings){};
void spiBeginTransaction() override;
void spiEndTransaction() override;
#if ARCH_PORTDUINO
void spiTransfer(uint8_t *out, size_t len, uint8_t *in) override;
#endif
};
#if defined(USE_STM32WLx)
/**
* A wrapper for the RadioLib STM32WLx_Module class, that doesn't connect any pins as they are virtual
*/
class STM32WLx_ModuleWrapper : public STM32WLx_Module
{
public:
STM32WLx_ModuleWrapper(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: STM32WLx_Module(){};
};
#endif
class RadioLibInterface : public RadioInterface, protected concurrency::NotifiedWorkerThread
{
/// Used as our notification from the ISR
enum PendingISR { ISR_NONE = 0, ISR_RX, ISR_TX, TRANSMIT_DELAY_COMPLETED };
/**
* Raw ISR handler that just calls our polymorphic method
*/
static void isrTxLevel0(), isrLevel0Common(PendingISR code);
MeshPacketQueue txQueue = MeshPacketQueue(MAX_TX_QUEUE);
protected:
ModemType_t modemType = RADIOLIB_MODEM_LORA;
DataRate_t getDataRate() const { return {.lora = {.spreadingFactor = sf, .bandwidth = bw, .codingRate = cr}}; }
PacketConfig_t getPacketConfig() const
{
return {.lora = {.preambleLength = preambleLength,
.implicitHeader = false,
.crcEnabled = true,
// We use auto LDRO, meaning it is enabled if the symbol time is >= 16msec
.ldrOptimize = (1 << sf) / bw >= 16}};
}
/**
* We use a meshtastic sync word, but hashed with the Channel name. For releases before 1.2 we used 0x12 (or for very old
* loads 0x14) Note: do not use 0x34 - that is reserved for lorawan
*
* We now use 0x2b (so that someday we can possibly use NOT 2b - because that would be funny pun). We will be staying with
* this code for a long time.
*/
const uint8_t syncWord = 0x2b;
float currentLimit = 100; // 100mA OCP - Should be acceptable for RFM95/SX127x chipset.
#if !defined(USE_STM32WLx)
Module module; // The HW interface to the radio
#else
STM32WLx_ModuleWrapper module;
#endif
/**
* provides lowest common denominator RadioLib API
*/
PhysicalLayer *iface;
/// are _trying_ to receive a packet currently (note - we might just be waiting for one)
bool isReceiving = false;
public:
/** Our ISR code currently needs this to find our active instance
*/
static RadioLibInterface *instance;
/**
* Glue functions called from ISR land
*/
virtual void disableInterrupt() = 0;
/**
* Enable a particular ISR callback glue function
*/
virtual void enableInterrupt(void (*)()) = 0;
/**
* Debugging counts
*/
uint32_t rxBad = 0, rxGood = 0, txGood = 0, txRelay = 0;
uint16_t txDrop = 0;
public:
RadioLibInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy, PhysicalLayer *iface = NULL);
virtual ErrorCode send(meshtastic_MeshPacket *p) override;
/**
* Return true if we think the board can go to sleep (i.e. our tx queue is empty, we are not sending or receiving)
*
* This method must be used before putting the CPU into deep or light sleep.
*/
virtual bool canSleep() override;
/**
* Start waiting to receive a message
*
* External functions can call this method to wake the device from sleep.
* Subclasses must override and call this base method
*/
virtual void startReceive();
/** can we detect a LoRa preamble on the current channel? */
virtual bool isChannelActive() = 0;
/** are we actively receiving a packet (only called during receiving state)
* This method is only public to facilitate debugging. Do not call.
*/
virtual bool isActivelyReceiving() = 0;
/** Are we are currently sending a packet?
* This method is public, intending to expose this information to other firmware components
*/
virtual bool isSending();
/** Attempt to cancel a previously sent packet. Returns true if a packet was found we could cancel */
virtual bool cancelSending(NodeNum from, PacketId id) override;
/** Attempt to find a packet in the TxQueue. Returns true if the packet was found. */
virtual bool findInTxQueue(NodeNum from, PacketId id) override;
private:
/** 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();
/**
* random timer with certain min. and max. settings
* @return Timestamp after which the packet may be sent
*/
void startTransmitTimer(bool withDelay = true);
/**
* timer scaled to SNR of to be flooded packet
* @return Timestamp after which the packet may be sent
*/
void startTransmitTimerRebroadcast(meshtastic_MeshPacket *p);
void handleTransmitInterrupt();
void handleReceiveInterrupt();
static void timerCallback(void *p1, uint32_t p2);
virtual void onNotify(uint32_t notification) override;
/** start an immediate transmit
* This method is virtual so subclasses can hook as needed, subclasses should not call directly
* @return true if packet was sent
*/
virtual bool startSend(meshtastic_MeshPacket *txp);
meshtastic_QueueStatus getQueueStatus();
protected:
uint32_t activeReceiveStart = 0;
bool receiveDetected(uint16_t irq, ulong syncWordHeaderValidFlag, ulong preambleDetectedFlag);
/** Do any hardware setup needed on entry into send configuration for the radio.
* Subclasses can customize, but must also call this base method */
virtual void configHardwareForSend();
/** Could we send right now (i.e. either not actively receiving or transmitting)? */
virtual bool canSendImmediately();
/**
* Raw ISR handler that just calls our polymorphic method
*/
static void isrRxLevel0();
/**
* If a send was in progress finish it and return the buffer to the pool */
void completeSending();
/**
* Add SNR data to received messages
*/
virtual void addReceiveMetadata(meshtastic_MeshPacket *mp) = 0;
/**
* Subclasses must override, implement and then call into this base class implementation
*/
virtual void setStandby();
/**
* Derive packet time either for a received (using header info) or a transmitted packet
*/
template <typename T> uint32_t computePacketTime(T &lora, uint32_t pl, bool received)
{
if (received) {
// First get the actual coding rate and CRC status from the received packet
uint8_t rxCR;
bool hasCRC;
lora.getLoRaRxHeaderInfo(&rxCR, &hasCRC);
// Go from raw header value to denominator
if (rxCR < 5) {
rxCR += 4;
} else if (rxCR == 7) {
rxCR = 8;
}
// Received packet configuration must be the same as configured, except for coding rate and CRC
DataRate_t dr = getDataRate();
dr.lora.codingRate = rxCR;
PacketConfig_t pc = getPacketConfig();
pc.lora.crcEnabled = hasCRC;
return lora.calculateTimeOnAir(modemType, dr, pc, pl) / 1000;
}
return lora.getTimeOnAir(pl) / 1000;
}
const char *radioLibErr = "RadioLib err=";
/**
* If the packet is not already in the late rebroadcast window, move it there
*/
void clampToLateRebroadcastWindow(NodeNum from, PacketId id);
/**
* If there is a packet pending TX in the queue with a worse hop limit, remove it pending replacement with a better version
* @return Whether a pending packet was removed
*/
bool removePendingTXPacket(NodeNum from, PacketId id, uint32_t hop_limit_lt) override;
};
@@ -0,0 +1,86 @@
#if RADIOLIB_EXCLUDE_SX127X != 1
#include "RadioLibRF95.h"
#include "configuration.h"
// From datasheet but radiolib doesn't know anything about this
#define SX127X_REG_TCXO 0x4B
RadioLibRF95::RadioLibRF95(Module *mod) : SX1278(mod) {}
int16_t RadioLibRF95::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength,
uint8_t gain)
{
// execute common part
uint8_t rf95versions[2] = {0x12, 0x11};
int16_t state = SX127x::begin(rf95versions, sizeof(rf95versions), syncWord, preambleLength);
RADIOLIB_ASSERT(state);
// current limit was removed from module' ctor
// override default value (60 mA)
state = setCurrentLimit(currentLimit);
LOG_DEBUG("Current limit set to %f", currentLimit);
LOG_DEBUG("Current limit set result %d", state);
// configure settings not accessible by API
// state = config();
RADIOLIB_ASSERT(state);
#ifdef RF95_TCXO
state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_TCXO, 0x10 | _mod->SPIgetRegValue(RADIOLIB_SX127X_REG_TCXO));
RADIOLIB_ASSERT(state);
#endif
// configure publicly accessible settings
state = setFrequency(freq);
RADIOLIB_ASSERT(state);
state = setBandwidth(bw);
RADIOLIB_ASSERT(state);
state = setSpreadingFactor(sf);
RADIOLIB_ASSERT(state);
state = setCodingRate(cr);
RADIOLIB_ASSERT(state);
#ifdef USE_RF95_RFO
state = setOutputPower(power, true);
#else
state = setOutputPower(power);
#endif
RADIOLIB_ASSERT(state);
state = setGain(gain);
return (state);
}
int16_t RadioLibRF95::setFrequency(float freq)
{
// RADIOLIB_CHECK_RANGE(freq, 862.0, 1020.0, ERR_INVALID_FREQUENCY);
// set frequency
return (SX127x::setFrequencyRaw(freq));
}
#define RH_RF95_MODEM_STATUS_CLEAR 0x10
#define RH_RF95_MODEM_STATUS_HEADER_INFO_VALID 0x08
#define RH_RF95_MODEM_STATUS_RX_ONGOING 0x04
#define RH_RF95_MODEM_STATUS_SIGNAL_SYNCHRONIZED 0x02
#define RH_RF95_MODEM_STATUS_SIGNAL_DETECTED 0x01
bool RadioLibRF95::isReceiving()
{
// 0x0b == Look for header info valid, signal synchronized or signal detected
uint8_t reg = readReg(RADIOLIB_SX127X_REG_MODEM_STAT);
// Serial.printf("reg %x", reg);
return (reg & (RH_RF95_MODEM_STATUS_SIGNAL_DETECTED | RH_RF95_MODEM_STATUS_SIGNAL_SYNCHRONIZED |
RH_RF95_MODEM_STATUS_HEADER_INFO_VALID)) != 0;
}
uint8_t RadioLibRF95::readReg(uint8_t addr)
{
Module *mod = this->getMod();
return mod->SPIreadRegister(addr);
}
#endif
@@ -0,0 +1,73 @@
#pragma once
#if RADIOLIB_EXCLUDE_SX127X != 1
#include <RadioLib.h>
/*!
\class RFM95
\brief Derived class for %RFM95 modules. Overrides some methods from SX1278 due to different parameter ranges.
*/
class RadioLibRF95 : public SX1278
{
public:
// constructor
/*!
\brief Default constructor. Called from Arduino sketch when creating new LoRa instance.
\param mod Instance of Module that will be used to communicate with the %LoRa chip.
*/
explicit RadioLibRF95(Module *mod);
// basic methods
/*!
\brief %LoRa modem initialization method. Must be called at least once from Arduino sketch to initialize the module.
\param freq Carrier frequency in MHz. Allowed values range from 868.0 MHz to 915.0 MHz.
\param bw %LoRa link bandwidth in kHz. Allowed values are 10.4, 15.6, 20.8, 31.25, 41.7, 62.5, 125, 250 and 500 kHz.
\param sf %LoRa link spreading factor. Allowed values range from 6 to 12.
\param cr %LoRa link coding rate denominator. Allowed values range from 5 to 8.
\param syncWord %LoRa sync word. Can be used to distinguish different networks. Note that value 0x34 is reserved for LoRaWAN
networks.
\param power Transmission output power in dBm. Allowed values range from 2 to 17 dBm.
\param preambleLength Length of %LoRa transmission preamble in symbols. The actual preamble length is 4.25 symbols longer
than the set number. Allowed values range from 6 to 65535.
\param gain Gain of receiver LNA (low-noise amplifier). Can be set to any integer in range 1 to 6 where 1 is the highest
gain. Set to 0 to enable automatic gain control (recommended).
\returns \ref status_codes
*/
int16_t begin(float freq = 915.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7,
uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 17, uint16_t preambleLength = 8, uint8_t gain = 0);
// configuration methods
/*!
\brief Sets carrier frequency. Allowed values range from 868.0 MHz to 915.0 MHz.
\param freq Carrier frequency to be set in MHz.
\returns \ref status_codes
*/
int16_t setFrequency(float freq);
// Return true if we are actively receiving a message currently
bool isReceiving();
/// For debugging
uint8_t readReg(uint8_t addr);
protected:
// since default current limit for SX126x/127x in updated RadioLib is 60mA
// use the previous value
float currentLimit = 100;
};
#endif
@@ -0,0 +1,197 @@
#include "ReliableRouter.h"
#include "Default.h"
#include "MeshTypes.h"
#include "configuration.h"
#include "memGet.h"
#include "mesh-pb-constants.h"
#include "modules/NodeInfoModule.h"
#include "modules/RoutingModule.h"
// ReliableRouter::ReliableRouter() {}
/**
* If the message is want_ack, then add it to a list of packets to retransmit.
* If we run out of retransmissions, send a nak packet towards the original client to indicate failure.
*/
ErrorCode ReliableRouter::send(meshtastic_MeshPacket *p)
{
if (p->want_ack) {
// If someone asks for acks on broadcast, we need the hop limit to be at least one, so that first node that receives our
// message will rebroadcast. But asking for hop_limit 0 in that context means the client app has no preference on hop
// counts and we want this message to get through the whole mesh, so use the default.
if (p->hop_limit == 0) {
p->hop_limit = Default::getConfiguredOrDefaultHopLimit(config.lora.hop_limit);
}
DEBUG_HEAP_BEFORE;
auto copy = packetPool.allocCopy(*p);
DEBUG_HEAP_AFTER("ReliableRouter::send", copy);
startRetransmission(copy, NUM_RELIABLE_RETX);
}
/* If we have pending retransmissions, add the airtime of this packet to it, because during that time we cannot receive an
(implicit) ACK. Otherwise, we might retransmit too early.
*/
for (auto i = pending.begin(); i != pending.end(); i++) {
if (i->first.id != p->id) {
i->second.nextTxMsec += iface->getPacketTime(p);
}
}
return isBroadcast(p->to) ? FloodingRouter::send(p) : NextHopRouter::send(p);
}
bool ReliableRouter::shouldFilterReceived(const meshtastic_MeshPacket *p)
{
// Note: do not use getFrom() here, because we want to ignore messages sent from phone
if (p->from == getNodeNum()) {
printPacket("Rx someone rebroadcasting for us", p);
// We are seeing someone rebroadcast one of our broadcast attempts.
// If this is the first time we saw this, cancel any retransmissions we have queued up and generate an internal ack for
// the original sending process.
// This "optimization", does save lots of airtime. For DMs, you also get a real ACK back
// from the intended recipient.
auto key = GlobalPacketId(getFrom(p), p->id);
auto old = findPendingPacket(key);
if (old) {
LOG_DEBUG("Generate implicit ack");
// NOTE: we do NOT check p->wantAck here because p is the INCOMING rebroadcast and that packet is not expected to be
// marked as wantAck
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, old->packet->channel);
// Only stop retransmissions if the rebroadcast came via LoRa
if (p->transport_mechanism == meshtastic_MeshPacket_TransportMechanism_TRANSPORT_LORA) {
stopRetransmission(key);
}
} else {
LOG_DEBUG("Didn't find pending packet");
}
}
/* At this point we have already deleted the pending retransmission if this packet was an (implicit) ACK to it.
Now for all other pending retransmissions, we have to add the airtime of this received packet to the retransmission timer,
because while receiving this packet, we could not have received an (implicit) ACK for it.
If we don't add this, we will likely retransmit too early.
*/
for (auto i = pending.begin(); i != pending.end(); i++) {
i->second.nextTxMsec += iface->getPacketTime(p, true);
}
return isBroadcast(p->to) ? FloodingRouter::shouldFilterReceived(p) : NextHopRouter::shouldFilterReceived(p);
}
/**
* If we receive a want_ack packet (do not check for wasSeenRecently), send back an ack (this might generate multiple ack sends in
* case the our first ack gets lost)
*
* If we receive an ack packet (do check wasSeenRecently), clear out any retransmissions and
* forward the ack to the application layer.
*
* If we receive a nak packet (do check wasSeenRecently), clear out any retransmissions
* and forward the nak to the application layer.
*
* Otherwise, let superclass handle it.
*/
void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c)
{
if (isToUs(p)) { // ignore ack/nak/want_ack packets that are not address to us (we only handle 0 hop reliability)
if (!MeshModule::currentReply) {
if (p->want_ack) {
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
/* A response may be set to want_ack for retransmissions, but we don't need to ACK a response if it received
an implicit ACK already. If we received it directly or via NextHopRouter, only ACK with a hop limit of 0 to
make sure the other side stops retransmitting. */
if (shouldSuccessAckWithWantAck(p)) {
// If this packet should always be ACKed reliably with want_ack back to the original sender, make sure we
// do that unconditionally.
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel,
routingModule->getHopLimitForResponse(p->hop_start, p->hop_limit), true);
} else if (!p->decoded.request_id && !p->decoded.reply_id) {
// If it's not an ACK or a reply, send an ACK.
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel,
routingModule->getHopLimitForResponse(p->hop_start, p->hop_limit));
} else if ((p->hop_start > 0 && p->hop_start == p->hop_limit) || p->next_hop != NO_NEXT_HOP_PREFERENCE) {
// If we received the packet directly from the original sender, send a 0-hop ACK since the original sender
// won't overhear any implicit ACKs. If we received the packet via NextHopRouter, also send a 0-hop ACK to
// stop the immediate relayer's retransmissions.
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel, 0);
}
} else if (p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag && p->channel == 0 &&
(nodeDB->getMeshNode(p->from) == nullptr || nodeDB->getMeshNode(p->from)->user.public_key.size == 0)) {
LOG_INFO("PKI packet from unknown node, send PKI_UNKNOWN_PUBKEY");
sendAckNak(meshtastic_Routing_Error_PKI_UNKNOWN_PUBKEY, getFrom(p), p->id, channels.getPrimaryIndex(),
routingModule->getHopLimitForResponse(p->hop_start, p->hop_limit));
} else {
// Send a 'NO_CHANNEL' error on the primary channel if want_ack packet destined for us cannot be decoded
sendAckNak(meshtastic_Routing_Error_NO_CHANNEL, getFrom(p), p->id, channels.getPrimaryIndex(),
routingModule->getHopLimitForResponse(p->hop_start, p->hop_limit));
}
} else if (p->next_hop == nodeDB->getLastByteOfNodeNum(getNodeNum()) && p->hop_limit > 0) {
// No wantAck, but we need to ACK with hop limit of 0 if we were the next hop to stop their retransmissions
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel, 0);
}
} else {
LOG_DEBUG("Another module replied to this message, no need for 2nd ack");
}
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag && c &&
c->error_reason == meshtastic_Routing_Error_PKI_UNKNOWN_PUBKEY) {
if (owner.public_key.size == 32) {
LOG_INFO("PKI decrypt failure, send a NodeInfo");
nodeInfoModule->sendOurNodeInfo(p->from, false, p->channel, true);
}
}
// We consider an ack to be either a !routing packet with a request ID or a routing packet with !error
PacketId ackId = ((c && c->error_reason == meshtastic_Routing_Error_NONE) || !c) ? p->decoded.request_id : 0;
// A nak is a routing packt that has an error code
PacketId nakId = (c && c->error_reason != meshtastic_Routing_Error_NONE) ? p->decoded.request_id : 0;
// We intentionally don't check wasSeenRecently, because it is harmless to delete non existent retransmission records
if (ackId || nakId) {
LOG_DEBUG("Received a %s for 0x%x, stopping retransmissions", ackId ? "ACK" : "NAK", ackId);
if (ackId) {
stopRetransmission(p->to, ackId);
} else {
stopRetransmission(p->to, nakId);
}
}
}
// handle the packet as normal
isBroadcast(p->to) ? FloodingRouter::sniffReceived(p, c) : NextHopRouter::sniffReceived(p, c);
}
/**
* If we ACK this packet, should we set want_ack=true on the ACK for reliable delivery of the ACK packet?
*/
bool ReliableRouter::shouldSuccessAckWithWantAck(const meshtastic_MeshPacket *p)
{
// Don't ACK-with-want-ACK outgoing packets
if (isFromUs(p))
return false;
// Only ACK-with-want-ACK if the original packet asked for want_ack
if (!p->want_ack)
return false;
// Only ACK-with-want-ACK packets to us (not broadcast)
if (!isToUs(p))
return false;
// Special case for text message DMs:
bool isTextMessage =
(p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) &&
IS_ONE_OF(p->decoded.portnum, meshtastic_PortNum_TEXT_MESSAGE_APP, meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP);
if (isTextMessage) {
// If it's a non-broadcast text message, and the original asked for want_ack,
// let's send an ACK that is itself want_ack to improve reliability of confirming delivery back to the sender.
// This should include all DMs regardless of whether or not reply_id is set.
return true;
}
return false;
}
@@ -0,0 +1,40 @@
#pragma once
#include "NextHopRouter.h"
/**
* This is a mixin that extends Router with the ability to do (one hop only) reliable message sends.
*/
class ReliableRouter : public NextHopRouter
{
public:
/**
* Constructor
*
*/
// ReliableRouter();
/**
* Send a packet on a suitable interface. This routine will
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*/
virtual ErrorCode send(meshtastic_MeshPacket *p) override;
protected:
/**
* Look for acks/naks or someone retransmitting us
*/
virtual void sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c) override;
/**
* We hook this method so we can see packets before FloodingRouter says they should be discarded
*/
virtual bool shouldFilterReceived(const meshtastic_MeshPacket *p) override;
private:
/**
* Should this packet be ACKed with a want_ack for reliable delivery?
*/
bool shouldSuccessAckWithWantAck(const meshtastic_MeshPacket *p);
};
@@ -0,0 +1,808 @@
#include "Router.h"
#include "Channels.h"
#include "CryptoEngine.h"
#include "MeshRadio.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "RTC.h"
#include "configuration.h"
#include "detect/LoRaRadioType.h"
#include "main.h"
#include "mesh-pb-constants.h"
#include "meshUtils.h"
#include "modules/RoutingModule.h"
#if !MESHTASTIC_EXCLUDE_MQTT
#include "mqtt/MQTT.h"
#endif
#include "Default.h"
#if ARCH_PORTDUINO
#include "platform/portduino/PortduinoGlue.h"
#endif
#if ENABLE_JSON_LOGGING || ARCH_PORTDUINO
#include "serialization/MeshPacketSerializer.h"
#endif
#define MAX_RX_FROMRADIO \
4 // max number of packets destined to our queue, we dispatch packets quickly so it doesn't need to be big
// I think this is right, one packet for each of the three fifos + one packet being currently assembled for TX or RX
// And every TX packet might have a retransmission packet or an ack alive at any moment
#ifdef ARCH_PORTDUINO
// Portduino (native) targets can use dynamic memory pools with runtime-configurable sizes
#define MAX_PACKETS \
(MAX_RX_TOPHONE + MAX_RX_FROMRADIO + 2 * MAX_TX_QUEUE + \
2) // max number of packets which can be in flight (either queued from reception or queued for sending)
static MemoryDynamic<meshtastic_MeshPacket> dynamicPool;
Allocator<meshtastic_MeshPacket> &packetPool = dynamicPool;
#elif defined(ARCH_STM32WL)
// On STM32 there isn't enough heap left over for the rest of the firmware if we allocate this statically.
// For now, make it dynamic again.
#define MAX_PACKETS \
(MAX_RX_TOPHONE + MAX_RX_FROMRADIO + 2 * MAX_TX_QUEUE + \
2) // max number of packets which can be in flight (either queued from reception or queued for sending)
static MemoryDynamic<meshtastic_MeshPacket> dynamicPool;
Allocator<meshtastic_MeshPacket> &packetPool = dynamicPool;
#else
// Embedded targets use static memory pools with compile-time constants
#define MAX_PACKETS_STATIC \
(MAX_RX_TOPHONE + MAX_RX_FROMRADIO + 2 * MAX_TX_QUEUE + \
2) // max number of packets which can be in flight (either queued from reception or queued for sending)
static MemoryPool<meshtastic_MeshPacket, MAX_PACKETS_STATIC> staticPool;
Allocator<meshtastic_MeshPacket> &packetPool = staticPool;
#endif
static uint8_t bytes[MAX_LORA_PAYLOAD_LEN + 1] __attribute__((__aligned__));
/**
* Constructor
*
* Currently we only allow one interface, that may change in the future
*/
Router::Router() : concurrency::OSThread("Router"), fromRadioQueue(MAX_RX_FROMRADIO)
{
// This is called pre main(), don't touch anything here, the following code is not safe
/* LOG_DEBUG("Size of NodeInfo %d", sizeof(NodeInfo));
LOG_DEBUG("Size of SubPacket %d", sizeof(SubPacket));
LOG_DEBUG("Size of MeshPacket %d", sizeof(MeshPacket)); */
fromRadioQueue.setReader(this);
// init Lockguard for crypt operations
assert(!cryptLock);
cryptLock = new concurrency::Lock();
}
bool Router::shouldDecrementHopLimit(const meshtastic_MeshPacket *p)
{
// First hop MUST always decrement to prevent retry issues
bool isFirstHop = (p->hop_start != 0 && p->hop_start == p->hop_limit);
if (isFirstHop) {
return true; // Always decrement on first hop
}
// Check if both local device and previous relay are routers (including CLIENT_BASE)
bool localIsRouter =
IS_ONE_OF(config.device.role, meshtastic_Config_DeviceConfig_Role_ROUTER, meshtastic_Config_DeviceConfig_Role_ROUTER_LATE,
meshtastic_Config_DeviceConfig_Role_CLIENT_BASE);
// If local device isn't a router, always decrement
if (!localIsRouter) {
return true;
}
// For subsequent hops, check if previous relay is a favorite router
// Optimized search for favorite routers with matching last byte
// Check ordering optimized for IoT devices (cheapest checks first)
for (size_t i = 0; i < nodeDB->getNumMeshNodes(); i++) {
meshtastic_NodeInfoLite *node = nodeDB->getMeshNodeByIndex(i);
if (!node)
continue;
// Check 1: is_favorite (cheapest - single bool)
if (!node->is_favorite)
continue;
// Check 2: has_user (cheap - single bool)
if (!node->has_user)
continue;
// Check 3: role check (moderate cost - multiple comparisons)
if (!IS_ONE_OF(node->user.role, meshtastic_Config_DeviceConfig_Role_ROUTER,
meshtastic_Config_DeviceConfig_Role_ROUTER_LATE)) {
continue;
}
// Check 4: last byte extraction and comparison (most expensive)
if (nodeDB->getLastByteOfNodeNum(node->num) == p->relay_node) {
// Found a favorite router match
LOG_DEBUG("Identified favorite relay router 0x%x from last byte 0x%x", node->num, p->relay_node);
return false; // Don't decrement hop_limit
}
}
// No favorite router match found, decrement hop_limit
return true;
}
/**
* do idle processing
* Mostly looking in our incoming rxPacket queue and calling handleReceived.
*/
int32_t Router::runOnce()
{
meshtastic_MeshPacket *mp;
while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL) {
// printPacket("handle fromRadioQ", mp);
perhapsHandleReceived(mp);
}
// LOG_DEBUG("Sleep forever!");
return INT32_MAX; // Wait a long time - until we get woken for the message queue
}
/**
* RadioInterface calls this to queue up packets that have been received from the radio. The router is now responsible for
* freeing the packet
*/
void Router::enqueueReceivedMessage(meshtastic_MeshPacket *p)
{
// Try enqueue until successful
while (!fromRadioQueue.enqueue(p, 0)) {
meshtastic_MeshPacket *old_p;
old_p = fromRadioQueue.dequeuePtr(0); // Dequeue and discard the oldest packet
if (old_p) {
printPacket("fromRadioQ full, drop oldest!", old_p);
packetPool.release(old_p);
}
}
// Nasty hack because our threading is primitive. interfaces shouldn't need to know about routers FIXME
setReceivedMessage();
}
/// Generate a unique packet id
// FIXME, move this someplace better
PacketId generatePacketId()
{
static uint32_t rollingPacketId; // Note: trying to keep this in noinit didn't help for working across reboots
static bool didInit = false;
if (!didInit) {
didInit = true;
// pick a random initial sequence number at boot (to prevent repeated reboots always starting at 0)
// Note: we mask the high order bit to ensure that we never pass a 'negative' number to random
rollingPacketId = random(UINT32_MAX & 0x7fffffff);
LOG_DEBUG("Initial packet id %u", rollingPacketId);
}
rollingPacketId++;
rollingPacketId &= ID_COUNTER_MASK; // Mask out the top 22 bits
PacketId id = rollingPacketId | random(UINT32_MAX & 0x7fffffff) << 10; // top 22 bits
LOG_DEBUG("Partially randomized packet id %u", id);
return id;
}
meshtastic_MeshPacket *Router::allocForSending()
{
meshtastic_MeshPacket *p = packetPool.allocZeroed();
p->which_payload_variant = meshtastic_MeshPacket_decoded_tag; // Assume payload is decoded at start.
p->from = nodeDB->getNodeNum();
p->to = NODENUM_BROADCAST;
p->hop_limit = Default::getConfiguredOrDefaultHopLimit(config.lora.hop_limit);
p->id = generatePacketId();
p->rx_time =
getValidTime(RTCQualityFromNet); // Just in case we process the packet locally - make sure it has a valid timestamp
return p;
}
/**
* Send an ack or a nak packet back towards whoever sent idFrom
*/
void Router::sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopLimit,
bool ackWantsAck)
{
routingModule->sendAckNak(err, to, idFrom, chIndex, hopLimit, ackWantsAck);
}
void Router::abortSendAndNak(meshtastic_Routing_Error err, meshtastic_MeshPacket *p)
{
LOG_ERROR("Error=%d, return NAK and drop packet", err);
sendAckNak(err, getFrom(p), p->id, p->channel);
packetPool.release(p);
}
void Router::setReceivedMessage()
{
// LOG_DEBUG("set interval to ASAP");
setInterval(0); // Run ASAP, so we can figure out our correct sleep time
runASAP = true;
}
meshtastic_QueueStatus Router::getQueueStatus()
{
if (!iface) {
meshtastic_QueueStatus qs;
qs.res = qs.mesh_packet_id = qs.free = qs.maxlen = 0;
return qs;
} else
return iface->getQueueStatus();
}
ErrorCode Router::sendLocal(meshtastic_MeshPacket *p, RxSource src)
{
if (p->to == 0) {
LOG_ERROR("Packet received with to: of 0!");
}
// No need to deliver externally if the destination is the local node
if (isToUs(p)) {
printPacket("Enqueued local", p);
enqueueReceivedMessage(p);
return ERRNO_OK;
} else if (!iface) {
// We must be sending to remote nodes also, fail if no interface found
abortSendAndNak(meshtastic_Routing_Error_NO_INTERFACE, p);
return ERRNO_NO_INTERFACES;
} else {
// If we are sending a broadcast, we also treat it as if we just received it ourself
// this allows local apps (and PCs) to see broadcasts sourced locally
if (isBroadcast(p->to)) {
handleReceived(p, src);
}
// don't override if a channel was requested and no need to set it when PKI is enforced
if (!p->channel && !p->pki_encrypted && !isBroadcast(p->to)) {
meshtastic_NodeInfoLite const *node = nodeDB->getMeshNode(p->to);
if (node) {
p->channel = node->channel;
LOG_DEBUG("localSend to channel %d", p->channel);
}
}
return send(p);
}
}
/**
* Send a packet on a suitable interface.
*/
ErrorCode Router::rawSend(meshtastic_MeshPacket *p)
{
assert(iface); // This should have been detected already in sendLocal (or we just received a packet from outside)
return iface->send(p);
}
/**
* Send a packet on a suitable interface. This routine will
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error.
*/
ErrorCode Router::send(meshtastic_MeshPacket *p)
{
if (isToUs(p)) {
LOG_ERROR("BUG! send() called with packet destined for local node!");
packetPool.release(p);
return meshtastic_Routing_Error_BAD_REQUEST;
} // should have already been handled by sendLocal
// Abort sending if we are violating the duty cycle
if (!config.lora.override_duty_cycle && myRegion->dutyCycle < 100) {
float hourlyTxPercent = airTime->utilizationTXPercent();
if (hourlyTxPercent > myRegion->dutyCycle) {
uint8_t silentMinutes = airTime->getSilentMinutes(hourlyTxPercent, myRegion->dutyCycle);
LOG_WARN("Duty cycle limit exceeded. Aborting send for now, you can send again in %d mins", silentMinutes);
meshtastic_ClientNotification *cn = clientNotificationPool.allocZeroed();
cn->has_reply_id = true;
cn->reply_id = p->id;
cn->level = meshtastic_LogRecord_Level_WARNING;
cn->time = getValidTime(RTCQualityFromNet);
sprintf(cn->message, "Duty cycle limit exceeded. You can send again in %d mins", silentMinutes);
service->sendClientNotification(cn);
meshtastic_Routing_Error err = meshtastic_Routing_Error_DUTY_CYCLE_LIMIT;
if (isFromUs(p)) { // only send NAK to API, not to the mesh
abortSendAndNak(err, p);
} else {
packetPool.release(p);
}
return err;
}
}
// PacketId nakId = p->decoded.which_ackVariant == SubPacket_fail_id_tag ? p->decoded.ackVariant.fail_id : 0;
// assert(!nakId); // I don't think we ever send 0hop naks over the wire (other than to the phone), test that assumption with
// assert
// Never set the want_ack flag on broadcast packets sent over the air.
if (isBroadcast(p->to))
p->want_ack = false;
// Up until this point we might have been using 0 for the from address (if it started with the phone), but when we send over
// the lora we need to make sure we have replaced it with our local address
p->from = getFrom(p);
p->relay_node = nodeDB->getLastByteOfNodeNum(getNodeNum()); // set the relayer to us
// If we are the original transmitter, set the hop limit with which we start
if (isFromUs(p))
p->hop_start = p->hop_limit;
// If the packet hasn't yet been encrypted, do so now (it might already be encrypted if we are just forwarding it)
if (!(p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag ||
p->which_payload_variant == meshtastic_MeshPacket_decoded_tag)) {
return meshtastic_Routing_Error_BAD_REQUEST;
}
fixPriority(p); // Before encryption, fix the priority if it's unset
// If the packet is not yet encrypted, do so now
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
ChannelIndex chIndex = p->channel; // keep as a local because we are about to change it
DEBUG_HEAP_BEFORE;
meshtastic_MeshPacket *p_decoded = packetPool.allocCopy(*p);
DEBUG_HEAP_AFTER("Router::send", p_decoded);
auto encodeResult = perhapsEncode(p);
if (encodeResult != meshtastic_Routing_Error_NONE) {
packetPool.release(p_decoded);
p->channel = 0; // Reset the channel to 0, so we don't use the failing hash again
abortSendAndNak(encodeResult, p);
return encodeResult; // FIXME - this isn't a valid ErrorCode
}
#if !MESHTASTIC_EXCLUDE_MQTT
// Only publish to MQTT if we're the original transmitter of the packet
if (moduleConfig.mqtt.enabled && isFromUs(p) && mqtt) {
mqtt->onSend(*p, *p_decoded, chIndex);
}
#endif
packetPool.release(p_decoded);
}
#if HAS_UDP_MULTICAST
if (udpHandler && config.network.enabled_protocols & meshtastic_Config_NetworkConfig_ProtocolFlags_UDP_BROADCAST) {
udpHandler->onSend(const_cast<meshtastic_MeshPacket *>(p));
}
#endif
assert(iface); // This should have been detected already in sendLocal (or we just received a packet from outside)
return iface->send(p);
}
/** Attempt to cancel a previously sent packet. Returns true if a packet was found we could cancel */
bool Router::cancelSending(NodeNum from, PacketId id)
{
if (iface && iface->cancelSending(from, id)) {
// We are not a relayer of this packet anymore
removeRelayer(nodeDB->getLastByteOfNodeNum(nodeDB->getNodeNum()), id, from);
return true;
}
return false;
}
/** Attempt to find a packet in the TxQueue. Returns true if the packet was found. */
bool Router::findInTxQueue(NodeNum from, PacketId id)
{
return iface->findInTxQueue(from, id);
}
/**
* Every (non duplicate) packet this node receives will be passed through this method. This allows subclasses to
* update routing tables etc... based on what we overhear (even for messages not destined to our node)
*/
void Router::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c)
{
// FIXME, update nodedb here for any packet that passes through us
}
DecodeState perhapsDecode(meshtastic_MeshPacket *p)
{
concurrency::LockGuard g(cryptLock);
if (config.device.rebroadcast_mode == meshtastic_Config_DeviceConfig_RebroadcastMode_KNOWN_ONLY &&
(nodeDB->getMeshNode(p->from) == NULL || !nodeDB->getMeshNode(p->from)->has_user)) {
LOG_DEBUG("Node 0x%x not in nodeDB-> Rebroadcast mode KNOWN_ONLY will ignore packet", p->from);
return DecodeState::DECODE_FAILURE;
}
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag)
return DecodeState::DECODE_SUCCESS; // If packet was already decoded just return
size_t rawSize = p->encrypted.size;
if (rawSize > sizeof(bytes)) {
LOG_ERROR("Packet too large to attempt decryption! (rawSize=%d > 256)", rawSize);
return DecodeState::DECODE_FATAL;
}
bool decrypted = false;
ChannelIndex chIndex = 0;
#if !(MESHTASTIC_EXCLUDE_PKI)
// Attempt PKI decryption first
if (p->channel == 0 && isToUs(p) && p->to > 0 && !isBroadcast(p->to) && nodeDB->getMeshNode(p->from) != nullptr &&
nodeDB->getMeshNode(p->from)->user.public_key.size > 0 && nodeDB->getMeshNode(p->to)->user.public_key.size > 0 &&
rawSize > MESHTASTIC_PKC_OVERHEAD) {
LOG_DEBUG("Attempt PKI decryption");
if (crypto->decryptCurve25519(p->from, nodeDB->getMeshNode(p->from)->user.public_key, p->id, rawSize, p->encrypted.bytes,
bytes)) {
LOG_INFO("PKI Decryption worked!");
meshtastic_Data decodedtmp;
memset(&decodedtmp, 0, sizeof(decodedtmp));
rawSize -= MESHTASTIC_PKC_OVERHEAD;
if (pb_decode_from_bytes(bytes, rawSize, &meshtastic_Data_msg, &decodedtmp) &&
decodedtmp.portnum != meshtastic_PortNum_UNKNOWN_APP) {
decrypted = true;
LOG_INFO("Packet decrypted using PKI!");
p->pki_encrypted = true;
memcpy(&p->public_key.bytes, nodeDB->getMeshNode(p->from)->user.public_key.bytes, 32);
p->public_key.size = 32;
p->decoded = decodedtmp;
p->which_payload_variant = meshtastic_MeshPacket_decoded_tag; // change type to decoded
} else {
LOG_ERROR("PKC Decrypted, but pb_decode failed!");
return DecodeState::DECODE_FAILURE;
}
} else {
LOG_WARN("PKC decrypt attempted but failed!");
}
}
#endif
// assert(p->which_payloadVariant == MeshPacket_encrypted_tag);
if (!decrypted) {
// Try to find a channel that works with this hash
for (chIndex = 0; chIndex < channels.getNumChannels(); chIndex++) {
// Try to use this hash/channel pair
if (channels.decryptForHash(chIndex, p->channel)) {
// we have to copy into a scratch buffer, because these bytes are a union with the decoded protobuf. Create a
// fresh copy for each decrypt attempt.
memcpy(bytes, p->encrypted.bytes, rawSize);
// Try to decrypt the packet if we can
crypto->decrypt(p->from, p->id, rawSize, bytes);
// printBytes("plaintext", bytes, p->encrypted.size);
// Take those raw bytes and convert them back into a well structured protobuf we can understand
meshtastic_Data decodedtmp;
memset(&decodedtmp, 0, sizeof(decodedtmp));
if (!pb_decode_from_bytes(bytes, rawSize, &meshtastic_Data_msg, &decodedtmp)) {
LOG_ERROR("Invalid protobufs in received mesh packet id=0x%08x (bad psk?)!", p->id);
} else if (decodedtmp.portnum == meshtastic_PortNum_UNKNOWN_APP) {
LOG_ERROR("Invalid portnum (bad psk?)!");
#if !(MESHTASTIC_EXCLUDE_PKI)
} else if (!owner.is_licensed && isToUs(p) && decodedtmp.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP) {
LOG_WARN("Rejecting legacy DM");
return DecodeState::DECODE_FAILURE;
#endif
} else {
p->decoded = decodedtmp;
p->which_payload_variant = meshtastic_MeshPacket_decoded_tag; // change type to decoded
decrypted = true;
break;
}
}
}
}
if (decrypted) {
// parsing was successful
p->channel = chIndex; // change to store the index instead of the hash
if (p->decoded.has_bitfield)
p->decoded.want_response |= p->decoded.bitfield & BITFIELD_WANT_RESPONSE_MASK;
/* Not actually ever used.
// Decompress if needed. jm
if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP) {
// Decompress the payload
char compressed_in[meshtastic_Constants_DATA_PAYLOAD_LEN] = {};
char decompressed_out[meshtastic_Constants_DATA_PAYLOAD_LEN] = {};
int decompressed_len;
memcpy(compressed_in, p->decoded.payload.bytes, p->decoded.payload.size);
decompressed_len = unishox2_decompress_simple(compressed_in, p->decoded.payload.size, decompressed_out);
// LOG_DEBUG("**Decompressed length - %d ", decompressed_len);
memcpy(p->decoded.payload.bytes, decompressed_out, decompressed_len);
// Switch the port from PortNum_TEXT_MESSAGE_COMPRESSED_APP to PortNum_TEXT_MESSAGE_APP
p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP;
} */
printPacket("decoded message", p);
#if ENABLE_JSON_LOGGING
LOG_TRACE("%s", MeshPacketSerializer::JsonSerialize(p, false).c_str());
#elif ARCH_PORTDUINO
if (portduino_config.traceFilename != "" || portduino_config.logoutputlevel == level_trace) {
LOG_TRACE("%s", MeshPacketSerializer::JsonSerialize(p, false).c_str());
}
#endif
return DecodeState::DECODE_SUCCESS;
} else {
LOG_WARN("No suitable channel found for decoding, hash was 0x%x!", p->channel);
return DecodeState::DECODE_FAILURE;
}
}
/** Return 0 for success or a Routing_Error code for failure
*/
meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p)
{
concurrency::LockGuard g(cryptLock);
int16_t hash;
// If the packet is not yet encrypted, do so now
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
if (isFromUs(p)) {
p->decoded.has_bitfield = true;
p->decoded.bitfield |= (config.lora.config_ok_to_mqtt << BITFIELD_OK_TO_MQTT_SHIFT);
p->decoded.bitfield |= (p->decoded.want_response << BITFIELD_WANT_RESPONSE_SHIFT);
}
size_t numbytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_Data_msg, &p->decoded);
/* Not actually used, so save the cycles
// TODO: Allow modules to opt into compression.
if (p->decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP) {
char original_payload[meshtastic_Constants_DATA_PAYLOAD_LEN];
memcpy(original_payload, p->decoded.payload.bytes, p->decoded.payload.size);
char compressed_out[meshtastic_Constants_DATA_PAYLOAD_LEN] = {0};
int compressed_len;
compressed_len = unishox2_compress_simple(original_payload, p->decoded.payload.size, compressed_out);
LOG_DEBUG("Original length - %d ", p->decoded.payload.size);
LOG_DEBUG("Compressed length - %d ", compressed_len);
LOG_DEBUG("Original message - %s ", p->decoded.payload.bytes);
// If the compressed length is greater than or equal to the original size, don't use the compressed form
if (compressed_len >= p->decoded.payload.size) {
LOG_DEBUG("Not using compressing message");
// Set the uncompressed payload variant anyway. Shouldn't hurt?
// p->decoded.which_payloadVariant = Data_payload_tag;
// Otherwise we use the compressor
} else {
LOG_DEBUG("Use compressed message");
// Copy the compressed data into the meshpacket
p->decoded.payload.size = compressed_len;
memcpy(p->decoded.payload.bytes, compressed_out, compressed_len);
p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP;
}
} */
if (numbytes + MESHTASTIC_HEADER_LENGTH > MAX_LORA_PAYLOAD_LEN)
return meshtastic_Routing_Error_TOO_LARGE;
// printBytes("plaintext", bytes, numbytes);
ChannelIndex chIndex = p->channel; // keep as a local because we are about to change it
#if !(MESHTASTIC_EXCLUDE_PKI)
meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(p->to);
// We may want to retool things so we can send a PKC packet when the client specifies a key and nodenum, even if the node
// is not in the local nodedb
// First, only PKC encrypt packets we are originating
if (isFromUs(p) &&
#if ARCH_PORTDUINO
// Sim radio via the cli flag skips PKC
!portduino_config.force_simradio &&
#endif
// Don't use PKC with Ham mode
!owner.is_licensed &&
// Don't use PKC on 'serial' or 'gpio' channels unless explicitly requested
!(p->pki_encrypted != true && (strcasecmp(channels.getName(chIndex), Channels::serialChannel) == 0 ||
strcasecmp(channels.getName(chIndex), Channels::gpioChannel) == 0)) &&
// Check for valid keys and single node destination
config.security.private_key.size == 32 && !isBroadcast(p->to) && node != nullptr &&
// Check for a known public key for the destination
(node->user.public_key.size == 32) &&
// Some portnums either make no sense to send with PKC
p->decoded.portnum != meshtastic_PortNum_TRACEROUTE_APP && p->decoded.portnum != meshtastic_PortNum_NODEINFO_APP &&
p->decoded.portnum != meshtastic_PortNum_ROUTING_APP && p->decoded.portnum != meshtastic_PortNum_POSITION_APP) {
LOG_DEBUG("Use PKI!");
if (numbytes + MESHTASTIC_HEADER_LENGTH + MESHTASTIC_PKC_OVERHEAD > MAX_LORA_PAYLOAD_LEN)
return meshtastic_Routing_Error_TOO_LARGE;
if (p->pki_encrypted && !memfll(p->public_key.bytes, 0, 32) &&
memcmp(p->public_key.bytes, node->user.public_key.bytes, 32) != 0) {
LOG_WARN("Client public key differs from requested: 0x%02x, stored key begins 0x%02x", *p->public_key.bytes,
*node->user.public_key.bytes);
return meshtastic_Routing_Error_PKI_FAILED;
}
crypto->encryptCurve25519(p->to, getFrom(p), node->user.public_key, p->id, numbytes, bytes, p->encrypted.bytes);
numbytes += MESHTASTIC_PKC_OVERHEAD;
p->channel = 0;
p->pki_encrypted = true;
} else {
if (p->pki_encrypted == true) {
// Client specifically requested PKI encryption
return meshtastic_Routing_Error_PKI_FAILED;
}
hash = channels.setActiveByIndex(chIndex);
// Now that we are encrypting the packet channel should be the hash (no longer the index)
p->channel = hash;
if (hash < 0) {
// No suitable channel could be found for
return meshtastic_Routing_Error_NO_CHANNEL;
}
crypto->encryptPacket(getFrom(p), p->id, numbytes, bytes);
memcpy(p->encrypted.bytes, bytes, numbytes);
}
#else
if (p->pki_encrypted == true) {
// Client specifically requested PKI encryption
return meshtastic_Routing_Error_PKI_FAILED;
}
hash = channels.setActiveByIndex(chIndex);
// Now that we are encrypting the packet channel should be the hash (no longer the index)
p->channel = hash;
if (hash < 0) {
// No suitable channel could be found for
return meshtastic_Routing_Error_NO_CHANNEL;
}
crypto->encryptPacket(getFrom(p), p->id, numbytes, bytes);
memcpy(p->encrypted.bytes, bytes, numbytes);
#endif
// Copy back into the packet and set the variant type
p->encrypted.size = numbytes;
p->which_payload_variant = meshtastic_MeshPacket_encrypted_tag;
}
return meshtastic_Routing_Error_NONE;
}
NodeNum Router::getNodeNum()
{
return nodeDB->getNodeNum();
}
/**
* Handle any packet that is received by an interface on this node.
* Note: some packets may merely being passed through this node and will be forwarded elsewhere.
*/
void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src)
{
bool skipHandle = false;
// Also, we should set the time from the ISR and it should have msec level resolution
p->rx_time = getValidTime(RTCQualityFromNet); // store the arrival timestamp for the phone
// Store a copy of encrypted packet for MQTT
DEBUG_HEAP_BEFORE;
meshtastic_MeshPacket *p_encrypted = packetPool.allocCopy(*p);
DEBUG_HEAP_AFTER("Router::handleReceived", p_encrypted);
// Take those raw bytes and convert them back into a well structured protobuf we can understand
auto decodedState = perhapsDecode(p);
if (decodedState == DecodeState::DECODE_FATAL) {
// Fatal decoding error, we can't do anything with this packet
LOG_WARN("Fatal decode error, dropping packet");
cancelSending(p->from, p->id);
skipHandle = true;
} else if (decodedState == DecodeState::DECODE_SUCCESS) {
// parsing was successful, queue for our recipient
if (src == RX_SRC_LOCAL)
printPacket("handleReceived(LOCAL)", p);
else if (src == RX_SRC_USER)
printPacket("handleReceived(USER)", p);
else
printPacket("handleReceived(REMOTE)", p);
// Neighbor info module is disabled, ignore expensive neighbor info packets
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag &&
p->decoded.portnum == meshtastic_PortNum_NEIGHBORINFO_APP &&
(!moduleConfig.has_neighbor_info || !moduleConfig.neighbor_info.enabled)) {
LOG_DEBUG("Neighbor info module is disabled, ignore neighbor packet");
cancelSending(p->from, p->id);
skipHandle = true;
}
bool shouldIgnoreNonstandardPorts =
config.device.rebroadcast_mode == meshtastic_Config_DeviceConfig_RebroadcastMode_CORE_PORTNUMS_ONLY;
#if USERPREFS_EVENT_MODE
shouldIgnoreNonstandardPorts = true;
#endif
if (shouldIgnoreNonstandardPorts && p->which_payload_variant == meshtastic_MeshPacket_decoded_tag &&
!IS_ONE_OF(p->decoded.portnum, meshtastic_PortNum_TEXT_MESSAGE_APP, meshtastic_PortNum_TEXT_MESSAGE_COMPRESSED_APP,
meshtastic_PortNum_POSITION_APP, meshtastic_PortNum_NODEINFO_APP, meshtastic_PortNum_ROUTING_APP,
meshtastic_PortNum_TELEMETRY_APP, meshtastic_PortNum_ADMIN_APP, meshtastic_PortNum_ALERT_APP,
meshtastic_PortNum_KEY_VERIFICATION_APP, meshtastic_PortNum_WAYPOINT_APP,
meshtastic_PortNum_STORE_FORWARD_APP, meshtastic_PortNum_TRACEROUTE_APP)) {
LOG_DEBUG("Ignore packet on non-standard portnum for CORE_PORTNUMS_ONLY");
cancelSending(p->from, p->id);
skipHandle = true;
}
} else {
printPacket("packet decoding failed or skipped (no PSK?)", p);
}
// call modules here
// If this could be a spoofed packet, don't let the modules see it.
if (!skipHandle) {
MeshModule::callModules(*p, src);
#if !MESHTASTIC_EXCLUDE_MQTT
// Mark as pki_encrypted if it is not yet decoded and MQTT encryption is also enabled, hash matches and it's a DM not to
// us (because we would be able to decrypt it)
if (decodedState == DecodeState::DECODE_FAILURE && moduleConfig.mqtt.encryption_enabled && p->channel == 0x00 &&
!isBroadcast(p->to) && !isToUs(p))
p_encrypted->pki_encrypted = true;
// After potentially altering it, publish received message to MQTT if we're not the original transmitter of the packet
if ((decodedState == DecodeState::DECODE_SUCCESS || p_encrypted->pki_encrypted) && moduleConfig.mqtt.enabled &&
!isFromUs(p) && mqtt)
mqtt->onSend(*p_encrypted, *p, p->channel);
#endif
}
packetPool.release(p_encrypted); // Release the encrypted packet
}
void Router::perhapsHandleReceived(meshtastic_MeshPacket *p)
{
#if ENABLE_JSON_LOGGING
// Even ignored packets get logged in the trace
p->rx_time = getValidTime(RTCQualityFromNet); // store the arrival timestamp for the phone
LOG_TRACE("%s", MeshPacketSerializer::JsonSerializeEncrypted(p).c_str());
#elif ARCH_PORTDUINO
// Even ignored packets get logged in the trace
if (portduino_config.traceFilename != "" || portduino_config.logoutputlevel == level_trace) {
p->rx_time = getValidTime(RTCQualityFromNet); // store the arrival timestamp for the phone
LOG_TRACE("%s", MeshPacketSerializer::JsonSerializeEncrypted(p).c_str());
}
#endif
// assert(radioConfig.has_preferences);
if (is_in_repeated(config.lora.ignore_incoming, p->from)) {
LOG_DEBUG("Ignore msg, 0x%x is in our ignore list", p->from);
packetPool.release(p);
return;
}
meshtastic_NodeInfoLite const *node = nodeDB->getMeshNode(p->from);
if (node != NULL && node->is_ignored) {
LOG_DEBUG("Ignore msg, 0x%x is ignored", p->from);
packetPool.release(p);
return;
}
if (p->from == NODENUM_BROADCAST) {
LOG_DEBUG("Ignore msg from broadcast address");
packetPool.release(p);
return;
}
if (config.lora.ignore_mqtt && p->via_mqtt) {
LOG_DEBUG("Msg came in via MQTT from 0x%x", p->from);
packetPool.release(p);
return;
}
if (shouldFilterReceived(p)) {
LOG_DEBUG("Incoming msg was filtered from 0x%x", p->from);
packetPool.release(p);
return;
}
// Note: we avoid calling shouldFilterReceived if we are supposed to ignore certain nodes - because some overrides might
// cache/learn of the existence of nodes (i.e. FloodRouter) that they should not
handleReceived(p);
packetPool.release(p);
}
@@ -0,0 +1,178 @@
#pragma once
#include "Channels.h"
#include "MemoryPool.h"
#include "MeshTypes.h"
#include "Observer.h"
#include "PacketHistory.h"
#include "PointerQueue.h"
#include "RadioInterface.h"
#include "concurrency/OSThread.h"
/**
* A mesh aware router that supports multiple interfaces.
*/
class Router : protected concurrency::OSThread, protected PacketHistory
{
private:
/// Packets which have just arrived from the radio, ready to be processed by this service and possibly
/// forwarded to the phone.
PointerQueue<meshtastic_MeshPacket> fromRadioQueue;
protected:
RadioInterface *iface = NULL;
public:
/**
* Constructor
*
*/
Router();
/**
* Currently we only allow one interface, that may change in the future
*/
void addInterface(RadioInterface *_iface) { iface = _iface; }
/**
* do idle processing
* Mostly looking in our incoming rxPacket queue and calling handleReceived.
*/
virtual int32_t runOnce() override;
/**
* Works like send, but if we are sending to the local node, we directly put the message in the receive queue.
* This is the primary method used for sending packets, because it handles both the remote and local cases.
*
* NOTE: This method will free the provided packet (even if we return an error code)
*/
ErrorCode sendLocal(meshtastic_MeshPacket *p, RxSource src = RX_SRC_RADIO);
/** Attempt to cancel a previously sent packet. Returns true if a packet was found we could cancel */
bool cancelSending(NodeNum from, PacketId id);
/** Attempt to find a packet in the TxQueue. Returns true if the packet was found. */
bool findInTxQueue(NodeNum from, PacketId id);
/** Allocate and return a meshpacket which defaults as send to broadcast from the current node.
* The returned packet is guaranteed to have a unique packet ID already assigned
*/
meshtastic_MeshPacket *allocForSending();
/** Return Underlying interface's TX queue status */
meshtastic_QueueStatus getQueueStatus();
/**
* @return our local nodenum */
NodeNum getNodeNum();
/** Wake up the router thread ASAP, because we just queued a message for it.
* FIXME, this is kinda a hack because we don't have a nice way yet to say 'wake us because we are 'blocked on this queue'
*/
void setReceivedMessage();
/**
* RadioInterface calls this to queue up packets that have been received from the radio. The router is now responsible for
* freeing the packet
*/
virtual void enqueueReceivedMessage(meshtastic_MeshPacket *p);
/**
* Send a packet on a suitable interface. This routine will
* later free() the packet to pool. This routine is not allowed to stall.
* If the txmit queue is full it might return an error
*
* NOTE: This method will free the provided packet (even if we return an error code)
*/
virtual ErrorCode send(meshtastic_MeshPacket *p);
virtual ErrorCode rawSend(meshtastic_MeshPacket *p);
/* Statistics for the amount of duplicate received packets and the amount of times we cancel a relay because someone did it
before us */
uint32_t rxDupe = 0, txRelayCanceled = 0;
protected:
friend class RoutingModule;
/**
* Should this incoming filter be dropped?
*
* FIXME, move this into the new RoutingModule and do the filtering there using the regular module logic
*
* Called immediately on reception, before any further processing.
* @return true to abandon the packet
*/
virtual bool shouldFilterReceived(const meshtastic_MeshPacket *p) { return false; }
/**
* Determine if hop_limit should be decremented for a relay operation.
* Returns false (preserve hop_limit) only if all conditions are met:
* - It's NOT the first hop (first hop must always decrement)
* - Local device is a ROUTER, ROUTER_LATE, or CLIENT_BASE
* - Previous relay is a favorite ROUTER, ROUTER_LATE, or CLIENT_BASE
*
* @param p The packet being relayed
* @return true if hop_limit should be decremented, false to preserve it
*/
bool shouldDecrementHopLimit(const meshtastic_MeshPacket *p);
/**
* Every (non duplicate) packet this node receives will be passed through this method. This allows subclasses to
* update routing tables etc... based on what we overhear (even for messages not destined to our node)
*/
virtual void sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c);
/**
* Send an ack or a nak packet back towards whoever sent idFrom
*/
void sendAckNak(meshtastic_Routing_Error err, NodeNum to, PacketId idFrom, ChannelIndex chIndex, uint8_t hopLimit = 0,
bool ackWantsAck = false);
private:
/**
* Called from loop()
* Handle any packet that is received by an interface on this node.
* Note: some packets may merely being passed through this node and will be forwarded elsewhere.
*
* Note: this packet will never be called for messages sent/generated by this node.
* Note: this method will free the provided packet.
*/
void perhapsHandleReceived(meshtastic_MeshPacket *p);
/**
* Called from perhapsHandleReceived() - allows subclass message delivery behavior.
* Handle any packet that is received by an interface on this node.
* Note: some packets may merely being passed through this node and will be forwarded elsewhere.
*
* Note: this packet will never be called for messages sent/generated by this node.
* Note: this method will free the provided packet.
*/
void handleReceived(meshtastic_MeshPacket *p, RxSource src = RX_SRC_RADIO);
/** Frees the provided packet, and generates a NAK indicating the specifed error while sending */
void abortSendAndNak(meshtastic_Routing_Error err, meshtastic_MeshPacket *p);
};
enum DecodeState { DECODE_SUCCESS, DECODE_FAILURE, DECODE_FATAL };
/** FIXME - move this into a mesh packet class
* Remove any encryption and decode the protobufs inside this packet (if necessary).
*
* @return true for success, false for corrupt packet.
*/
DecodeState perhapsDecode(meshtastic_MeshPacket *p);
/** Return 0 for success or a Routing_Error code for failure
*/
meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p);
extern Router *router;
/// Generate a unique packet id
// FIXME, move this someplace better
PacketId generatePacketId();
#define BITFIELD_WANT_RESPONSE_SHIFT 1
#define BITFIELD_OK_TO_MQTT_SHIFT 0
#define BITFIELD_WANT_RESPONSE_MASK (1 << BITFIELD_WANT_RESPONSE_SHIFT)
#define BITFIELD_OK_TO_MQTT_MASK (1 << BITFIELD_OK_TO_MQTT_SHIFT)
@@ -0,0 +1,44 @@
#include "configuration.h"
#ifdef ARCH_STM32WL
#include "STM32WLE5JCInterface.h"
#include "error.h"
#ifndef STM32WLx_MAX_POWER
#define STM32WLx_MAX_POWER 22
#endif
STM32WLE5JCInterface::STM32WLE5JCInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq,
RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy)
: SX126xInterface(hal, cs, irq, rst, busy)
{
}
bool STM32WLE5JCInterface::init()
{
RadioLibInterface::init();
// https://github.com/Seeed-Studio/LoRaWan-E5-Node/blob/main/Middlewares/Third_Party/SubGHz_Phy/stm32_radio_driver/radio_driver.c
#if (!defined(_VARIANT_RAK3172_))
setTCXOVoltage(1.7);
#endif
lora.setRfSwitchTable(rfswitch_pins, rfswitch_table);
limitPower(STM32WLx_MAX_POWER);
int res = lora.begin(getFreq(), bw, sf, cr, syncWord, power, preambleLength, tcxoVoltage);
LOG_INFO("STM32WLx init result %d", res);
LOG_INFO("Frequency set to %f", getFreq());
LOG_INFO("Bandwidth set to %f", bw);
LOG_INFO("Power output set to %d", power);
if (res == RADIOLIB_ERR_NONE)
startReceive(); // start receiving
return res == RADIOLIB_ERR_NONE;
}
#endif // ARCH_STM32WL
@@ -0,0 +1,19 @@
#pragma once
#ifdef ARCH_STM32WL
#include "SX126xInterface.h"
#include "rfswitch.h"
/**
* Our adapter for STM32WLE5JC radios
*/
class STM32WLE5JCInterface : public SX126xInterface<STM32WLx>
{
public:
STM32WLE5JCInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
virtual bool init() override;
};
#endif // ARCH_STM32WL
@@ -0,0 +1,11 @@
#if RADIOLIB_EXCLUDE_SX126X != 1
#include "SX1262Interface.h"
#include "configuration.h"
#include "error.h"
SX1262Interface::SX1262Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: SX126xInterface(hal, cs, irq, rst, busy)
{
}
#endif
@@ -0,0 +1,15 @@
#if RADIOLIB_EXCLUDE_SX126X != 1
#pragma once
#include "SX126xInterface.h"
/**
* Our adapter for SX1262 radios
*/
class SX1262Interface : public SX126xInterface<SX1262>
{
public:
SX1262Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
};
#endif
@@ -0,0 +1,20 @@
#if RADIOLIB_EXCLUDE_SX126X != 1
#include "SX1268Interface.h"
#include "configuration.h"
#include "error.h"
SX1268Interface::SX1268Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: SX126xInterface(hal, cs, irq, rst, busy)
{
}
float SX1268Interface::getFreq()
{
// Set frequency to default of EU_433 if outside of allowed range (e.g. when region is UNSET)
if (savedFreq < 410 || savedFreq > 810)
return 433.125f;
else
return savedFreq;
}
#endif
@@ -0,0 +1,17 @@
#pragma once
#if RADIOLIB_EXCLUDE_SX126X != 1
#include "SX126xInterface.h"
/**
* Our adapter for SX1268 radios
*/
class SX1268Interface : public SX126xInterface<SX1268>
{
public:
virtual float getFreq() override;
SX1268Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
};
#endif
@@ -0,0 +1,378 @@
#if RADIOLIB_EXCLUDE_SX126X != 1
#include "SX126xInterface.h"
#include "configuration.h"
#include "error.h"
#include "mesh/NodeDB.h"
#ifdef ARCH_PORTDUINO
#include "PortduinoGlue.h"
#endif
#include "Throttle.h"
// Particular boards might define a different max power based on what their hardware can do, default to max power output if not
// specified (may be dangerous if using external PA and SX126x power config forgotten)
#if ARCH_PORTDUINO
#define SX126X_MAX_POWER portduino_config.sx126x_max_power
#endif
#ifndef SX126X_MAX_POWER
#define SX126X_MAX_POWER 22
#endif
template <typename T>
SX126xInterface<T>::SX126xInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: RadioLibInterface(hal, cs, irq, rst, busy, &lora), lora(&module)
{
LOG_DEBUG("SX126xInterface(cs=%d, irq=%d, rst=%d, busy=%d)", cs, irq, rst, busy);
}
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
template <typename T> bool SX126xInterface<T>::init()
{
// Typically, the RF switch on SX126x boards is controlled by two signals, which are negations of each other (switched RFIO
// paths). The negation is usually performed in hardware, or (suboptimal design) TXEN and RXEN are the two inputs to this style of
// RF switch. On some boards, there is no hardware negation between CTRL and ¬CTRL, but CTRL is internally connected to DIO2, and
// DIO2's switching is done by the SX126X itself, so the MCU can't control ¬CTRL at exactly the same time. One solution would be
// to set ¬CTRL as SX126X_TXEN or SX126X_RXEN, but they may already be used for another purpose, such as controlling another
// PA/LNA. Keeping ¬CTRL high seems to work, as long CTRL=1, ¬CTRL=1 has the opposite and stable RF path effect as CTRL=0 and
// ¬CTRL=1, this depends on the RF switch, but it seems this usually works. Better hardware design, which is done most the time,
// means this workaround is not necessary.
#ifdef SX126X_ANT_SW // Perhaps add RADIOLIB_NC check, and beforehand define as such if it is undefined, but it is not commonly
// used and not part of the 'default' set of pin definitions.
digitalWrite(SX126X_ANT_SW, HIGH);
pinMode(SX126X_ANT_SW, OUTPUT);
#endif
#ifdef SX126X_POWER_EN // Perhaps add RADIOLIB_NC check, and beforehand define as such if it is undefined, but it is not commonly
// used and not part of the 'default' set of pin definitions.
digitalWrite(SX126X_POWER_EN, HIGH);
pinMode(SX126X_POWER_EN, OUTPUT);
#endif
#if defined(USE_GC1109_PA)
pinMode(LORA_PA_POWER, OUTPUT);
digitalWrite(LORA_PA_POWER, HIGH);
pinMode(LORA_PA_EN, OUTPUT);
digitalWrite(LORA_PA_EN, LOW);
pinMode(LORA_PA_TX_EN, OUTPUT);
digitalWrite(LORA_PA_TX_EN, LOW);
#endif
#if ARCH_PORTDUINO
tcxoVoltage = (float)portduino_config.dio3_tcxo_voltage / 1000;
if (portduino_config.lora_sx126x_ant_sw_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_sx126x_ant_sw_pin.pin, HIGH);
pinMode(portduino_config.lora_sx126x_ant_sw_pin.pin, OUTPUT);
}
#endif
if (tcxoVoltage == 0.0)
LOG_DEBUG("SX126X_DIO3_TCXO_VOLTAGE not defined, not using DIO3 as TCXO reference voltage");
else
LOG_DEBUG("SX126X_DIO3_TCXO_VOLTAGE defined, using DIO3 as TCXO reference voltage at %f V", tcxoVoltage);
setTransmitEnable(false);
// FIXME: May want to set depending on a definition, currently all SX126x variant files use the DC-DC regulator option
bool useRegulatorLDO = false; // Seems to depend on the connection to pin 9/DCC_SW - if an inductor DCDC?
RadioLibInterface::init();
limitPower(SX126X_MAX_POWER);
// Make sure we reach the minimum power supported to turn the chip on (-9dBm)
if (power < -9)
power = -9;
int res = lora.begin(getFreq(), bw, sf, cr, syncWord, power, preambleLength, tcxoVoltage, useRegulatorLDO);
// \todo Display actual typename of the adapter, not just `SX126x`
LOG_INFO("SX126x init result %d", res);
if (res == RADIOLIB_ERR_CHIP_NOT_FOUND || res == RADIOLIB_ERR_SPI_CMD_FAILED)
return false;
LOG_INFO("Frequency set to %f", getFreq());
LOG_INFO("Bandwidth set to %f", bw);
LOG_INFO("Power output set to %d", power);
// Overriding current limit
// (https://github.com/jgromes/RadioLib/blob/690a050ebb46e6097c5d00c371e961c1caa3b52e/src/modules/SX126x/SX126x.cpp#L85) using
// value in SX126xInterface.h (currently 140 mA) It may or may not be necessary, depending on how RadioLib functions, from
// SX1261/2 datasheet: OCP after setting DeviceSel with SetPaConfig(): SX1261 - 60 mA, SX1262 - 140 mA For the SX1268 the IC
// defaults to 140mA no matter the set power level, but RadioLib set it lower, this would need further checking Default values
// are: SX1262, SX1268: 0x38 (140 mA), SX1261: 0x18 (60 mA)
// FIXME: Not ideal to increase SX1261 current limit above 60mA as it can only transmit max 15dBm, should probably only do it
// if using SX1262 or SX1268
res = lora.setCurrentLimit(currentLimit);
LOG_DEBUG("Current limit set to %f", currentLimit);
LOG_DEBUG("Current limit set result %d", res);
if (res == RADIOLIB_ERR_NONE) {
#ifdef SX126X_DIO2_AS_RF_SWITCH
bool dio2AsRfSwitch = true;
#elif defined(ARCH_PORTDUINO)
bool dio2AsRfSwitch = false;
if (portduino_config.dio2_as_rf_switch) {
dio2AsRfSwitch = true;
}
#else
bool dio2AsRfSwitch = false;
#endif
res = lora.setDio2AsRfSwitch(dio2AsRfSwitch);
LOG_DEBUG("Set DIO2 as %sRF switch, result: %d", dio2AsRfSwitch ? "" : "not ", res);
}
// If a pin isn't defined, we set it to RADIOLIB_NC, it is safe to always do external RF switching with RADIOLIB_NC as it has
// no effect
#if ARCH_PORTDUINO
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("Use MCU pin %i as RXEN and pin %i as TXEN to control RF switching", portduino_config.lora_rxen_pin.pin,
portduino_config.lora_txen_pin.pin);
lora.setRfSwitchPins(portduino_config.lora_rxen_pin.pin, portduino_config.lora_txen_pin.pin);
}
#else
#ifndef SX126X_RXEN
#define SX126X_RXEN RADIOLIB_NC
LOG_DEBUG("SX126X_RXEN not defined, defaulting to RADIOLIB_NC");
#endif
#ifndef SX126X_TXEN
#define SX126X_TXEN RADIOLIB_NC
LOG_DEBUG("SX126X_TXEN not defined, defaulting to RADIOLIB_NC");
#endif
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("Use MCU pin %i as RXEN and pin %i as TXEN to control RF switching", SX126X_RXEN, SX126X_TXEN);
lora.setRfSwitchPins(SX126X_RXEN, SX126X_TXEN);
}
#endif
if (config.lora.sx126x_rx_boosted_gain) {
uint16_t result = lora.setRxBoostedGainMode(true);
LOG_INFO("Set RX gain to boosted mode; result: %d", result);
} else {
uint16_t result = lora.setRxBoostedGainMode(false);
LOG_INFO("Set RX gain to power saving mode (boosted mode off); result: %d", result);
}
#if 0
// Read/write a register we are not using (only used for FSK mode) to test SPI comms
uint8_t crcLSB = 0;
int err = lora.readRegister(SX126X_REG_CRC_POLYNOMIAL_LSB, &crcLSB, 1);
if(err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_SX1262Failure);
//if(crcLSB != 0x0f)
// RECORD_CRITICALERROR(CriticalErrorCode_SX1262Failure);
crcLSB = 0x5a;
err = lora.writeRegister(SX126X_REG_CRC_POLYNOMIAL_LSB, &crcLSB, 1);
if(err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_SX1262Failure);
err = lora.readRegister(SX126X_REG_CRC_POLYNOMIAL_LSB, &crcLSB, 1);
if(err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(CriticalErrorCode_SX1262Failure);
if(crcLSB != 0x5a)
RECORD_CRITICALERROR(CriticalErrorCode_SX1262Failure);
// If we got this far register accesses (and therefore SPI comms) are good
#endif
if (res == RADIOLIB_ERR_NONE)
res = lora.setCRC(RADIOLIB_SX126X_LORA_CRC_ON);
if (res == RADIOLIB_ERR_NONE)
startReceive(); // start receiving
return res == RADIOLIB_ERR_NONE;
}
template <typename T> bool SX126xInterface<T>::reconfigure()
{
RadioLibInterface::reconfigure();
// set mode to standby
setStandby();
// configure publicly accessible settings
int err = lora.setSpreadingFactor(sf);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setBandwidth(bw);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setCodingRate(cr);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setSyncWord(syncWord);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX126X setSyncWord %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
err = lora.setCurrentLimit(currentLimit);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX126X setCurrentLimit %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
err = lora.setPreambleLength(preambleLength);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX126X setPreambleLength %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
err = lora.setFrequency(getFreq());
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
if (power > SX126X_MAX_POWER) // This chip has lower power limits than some
power = SX126X_MAX_POWER;
err = lora.setOutputPower(power);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX126X setOutputPower %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
startReceive(); // restart receiving
return RADIOLIB_ERR_NONE;
}
template <typename T> void INTERRUPT_ATTR SX126xInterface<T>::disableInterrupt()
{
lora.clearDio1Action();
}
template <typename T> void SX126xInterface<T>::setStandby()
{
checkNotification(); // handle any pending interrupts before we force standby
int err = lora.standby();
if (err != RADIOLIB_ERR_NONE)
LOG_DEBUG("SX126x standby %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
isReceiving = false; // If we were receiving, not any more
activeReceiveStart = 0;
disableInterrupt();
completeSending(); // If we were sending, not anymore
RadioLibInterface::setStandby();
}
/**
* Add SNR data to received messages
*/
template <typename T> void SX126xInterface<T>::addReceiveMetadata(meshtastic_MeshPacket *mp)
{
// LOG_DEBUG("PacketStatus %x", lora.getPacketStatus());
mp->rx_snr = lora.getSNR();
mp->rx_rssi = lround(lora.getRSSI());
LOG_DEBUG("Corrected frequency offset: %f", lora.getFrequencyError());
}
/** We override to turn on transmitter power as needed.
*/
template <typename T> void SX126xInterface<T>::configHardwareForSend()
{
setTransmitEnable(true);
RadioLibInterface::configHardwareForSend();
}
// For power draw measurements, helpful to force radio to stay sleeping
// #define SLEEP_ONLY
template <typename T> void SX126xInterface<T>::startReceive()
{
#ifdef SLEEP_ONLY
sleep();
#else
setTransmitEnable(false);
setStandby();
// We use a 16 bit preamble so this should save some power by letting radio sit in standby mostly.
int err = lora.startReceiveDutyCycleAuto(preambleLength, 8, MESHTASTIC_RADIOLIB_IRQ_RX_FLAGS);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX126X startReceiveDutyCycleAuto %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
RadioLibInterface::startReceive();
// Must be done AFTER, starting transmit, because startTransmit clears (possibly stale) interrupt pending register bits
enableInterrupt(isrRxLevel0);
#endif
}
/** Is the channel currently active? */
template <typename T> bool SX126xInterface<T>::isChannelActive()
{
// check if we can detect a LoRa preamble on the current channel
ChannelScanConfig_t cfg = {.cad = {.symNum = NUM_SYM_CAD,
.detPeak = RADIOLIB_SX126X_CAD_PARAM_DEFAULT,
.detMin = RADIOLIB_SX126X_CAD_PARAM_DEFAULT,
.exitMode = RADIOLIB_SX126X_CAD_PARAM_DEFAULT,
.timeout = 0,
.irqFlags = RADIOLIB_IRQ_CAD_DEFAULT_FLAGS,
.irqMask = RADIOLIB_IRQ_CAD_DEFAULT_MASK}};
int16_t result;
setTransmitEnable(false);
setStandby();
result = lora.scanChannel(cfg);
if (result == RADIOLIB_LORA_DETECTED)
return true;
if (result != RADIOLIB_CHANNEL_FREE)
LOG_ERROR("SX126X scanChannel %s%d", radioLibErr, result);
assert(result != RADIOLIB_ERR_WRONG_MODEM);
return false;
}
/** Could we send right now (i.e. either not actively receiving or transmitting)? */
template <typename T> bool SX126xInterface<T>::isActivelyReceiving()
{
// The IRQ status will be cleared when we start our read operation. Check if we've started a header, but haven't yet
// received and handled the interrupt for reading the packet/handling errors.
return receiveDetected(lora.getIrqFlags(), RADIOLIB_SX126X_IRQ_HEADER_VALID, RADIOLIB_SX126X_IRQ_PREAMBLE_DETECTED);
}
template <typename T> bool SX126xInterface<T>::sleep()
{
// Not keeping config is busted - next time nrf52 board boots lora sending fails tcxo related? - see datasheet
// \todo Display actual typename of the adapter, not just `SX126x`
LOG_DEBUG("SX126x entering sleep mode"); // (FIXME, don't keep config)
setStandby(); // Stop any pending operations
// turn off TCXO if it was powered
// FIXME - this isn't correct
// lora.setTCXO(0);
// put chipset into sleep mode (we've already disabled interrupts by now)
bool keepConfig = true;
lora.sleep(keepConfig); // Note: we do not keep the config, full reinit will be needed
#ifdef SX126X_POWER_EN
digitalWrite(SX126X_POWER_EN, LOW);
#endif
#if defined(USE_GC1109_PA)
/*
* Do not switch the power on and off frequently.
* After turning off LORA_PA_EN, the power consumption has dropped to the uA level.
* // digitalWrite(LORA_PA_POWER, LOW);
*/
digitalWrite(LORA_PA_EN, LOW);
digitalWrite(LORA_PA_TX_EN, LOW);
#endif
return true;
}
/** Some boards require GPIO control of tx vs rx paths */
template <typename T> void SX126xInterface<T>::setTransmitEnable(bool txon)
{
#if defined(USE_GC1109_PA)
digitalWrite(LORA_PA_POWER, HIGH);
digitalWrite(LORA_PA_EN, HIGH);
digitalWrite(LORA_PA_TX_EN, txon ? 1 : 0);
#endif
}
#endif
@@ -0,0 +1,81 @@
#pragma once
#if RADIOLIB_EXCLUDE_SX126X != 1
#include "RadioLibInterface.h"
/**
* \brief Adapter for SX126x radio family. Implements common logic for child classes.
* \tparam T RadioLib module type for SX126x: SX1262, SX1268.
*/
template <class T> class SX126xInterface : public RadioLibInterface
{
public:
SX126xInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool init() override;
/// Apply any radio provisioning changes
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool reconfigure() override;
/// Prepare hardware for sleep. Call this _only_ for deep sleep, not needed for light sleep.
virtual bool sleep() override;
bool isIRQPending() override { return lora.getIrqFlags() != 0; }
void setTCXOVoltage(float voltage) { tcxoVoltage = voltage; }
protected:
float currentLimit = 140; // Higher OCP limit for SX126x PA
float tcxoVoltage = 0.0;
/**
* Specific module instance
*/
T lora;
/**
* Glue functions called from ISR land
*/
virtual void disableInterrupt() override;
/**
* Enable a particular ISR callback glue function
*/
virtual void enableInterrupt(void (*callback)()) { lora.setDio1Action(callback); }
/** can we detect a LoRa preamble on the current channel? */
virtual bool isChannelActive() override;
/** are we actively receiving a packet (only called during receiving state) */
virtual bool isActivelyReceiving() override;
/**
* Start waiting to receive a message
*/
virtual void startReceive() override;
/**
* We override to turn on transmitter power as needed.
*/
virtual void configHardwareForSend() override;
/**
* Add SNR data to received messages
*/
virtual void addReceiveMetadata(meshtastic_MeshPacket *mp) override;
virtual void setStandby() override;
uint32_t getPacketTime(uint32_t pl, bool received) override { return computePacketTime(lora, pl, received); }
private:
/** Some boards require GPIO control of tx vs rx paths */
void setTransmitEnable(bool txon);
};
#endif
@@ -0,0 +1,11 @@
#if RADIOLIB_EXCLUDE_SX128X != 1
#include "SX1280Interface.h"
#include "configuration.h"
#include "error.h"
SX1280Interface::SX1280Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: SX128xInterface(hal, cs, irq, rst, busy)
{
}
#endif
@@ -0,0 +1,15 @@
#pragma once
#if RADIOLIB_EXCLUDE_SX128X != 1
#include "SX128xInterface.h"
/**
* Our adapter for SX1280 radios
*/
class SX1280Interface : public SX128xInterface<SX1280>
{
public:
SX1280Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
};
#endif
@@ -0,0 +1,326 @@
#if RADIOLIB_EXCLUDE_SX128X != 1
#include "SX128xInterface.h"
#include "Throttle.h"
#include "configuration.h"
#include "error.h"
#include "mesh/NodeDB.h"
#if ARCH_PORTDUINO
#include "PortduinoGlue.h"
#endif
// Particular boards might define a different max power based on what their hardware can do
#if ARCH_PORTDUINO
#define SX128X_MAX_POWER portduino_config.sx128x_max_power
#endif
#ifndef SX128X_MAX_POWER
#define SX128X_MAX_POWER 13
#endif
template <typename T>
SX128xInterface<T>::SX128xInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy)
: RadioLibInterface(hal, cs, irq, rst, busy, &lora), lora(&module)
{
LOG_DEBUG("SX128xInterface(cs=%d, irq=%d, rst=%d, busy=%d)", cs, irq, rst, busy);
}
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
template <typename T> bool SX128xInterface<T>::init()
{
#ifdef SX128X_POWER_EN
pinMode(SX128X_POWER_EN, OUTPUT);
digitalWrite(SX128X_POWER_EN, HIGH);
#endif
#ifdef RF95_FAN_EN
pinMode(RF95_FAN_EN, OUTPUT);
digitalWrite(RF95_FAN_EN, 1);
#endif
#if ARCH_PORTDUINO
if (portduino_config.lora_rxen_pin.pin != RADIOLIB_NC) {
pinMode(portduino_config.lora_rxen_pin.pin, OUTPUT);
digitalWrite(portduino_config.lora_rxen_pin.pin, LOW); // Set low before becoming an output
}
if (portduino_config.lora_txen_pin.pin != RADIOLIB_NC) {
pinMode(portduino_config.lora_txen_pin.pin, OUTPUT);
digitalWrite(portduino_config.lora_txen_pin.pin, LOW); // Set low before becoming an output
}
#else
#if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC) // set not rx or tx mode
pinMode(SX128X_RXEN, OUTPUT);
digitalWrite(SX128X_RXEN, LOW); // Set low before becoming an output
#endif
#if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC)
pinMode(SX128X_TXEN, OUTPUT);
digitalWrite(SX128X_TXEN, LOW);
#endif
#endif
RadioLibInterface::init();
limitPower(SX128X_MAX_POWER);
preambleLength = 12; // 12 is the default for this chip, 32 does not RX at all
int res = lora.begin(getFreq(), bw, sf, cr, syncWord, power, preambleLength);
// \todo Display actual typename of the adapter, not just `SX128x`
LOG_INFO("SX128x init result %d", res);
if ((config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24) && (res == RADIOLIB_ERR_INVALID_FREQUENCY)) {
LOG_WARN("Radio only supports 2.4GHz LoRa. Adjusting Region and rebooting");
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_LORA_24;
nodeDB->saveToDisk(SEGMENT_CONFIG);
delay(2000);
#if defined(ARCH_ESP32)
ESP.restart();
#elif defined(ARCH_NRF52)
NVIC_SystemReset();
#else
LOG_ERROR("FIXME implement reboot for this platform. Skip for now");
#endif
}
LOG_INFO("Frequency set to %f", getFreq());
LOG_INFO("Bandwidth set to %f", bw);
LOG_INFO("Power output set to %d", power);
#if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC) && defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC)
if (res == RADIOLIB_ERR_NONE) {
lora.setRfSwitchPins(SX128X_RXEN, SX128X_TXEN);
}
#elif ARCH_PORTDUINO
if (res == RADIOLIB_ERR_NONE && portduino_config.lora_rxen_pin.pin != RADIOLIB_NC &&
portduino_config.lora_txen_pin.pin != RADIOLIB_NC) {
lora.setRfSwitchPins(portduino_config.lora_rxen_pin.pin, portduino_config.lora_txen_pin.pin);
}
#endif
if (res == RADIOLIB_ERR_NONE)
res = lora.setCRC(2);
if (res == RADIOLIB_ERR_NONE)
startReceive(); // start receiving
return res == RADIOLIB_ERR_NONE;
}
template <typename T> bool SX128xInterface<T>::reconfigure()
{
RadioLibInterface::reconfigure();
// set mode to standby
setStandby();
// configure publicly accessible settings
int err = lora.setSpreadingFactor(sf);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setBandwidth(bw);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setCodingRate(cr);
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
err = lora.setSyncWord(syncWord);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX128X setSyncWord %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
err = lora.setPreambleLength(preambleLength);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX128X setPreambleLength %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
err = lora.setFrequency(getFreq());
if (err != RADIOLIB_ERR_NONE)
RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_INVALID_RADIO_SETTING);
if (power > SX128X_MAX_POWER) // This chip has lower power limits than some
power = SX128X_MAX_POWER;
err = lora.setOutputPower(power);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX128X setOutputPower %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
startReceive(); // restart receiving
return RADIOLIB_ERR_NONE;
}
template <typename T> void INTERRUPT_ATTR SX128xInterface<T>::disableInterrupt()
{
lora.clearDio1Action();
}
template <typename T> bool SX128xInterface<T>::wideLora()
{
return true;
}
template <typename T> void SX128xInterface<T>::setStandby()
{
checkNotification(); // handle any pending interrupts before we force standby
int err = lora.standby();
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX128x standby %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
#if ARCH_PORTDUINO
if (portduino_config.lora_rxen_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_rxen_pin.pin, LOW);
}
if (portduino_config.lora_txen_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_txen_pin.pin, LOW);
}
#else
#if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC) // we have RXEN/TXEN control - turn off RX and TX power
digitalWrite(SX128X_RXEN, LOW);
#endif
#if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC)
digitalWrite(SX128X_TXEN, LOW);
#endif
#endif
isReceiving = false; // If we were receiving, not any more
activeReceiveStart = 0;
disableInterrupt();
completeSending(); // If we were sending, not anymore
RadioLibInterface::setStandby();
}
/**
* Add SNR data to received messages
*/
template <typename T> void SX128xInterface<T>::addReceiveMetadata(meshtastic_MeshPacket *mp)
{
// LOG_DEBUG("PacketStatus %x", lora.getPacketStatus());
mp->rx_snr = lora.getSNR();
mp->rx_rssi = lround(lora.getRSSI());
LOG_DEBUG("Corrected frequency offset: %f", lora.getFrequencyError());
}
/** We override to turn on transmitter power as needed.
*/
template <typename T> void SX128xInterface<T>::configHardwareForSend()
{
#if ARCH_PORTDUINO
if (portduino_config.lora_txen_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_txen_pin.pin, HIGH);
}
if (portduino_config.lora_rxen_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_rxen_pin.pin, LOW);
}
#else
#if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC) // we have RXEN/TXEN control - turn on TX power / off RX power
digitalWrite(SX128X_TXEN, HIGH);
#endif
#if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC)
digitalWrite(SX128X_RXEN, LOW);
#endif
#endif
RadioLibInterface::configHardwareForSend();
}
// For power draw measurements, helpful to force radio to stay sleeping
// #define SLEEP_ONLY
template <typename T> void SX128xInterface<T>::startReceive()
{
#ifdef SLEEP_ONLY
sleep();
#else
setStandby();
#if ARCH_PORTDUINO
if (portduino_config.lora_rxen_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_rxen_pin.pin, HIGH);
}
if (portduino_config.lora_txen_pin.pin != RADIOLIB_NC) {
digitalWrite(portduino_config.lora_txen_pin.pin, LOW);
}
#else
#if defined(SX128X_RXEN) && (SX128X_RXEN != RADIOLIB_NC) // we have RXEN/TXEN control - turn on RX power / off TX power
digitalWrite(SX128X_RXEN, HIGH);
#endif
#if defined(SX128X_TXEN) && (SX128X_TXEN != RADIOLIB_NC)
digitalWrite(SX128X_TXEN, LOW);
#endif
#endif
int err = lora.startReceive(RADIOLIB_SX128X_RX_TIMEOUT_INF, MESHTASTIC_RADIOLIB_IRQ_RX_FLAGS);
if (err != RADIOLIB_ERR_NONE)
LOG_ERROR("SX128X startReceive %s%d", radioLibErr, err);
assert(err == RADIOLIB_ERR_NONE);
RadioLibInterface::startReceive();
// Must be done AFTER, starting transmit, because startTransmit clears (possibly stale) interrupt pending register bits
enableInterrupt(isrRxLevel0);
#endif
}
/** Is the channel currently active? */
template <typename T> bool SX128xInterface<T>::isChannelActive()
{
// check if we can detect a LoRa preamble on the current channel
ChannelScanConfig_t cfg = {.cad = {.symNum = NUM_SYM_CAD_24GHZ,
.detPeak = 0,
.detMin = 0,
.exitMode = 0,
.timeout = 0,
.irqFlags = RADIOLIB_IRQ_CAD_DEFAULT_FLAGS,
.irqMask = RADIOLIB_IRQ_CAD_DEFAULT_MASK}};
int16_t result;
setStandby();
result = lora.scanChannel(cfg);
if (result == RADIOLIB_LORA_DETECTED)
return true;
if (result != RADIOLIB_CHANNEL_FREE)
LOG_ERROR("SX128X scanChannel %s%d", radioLibErr, result);
assert(result != RADIOLIB_ERR_WRONG_MODEM);
return false;
}
/** Could we send right now (i.e. either not actively receiving or transmitting)? */
template <typename T> bool SX128xInterface<T>::isActivelyReceiving()
{
return receiveDetected(lora.getIrqStatus(), RADIOLIB_SX128X_IRQ_HEADER_VALID, RADIOLIB_SX128X_IRQ_PREAMBLE_DETECTED);
}
template <typename T> bool SX128xInterface<T>::sleep()
{
// Not keeping config is busted - next time nrf52 board boots lora sending fails tcxo related? - see datasheet
// \todo Display actual typename of the adapter, not just `SX128x`
LOG_DEBUG("SX128x entering sleep mode"); // (FIXME, don't keep config)
setStandby(); // Stop any pending operations
// turn off TCXO if it was powered
// FIXME - this isn't correct
// lora.setTCXO(0);
// put chipset into sleep mode (we've already disabled interrupts by now)
bool keepConfig = true;
lora.sleep(keepConfig); // Note: we do not keep the config, full reinit will be needed
#ifdef SX128X_POWER_EN
digitalWrite(SX128X_POWER_EN, LOW);
#endif
return true;
}
#endif
@@ -0,0 +1,72 @@
#pragma once
#include "RadioLibInterface.h"
/**
* \brief Adapter for SX128x radio family. Implements common logic for child classes.
* \tparam T RadioLib module type for SX128x: SX1280.
*/
template <class T> class SX128xInterface : public RadioLibInterface
{
public:
SX128xInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
RADIOLIB_PIN_TYPE busy);
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool init() override;
virtual bool wideLora() override;
/// Apply any radio provisioning changes
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool reconfigure() override;
/// Prepare hardware for sleep. Call this _only_ for deep sleep, not needed for light sleep.
virtual bool sleep() override;
bool isIRQPending() override { return lora.getIrqFlags() != 0; }
protected:
/**
* Specific module instance
*/
T lora;
/**
* Glue functions called from ISR land
*/
virtual void disableInterrupt() override;
/**
* Enable a particular ISR callback glue function
*/
virtual void enableInterrupt(void (*callback)()) { lora.setDio1Action(callback); }
/** can we detect a LoRa preamble on the current channel? */
virtual bool isChannelActive() override;
/** are we actively receiving a packet (only called during receiving state) */
virtual bool isActivelyReceiving() override;
/**
* Start waiting to receive a message
*/
virtual void startReceive() override;
/**
* We override to turn on transmitter power as needed.
*/
virtual void configHardwareForSend() override;
/**
* Add SNR data to received messages
*/
virtual void addReceiveMetadata(meshtastic_MeshPacket *mp) override;
virtual void setStandby() override;
uint32_t getPacketTime(uint32_t pl, bool received) override { return computePacketTime(lora, pl, received); }
};
@@ -0,0 +1,39 @@
#pragma once
#include "MeshModule.h"
#include "Router.h"
/**
* Most modules are only interested in sending/receiving one particular portnum. This baseclass simplifies that common
* case.
*/
class SinglePortModule : public MeshModule
{
protected:
meshtastic_PortNum ourPortNum;
public:
/** Constructor
* name is for debugging output
*/
SinglePortModule(const char *_name, meshtastic_PortNum _ourPortNum) : MeshModule(_name), ourPortNum(_ourPortNum) {}
protected:
/**
* @return true if you want to receive the specified portnum
*/
virtual bool wantPacket(const meshtastic_MeshPacket *p) override { return p->decoded.portnum == ourPortNum; }
/**
* Return a mesh packet which has been preinited as a data packet with a particular port number.
* You can then send this packet (after customizing any of the payload fields you might need) with
* service->sendToMesh()
*/
meshtastic_MeshPacket *allocDataPacket()
{
// Update our local node info with our position (even if we don't decide to update anyone else)
meshtastic_MeshPacket *p = router->allocForSending();
p->decoded.portnum = ourPortNum;
return p;
}
};
@@ -0,0 +1,77 @@
#pragma once
#include "concurrency/OSThread.h"
#include "freertosinc.h"
#include <cassert>
/**
* A static circular buffer queue for pointers.
* This provides the same interface as PointerQueue but uses a statically allocated
* buffer instead of dynamic allocation.
*/
template <class T, int MaxElements> class StaticPointerQueue
{
static_assert(MaxElements > 0, "MaxElements must be greater than 0");
T *buffer[MaxElements];
int head = 0;
int tail = 0;
int count = 0;
concurrency::OSThread *reader = nullptr;
public:
StaticPointerQueue()
{
// Initialize all buffer elements to nullptr to silence warnings and ensure clean state
for (int i = 0; i < MaxElements; i++) {
buffer[i] = nullptr;
}
}
int numFree() const { return MaxElements - count; }
bool isEmpty() const { return count == 0; }
int numUsed() const { return count; }
bool enqueue(T *x, TickType_t maxWait = portMAX_DELAY)
{
if (count >= MaxElements) {
return false; // Queue is full
}
if (reader) {
reader->setInterval(0);
concurrency::mainDelay.interrupt();
}
buffer[tail] = x;
tail = (tail + 1) % MaxElements;
count++;
return true;
}
bool dequeue(T **p, TickType_t maxWait = portMAX_DELAY)
{
if (count == 0) {
return false; // Queue is empty
}
*p = buffer[head];
head = (head + 1) % MaxElements;
count--;
return true;
}
// returns a ptr or null if the queue was empty
T *dequeuePtr(TickType_t maxWait = portMAX_DELAY)
{
T *p;
return dequeue(&p, maxWait) ? p : nullptr;
}
void setReader(concurrency::OSThread *t) { reader = t; }
// For compatibility with PointerQueue interface
int getMaxLen() const { return MaxElements; }
};
@@ -0,0 +1,227 @@
#include "StreamAPI.h"
#include "PowerFSM.h"
#include "RTC.h"
#include "Throttle.h"
#include "configuration.h"
#define START1 0x94
#define START2 0xc3
#define HEADER_LEN 4
int32_t StreamAPI::runOncePart()
{
auto result = readStream();
writeStream();
checkConnectionTimeout();
return result;
}
int32_t StreamAPI::runOncePart(char *buf, uint16_t bufLen)
{
auto result = readStream(buf, bufLen);
writeStream();
checkConnectionTimeout();
return result;
}
/**
* Read any rx chars from the link and call handleRecStream
*/
int32_t StreamAPI::readStream(char *buf, uint16_t bufLen)
{
if (bufLen < 1) {
// Nothing available this time, if the computer has talked to us recently, poll often, otherwise let CPU sleep a long time
bool recentRx = Throttle::isWithinTimespanMs(lastRxMsec, 2000);
return recentRx ? 5 : 250;
} else {
handleRecStream(buf, bufLen);
// we had bytes available this time, so assume we might have them next time also
lastRxMsec = millis();
return 0;
}
}
/**
* call getFromRadio() and deliver encapsulated packets to the Stream
*/
void StreamAPI::writeStream()
{
if (canWrite) {
uint32_t len;
do {
// Send every packet we can
len = getFromRadio(txBuf + HEADER_LEN);
emitTxBuffer(len);
} while (len);
}
}
int32_t StreamAPI::handleRecStream(char *buf, uint16_t bufLen)
{
uint16_t index = 0;
while (bufLen > index) { // Currently we never want to block
int cInt = buf[index++];
if (cInt < 0)
break; // We ran out of characters (even though available said otherwise) - this can happen on rf52 adafruit
// arduino
uint8_t c = (uint8_t)cInt;
// Use the read pointer for a little state machine, first look for framing, then length bytes, then payload
size_t ptr = rxPtr;
rxPtr++; // assume we will probably advance the rxPtr
rxBuf[ptr] = c; // store all bytes (including framing)
// console->printf("rxPtr %d ptr=%d c=0x%x\n", rxPtr, ptr, c);
if (ptr == 0) { // looking for START1
if (c != START1)
rxPtr = 0; // failed to find framing
} else if (ptr == 1) { // looking for START2
if (c != START2)
rxPtr = 0; // failed to find framing
} else if (ptr >= HEADER_LEN - 1) { // we have at least read our 4 byte framing
uint32_t len = (rxBuf[2] << 8) + rxBuf[3]; // big endian 16 bit length follows framing
// console->printf("len %d\n", len);
if (ptr == HEADER_LEN - 1) {
// we _just_ finished our 4 byte header, validate length now (note: a length of zero is a valid
// protobuf also)
if (len > MAX_TO_FROM_RADIO_SIZE)
rxPtr = 0; // length is bogus, restart search for framing
}
if (rxPtr != 0) // Is packet still considered 'good'?
if (ptr + 1 >= len + HEADER_LEN) { // have we received all of the payload?
rxPtr = 0; // start over again on the next packet
// If we didn't just fail the packet and we now have the right # of bytes, parse it
handleToRadio(rxBuf + HEADER_LEN, len);
}
}
}
return 0;
}
/**
* Read any rx chars from the link and call handleToRadio
*/
int32_t StreamAPI::readStream()
{
if (!stream->available()) {
// Nothing available this time, if the computer has talked to us recently, poll often, otherwise let CPU sleep a long time
bool recentRx = Throttle::isWithinTimespanMs(lastRxMsec, 2000);
return recentRx ? 5 : 250;
} else {
while (stream->available()) { // Currently we never want to block
int cInt = stream->read();
if (cInt < 0)
break; // We ran out of characters (even though available said otherwise) - this can happen on rf52 adafruit
// arduino
uint8_t c = (uint8_t)cInt;
// Use the read pointer for a little state machine, first look for framing, then length bytes, then payload
size_t ptr = rxPtr;
rxPtr++; // assume we will probably advance the rxPtr
rxBuf[ptr] = c; // store all bytes (including framing)
// console->printf("rxPtr %d ptr=%d c=0x%x\n", rxPtr, ptr, c);
if (ptr == 0) { // looking for START1
if (c != START1)
rxPtr = 0; // failed to find framing
} else if (ptr == 1) { // looking for START2
if (c != START2)
rxPtr = 0; // failed to find framing
} else if (ptr >= HEADER_LEN - 1) { // we have at least read our 4 byte framing
uint32_t len = (rxBuf[2] << 8) + rxBuf[3]; // big endian 16 bit length follows framing
// console->printf("len %d\n", len);
if (ptr == HEADER_LEN - 1) {
// we _just_ finished our 4 byte header, validate length now (note: a length of zero is a valid
// protobuf also)
if (len > MAX_TO_FROM_RADIO_SIZE)
rxPtr = 0; // length is bogus, restart search for framing
}
if (rxPtr != 0) // Is packet still considered 'good'?
if (ptr + 1 >= len + HEADER_LEN) { // have we received all of the payload?
rxPtr = 0; // start over again on the next packet
// If we didn't just fail the packet and we now have the right # of bytes, parse it
handleToRadio(rxBuf + HEADER_LEN, len);
}
}
}
// we had bytes available this time, so assume we might have them next time also
lastRxMsec = millis();
return 0;
}
}
/**
* Send the current txBuffer over our stream
*/
void StreamAPI::emitTxBuffer(size_t len)
{
if (len != 0) {
txBuf[0] = START1;
txBuf[1] = START2;
txBuf[2] = (len >> 8) & 0xff;
txBuf[3] = len & 0xff;
auto totalLen = len + HEADER_LEN;
stream->write(txBuf, totalLen);
stream->flush();
}
}
void StreamAPI::emitRebooted()
{
// In case we send a FromRadio packet
memset(&fromRadioScratch, 0, sizeof(fromRadioScratch));
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_rebooted_tag;
fromRadioScratch.rebooted = true;
// LOG_DEBUG("Emitting reboot packet for serial shell");
emitTxBuffer(pb_encode_to_bytes(txBuf + HEADER_LEN, meshtastic_FromRadio_size, &meshtastic_FromRadio_msg, &fromRadioScratch));
}
void StreamAPI::emitLogRecord(meshtastic_LogRecord_Level level, const char *src, const char *format, va_list arg)
{
// In case we send a FromRadio packet
memset(&fromRadioScratch, 0, sizeof(fromRadioScratch));
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_log_record_tag;
fromRadioScratch.log_record.level = level;
uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice, true);
fromRadioScratch.log_record.time = rtc_sec;
strncpy(fromRadioScratch.log_record.source, src, sizeof(fromRadioScratch.log_record.source) - 1);
auto num_printed =
vsnprintf(fromRadioScratch.log_record.message, sizeof(fromRadioScratch.log_record.message) - 1, format, arg);
if (num_printed > 0 && fromRadioScratch.log_record.message[num_printed - 1] ==
'\n') // Strip any ending newline, because we have records for framing instead.
fromRadioScratch.log_record.message[num_printed - 1] = '\0';
emitTxBuffer(pb_encode_to_bytes(txBuf + HEADER_LEN, meshtastic_FromRadio_size, &meshtastic_FromRadio_msg, &fromRadioScratch));
}
/// Hookable to find out when connection changes
void StreamAPI::onConnectionChanged(bool connected)
{
// FIXME do reference counting instead
if (connected) { // To prevent user confusion, turn off bluetooth while using the serial port api
powerFSM.trigger(EVENT_SERIAL_CONNECTED);
} else {
// FIXME, we get no notice of serial going away, we should instead automatically generate this event if we haven't
// received a packet in a while
powerFSM.trigger(EVENT_SERIAL_DISCONNECTED);
}
}
@@ -0,0 +1,92 @@
#pragma once
#include "PhoneAPI.h"
#include "Stream.h"
#include "concurrency/OSThread.h"
#include <cstdarg>
// A To/FromRadio packet + our 32 bit header
#define MAX_STREAM_BUF_SIZE (MAX_TO_FROM_RADIO_SIZE + sizeof(uint32_t))
/**
* A version of our 'phone' API that talks over a Stream. So therefore well suited to use with serial links
* or TCP connections.
*
* ## Wire encoding
When sending protobuf packets over serial or TCP each packet is preceded by uint32 sent in network byte order (big endian).
The upper 16 bits must be 0x94C3. The lower 16 bits are packet length (this encoding gives room to eventually allow quite large
packets).
Implementations validate length against the maximum possible size of a BLE packet (our lowest common denominator) of 512 bytes. If
the length provided is larger than that we assume the packet is corrupted and begin again looking for 0x4403 framing.
The packets flowing towards the device are ToRadio protobufs, the packets flowing from the device are FromRadio protobufs.
The 0x94C3 marker can be used as framing to (eventually) resync if packets are corrupted over the wire.
Note: the 0x94C3 framing was chosen to prevent confusion with the 7 bit ascii character set. It also doesn't collide with any
valid utf8 encoding. This makes it a bit easier to start a device outputting regular debug output on its serial port and then only
after it has received a valid packet from the PC, turn off unencoded debug printing and switch to this packet encoding.
*/
class StreamAPI : public PhoneAPI
{
/**
* The stream we read/write from
*/
Stream *stream;
uint8_t rxBuf[MAX_STREAM_BUF_SIZE] = {0};
size_t rxPtr = 0;
/// time of last rx, used, to slow down our polling if we haven't heard from anyone
uint32_t lastRxMsec = 0;
public:
StreamAPI(Stream *_stream) : stream(_stream) {}
/**
* Currently we require frequent invocation from loop() to check for arrived serial packets and to send new packets to the
* phone.
*/
virtual int32_t runOncePart();
virtual int32_t runOncePart(char *buf, uint16_t bufLen);
private:
/**
* Read any rx chars from the link and call handleToRadio
*/
int32_t readStream();
int32_t readStream(char *buf, uint16_t bufLen);
int32_t handleRecStream(char *buf, uint16_t bufLen);
/**
* call getFromRadio() and deliver encapsulated packets to the Stream
*/
void writeStream();
protected:
/**
* Send a FromRadio.rebooted = true packet to the phone
*/
void emitRebooted();
virtual void onConnectionChanged(bool connected) override;
/// Check the current underlying physical link to see if the client is currently connected
virtual bool checkIsConnected() override = 0;
/**
* Send the current txBuffer over our stream
*/
void emitTxBuffer(size_t len);
/// Are we allowed to write packets to our output stream (subclasses can turn this off - i.e. SerialConsole)
bool canWrite = true;
/// Subclasses can use this scratch buffer if they wish
uint8_t txBuf[MAX_STREAM_BUF_SIZE] = {0};
/// Low level function to emit a protobuf encapsulated log record
void emitLogRecord(meshtastic_LogRecord_Level level, const char *src, const char *format, va_list arg);
};
@@ -0,0 +1,35 @@
#include "Throttle.h"
#include <Arduino.h>
/// @brief Execute a function throttled to a minimum interval
/// @param lastExecutionMs Pointer to the last execution time in milliseconds
/// @param minumumIntervalMs Minimum execution interval in milliseconds
/// @param throttleFunc Function to execute if the execution is not deferred
/// @param onDefer Default to NULL, execute the function if the execution is deferred
/// @return true if the function was executed, false if it was deferred
bool Throttle::execute(uint32_t *lastExecutionMs, uint32_t minumumIntervalMs, void (*throttleFunc)(void), void (*onDefer)(void))
{
if (*lastExecutionMs == 0) {
*lastExecutionMs = millis();
throttleFunc();
return true;
}
uint32_t now = millis();
if ((now - *lastExecutionMs) >= minumumIntervalMs) {
throttleFunc();
*lastExecutionMs = now;
return true;
} else if (onDefer != NULL) {
onDefer();
}
return false;
}
/// @brief Check if the last execution time is within the interval
/// @param lastExecutionMs The last execution time in milliseconds
/// @param timeSpanMs The interval in milliseconds of the timespan
bool Throttle::isWithinTimespanMs(uint32_t lastExecutionMs, uint32_t timeSpanMs)
{
return (millis() - lastExecutionMs) < timeSpanMs;
}
@@ -0,0 +1,10 @@
#pragma once
#include <cstddef>
#include <cstdint>
class Throttle
{
public:
static bool execute(uint32_t *lastExecutionMs, uint32_t minumumIntervalMs, void (*func)(void), void (*onDefer)(void) = NULL);
static bool isWithinTimespanMs(uint32_t lastExecutionMs, uint32_t intervalMs);
};
@@ -0,0 +1,112 @@
#include "TypeConversions.h"
#include "mesh/generated/meshtastic/deviceonly.pb.h"
#include "mesh/generated/meshtastic/mesh.pb.h"
meshtastic_NodeInfo TypeConversions::ConvertToNodeInfo(const meshtastic_NodeInfoLite *lite)
{
meshtastic_NodeInfo info = meshtastic_NodeInfo_init_default;
info.num = lite->num;
info.snr = lite->snr;
info.last_heard = lite->last_heard;
info.channel = lite->channel;
info.via_mqtt = lite->via_mqtt;
info.is_favorite = lite->is_favorite;
info.is_ignored = lite->is_ignored;
info.is_key_manually_verified = lite->bitfield & NODEINFO_BITFIELD_IS_KEY_MANUALLY_VERIFIED_MASK;
if (lite->has_hops_away) {
info.has_hops_away = true;
info.hops_away = lite->hops_away;
}
if (lite->has_position) {
info.has_position = true;
if (lite->position.latitude_i != 0)
info.position.has_latitude_i = true;
info.position.latitude_i = lite->position.latitude_i;
if (lite->position.longitude_i != 0)
info.position.has_longitude_i = true;
info.position.longitude_i = lite->position.longitude_i;
if (lite->position.altitude != 0)
info.position.has_altitude = true;
info.position.altitude = lite->position.altitude;
info.position.location_source = lite->position.location_source;
info.position.time = lite->position.time;
}
if (lite->has_user) {
info.has_user = true;
info.user = ConvertToUser(lite->num, lite->user);
}
if (lite->has_device_metrics) {
info.has_device_metrics = true;
info.device_metrics = lite->device_metrics;
}
return info;
}
meshtastic_PositionLite TypeConversions::ConvertToPositionLite(meshtastic_Position position)
{
meshtastic_PositionLite lite = meshtastic_PositionLite_init_default;
lite.latitude_i = position.latitude_i;
lite.longitude_i = position.longitude_i;
lite.altitude = position.altitude;
lite.location_source = position.location_source;
lite.time = position.time;
return lite;
}
meshtastic_Position TypeConversions::ConvertToPosition(meshtastic_PositionLite lite)
{
meshtastic_Position position = meshtastic_Position_init_default;
if (lite.latitude_i != 0)
position.has_latitude_i = true;
position.latitude_i = lite.latitude_i;
if (lite.longitude_i != 0)
position.has_longitude_i = true;
position.longitude_i = lite.longitude_i;
if (lite.altitude != 0)
position.has_altitude = true;
position.altitude = lite.altitude;
position.location_source = lite.location_source;
position.time = lite.time;
return position;
}
meshtastic_UserLite TypeConversions::ConvertToUserLite(meshtastic_User user)
{
meshtastic_UserLite lite = meshtastic_UserLite_init_default;
strncpy(lite.long_name, user.long_name, sizeof(lite.long_name));
strncpy(lite.short_name, user.short_name, sizeof(lite.short_name));
lite.hw_model = user.hw_model;
lite.role = user.role;
lite.is_licensed = user.is_licensed;
memcpy(lite.macaddr, user.macaddr, sizeof(lite.macaddr));
memcpy(lite.public_key.bytes, user.public_key.bytes, sizeof(lite.public_key.bytes));
lite.public_key.size = user.public_key.size;
lite.has_is_unmessagable = user.has_is_unmessagable;
lite.is_unmessagable = user.is_unmessagable;
return lite;
}
meshtastic_User TypeConversions::ConvertToUser(uint32_t nodeNum, meshtastic_UserLite lite)
{
meshtastic_User user = meshtastic_User_init_default;
snprintf(user.id, sizeof(user.id), "!%08x", nodeNum);
strncpy(user.long_name, lite.long_name, sizeof(user.long_name));
strncpy(user.short_name, lite.short_name, sizeof(user.short_name));
user.hw_model = lite.hw_model;
user.role = lite.role;
user.is_licensed = lite.is_licensed;
memcpy(user.macaddr, lite.macaddr, sizeof(user.macaddr));
memcpy(user.public_key.bytes, lite.public_key.bytes, sizeof(user.public_key.bytes));
user.public_key.size = lite.public_key.size;
user.has_is_unmessagable = lite.has_is_unmessagable;
user.is_unmessagable = lite.is_unmessagable;
return user;
}
@@ -0,0 +1,15 @@
#include "mesh/generated/meshtastic/deviceonly.pb.h"
#include "mesh/generated/meshtastic/mesh.pb.h"
#pragma once
#include "NodeDB.h"
class TypeConversions
{
public:
static meshtastic_NodeInfo ConvertToNodeInfo(const meshtastic_NodeInfoLite *lite);
static meshtastic_PositionLite ConvertToPositionLite(meshtastic_Position position);
static meshtastic_Position ConvertToPosition(meshtastic_PositionLite lite);
static meshtastic_UserLite ConvertToUserLite(meshtastic_User user);
static meshtastic_User ConvertToUser(uint32_t nodeNum, meshtastic_UserLite lite);
};
@@ -0,0 +1,124 @@
#pragma once
#include <cassert>
#include <type_traits>
#include "concurrency/OSThread.h"
#include "freertosinc.h"
#ifdef HAS_FREE_RTOS
/**
* A wrapper for freertos queues. Note: each element object should be small
* and POD (Plain Old Data type) as elements are memcpied by value.
*/
template <class T> class TypedQueue
{
static_assert(std::is_standard_layout<T>::value, "T must be standard layout");
QueueHandle_t h;
concurrency::OSThread *reader = NULL;
public:
explicit TypedQueue(int maxElements) : h(xQueueCreate(maxElements, sizeof(T))) { assert(h); }
~TypedQueue() { vQueueDelete(h); }
int numFree() { return uxQueueSpacesAvailable(h); }
bool isEmpty() { return uxQueueMessagesWaiting(h) == 0; }
int numUsed() { return uxQueueMessagesWaiting(h); }
/** euqueue a packet. Also, maxWait used to default to portMAX_DELAY, but we now want to callers to THINK about what blocking
* they want */
bool enqueue(T x, TickType_t maxWait)
{
if (reader) {
reader->setInterval(0);
concurrency::mainDelay.interrupt();
}
return xQueueSendToBack(h, &x, maxWait) == pdTRUE;
}
bool enqueueFromISR(T x, BaseType_t *higherPriWoken)
{
if (reader) {
reader->setInterval(0);
concurrency::mainDelay.interruptFromISR(higherPriWoken);
}
return xQueueSendToBackFromISR(h, &x, higherPriWoken) == pdTRUE;
}
bool dequeue(T *p, TickType_t maxWait = portMAX_DELAY) { return xQueueReceive(h, p, maxWait) == pdTRUE; }
bool dequeueFromISR(T *p, BaseType_t *higherPriWoken) { return xQueueReceiveFromISR(h, p, higherPriWoken); }
/**
* Set a thread that is reading from this queue
* If a message is pushed to this queue that thread will be scheduled to run ASAP.
*
* Note: thread will not be automatically enabled, just have its interval set to 0
*/
void setReader(concurrency::OSThread *t) { reader = t; }
};
#else
#include <queue>
/**
* A wrapper for freertos queues. Note: each element object should be small
* and POD (Plain Old Data type) as elements are memcpied by value.
*/
template <class T> class TypedQueue
{
std::queue<T> q;
concurrency::OSThread *reader = NULL;
int maxElements;
public:
explicit TypedQueue(int _maxElements) : maxElements(_maxElements) {}
int numFree()
{
if (maxElements <= 0)
return 1; // Always claim 1 free, because we can grow to any size
return maxElements - numUsed();
}
bool isEmpty() { return q.empty(); }
int numUsed() { return q.size(); }
bool enqueue(T x, TickType_t maxWait = portMAX_DELAY)
{
if (numFree() <= 0)
return false;
if (reader) {
reader->setInterval(0);
concurrency::mainDelay.interrupt();
}
q.push(x);
return true;
}
// bool enqueueFromISR(T x, BaseType_t *higherPriWoken) { return xQueueSendToBackFromISR(h, &x, higherPriWoken) == pdTRUE; }
bool dequeue(T *p, TickType_t maxWait = portMAX_DELAY)
{
if (isEmpty())
return false;
else {
*p = q.front();
q.pop();
return true;
}
}
// bool dequeueFromISR(T *p, BaseType_t *higherPriWoken) { return xQueueReceiveFromISR(h, p, higherPriWoken); }
void setReader(concurrency::OSThread *t) { reader = t; }
};
#endif
@@ -0,0 +1,180 @@
/*
* Counter with CBC-MAC (CCM) with AES
*
* Copyright (c) 2010-2012, Jouni Malinen <j@w1.fi>
*
* This software may be distributed under the terms of the BSD license.
* See README for more details.
*/
#define AES_BLOCK_SIZE 16
#include "aes-ccm.h"
#if !MESHTASTIC_EXCLUDE_PKI
/**
* Constant-time comparison of two byte arrays
*
* @param a First byte array to compare
* @param b Second byte array to compare
* @param len Number of bytes to compare
* @return 0 if arrays are equal, -1 if different or if inputs are invalid
*/
static int constant_time_compare(const void *a_, const void *b_, size_t len)
{
/* Cast to volatile to prevent the compiler from optimizing out their comparison. */
const volatile uint8_t *volatile a = (const volatile uint8_t *volatile)a_;
const volatile uint8_t *volatile b = (const volatile uint8_t *volatile)b_;
if (len == 0)
return 0;
if (a == NULL || b == NULL)
return -1;
size_t i;
volatile uint8_t d = 0U;
for (i = 0U; i < len; i++) {
d |= (a[i] ^ b[i]);
}
/* Constant time bit arithmetic to convert d > 0 to -1 and d = 0 to 0. */
return (1 & ((d - 1) >> 8)) - 1;
}
static void WPA_PUT_BE16(uint8_t *a, uint16_t val)
{
a[0] = val >> 8;
a[1] = val & 0xff;
}
static void xor_aes_block(uint8_t *dst, const uint8_t *src)
{
for (uint8_t i = 0; i < AES_BLOCK_SIZE; i++) {
dst[i] ^= src[i];
}
}
static void aes_ccm_auth_start(size_t M, size_t L, const uint8_t *nonce, const uint8_t *aad, size_t aad_len, size_t plain_len,
uint8_t *x)
{
uint8_t aad_buf[2 * AES_BLOCK_SIZE];
uint8_t b[AES_BLOCK_SIZE];
/* Authentication */
/* B_0: Flags | Nonce N | l(m) */
b[0] = aad_len ? 0x40 : 0 /* Adata */;
b[0] |= (((M - 2) / 2) /* M' */ << 3);
b[0] |= (L - 1) /* L' */;
memcpy(&b[1], nonce, 15 - L);
WPA_PUT_BE16(&b[AES_BLOCK_SIZE - L], plain_len);
crypto->aesEncrypt(b, x); /* X_1 = E(K, B_0) */
if (!aad_len)
return;
WPA_PUT_BE16(aad_buf, aad_len);
memcpy(aad_buf + 2, aad, aad_len);
memset(aad_buf + 2 + aad_len, 0, sizeof(aad_buf) - 2 - aad_len);
xor_aes_block(aad_buf, x);
crypto->aesEncrypt(aad_buf, x); /* X_2 = E(K, X_1 XOR B_1) */
if (aad_len > AES_BLOCK_SIZE - 2) {
xor_aes_block(&aad_buf[AES_BLOCK_SIZE], x);
/* X_3 = E(K, X_2 XOR B_2) */
crypto->aesEncrypt(&aad_buf[AES_BLOCK_SIZE], x);
}
}
static void aes_ccm_auth(const uint8_t *data, size_t len, uint8_t *x)
{
size_t last = len % AES_BLOCK_SIZE;
size_t i;
for (i = 0; i < len / AES_BLOCK_SIZE; i++) {
/* X_i+1 = E(K, X_i XOR B_i) */
xor_aes_block(x, data);
data += AES_BLOCK_SIZE;
crypto->aesEncrypt(x, x);
}
if (last) {
/* XOR zero-padded last block */
for (i = 0; i < last; i++)
x[i] ^= *data++;
crypto->aesEncrypt(x, x);
}
}
static void aes_ccm_encr_start(size_t L, const uint8_t *nonce, uint8_t *a)
{
/* A_i = Flags | Nonce N | Counter i */
a[0] = L - 1; /* Flags = L' */
memcpy(&a[1], nonce, 15 - L);
}
static void aes_ccm_encr(size_t L, const uint8_t *in, size_t len, uint8_t *out, uint8_t *a)
{
size_t last = len % AES_BLOCK_SIZE;
size_t i;
/* crypt = msg XOR (S_1 | S_2 | ... | S_n) */
for (i = 1; i <= len / AES_BLOCK_SIZE; i++) {
WPA_PUT_BE16(&a[AES_BLOCK_SIZE - 2], i);
/* S_i = E(K, A_i) */
crypto->aesEncrypt(a, out);
xor_aes_block(out, in);
out += AES_BLOCK_SIZE;
in += AES_BLOCK_SIZE;
}
if (last) {
WPA_PUT_BE16(&a[AES_BLOCK_SIZE - 2], i);
crypto->aesEncrypt(a, out);
/* XOR zero-padded last block */
for (i = 0; i < last; i++)
*out++ ^= *in++;
}
}
static void aes_ccm_encr_auth(size_t M, const uint8_t *x, uint8_t *a, uint8_t *auth)
{
size_t i;
uint8_t tmp[AES_BLOCK_SIZE];
/* U = T XOR S_0; S_0 = E(K, A_0) */
WPA_PUT_BE16(&a[AES_BLOCK_SIZE - 2], 0);
crypto->aesEncrypt(a, tmp);
for (i = 0; i < M; i++)
auth[i] = x[i] ^ tmp[i];
}
static void aes_ccm_decr_auth(size_t M, uint8_t *a, const uint8_t *auth, uint8_t *t)
{
size_t i;
uint8_t tmp[AES_BLOCK_SIZE];
/* U = T XOR S_0; S_0 = E(K, A_0) */
WPA_PUT_BE16(&a[AES_BLOCK_SIZE - 2], 0);
crypto->aesEncrypt(a, tmp);
for (i = 0; i < M; i++)
t[i] = auth[i] ^ tmp[i];
}
/* AES-CCM with fixed L=2 and aad_len <= 30 assumption */
int aes_ccm_ae(const uint8_t *key, size_t key_len, const uint8_t *nonce, size_t M, const uint8_t *plain, size_t plain_len,
const uint8_t *aad, size_t aad_len, uint8_t *crypt, uint8_t *auth)
{
const size_t L = 2;
uint8_t x[AES_BLOCK_SIZE], a[AES_BLOCK_SIZE];
if (aad_len > 30 || M > AES_BLOCK_SIZE)
return -1;
crypto->aesSetKey(key, key_len);
aes_ccm_auth_start(M, L, nonce, aad, aad_len, plain_len, x);
aes_ccm_auth(plain, plain_len, x);
/* Encryption */
aes_ccm_encr_start(L, nonce, a);
aes_ccm_encr(L, plain, plain_len, crypt, a);
aes_ccm_encr_auth(M, x, a, auth);
return 0;
}
/* AES-CCM with fixed L=2 and aad_len <= 30 assumption */
bool aes_ccm_ad(const uint8_t *key, size_t key_len, const uint8_t *nonce, size_t M, const uint8_t *crypt, size_t crypt_len,
const uint8_t *aad, size_t aad_len, const uint8_t *auth, uint8_t *plain)
{
const size_t L = 2;
uint8_t x[AES_BLOCK_SIZE], a[AES_BLOCK_SIZE];
uint8_t t[AES_BLOCK_SIZE];
if (aad_len > 30 || M > AES_BLOCK_SIZE)
return false;
crypto->aesSetKey(key, key_len);
/* Decryption */
aes_ccm_encr_start(L, nonce, a);
aes_ccm_decr_auth(M, a, auth, t);
/* plaintext = msg XOR (S_1 | S_2 | ... | S_n) */
aes_ccm_encr(L, crypt, crypt_len, plain, a);
aes_ccm_auth_start(M, L, nonce, aad, aad_len, crypt_len, x);
aes_ccm_auth(plain, crypt_len, x);
if (constant_time_compare(x, t, M) != 0) {
return false;
}
return true;
}
#endif
@@ -0,0 +1,10 @@
#pragma once
#include "CryptoEngine.h"
#if !MESHTASTIC_EXCLUDE_PKI
int aes_ccm_ae(const uint8_t *key, size_t key_len, const uint8_t *nonce, size_t M, const uint8_t *plain, size_t plain_len,
const uint8_t *aad, size_t aad_len, uint8_t *crypt, uint8_t *auth);
bool aes_ccm_ad(const uint8_t *key, size_t key_len, const uint8_t *nonce, size_t M, const uint8_t *crypt, size_t crypt_len,
const uint8_t *aad, size_t aad_len, const uint8_t *auth, uint8_t *plain);
#endif
@@ -0,0 +1,131 @@
#ifdef USE_PACKET_API
#include "api/PacketAPI.h"
#include "MeshService.h"
#include "PowerFSM.h"
#include "RadioInterface.h"
#include "modules/NodeInfoModule.h"
PacketAPI *packetAPI = nullptr;
PacketAPI *PacketAPI::create(PacketServer *_server)
{
if (!packetAPI) {
packetAPI = new PacketAPI(_server);
}
return packetAPI;
}
PacketAPI::PacketAPI(PacketServer *_server)
: concurrency::OSThread("PacketAPI"), isConnected(false), programmingMode(false), server(_server)
{
api_type = TYPE_PACKET;
}
int32_t PacketAPI::runOnce()
{
bool success = false;
#ifndef ARCH_PORTDUINO
if (config.bluetooth.enabled) {
if (!programmingMode) {
// in programmingMode we don't send any packets to the client except this one notify
programmingMode = true;
success = notifyProgrammingMode();
}
} else
#endif
{
success = sendPacket();
}
success |= receivePacket();
return success ? 10 : 50;
}
bool PacketAPI::receivePacket(void)
{
bool data_received = false;
while (server->hasData()) {
isConnected = true;
data_received = true;
powerFSM.trigger(EVENT_CONTACT_FROM_PHONE);
lastContactMsec = millis();
meshtastic_ToRadio *mr;
auto p = server->receivePacket()->move();
int id = p->getPacketId();
LOG_DEBUG("Received packet id=%u", id);
mr = (meshtastic_ToRadio *)&static_cast<DataPacket<meshtastic_ToRadio> *>(p.get())->getData();
switch (mr->which_payload_variant) {
case meshtastic_ToRadio_packet_tag: {
meshtastic_MeshPacket *mp = &mr->packet;
mp->transport_mechanism = meshtastic_MeshPacket_TransportMechanism_TRANSPORT_API;
printPacket("PACKET FROM QUEUE", mp);
service->handleToRadio(*mp);
break;
}
case meshtastic_ToRadio_want_config_id_tag: {
uint32_t config_nonce = mr->want_config_id;
LOG_INFO("Screen wants config, nonce=%u", config_nonce);
handleStartConfig();
break;
}
case meshtastic_ToRadio_heartbeat_tag:
if (mr->heartbeat.nonce == 1) {
if (nodeInfoModule) {
LOG_INFO("Broadcasting nodeinfo ping");
nodeInfoModule->sendOurNodeInfo(NODENUM_BROADCAST, true, 0, true);
}
} else {
LOG_DEBUG("Got client heartbeat");
}
break;
default:
LOG_ERROR("Error: unhandled meshtastic_ToRadio variant: %d", mr->which_payload_variant);
break;
}
}
return data_received;
}
bool PacketAPI::sendPacket(void)
{
if (server->available()) {
// fill dummy buffer; we don't use it, we directly send the fromRadio structure
uint32_t len = getFromRadio(txBuf);
if (len != 0) {
static uint32_t id = 0;
fromRadioScratch.id = ++id;
bool result = server->sendPacket(DataPacket<meshtastic_FromRadio>(id, fromRadioScratch));
if (!result) {
LOG_ERROR("send queue full");
}
return result;
}
}
return false;
}
bool PacketAPI::notifyProgrammingMode(void)
{
// tell the client we are in programming mode by sending only the bluetooth config state
LOG_INFO("force client into programmingMode");
memset(&fromRadioScratch, 0, sizeof(fromRadioScratch));
fromRadioScratch.id = nodeDB->getNodeNum();
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_tag;
fromRadioScratch.config.which_payload_variant = meshtastic_Config_bluetooth_tag;
fromRadioScratch.config.payload_variant.bluetooth = config.bluetooth;
return server->sendPacket(DataPacket<meshtastic_FromRadio>(0, fromRadioScratch));
}
/**
* return true if we got (once!) contact from our client and the server send queue is not full
*/
bool PacketAPI::checkIsConnected()
{
isConnected |= server->hasData();
return isConnected && server->available();
}
#endif
@@ -0,0 +1,38 @@
#pragma once
#include "PhoneAPI.h"
#include "comms/PacketServer.h"
#include "concurrency/OSThread.h"
/**
* A version of the phone API used for inter task communication based on protobuf packets, e.g.
* between two tasks running on CPU0 and CPU1, respectively.
*
*/
class PacketAPI : public PhoneAPI, public concurrency::OSThread
{
public:
static PacketAPI *create(PacketServer *_server);
virtual ~PacketAPI(){};
virtual int32_t runOnce();
protected:
PacketAPI(PacketServer *_server);
// Check the current underlying physical queue to see if the client is fetching packets
bool checkIsConnected() override;
void onNowHasData(uint32_t fromRadioNum) override {}
void onConnectionChanged(bool connected) override {}
private:
bool receivePacket(void);
bool sendPacket(void);
bool notifyProgrammingMode(void);
bool isConnected;
bool programmingMode;
PacketServer *server;
uint8_t txBuf[MAX_TO_FROM_RADIO_SIZE] = {0}; // dummy buf to obey PhoneAPI
};
extern PacketAPI *packetAPI;
@@ -0,0 +1,83 @@
#include "ServerAPI.h"
#include "configuration.h"
#include <Arduino.h>
template <typename T>
ServerAPI<T>::ServerAPI(T &_client) : StreamAPI(&client), concurrency::OSThread("ServerAPI"), client(_client)
{
LOG_INFO("Incoming API connection");
}
template <typename T> ServerAPI<T>::~ServerAPI()
{
client.stop();
}
template <typename T> void ServerAPI<T>::close()
{
client.stop(); // drop tcp connection
StreamAPI::close();
}
/// Check the current underlying physical link to see if the client is currently connected
template <typename T> bool ServerAPI<T>::checkIsConnected()
{
return client.connected();
}
template <class T> int32_t ServerAPI<T>::runOnce()
{
if (client.connected()) {
return StreamAPI::runOncePart();
} else {
LOG_INFO("Client dropped connection, suspend API service");
enabled = false; // we no longer need to run
return 0;
}
}
template <class T, class U> APIServerPort<T, U>::APIServerPort(int port) : U(port), concurrency::OSThread("ApiServer") {}
template <class T, class U> void APIServerPort<T, U>::init()
{
U::begin();
}
template <class T, class U> int32_t APIServerPort<T, U>::runOnce()
{
#ifdef ARCH_ESP32
#if ESP_ARDUINO_VERSION >= ESP_ARDUINO_VERSION_VAL(3, 0, 0)
auto client = U::accept();
#else
auto client = U::available();
#endif
#elif defined(ARCH_RP2040)
auto client = U::accept();
#else
auto client = U::available();
#endif
if (client) {
// Close any previous connection (see FIXME in header file)
if (openAPI) {
#if RAK_4631
// RAK13800 Ethernet requests periodically take more time
// This backoff addresses most cases keeping max wait < 1s
// Reconnections are delayed by full wait time
if (waitTime < 400) {
waitTime *= 2;
LOG_INFO("Previous TCP connection still open, try again in %dms", waitTime);
return waitTime;
}
#endif
LOG_INFO("Force close previous TCP connection");
delete openAPI;
}
openAPI = new T(client);
}
#if RAK_4631
waitTime = 100;
#endif
return 100; // only check occasionally for incoming connections
}
@@ -0,0 +1,58 @@
#pragma once
#include "StreamAPI.h"
#define SERVER_API_DEFAULT_PORT 4403
/**
* Provides both debug printing and, if the client starts sending protobufs to us, switches to send/receive protobufs
* (and starts dropping debug printing - FIXME, eventually those prints should be encapsulated in protobufs).
*/
template <class T> class ServerAPI : public StreamAPI, private concurrency::OSThread
{
private:
T client;
public:
explicit ServerAPI(T &_client);
virtual ~ServerAPI();
/// override close to also shutdown the TCP link
virtual void close();
protected:
/// We override this method to prevent publishing EVENT_SERIAL_CONNECTED/DISCONNECTED for wifi links (we want the board to
/// stay in the POWERED state to prevent disabling wifi)
virtual void onConnectionChanged(bool connected) override {}
virtual int32_t runOnce() override; // Check for dropped client connections
/// Check the current underlying physical link to see if the client is currently connected
virtual bool checkIsConnected() override;
};
/**
* Listens for incoming connections and does accepts and creates instances of ServerAPI as needed
*/
template <class T, class U> class APIServerPort : public U, private concurrency::OSThread
{
/** The currently open port
*
* FIXME: We currently only allow one open TCP connection at a time, because we depend on the loop() call in this class to
* delegate to the worker. Once coroutines are implemented we can relax this restriction.
*/
T *openAPI = NULL;
#if defined(RAK_4631) || defined(RAK11310)
// Track wait time for RAK13800 Ethernet requests
int32_t waitTime = 100;
#endif
public:
explicit APIServerPort(int port);
void init();
protected:
int32_t runOnce() override;
};
@@ -0,0 +1,33 @@
#include "configuration.h"
#include <Arduino.h>
#if HAS_WIFI
#include "WiFiServerAPI.h"
static WiFiServerPort *apiPort;
void initApiServer(int port)
{
// Start API server on port 4403
if (!apiPort) {
apiPort = new WiFiServerPort(port);
LOG_INFO("API server listen on TCP port %d", port);
apiPort->init();
}
}
void deInitApiServer()
{
if (apiPort) {
delete apiPort;
apiPort = nullptr;
}
}
WiFiServerAPI::WiFiServerAPI(WiFiClient &_client) : ServerAPI(_client)
{
api_type = TYPE_WIFI;
LOG_INFO("Incoming wifi connection");
}
WiFiServerPort::WiFiServerPort(int port) : APIServerPort(port) {}
#endif
@@ -0,0 +1,31 @@
#pragma once
#include "ServerAPI.h"
#include <WiFi.h>
#if HAS_ETHERNET && defined(USE_WS5500)
#include <ETHClass2.h>
#define ETH ETH2
#endif // HAS_ETHERNET
/**
* Provides both debug printing and, if the client starts sending protobufs to us, switches to send/receive protobufs
* (and starts dropping debug printing - FIXME, eventually those prints should be encapsulated in protobufs).
*/
class WiFiServerAPI : public ServerAPI<WiFiClient>
{
public:
explicit WiFiServerAPI(WiFiClient &_client);
};
/**
* Listens for incoming connections and does accepts and creates instances of WiFiServerAPI as needed
*/
class WiFiServerPort : public APIServerPort<WiFiServerAPI, WiFiServer>
{
public:
explicit WiFiServerPort(int port);
};
void initApiServer(int port = SERVER_API_DEFAULT_PORT);
void deInitApiServer();
@@ -0,0 +1,28 @@
#include "configuration.h"
#include <Arduino.h>
#if HAS_ETHERNET && !defined(USE_WS5500)
#include "ethServerAPI.h"
static ethServerPort *apiPort;
void initApiServer(int port)
{
// Start API server on port 4403
if (!apiPort) {
apiPort = new ethServerPort(port);
LOG_INFO("API server listening on TCP port %d", port);
apiPort->init();
}
}
ethServerAPI::ethServerAPI(EthernetClient &_client) : ServerAPI(_client)
{
LOG_INFO("Incoming ethernet connection");
api_type = TYPE_ETH;
}
ethServerPort::ethServerPort(int port) : APIServerPort(port) {}
#endif
@@ -0,0 +1,27 @@
#pragma once
#include "ServerAPI.h"
#ifndef USE_WS5500
#include <RAK13800_W5100S.h>
/**
* Provides both debug printing and, if the client starts sending protobufs to us, switches to send/receive protobufs
* (and starts dropping debug printing - FIXME, eventually those prints should be encapsulated in protobufs).
*/
class ethServerAPI : public ServerAPI<EthernetClient>
{
public:
explicit ethServerAPI(EthernetClient &_client);
};
/**
* Listens for incoming connections and does accepts and creates instances of EthernetServerAPI as needed
*/
class ethServerPort : public APIServerPort<ethServerAPI, EthernetServer>
{
public:
explicit ethServerPort(int port);
};
void initApiServer(int port = SERVER_API_DEFAULT_PORT);
#endif
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,347 @@
/*
* 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
@@ -0,0 +1,200 @@
#include "mesh/eth/ethClient.h"
#include "NodeDB.h"
#include "RTC.h"
#include "concurrency/Periodic.h"
#include "configuration.h"
#include "main.h"
#include "mesh/api/ethServerAPI.h"
#include "target_specific.h"
#include <RAK13800_W5100S.h>
#include <SPI.h>
#if HAS_NETWORKING
#ifndef DISABLE_NTP
#include <NTPClient.h>
// NTP
EthernetUDP ntpUDP;
NTPClient timeClient(ntpUDP, config.network.ntp_server);
uint32_t ntp_renew = 0;
#endif
EthernetUDP syslogClient;
Syslog syslog(syslogClient);
bool ethStartupComplete = 0;
using namespace concurrency;
static Periodic *ethEvent;
static int32_t reconnectETH()
{
if (config.network.eth_enabled) {
Ethernet.maintain();
if (!ethStartupComplete) {
// Start web server
LOG_INFO("Start Ethernet network services");
#ifndef DISABLE_NTP
LOG_INFO("Start NTP time client");
timeClient.begin();
timeClient.setUpdateInterval(60 * 60); // Update once an hour
#endif
if (config.network.rsyslog_server[0]) {
LOG_INFO("Start Syslog client");
// Defaults
int serverPort = 514;
const char *serverAddr = config.network.rsyslog_server;
String server = String(serverAddr);
int delimIndex = server.indexOf(':');
if (delimIndex > 0) {
String port = server.substring(delimIndex + 1, server.length());
server[delimIndex] = 0;
serverPort = port.toInt();
serverAddr = server.c_str();
}
syslog.server(serverAddr, serverPort);
syslog.deviceHostname(getDeviceName());
syslog.appName("Meshtastic");
syslog.defaultPriority(LOGLEVEL_USER);
syslog.enable();
}
#if !MESHTASTIC_EXCLUDE_SOCKETAPI
if (config.display.displaymode != meshtastic_Config_DisplayConfig_DisplayMode_COLOR) {
initApiServer();
}
#endif
#if HAS_UDP_MULTICAST
if (udpHandler && config.network.enabled_protocols & meshtastic_Config_NetworkConfig_ProtocolFlags_UDP_BROADCAST) {
udpHandler->start();
}
#endif
ethStartupComplete = true;
}
}
#ifndef DISABLE_NTP
if (isEthernetAvailable() && (ntp_renew < millis())) {
LOG_INFO("Update NTP time from %s", config.network.ntp_server);
if (timeClient.update()) {
LOG_DEBUG("NTP Request Success - Set RTCQualityNTP if needed");
struct timeval tv;
tv.tv_sec = timeClient.getEpochTime();
tv.tv_usec = 0;
perhapsSetRTC(RTCQualityNTP, &tv);
ntp_renew = millis() + 43200 * 1000; // success, refresh every 12 hours
} else {
LOG_ERROR("NTP Update failed");
ntp_renew = millis() + 300 * 1000; // failure, retry every 5 minutes
}
}
#endif
return 5000; // every 5 seconds
}
// Startup Ethernet
bool initEthernet()
{
if (config.network.eth_enabled) {
#ifdef PIN_ETH_POWER_EN
pinMode(PIN_ETH_POWER_EN, OUTPUT);
digitalWrite(PIN_ETH_POWER_EN, HIGH); // Power up.
delay(100);
#endif
#ifdef PIN_ETHERNET_RESET
pinMode(PIN_ETHERNET_RESET, OUTPUT);
digitalWrite(PIN_ETHERNET_RESET, LOW); // Reset Time.
delay(100);
digitalWrite(PIN_ETHERNET_RESET, HIGH); // Reset Time.
#endif
#ifdef RAK11310 // Initialize the SPI port
ETH_SPI_PORT.setSCK(PIN_SPI0_SCK);
ETH_SPI_PORT.setTX(PIN_SPI0_MOSI);
ETH_SPI_PORT.setRX(PIN_SPI0_MISO);
ETH_SPI_PORT.begin();
#endif
Ethernet.init(ETH_SPI_PORT, PIN_ETHERNET_SS);
uint8_t mac[6];
int status = 0;
// createSSLCert();
getMacAddr(mac); // FIXME use the BLE MAC for now...
mac[0] &= 0xfe; // Make sure this is not a multicast MAC
if (config.network.address_mode == meshtastic_Config_NetworkConfig_AddressMode_DHCP) {
LOG_INFO("Start Ethernet DHCP");
status = Ethernet.begin(mac);
} 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,
config.network.ipv4_config.subnet);
status = 1;
} else {
LOG_INFO("Ethernet Disabled");
return false;
}
if (status == 0) {
if (Ethernet.hardwareStatus() == EthernetNoHardware) {
LOG_ERROR("Ethernet shield was not found");
return false;
} else if (Ethernet.linkStatus() == LinkOFF) {
LOG_ERROR("Ethernet cable is not connected");
return false;
} else {
LOG_ERROR("Unknown Ethernet error");
return false;
}
} else {
LOG_INFO("Local IP %u.%u.%u.%u", Ethernet.localIP()[0], Ethernet.localIP()[1], Ethernet.localIP()[2],
Ethernet.localIP()[3]);
LOG_INFO("Subnet Mask %u.%u.%u.%u", Ethernet.subnetMask()[0], Ethernet.subnetMask()[1], Ethernet.subnetMask()[2],
Ethernet.subnetMask()[3]);
LOG_INFO("Gateway IP %u.%u.%u.%u", Ethernet.gatewayIP()[0], Ethernet.gatewayIP()[1], Ethernet.gatewayIP()[2],
Ethernet.gatewayIP()[3]);
LOG_INFO("DNS Server IP %u.%u.%u.%u", Ethernet.dnsServerIP()[0], Ethernet.dnsServerIP()[1], Ethernet.dnsServerIP()[2],
Ethernet.dnsServerIP()[3]);
}
ethEvent = new Periodic("ethConnect", reconnectETH);
return true;
} else {
LOG_INFO("Not using Ethernet");
return false;
}
}
bool isEthernetAvailable()
{
if (!config.network.eth_enabled) {
syslog.disable();
return false;
} else if (Ethernet.hardwareStatus() == EthernetNoHardware) {
syslog.disable();
return false;
} else if (Ethernet.linkStatus() == LinkOFF) {
syslog.disable();
return false;
} else {
return true;
}
}
#endif
@@ -0,0 +1,7 @@
#pragma once
#include "configuration.h"
#include <Arduino.h>
bool initEthernet();
bool isEthernetAvailable();
@@ -0,0 +1,2 @@
DisableFormat: true
SortIncludes: false
@@ -0,0 +1,35 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.9.1 */
#include "meshtastic/admin.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(meshtastic_AdminMessage, meshtastic_AdminMessage, 2)
PB_BIND(meshtastic_AdminMessage_InputEvent, meshtastic_AdminMessage_InputEvent, AUTO)
PB_BIND(meshtastic_HamParameters, meshtastic_HamParameters, AUTO)
PB_BIND(meshtastic_NodeRemoteHardwarePinsResponse, meshtastic_NodeRemoteHardwarePinsResponse, 2)
PB_BIND(meshtastic_SharedContact, meshtastic_SharedContact, AUTO)
PB_BIND(meshtastic_KeyVerificationAdmin, meshtastic_KeyVerificationAdmin, AUTO)
@@ -0,0 +1,553 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.9.1 */
#ifndef PB_MESHTASTIC_MESHTASTIC_ADMIN_PB_H_INCLUDED
#define PB_MESHTASTIC_MESHTASTIC_ADMIN_PB_H_INCLUDED
#include <pb.h>
#include "meshtastic/channel.pb.h"
#include "meshtastic/config.pb.h"
#include "meshtastic/connection_status.pb.h"
#include "meshtastic/device_ui.pb.h"
#include "meshtastic/mesh.pb.h"
#include "meshtastic/module_config.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Enum definitions */
/* TODO: REPLACE */
typedef enum _meshtastic_AdminMessage_ConfigType {
/* TODO: REPLACE */
meshtastic_AdminMessage_ConfigType_DEVICE_CONFIG = 0,
/* TODO: REPLACE */
meshtastic_AdminMessage_ConfigType_POSITION_CONFIG = 1,
/* TODO: REPLACE */
meshtastic_AdminMessage_ConfigType_POWER_CONFIG = 2,
/* TODO: REPLACE */
meshtastic_AdminMessage_ConfigType_NETWORK_CONFIG = 3,
/* TODO: REPLACE */
meshtastic_AdminMessage_ConfigType_DISPLAY_CONFIG = 4,
/* TODO: REPLACE */
meshtastic_AdminMessage_ConfigType_LORA_CONFIG = 5,
/* TODO: REPLACE */
meshtastic_AdminMessage_ConfigType_BLUETOOTH_CONFIG = 6,
/* TODO: REPLACE */
meshtastic_AdminMessage_ConfigType_SECURITY_CONFIG = 7,
/* Session key config */
meshtastic_AdminMessage_ConfigType_SESSIONKEY_CONFIG = 8,
/* device-ui config */
meshtastic_AdminMessage_ConfigType_DEVICEUI_CONFIG = 9
} meshtastic_AdminMessage_ConfigType;
/* TODO: REPLACE */
typedef enum _meshtastic_AdminMessage_ModuleConfigType {
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_MQTT_CONFIG = 0,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_SERIAL_CONFIG = 1,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_EXTNOTIF_CONFIG = 2,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_STOREFORWARD_CONFIG = 3,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_RANGETEST_CONFIG = 4,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_TELEMETRY_CONFIG = 5,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_CANNEDMSG_CONFIG = 6,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_AUDIO_CONFIG = 7,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_REMOTEHARDWARE_CONFIG = 8,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_NEIGHBORINFO_CONFIG = 9,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_AMBIENTLIGHTING_CONFIG = 10,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_DETECTIONSENSOR_CONFIG = 11,
/* TODO: REPLACE */
meshtastic_AdminMessage_ModuleConfigType_PAXCOUNTER_CONFIG = 12
} meshtastic_AdminMessage_ModuleConfigType;
typedef enum _meshtastic_AdminMessage_BackupLocation {
/* Backup to the internal flash */
meshtastic_AdminMessage_BackupLocation_FLASH = 0,
/* Backup to the SD card */
meshtastic_AdminMessage_BackupLocation_SD = 1
} meshtastic_AdminMessage_BackupLocation;
/* Three stages of this request. */
typedef enum _meshtastic_KeyVerificationAdmin_MessageType {
/* This is the first stage, where a client initiates */
meshtastic_KeyVerificationAdmin_MessageType_INITIATE_VERIFICATION = 0,
/* After the nonce has been returned over the mesh, the client prompts for the security number
And uses this message to provide it to the node. */
meshtastic_KeyVerificationAdmin_MessageType_PROVIDE_SECURITY_NUMBER = 1,
/* Once the user has compared the verification message, this message notifies the node. */
meshtastic_KeyVerificationAdmin_MessageType_DO_VERIFY = 2,
/* This is the cancel path, can be taken at any point */
meshtastic_KeyVerificationAdmin_MessageType_DO_NOT_VERIFY = 3
} meshtastic_KeyVerificationAdmin_MessageType;
/* Struct definitions */
/* Input event message to be sent to the node. */
typedef struct _meshtastic_AdminMessage_InputEvent {
/* The input event code */
uint8_t event_code;
/* Keyboard character code */
uint8_t kb_char;
/* The touch X coordinate */
uint16_t touch_x;
/* The touch Y coordinate */
uint16_t touch_y;
} meshtastic_AdminMessage_InputEvent;
/* Parameters for setting up Meshtastic for ameteur radio usage */
typedef struct _meshtastic_HamParameters {
/* Amateur radio call sign, eg. KD2ABC */
char call_sign[8];
/* Transmit power in dBm at the LoRA transceiver, not including any amplification */
int32_t tx_power;
/* The selected frequency of LoRA operation
Please respect your local laws, regulations, and band plans.
Ensure your radio is capable of operating of the selected frequency before setting this. */
float frequency;
/* Optional short name of user */
char short_name[5];
} meshtastic_HamParameters;
/* Response envelope for node_remote_hardware_pins */
typedef struct _meshtastic_NodeRemoteHardwarePinsResponse {
/* Nodes and their respective remote hardware GPIO pins */
pb_size_t node_remote_hardware_pins_count;
meshtastic_NodeRemoteHardwarePin node_remote_hardware_pins[16];
} meshtastic_NodeRemoteHardwarePinsResponse;
typedef struct _meshtastic_SharedContact {
/* The node number of the contact */
uint32_t node_num;
/* The User of the contact */
bool has_user;
meshtastic_User user;
/* Add this contact to the blocked / ignored list */
bool should_ignore;
/* Set the IS_KEY_MANUALLY_VERIFIED bit */
bool manually_verified;
} meshtastic_SharedContact;
/* This message is used by a client to initiate or complete a key verification */
typedef struct _meshtastic_KeyVerificationAdmin {
meshtastic_KeyVerificationAdmin_MessageType message_type;
/* The nodenum we're requesting */
uint32_t remote_nodenum;
/* The nonce is used to track the connection */
uint64_t nonce;
/* The 4 digit code generated by the remote node, and communicated outside the mesh */
bool has_security_number;
uint32_t security_number;
} meshtastic_KeyVerificationAdmin;
typedef PB_BYTES_ARRAY_T(8) meshtastic_AdminMessage_session_passkey_t;
/* This message is handled by the Admin module and is responsible for all settings/channel read/write operations.
This message is used to do settings operations to both remote AND local nodes.
(Prior to 1.2 these operations were done via special ToRadio operations) */
typedef struct _meshtastic_AdminMessage {
pb_size_t which_payload_variant;
union {
/* Send the specified channel in the response to this message
NOTE: This field is sent with the channel index + 1 (to ensure we never try to send 'zero' - which protobufs treats as not present) */
uint32_t get_channel_request;
/* TODO: REPLACE */
meshtastic_Channel get_channel_response;
/* Send the current owner data in the response to this message. */
bool get_owner_request;
/* TODO: REPLACE */
meshtastic_User get_owner_response;
/* Ask for the following config data to be sent */
meshtastic_AdminMessage_ConfigType get_config_request;
/* Send the current Config in the response to this message. */
meshtastic_Config get_config_response;
/* Ask for the following config data to be sent */
meshtastic_AdminMessage_ModuleConfigType get_module_config_request;
/* Send the current Config in the response to this message. */
meshtastic_ModuleConfig get_module_config_response;
/* Get the Canned Message Module messages in the response to this message. */
bool get_canned_message_module_messages_request;
/* Get the Canned Message Module messages in the response to this message. */
char get_canned_message_module_messages_response[201];
/* Request the node to send device metadata (firmware, protobuf version, etc) */
bool get_device_metadata_request;
/* Device metadata response */
meshtastic_DeviceMetadata get_device_metadata_response;
/* Get the Ringtone in the response to this message. */
bool get_ringtone_request;
/* Get the Ringtone in the response to this message. */
char get_ringtone_response[231];
/* Request the node to send it's connection status */
bool get_device_connection_status_request;
/* Device connection status response */
meshtastic_DeviceConnectionStatus get_device_connection_status_response;
/* Setup a node for licensed amateur (ham) radio operation */
meshtastic_HamParameters set_ham_mode;
/* Get the mesh's nodes with their available gpio pins for RemoteHardware module use */
bool get_node_remote_hardware_pins_request;
/* Respond with the mesh's nodes with their available gpio pins for RemoteHardware module use */
meshtastic_NodeRemoteHardwarePinsResponse get_node_remote_hardware_pins_response;
/* Enter (UF2) DFU mode
Only implemented on NRF52 currently */
bool enter_dfu_mode_request;
/* Delete the file by the specified path from the device */
char delete_file_request[201];
/* Set zero and offset for scale chips */
uint32_t set_scale;
/* Backup the node's preferences */
meshtastic_AdminMessage_BackupLocation backup_preferences;
/* Restore the node's preferences */
meshtastic_AdminMessage_BackupLocation restore_preferences;
/* Remove backups of the node's preferences */
meshtastic_AdminMessage_BackupLocation remove_backup_preferences;
/* Send an input event to the node.
This is used to trigger physical input events like button presses, touch events, etc. */
meshtastic_AdminMessage_InputEvent send_input_event;
/* Set the owner for this node */
meshtastic_User set_owner;
/* Set channels (using the new API).
A special channel is the "primary channel".
The other records are secondary channels.
Note: only one channel can be marked as primary.
If the client sets a particular channel to be primary, the previous channel will be set to SECONDARY automatically. */
meshtastic_Channel set_channel;
/* Set the current Config */
meshtastic_Config set_config;
/* Set the current Config */
meshtastic_ModuleConfig set_module_config;
/* Set the Canned Message Module messages text. */
char set_canned_message_module_messages[201];
/* Set the ringtone for ExternalNotification. */
char set_ringtone_message[231];
/* Remove the node by the specified node-num from the NodeDB on the device */
uint32_t remove_by_nodenum;
/* Set specified node-num to be favorited on the NodeDB on the device */
uint32_t set_favorite_node;
/* Set specified node-num to be un-favorited on the NodeDB on the device */
uint32_t remove_favorite_node;
/* Set fixed position data on the node and then set the position.fixed_position = true */
meshtastic_Position set_fixed_position;
/* Clear fixed position coordinates and then set position.fixed_position = false */
bool remove_fixed_position;
/* Set time only on the node
Convenience method to set the time on the node (as Net quality) without any other position data */
uint32_t set_time_only;
/* Tell the node to send the stored ui data. */
bool get_ui_config_request;
/* Reply stored device ui data. */
meshtastic_DeviceUIConfig get_ui_config_response;
/* Tell the node to store UI data persistently. */
meshtastic_DeviceUIConfig store_ui_config;
/* Set specified node-num to be ignored on the NodeDB on the device */
uint32_t set_ignored_node;
/* Set specified node-num to be un-ignored on the NodeDB on the device */
uint32_t remove_ignored_node;
/* Begins an edit transaction for config, module config, owner, and channel settings changes
This will delay the standard *implicit* save to the file system and subsequent reboot behavior until committed (commit_edit_settings) */
bool begin_edit_settings;
/* Commits an open transaction for any edits made to config, module config, owner, and channel settings */
bool commit_edit_settings;
/* Add a contact (User) to the nodedb */
meshtastic_SharedContact add_contact;
/* Initiate or respond to a key verification request */
meshtastic_KeyVerificationAdmin key_verification;
/* Tell the node to factory reset config everything; all device state and configuration will be returned to factory defaults and BLE bonds will be cleared. */
int32_t factory_reset_device;
/* Tell the node to reboot into the OTA Firmware in this many seconds (or <0 to cancel reboot)
Only Implemented for ESP32 Devices. This needs to be issued to send a new main firmware via bluetooth. */
int32_t reboot_ota_seconds;
/* This message is only supported for the simulator Portduino build.
If received the simulator will exit successfully. */
bool exit_simulator;
/* Tell the node to reboot in this many seconds (or <0 to cancel reboot) */
int32_t reboot_seconds;
/* Tell the node to shutdown in this many seconds (or <0 to cancel shutdown) */
int32_t shutdown_seconds;
/* Tell the node to factory reset config; all device state and configuration will be returned to factory defaults; BLE bonds will be preserved. */
int32_t factory_reset_config;
/* Tell the node to reset the nodedb.
When true, favorites are preserved through reset. */
bool nodedb_reset;
};
/* The node generates this key and sends it with any get_x_response packets.
The client MUST include the same key with any set_x commands. Key expires after 300 seconds.
Prevents replay attacks for admin messages. */
meshtastic_AdminMessage_session_passkey_t session_passkey;
} meshtastic_AdminMessage;
#ifdef __cplusplus
extern "C" {
#endif
/* Helper constants for enums */
#define _meshtastic_AdminMessage_ConfigType_MIN meshtastic_AdminMessage_ConfigType_DEVICE_CONFIG
#define _meshtastic_AdminMessage_ConfigType_MAX meshtastic_AdminMessage_ConfigType_DEVICEUI_CONFIG
#define _meshtastic_AdminMessage_ConfigType_ARRAYSIZE ((meshtastic_AdminMessage_ConfigType)(meshtastic_AdminMessage_ConfigType_DEVICEUI_CONFIG+1))
#define _meshtastic_AdminMessage_ModuleConfigType_MIN meshtastic_AdminMessage_ModuleConfigType_MQTT_CONFIG
#define _meshtastic_AdminMessage_ModuleConfigType_MAX meshtastic_AdminMessage_ModuleConfigType_PAXCOUNTER_CONFIG
#define _meshtastic_AdminMessage_ModuleConfigType_ARRAYSIZE ((meshtastic_AdminMessage_ModuleConfigType)(meshtastic_AdminMessage_ModuleConfigType_PAXCOUNTER_CONFIG+1))
#define _meshtastic_AdminMessage_BackupLocation_MIN meshtastic_AdminMessage_BackupLocation_FLASH
#define _meshtastic_AdminMessage_BackupLocation_MAX meshtastic_AdminMessage_BackupLocation_SD
#define _meshtastic_AdminMessage_BackupLocation_ARRAYSIZE ((meshtastic_AdminMessage_BackupLocation)(meshtastic_AdminMessage_BackupLocation_SD+1))
#define _meshtastic_KeyVerificationAdmin_MessageType_MIN meshtastic_KeyVerificationAdmin_MessageType_INITIATE_VERIFICATION
#define _meshtastic_KeyVerificationAdmin_MessageType_MAX meshtastic_KeyVerificationAdmin_MessageType_DO_NOT_VERIFY
#define _meshtastic_KeyVerificationAdmin_MessageType_ARRAYSIZE ((meshtastic_KeyVerificationAdmin_MessageType)(meshtastic_KeyVerificationAdmin_MessageType_DO_NOT_VERIFY+1))
#define meshtastic_AdminMessage_payload_variant_get_config_request_ENUMTYPE meshtastic_AdminMessage_ConfigType
#define meshtastic_AdminMessage_payload_variant_get_module_config_request_ENUMTYPE meshtastic_AdminMessage_ModuleConfigType
#define meshtastic_AdminMessage_payload_variant_backup_preferences_ENUMTYPE meshtastic_AdminMessage_BackupLocation
#define meshtastic_AdminMessage_payload_variant_restore_preferences_ENUMTYPE meshtastic_AdminMessage_BackupLocation
#define meshtastic_AdminMessage_payload_variant_remove_backup_preferences_ENUMTYPE meshtastic_AdminMessage_BackupLocation
#define meshtastic_KeyVerificationAdmin_message_type_ENUMTYPE meshtastic_KeyVerificationAdmin_MessageType
/* Initializer values for message structs */
#define meshtastic_AdminMessage_init_default {0, {0}, {0, {0}}}
#define meshtastic_AdminMessage_InputEvent_init_default {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}
#define meshtastic_KeyVerificationAdmin_init_default {_meshtastic_KeyVerificationAdmin_MessageType_MIN, 0, 0, false, 0}
#define meshtastic_AdminMessage_init_zero {0, {0}, {0, {0}}}
#define meshtastic_AdminMessage_InputEvent_init_zero {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}
#define meshtastic_KeyVerificationAdmin_init_zero {_meshtastic_KeyVerificationAdmin_MessageType_MIN, 0, 0, false, 0}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_AdminMessage_InputEvent_event_code_tag 1
#define meshtastic_AdminMessage_InputEvent_kb_char_tag 2
#define meshtastic_AdminMessage_InputEvent_touch_x_tag 3
#define meshtastic_AdminMessage_InputEvent_touch_y_tag 4
#define meshtastic_HamParameters_call_sign_tag 1
#define meshtastic_HamParameters_tx_power_tag 2
#define meshtastic_HamParameters_frequency_tag 3
#define meshtastic_HamParameters_short_name_tag 4
#define meshtastic_NodeRemoteHardwarePinsResponse_node_remote_hardware_pins_tag 1
#define meshtastic_SharedContact_node_num_tag 1
#define meshtastic_SharedContact_user_tag 2
#define meshtastic_SharedContact_should_ignore_tag 3
#define meshtastic_SharedContact_manually_verified_tag 4
#define meshtastic_KeyVerificationAdmin_message_type_tag 1
#define meshtastic_KeyVerificationAdmin_remote_nodenum_tag 2
#define meshtastic_KeyVerificationAdmin_nonce_tag 3
#define meshtastic_KeyVerificationAdmin_security_number_tag 4
#define meshtastic_AdminMessage_get_channel_request_tag 1
#define meshtastic_AdminMessage_get_channel_response_tag 2
#define meshtastic_AdminMessage_get_owner_request_tag 3
#define meshtastic_AdminMessage_get_owner_response_tag 4
#define meshtastic_AdminMessage_get_config_request_tag 5
#define meshtastic_AdminMessage_get_config_response_tag 6
#define meshtastic_AdminMessage_get_module_config_request_tag 7
#define meshtastic_AdminMessage_get_module_config_response_tag 8
#define meshtastic_AdminMessage_get_canned_message_module_messages_request_tag 10
#define meshtastic_AdminMessage_get_canned_message_module_messages_response_tag 11
#define meshtastic_AdminMessage_get_device_metadata_request_tag 12
#define meshtastic_AdminMessage_get_device_metadata_response_tag 13
#define meshtastic_AdminMessage_get_ringtone_request_tag 14
#define meshtastic_AdminMessage_get_ringtone_response_tag 15
#define meshtastic_AdminMessage_get_device_connection_status_request_tag 16
#define meshtastic_AdminMessage_get_device_connection_status_response_tag 17
#define meshtastic_AdminMessage_set_ham_mode_tag 18
#define meshtastic_AdminMessage_get_node_remote_hardware_pins_request_tag 19
#define meshtastic_AdminMessage_get_node_remote_hardware_pins_response_tag 20
#define meshtastic_AdminMessage_enter_dfu_mode_request_tag 21
#define meshtastic_AdminMessage_delete_file_request_tag 22
#define meshtastic_AdminMessage_set_scale_tag 23
#define meshtastic_AdminMessage_backup_preferences_tag 24
#define meshtastic_AdminMessage_restore_preferences_tag 25
#define meshtastic_AdminMessage_remove_backup_preferences_tag 26
#define meshtastic_AdminMessage_send_input_event_tag 27
#define meshtastic_AdminMessage_set_owner_tag 32
#define meshtastic_AdminMessage_set_channel_tag 33
#define meshtastic_AdminMessage_set_config_tag 34
#define meshtastic_AdminMessage_set_module_config_tag 35
#define meshtastic_AdminMessage_set_canned_message_module_messages_tag 36
#define meshtastic_AdminMessage_set_ringtone_message_tag 37
#define meshtastic_AdminMessage_remove_by_nodenum_tag 38
#define meshtastic_AdminMessage_set_favorite_node_tag 39
#define meshtastic_AdminMessage_remove_favorite_node_tag 40
#define meshtastic_AdminMessage_set_fixed_position_tag 41
#define meshtastic_AdminMessage_remove_fixed_position_tag 42
#define meshtastic_AdminMessage_set_time_only_tag 43
#define meshtastic_AdminMessage_get_ui_config_request_tag 44
#define meshtastic_AdminMessage_get_ui_config_response_tag 45
#define meshtastic_AdminMessage_store_ui_config_tag 46
#define meshtastic_AdminMessage_set_ignored_node_tag 47
#define meshtastic_AdminMessage_remove_ignored_node_tag 48
#define meshtastic_AdminMessage_begin_edit_settings_tag 64
#define meshtastic_AdminMessage_commit_edit_settings_tag 65
#define meshtastic_AdminMessage_add_contact_tag 66
#define meshtastic_AdminMessage_key_verification_tag 67
#define meshtastic_AdminMessage_factory_reset_device_tag 94
#define meshtastic_AdminMessage_reboot_ota_seconds_tag 95
#define meshtastic_AdminMessage_exit_simulator_tag 96
#define meshtastic_AdminMessage_reboot_seconds_tag 97
#define meshtastic_AdminMessage_shutdown_seconds_tag 98
#define meshtastic_AdminMessage_factory_reset_config_tag 99
#define meshtastic_AdminMessage_nodedb_reset_tag 100
#define meshtastic_AdminMessage_session_passkey_tag 101
/* Struct field encoding specification for nanopb */
#define meshtastic_AdminMessage_FIELDLIST(X, a) \
X(a, STATIC, ONEOF, UINT32, (payload_variant,get_channel_request,get_channel_request), 1) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_channel_response,get_channel_response), 2) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,get_owner_request,get_owner_request), 3) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_owner_response,get_owner_response), 4) \
X(a, STATIC, ONEOF, UENUM, (payload_variant,get_config_request,get_config_request), 5) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_config_response,get_config_response), 6) \
X(a, STATIC, ONEOF, UENUM, (payload_variant,get_module_config_request,get_module_config_request), 7) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_module_config_response,get_module_config_response), 8) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,get_canned_message_module_messages_request,get_canned_message_module_messages_request), 10) \
X(a, STATIC, ONEOF, STRING, (payload_variant,get_canned_message_module_messages_response,get_canned_message_module_messages_response), 11) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,get_device_metadata_request,get_device_metadata_request), 12) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_device_metadata_response,get_device_metadata_response), 13) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,get_ringtone_request,get_ringtone_request), 14) \
X(a, STATIC, ONEOF, STRING, (payload_variant,get_ringtone_response,get_ringtone_response), 15) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,get_device_connection_status_request,get_device_connection_status_request), 16) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_device_connection_status_response,get_device_connection_status_response), 17) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_ham_mode,set_ham_mode), 18) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,get_node_remote_hardware_pins_request,get_node_remote_hardware_pins_request), 19) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_node_remote_hardware_pins_response,get_node_remote_hardware_pins_response), 20) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,enter_dfu_mode_request,enter_dfu_mode_request), 21) \
X(a, STATIC, ONEOF, STRING, (payload_variant,delete_file_request,delete_file_request), 22) \
X(a, STATIC, ONEOF, UINT32, (payload_variant,set_scale,set_scale), 23) \
X(a, STATIC, ONEOF, UENUM, (payload_variant,backup_preferences,backup_preferences), 24) \
X(a, STATIC, ONEOF, UENUM, (payload_variant,restore_preferences,restore_preferences), 25) \
X(a, STATIC, ONEOF, UENUM, (payload_variant,remove_backup_preferences,remove_backup_preferences), 26) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,send_input_event,send_input_event), 27) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_owner,set_owner), 32) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_channel,set_channel), 33) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_config,set_config), 34) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_module_config,set_module_config), 35) \
X(a, STATIC, ONEOF, STRING, (payload_variant,set_canned_message_module_messages,set_canned_message_module_messages), 36) \
X(a, STATIC, ONEOF, STRING, (payload_variant,set_ringtone_message,set_ringtone_message), 37) \
X(a, STATIC, ONEOF, UINT32, (payload_variant,remove_by_nodenum,remove_by_nodenum), 38) \
X(a, STATIC, ONEOF, UINT32, (payload_variant,set_favorite_node,set_favorite_node), 39) \
X(a, STATIC, ONEOF, UINT32, (payload_variant,remove_favorite_node,remove_favorite_node), 40) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,set_fixed_position,set_fixed_position), 41) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,remove_fixed_position,remove_fixed_position), 42) \
X(a, STATIC, ONEOF, FIXED32, (payload_variant,set_time_only,set_time_only), 43) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,get_ui_config_request,get_ui_config_request), 44) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,get_ui_config_response,get_ui_config_response), 45) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,store_ui_config,store_ui_config), 46) \
X(a, STATIC, ONEOF, UINT32, (payload_variant,set_ignored_node,set_ignored_node), 47) \
X(a, STATIC, ONEOF, UINT32, (payload_variant,remove_ignored_node,remove_ignored_node), 48) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,begin_edit_settings,begin_edit_settings), 64) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,commit_edit_settings,commit_edit_settings), 65) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,add_contact,add_contact), 66) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,key_verification,key_verification), 67) \
X(a, STATIC, ONEOF, INT32, (payload_variant,factory_reset_device,factory_reset_device), 94) \
X(a, STATIC, ONEOF, INT32, (payload_variant,reboot_ota_seconds,reboot_ota_seconds), 95) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,exit_simulator,exit_simulator), 96) \
X(a, STATIC, ONEOF, INT32, (payload_variant,reboot_seconds,reboot_seconds), 97) \
X(a, STATIC, ONEOF, INT32, (payload_variant,shutdown_seconds,shutdown_seconds), 98) \
X(a, STATIC, ONEOF, INT32, (payload_variant,factory_reset_config,factory_reset_config), 99) \
X(a, STATIC, ONEOF, BOOL, (payload_variant,nodedb_reset,nodedb_reset), 100) \
X(a, STATIC, SINGULAR, BYTES, session_passkey, 101)
#define meshtastic_AdminMessage_CALLBACK NULL
#define meshtastic_AdminMessage_DEFAULT NULL
#define meshtastic_AdminMessage_payload_variant_get_channel_response_MSGTYPE meshtastic_Channel
#define meshtastic_AdminMessage_payload_variant_get_owner_response_MSGTYPE meshtastic_User
#define meshtastic_AdminMessage_payload_variant_get_config_response_MSGTYPE meshtastic_Config
#define meshtastic_AdminMessage_payload_variant_get_module_config_response_MSGTYPE meshtastic_ModuleConfig
#define meshtastic_AdminMessage_payload_variant_get_device_metadata_response_MSGTYPE meshtastic_DeviceMetadata
#define meshtastic_AdminMessage_payload_variant_get_device_connection_status_response_MSGTYPE meshtastic_DeviceConnectionStatus
#define meshtastic_AdminMessage_payload_variant_set_ham_mode_MSGTYPE meshtastic_HamParameters
#define meshtastic_AdminMessage_payload_variant_get_node_remote_hardware_pins_response_MSGTYPE meshtastic_NodeRemoteHardwarePinsResponse
#define meshtastic_AdminMessage_payload_variant_send_input_event_MSGTYPE meshtastic_AdminMessage_InputEvent
#define meshtastic_AdminMessage_payload_variant_set_owner_MSGTYPE meshtastic_User
#define meshtastic_AdminMessage_payload_variant_set_channel_MSGTYPE meshtastic_Channel
#define meshtastic_AdminMessage_payload_variant_set_config_MSGTYPE meshtastic_Config
#define meshtastic_AdminMessage_payload_variant_set_module_config_MSGTYPE meshtastic_ModuleConfig
#define meshtastic_AdminMessage_payload_variant_set_fixed_position_MSGTYPE meshtastic_Position
#define meshtastic_AdminMessage_payload_variant_get_ui_config_response_MSGTYPE meshtastic_DeviceUIConfig
#define meshtastic_AdminMessage_payload_variant_store_ui_config_MSGTYPE meshtastic_DeviceUIConfig
#define meshtastic_AdminMessage_payload_variant_add_contact_MSGTYPE meshtastic_SharedContact
#define meshtastic_AdminMessage_payload_variant_key_verification_MSGTYPE meshtastic_KeyVerificationAdmin
#define meshtastic_AdminMessage_InputEvent_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, event_code, 1) \
X(a, STATIC, SINGULAR, UINT32, kb_char, 2) \
X(a, STATIC, SINGULAR, UINT32, touch_x, 3) \
X(a, STATIC, SINGULAR, UINT32, touch_y, 4)
#define meshtastic_AdminMessage_InputEvent_CALLBACK NULL
#define meshtastic_AdminMessage_InputEvent_DEFAULT NULL
#define meshtastic_HamParameters_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, STRING, call_sign, 1) \
X(a, STATIC, SINGULAR, INT32, tx_power, 2) \
X(a, STATIC, SINGULAR, FLOAT, frequency, 3) \
X(a, STATIC, SINGULAR, STRING, short_name, 4)
#define meshtastic_HamParameters_CALLBACK NULL
#define meshtastic_HamParameters_DEFAULT NULL
#define meshtastic_NodeRemoteHardwarePinsResponse_FIELDLIST(X, a) \
X(a, STATIC, REPEATED, MESSAGE, node_remote_hardware_pins, 1)
#define meshtastic_NodeRemoteHardwarePinsResponse_CALLBACK NULL
#define meshtastic_NodeRemoteHardwarePinsResponse_DEFAULT NULL
#define meshtastic_NodeRemoteHardwarePinsResponse_node_remote_hardware_pins_MSGTYPE meshtastic_NodeRemoteHardwarePin
#define meshtastic_SharedContact_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, node_num, 1) \
X(a, STATIC, OPTIONAL, MESSAGE, user, 2) \
X(a, STATIC, SINGULAR, BOOL, should_ignore, 3) \
X(a, STATIC, SINGULAR, BOOL, manually_verified, 4)
#define meshtastic_SharedContact_CALLBACK NULL
#define meshtastic_SharedContact_DEFAULT NULL
#define meshtastic_SharedContact_user_MSGTYPE meshtastic_User
#define meshtastic_KeyVerificationAdmin_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UENUM, message_type, 1) \
X(a, STATIC, SINGULAR, UINT32, remote_nodenum, 2) \
X(a, STATIC, SINGULAR, UINT64, nonce, 3) \
X(a, STATIC, OPTIONAL, UINT32, security_number, 4)
#define meshtastic_KeyVerificationAdmin_CALLBACK NULL
#define meshtastic_KeyVerificationAdmin_DEFAULT NULL
extern const pb_msgdesc_t meshtastic_AdminMessage_msg;
extern const pb_msgdesc_t meshtastic_AdminMessage_InputEvent_msg;
extern const pb_msgdesc_t meshtastic_HamParameters_msg;
extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePinsResponse_msg;
extern const pb_msgdesc_t meshtastic_SharedContact_msg;
extern const pb_msgdesc_t meshtastic_KeyVerificationAdmin_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define meshtastic_AdminMessage_fields &meshtastic_AdminMessage_msg
#define meshtastic_AdminMessage_InputEvent_fields &meshtastic_AdminMessage_InputEvent_msg
#define meshtastic_HamParameters_fields &meshtastic_HamParameters_msg
#define meshtastic_NodeRemoteHardwarePinsResponse_fields &meshtastic_NodeRemoteHardwarePinsResponse_msg
#define meshtastic_SharedContact_fields &meshtastic_SharedContact_msg
#define meshtastic_KeyVerificationAdmin_fields &meshtastic_KeyVerificationAdmin_msg
/* Maximum encoded size of messages (where known) */
#define MESHTASTIC_MESHTASTIC_ADMIN_PB_H_MAX_SIZE meshtastic_AdminMessage_size
#define meshtastic_AdminMessage_InputEvent_size 14
#define meshtastic_AdminMessage_size 511
#define meshtastic_HamParameters_size 31
#define meshtastic_KeyVerificationAdmin_size 25
#define meshtastic_NodeRemoteHardwarePinsResponse_size 496
#define meshtastic_SharedContact_size 127
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif
@@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.9.1 */
#include "meshtastic/apponly.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(meshtastic_ChannelSet, meshtastic_ChannelSet, 2)
@@ -0,0 +1,64 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.9.1 */
#ifndef PB_MESHTASTIC_MESHTASTIC_APPONLY_PB_H_INCLUDED
#define PB_MESHTASTIC_MESHTASTIC_APPONLY_PB_H_INCLUDED
#include <pb.h>
#include "meshtastic/channel.pb.h"
#include "meshtastic/config.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* This is the most compact possible representation for a set of channels.
It includes only one PRIMARY channel (which must be first) and
any SECONDARY channels.
No DISABLED channels are included.
This abstraction is used only on the the 'app side' of the world (ie python, javascript and android etc) to show a group of Channels as a (long) URL */
typedef struct _meshtastic_ChannelSet {
/* Channel list with settings */
pb_size_t settings_count;
meshtastic_ChannelSettings settings[8];
/* LoRa config */
bool has_lora_config;
meshtastic_Config_LoRaConfig lora_config;
} meshtastic_ChannelSet;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define meshtastic_ChannelSet_init_default {0, {meshtastic_ChannelSettings_init_default, meshtastic_ChannelSettings_init_default, meshtastic_ChannelSettings_init_default, meshtastic_ChannelSettings_init_default, meshtastic_ChannelSettings_init_default, meshtastic_ChannelSettings_init_default, meshtastic_ChannelSettings_init_default, meshtastic_ChannelSettings_init_default}, false, meshtastic_Config_LoRaConfig_init_default}
#define meshtastic_ChannelSet_init_zero {0, {meshtastic_ChannelSettings_init_zero, meshtastic_ChannelSettings_init_zero, meshtastic_ChannelSettings_init_zero, meshtastic_ChannelSettings_init_zero, meshtastic_ChannelSettings_init_zero, meshtastic_ChannelSettings_init_zero, meshtastic_ChannelSettings_init_zero, meshtastic_ChannelSettings_init_zero}, false, meshtastic_Config_LoRaConfig_init_zero}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_ChannelSet_settings_tag 1
#define meshtastic_ChannelSet_lora_config_tag 2
/* Struct field encoding specification for nanopb */
#define meshtastic_ChannelSet_FIELDLIST(X, a) \
X(a, STATIC, REPEATED, MESSAGE, settings, 1) \
X(a, STATIC, OPTIONAL, MESSAGE, lora_config, 2)
#define meshtastic_ChannelSet_CALLBACK NULL
#define meshtastic_ChannelSet_DEFAULT NULL
#define meshtastic_ChannelSet_settings_MSGTYPE meshtastic_ChannelSettings
#define meshtastic_ChannelSet_lora_config_MSGTYPE meshtastic_Config_LoRaConfig
extern const pb_msgdesc_t meshtastic_ChannelSet_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define meshtastic_ChannelSet_fields &meshtastic_ChannelSet_msg
/* Maximum encoded size of messages (where known) */
#define MESHTASTIC_MESHTASTIC_APPONLY_PB_H_MAX_SIZE meshtastic_ChannelSet_size
#define meshtastic_ChannelSet_size 679
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif
@@ -0,0 +1,31 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.9.1 */
#include "meshtastic/atak.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(meshtastic_TAKPacket, meshtastic_TAKPacket, 2)
PB_BIND(meshtastic_GeoChat, meshtastic_GeoChat, 2)
PB_BIND(meshtastic_Group, meshtastic_Group, AUTO)
PB_BIND(meshtastic_Status, meshtastic_Status, AUTO)
PB_BIND(meshtastic_Contact, meshtastic_Contact, AUTO)
PB_BIND(meshtastic_PLI, meshtastic_PLI, AUTO)
@@ -0,0 +1,286 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.9.1 */
#ifndef PB_MESHTASTIC_MESHTASTIC_ATAK_PB_H_INCLUDED
#define PB_MESHTASTIC_MESHTASTIC_ATAK_PB_H_INCLUDED
#include <pb.h>
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Enum definitions */
typedef enum _meshtastic_Team {
/* Unspecifed */
meshtastic_Team_Unspecifed_Color = 0,
/* White */
meshtastic_Team_White = 1,
/* Yellow */
meshtastic_Team_Yellow = 2,
/* Orange */
meshtastic_Team_Orange = 3,
/* Magenta */
meshtastic_Team_Magenta = 4,
/* Red */
meshtastic_Team_Red = 5,
/* Maroon */
meshtastic_Team_Maroon = 6,
/* Purple */
meshtastic_Team_Purple = 7,
/* Dark Blue */
meshtastic_Team_Dark_Blue = 8,
/* Blue */
meshtastic_Team_Blue = 9,
/* Cyan */
meshtastic_Team_Cyan = 10,
/* Teal */
meshtastic_Team_Teal = 11,
/* Green */
meshtastic_Team_Green = 12,
/* Dark Green */
meshtastic_Team_Dark_Green = 13,
/* Brown */
meshtastic_Team_Brown = 14
} meshtastic_Team;
/* Role of the group member */
typedef enum _meshtastic_MemberRole {
/* Unspecifed */
meshtastic_MemberRole_Unspecifed = 0,
/* Team Member */
meshtastic_MemberRole_TeamMember = 1,
/* Team Lead */
meshtastic_MemberRole_TeamLead = 2,
/* Headquarters */
meshtastic_MemberRole_HQ = 3,
/* Airsoft enthusiast */
meshtastic_MemberRole_Sniper = 4,
/* Medic */
meshtastic_MemberRole_Medic = 5,
/* ForwardObserver */
meshtastic_MemberRole_ForwardObserver = 6,
/* Radio Telephone Operator */
meshtastic_MemberRole_RTO = 7,
/* Doggo */
meshtastic_MemberRole_K9 = 8
} meshtastic_MemberRole;
/* Struct definitions */
/* ATAK GeoChat message */
typedef struct _meshtastic_GeoChat {
/* The text message */
char message[200];
/* Uid recipient of the message */
bool has_to;
char to[120];
/* Callsign of the recipient for the message */
bool has_to_callsign;
char to_callsign[120];
} meshtastic_GeoChat;
/* ATAK Group
<__group role='Team Member' name='Cyan'/> */
typedef struct _meshtastic_Group {
/* Role of the group member */
meshtastic_MemberRole role;
/* Team (color)
Default Cyan */
meshtastic_Team team;
} meshtastic_Group;
/* ATAK EUD Status
<status battery='100' /> */
typedef struct _meshtastic_Status {
/* Battery level */
uint8_t battery;
} meshtastic_Status;
/* ATAK Contact
<contact endpoint='0.0.0.0:4242:tcp' phone='+12345678' callsign='FALKE'/> */
typedef struct _meshtastic_Contact {
/* Callsign */
char callsign[120];
/* Device callsign */
char device_callsign[120]; /* IP address of endpoint in integer form (0.0.0.0 default) */
} meshtastic_Contact;
/* Position Location Information from ATAK */
typedef struct _meshtastic_PLI {
/* The new preferred location encoding, multiply by 1e-7 to get degrees
in floating point */
int32_t latitude_i;
/* The new preferred location encoding, multiply by 1e-7 to get degrees
in floating point */
int32_t longitude_i;
/* Altitude (ATAK prefers HAE) */
int32_t altitude;
/* Speed */
uint32_t speed;
/* Course in degrees */
uint16_t course;
} meshtastic_PLI;
typedef PB_BYTES_ARRAY_T(220) meshtastic_TAKPacket_detail_t;
/* Packets for the official ATAK Plugin */
typedef struct _meshtastic_TAKPacket {
/* Are the payloads strings compressed for LoRA transport? */
bool is_compressed;
/* The contact / callsign for ATAK user */
bool has_contact;
meshtastic_Contact contact;
/* The group for ATAK user */
bool has_group;
meshtastic_Group group;
/* The status of the ATAK EUD */
bool has_status;
meshtastic_Status status;
pb_size_t which_payload_variant;
union {
/* TAK position report */
meshtastic_PLI pli;
/* ATAK GeoChat message */
meshtastic_GeoChat chat;
/* Generic CoT detail XML
May be compressed / truncated by the sender (EUD) */
meshtastic_TAKPacket_detail_t detail;
} payload_variant;
} meshtastic_TAKPacket;
#ifdef __cplusplus
extern "C" {
#endif
/* Helper constants for enums */
#define _meshtastic_Team_MIN meshtastic_Team_Unspecifed_Color
#define _meshtastic_Team_MAX meshtastic_Team_Brown
#define _meshtastic_Team_ARRAYSIZE ((meshtastic_Team)(meshtastic_Team_Brown+1))
#define _meshtastic_MemberRole_MIN meshtastic_MemberRole_Unspecifed
#define _meshtastic_MemberRole_MAX meshtastic_MemberRole_K9
#define _meshtastic_MemberRole_ARRAYSIZE ((meshtastic_MemberRole)(meshtastic_MemberRole_K9+1))
#define meshtastic_Group_role_ENUMTYPE meshtastic_MemberRole
#define meshtastic_Group_team_ENUMTYPE meshtastic_Team
/* 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, ""}
#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_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, ""}
#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}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_GeoChat_message_tag 1
#define meshtastic_GeoChat_to_tag 2
#define meshtastic_GeoChat_to_callsign_tag 3
#define meshtastic_Group_role_tag 1
#define meshtastic_Group_team_tag 2
#define meshtastic_Status_battery_tag 1
#define meshtastic_Contact_callsign_tag 1
#define meshtastic_Contact_device_callsign_tag 2
#define meshtastic_PLI_latitude_i_tag 1
#define meshtastic_PLI_longitude_i_tag 2
#define meshtastic_PLI_altitude_tag 3
#define meshtastic_PLI_speed_tag 4
#define meshtastic_PLI_course_tag 5
#define meshtastic_TAKPacket_is_compressed_tag 1
#define meshtastic_TAKPacket_contact_tag 2
#define meshtastic_TAKPacket_group_tag 3
#define meshtastic_TAKPacket_status_tag 4
#define meshtastic_TAKPacket_pli_tag 5
#define meshtastic_TAKPacket_chat_tag 6
#define meshtastic_TAKPacket_detail_tag 7
/* Struct field encoding specification for nanopb */
#define meshtastic_TAKPacket_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, BOOL, is_compressed, 1) \
X(a, STATIC, OPTIONAL, MESSAGE, contact, 2) \
X(a, STATIC, OPTIONAL, MESSAGE, group, 3) \
X(a, STATIC, OPTIONAL, MESSAGE, status, 4) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,pli,payload_variant.pli), 5) \
X(a, STATIC, ONEOF, MESSAGE, (payload_variant,chat,payload_variant.chat), 6) \
X(a, STATIC, ONEOF, BYTES, (payload_variant,detail,payload_variant.detail), 7)
#define meshtastic_TAKPacket_CALLBACK NULL
#define meshtastic_TAKPacket_DEFAULT NULL
#define meshtastic_TAKPacket_contact_MSGTYPE meshtastic_Contact
#define meshtastic_TAKPacket_group_MSGTYPE meshtastic_Group
#define meshtastic_TAKPacket_status_MSGTYPE meshtastic_Status
#define meshtastic_TAKPacket_payload_variant_pli_MSGTYPE meshtastic_PLI
#define meshtastic_TAKPacket_payload_variant_chat_MSGTYPE meshtastic_GeoChat
#define meshtastic_GeoChat_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, STRING, message, 1) \
X(a, STATIC, OPTIONAL, STRING, to, 2) \
X(a, STATIC, OPTIONAL, STRING, to_callsign, 3)
#define meshtastic_GeoChat_CALLBACK NULL
#define meshtastic_GeoChat_DEFAULT NULL
#define meshtastic_Group_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UENUM, role, 1) \
X(a, STATIC, SINGULAR, UENUM, team, 2)
#define meshtastic_Group_CALLBACK NULL
#define meshtastic_Group_DEFAULT NULL
#define meshtastic_Status_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, battery, 1)
#define meshtastic_Status_CALLBACK NULL
#define meshtastic_Status_DEFAULT NULL
#define meshtastic_Contact_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, STRING, callsign, 1) \
X(a, STATIC, SINGULAR, STRING, device_callsign, 2)
#define meshtastic_Contact_CALLBACK NULL
#define meshtastic_Contact_DEFAULT NULL
#define meshtastic_PLI_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, SFIXED32, latitude_i, 1) \
X(a, STATIC, SINGULAR, SFIXED32, longitude_i, 2) \
X(a, STATIC, SINGULAR, INT32, altitude, 3) \
X(a, STATIC, SINGULAR, UINT32, speed, 4) \
X(a, STATIC, SINGULAR, UINT32, course, 5)
#define meshtastic_PLI_CALLBACK NULL
#define meshtastic_PLI_DEFAULT NULL
extern const pb_msgdesc_t meshtastic_TAKPacket_msg;
extern const pb_msgdesc_t meshtastic_GeoChat_msg;
extern const pb_msgdesc_t meshtastic_Group_msg;
extern const pb_msgdesc_t meshtastic_Status_msg;
extern const pb_msgdesc_t meshtastic_Contact_msg;
extern const pb_msgdesc_t meshtastic_PLI_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define meshtastic_TAKPacket_fields &meshtastic_TAKPacket_msg
#define meshtastic_GeoChat_fields &meshtastic_GeoChat_msg
#define meshtastic_Group_fields &meshtastic_Group_msg
#define meshtastic_Status_fields &meshtastic_Status_msg
#define meshtastic_Contact_fields &meshtastic_Contact_msg
#define meshtastic_PLI_fields &meshtastic_PLI_msg
/* Maximum encoded size of messages (where known) */
#define MESHTASTIC_MESHTASTIC_ATAK_PB_H_MAX_SIZE meshtastic_TAKPacket_size
#define meshtastic_Contact_size 242
#define meshtastic_GeoChat_size 444
#define meshtastic_Group_size 4
#define meshtastic_PLI_size 31
#define meshtastic_Status_size 3
#define meshtastic_TAKPacket_size 705
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif
@@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.9.1 */
#include "meshtastic/cannedmessages.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(meshtastic_CannedMessageModuleConfig, meshtastic_CannedMessageModuleConfig, AUTO)
@@ -0,0 +1,50 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.9.1 */
#ifndef PB_MESHTASTIC_MESHTASTIC_CANNEDMESSAGES_PB_H_INCLUDED
#define PB_MESHTASTIC_MESHTASTIC_CANNEDMESSAGES_PB_H_INCLUDED
#include <pb.h>
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* Canned message module configuration. */
typedef struct _meshtastic_CannedMessageModuleConfig {
/* Predefined messages for canned message module separated by '|' characters. */
char messages[201];
} meshtastic_CannedMessageModuleConfig;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define meshtastic_CannedMessageModuleConfig_init_default {""}
#define meshtastic_CannedMessageModuleConfig_init_zero {""}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_CannedMessageModuleConfig_messages_tag 1
/* Struct field encoding specification for nanopb */
#define meshtastic_CannedMessageModuleConfig_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, STRING, messages, 1)
#define meshtastic_CannedMessageModuleConfig_CALLBACK NULL
#define meshtastic_CannedMessageModuleConfig_DEFAULT NULL
extern const pb_msgdesc_t meshtastic_CannedMessageModuleConfig_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define meshtastic_CannedMessageModuleConfig_fields &meshtastic_CannedMessageModuleConfig_msg
/* Maximum encoded size of messages (where known) */
#define MESHTASTIC_MESHTASTIC_CANNEDMESSAGES_PB_H_MAX_SIZE meshtastic_CannedMessageModuleConfig_size
#define meshtastic_CannedMessageModuleConfig_size 203
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif
@@ -0,0 +1,20 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.9.1 */
#include "meshtastic/channel.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(meshtastic_ChannelSettings, meshtastic_ChannelSettings, AUTO)
PB_BIND(meshtastic_ModuleSettings, meshtastic_ModuleSettings, AUTO)
PB_BIND(meshtastic_Channel, meshtastic_Channel, AUTO)
@@ -0,0 +1,198 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.9.1 */
#ifndef PB_MESHTASTIC_MESHTASTIC_CHANNEL_PB_H_INCLUDED
#define PB_MESHTASTIC_MESHTASTIC_CHANNEL_PB_H_INCLUDED
#include <pb.h>
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Enum definitions */
/* How this channel is being used (or not).
Note: this field is an enum to give us options for the future.
In particular, someday we might make a 'SCANNING' option.
SCANNING channels could have different frequencies and the radio would
occasionally check that freq to see if anything is being transmitted.
For devices that have multiple physical radios attached, we could keep multiple PRIMARY/SCANNING channels active at once to allow
cross band routing as needed.
If a device has only a single radio (the common case) only one channel can be PRIMARY at a time
(but any number of SECONDARY channels can't be sent received on that common frequency) */
typedef enum _meshtastic_Channel_Role {
/* This channel is not in use right now */
meshtastic_Channel_Role_DISABLED = 0,
/* This channel is used to set the frequency for the radio - all other enabled channels must be SECONDARY */
meshtastic_Channel_Role_PRIMARY = 1,
/* Secondary channels are only used for encryption/decryption/authentication purposes.
Their radio settings (freq etc) are ignored, only psk is used. */
meshtastic_Channel_Role_SECONDARY = 2
} meshtastic_Channel_Role;
/* Struct definitions */
/* This message is specifically for modules to store per-channel configuration data. */
typedef struct _meshtastic_ModuleSettings {
/* Bits of precision for the location sent in position packets. */
uint32_t position_precision;
/* Controls whether or not the client / device should mute the current channel
Useful for noisy public channels you don't necessarily want to disable */
bool is_muted;
} meshtastic_ModuleSettings;
typedef PB_BYTES_ARRAY_T(32) meshtastic_ChannelSettings_psk_t;
/* This information can be encoded as a QRcode/url so that other users can configure
their radio to join the same channel.
A note about how channel names are shown to users: channelname-X
poundsymbol is a prefix used to indicate this is a channel name (idea from @professr).
Where X is a letter from A-Z (base 26) representing a hash of the PSK for this
channel - so that if the user changes anything about the channel (which does
force a new PSK) this letter will also change. Thus preventing user confusion if
two friends try to type in a channel name of "BobsChan" and then can't talk
because their PSKs will be different.
The PSK is hashed into this letter by "0x41 + [xor all bytes of the psk ] modulo 26"
This also allows the option of someday if people have the PSK off (zero), the
users COULD type in a channel name and be able to talk.
FIXME: Add description of multi-channel support and how primary vs secondary channels are used.
FIXME: explain how apps use channels for security.
explain how remote settings and remote gpio are managed as an example */
typedef struct _meshtastic_ChannelSettings {
/* Deprecated in favor of LoraConfig.channel_num */
uint32_t channel_num;
/* A simple pre-shared key for now for crypto.
Must be either 0 bytes (no crypto), 16 bytes (AES128), or 32 bytes (AES256).
A special shorthand is used for 1 byte long psks.
These psks should be treated as only minimally secure,
because they are listed in this source code.
Those bytes are mapped using the following scheme:
`0` = No crypto
`1` = The special "default" channel key: {0xd4, 0xf1, 0xbb, 0x3a, 0x20, 0x29, 0x07, 0x59, 0xf0, 0xbc, 0xff, 0xab, 0xcf, 0x4e, 0x69, 0x01}
`2` through 10 = The default channel key, except with 1 through 9 added to the last byte.
Shown to user as simple1 through 10 */
meshtastic_ChannelSettings_psk_t psk;
/* A SHORT name that will be packed into the URL.
Less than 12 bytes.
Something for end users to call the channel
If this is the empty string it is assumed that this channel
is the special (minimally secure) "Default"channel.
In user interfaces it should be rendered as a local language translation of "X".
For channel_num hashing empty string will be treated as "X".
Where "X" is selected based on the English words listed above for ModemPreset */
char name[12];
/* Used to construct a globally unique channel ID.
The full globally unique ID will be: "name.id" where ID is shown as base36.
Assuming that the number of meshtastic users is below 20K (true for a long time)
the chance of this 64 bit random number colliding with anyone else is super low.
And the penalty for collision is low as well, it just means that anyone trying to decrypt channel messages might need to
try multiple candidate channels.
Any time a non wire compatible change is made to a channel, this field should be regenerated.
There are a small number of 'special' globally known (and fairly) insecure standard channels.
Those channels do not have a numeric id included in the settings, but instead it is pulled from
a table of well known IDs.
(see Well Known Channels FIXME) */
uint32_t id;
/* If true, messages on the mesh will be sent to the *public* internet by any gateway ndoe */
bool uplink_enabled;
/* If true, messages seen on the internet will be forwarded to the local mesh. */
bool downlink_enabled;
/* Per-channel module settings. */
bool has_module_settings;
meshtastic_ModuleSettings module_settings;
} meshtastic_ChannelSettings;
/* A pair of a channel number, mode and the (sharable) settings for that channel */
typedef struct _meshtastic_Channel {
/* The index of this channel in the channel table (from 0 to MAX_NUM_CHANNELS-1)
(Someday - not currently implemented) An index of -1 could be used to mean "set by name",
in which case the target node will find and set the channel by settings.name. */
int8_t index;
/* The new settings, or NULL to disable that channel */
bool has_settings;
meshtastic_ChannelSettings settings;
/* TODO: REPLACE */
meshtastic_Channel_Role role;
} meshtastic_Channel;
#ifdef __cplusplus
extern "C" {
#endif
/* Helper constants for enums */
#define _meshtastic_Channel_Role_MIN meshtastic_Channel_Role_DISABLED
#define _meshtastic_Channel_Role_MAX meshtastic_Channel_Role_SECONDARY
#define _meshtastic_Channel_Role_ARRAYSIZE ((meshtastic_Channel_Role)(meshtastic_Channel_Role_SECONDARY+1))
#define meshtastic_Channel_role_ENUMTYPE meshtastic_Channel_Role
/* Initializer values for message structs */
#define meshtastic_ChannelSettings_init_default {0, {0, {0}}, "", 0, 0, 0, false, meshtastic_ModuleSettings_init_default}
#define meshtastic_ModuleSettings_init_default {0, 0}
#define meshtastic_Channel_init_default {0, false, meshtastic_ChannelSettings_init_default, _meshtastic_Channel_Role_MIN}
#define meshtastic_ChannelSettings_init_zero {0, {0, {0}}, "", 0, 0, 0, false, meshtastic_ModuleSettings_init_zero}
#define meshtastic_ModuleSettings_init_zero {0, 0}
#define meshtastic_Channel_init_zero {0, false, meshtastic_ChannelSettings_init_zero, _meshtastic_Channel_Role_MIN}
/* Field tags (for use in manual encoding/decoding) */
#define meshtastic_ModuleSettings_position_precision_tag 1
#define meshtastic_ModuleSettings_is_muted_tag 2
#define meshtastic_ChannelSettings_channel_num_tag 1
#define meshtastic_ChannelSettings_psk_tag 2
#define meshtastic_ChannelSettings_name_tag 3
#define meshtastic_ChannelSettings_id_tag 4
#define meshtastic_ChannelSettings_uplink_enabled_tag 5
#define meshtastic_ChannelSettings_downlink_enabled_tag 6
#define meshtastic_ChannelSettings_module_settings_tag 7
#define meshtastic_Channel_index_tag 1
#define meshtastic_Channel_settings_tag 2
#define meshtastic_Channel_role_tag 3
/* Struct field encoding specification for nanopb */
#define meshtastic_ChannelSettings_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, channel_num, 1) \
X(a, STATIC, SINGULAR, BYTES, psk, 2) \
X(a, STATIC, SINGULAR, STRING, name, 3) \
X(a, STATIC, SINGULAR, FIXED32, id, 4) \
X(a, STATIC, SINGULAR, BOOL, uplink_enabled, 5) \
X(a, STATIC, SINGULAR, BOOL, downlink_enabled, 6) \
X(a, STATIC, OPTIONAL, MESSAGE, module_settings, 7)
#define meshtastic_ChannelSettings_CALLBACK NULL
#define meshtastic_ChannelSettings_DEFAULT NULL
#define meshtastic_ChannelSettings_module_settings_MSGTYPE meshtastic_ModuleSettings
#define meshtastic_ModuleSettings_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, UINT32, position_precision, 1) \
X(a, STATIC, SINGULAR, BOOL, is_muted, 2)
#define meshtastic_ModuleSettings_CALLBACK NULL
#define meshtastic_ModuleSettings_DEFAULT NULL
#define meshtastic_Channel_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, index, 1) \
X(a, STATIC, OPTIONAL, MESSAGE, settings, 2) \
X(a, STATIC, SINGULAR, UENUM, role, 3)
#define meshtastic_Channel_CALLBACK NULL
#define meshtastic_Channel_DEFAULT NULL
#define meshtastic_Channel_settings_MSGTYPE meshtastic_ChannelSettings
extern const pb_msgdesc_t meshtastic_ChannelSettings_msg;
extern const pb_msgdesc_t meshtastic_ModuleSettings_msg;
extern const pb_msgdesc_t meshtastic_Channel_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define meshtastic_ChannelSettings_fields &meshtastic_ChannelSettings_msg
#define meshtastic_ModuleSettings_fields &meshtastic_ModuleSettings_msg
#define meshtastic_Channel_fields &meshtastic_Channel_msg
/* Maximum encoded size of messages (where known) */
#define MESHTASTIC_MESHTASTIC_CHANNEL_PB_H_MAX_SIZE meshtastic_Channel_size
#define meshtastic_ChannelSettings_size 72
#define meshtastic_Channel_size 87
#define meshtastic_ModuleSettings_size 8
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif
@@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.9.1 */
#include "meshtastic/clientonly.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(meshtastic_DeviceProfile, meshtastic_DeviceProfile, 2)

Some files were not shown because too many files have changed in this diff Show More