Merge branch 'master' into raspi-portduino

This commit is contained in:
Thomas Göttgens 2023-09-28 09:29:45 +02:00 committed by GitHub
commit 7f16b6b342
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
137 changed files with 2433 additions and 1590 deletions

22
.github/workflows/trunk-check.yml vendored Normal file
View File

@ -0,0 +1,22 @@
name: Pull Request
on: [pull_request]
concurrency:
group: ${{ github.head_ref || github.run_id }}
cancel-in-progress: true
permissions: read-all
jobs:
trunk_check:
name: Trunk Check Runner
runs-on: ubuntu-latest
permissions:
checks: write # For trunk to post annotations
contents: read # For repo checkout
steps:
- name: Checkout
uses: actions/checkout@v3
- name: Trunk Check
uses: trunk-io/trunk-action@v1

2
.trunk/.gitignore vendored
View File

@ -5,4 +5,4 @@
plugins
user_trunk.yaml
user.yaml
shims
tools

View File

@ -1,37 +1,42 @@
version: 0.1
cli:
version: 1.10.0
version: 1.13.0
plugins:
sources:
- id: trunk
ref: v0.0.17
ref: v1.1.1
uri: https://github.com/trunk-io/plugins
lint:
enabled:
- taplo@0.7.0
- ruff@0.0.265
- bandit@1.7.5
- checkov@2.4.1
- terrascan@1.18.3
- trivy@0.44.1
- trufflehog@3.48.0
- taplo@0.8.1
- ruff@0.0.284
- yamllint@1.32.0
- isort@5.12.0
- markdownlint@0.34.0
- markdownlint@0.35.0
- oxipng@8.0.0
- svgo@3.0.2
- actionlint@1.6.24
- flake8@6.0.0
- actionlint@1.6.25
- flake8@6.1.0
- hadolint@2.12.0
- shfmt@3.5.0
- shfmt@3.6.0
- shellcheck@0.9.0
- black@23.3.0
- black@23.7.0
- git-diff-check
- gitleaks@8.16.3
- clang-format@14.0.0
- prettier@2.8.8
- gitleaks@8.17.0
- clang-format@16.0.3
- prettier@3.0.2
disabled:
- taplo@0.7.0
- taplo@0.8.1
- shellcheck@0.9.0
- shfmt@3.5.0
- shfmt@3.6.0
- oxipng@8.0.0
- actionlint@1.6.22
- markdownlint@0.34.0
- markdownlint@0.35.0
- hadolint@2.12.0
- svgo@3.0.2
runtimes:

View File

@ -1,7 +1,7 @@
; Common settings for ESP targes, mixin with extends = esp32_base
[esp32_base]
extends = arduino_base
platform = platformio/espressif32@^6.3.2
platform = platformio/espressif32@6.3.2 # This is a temporary fix to the S3-based devices bluetooth issues until we can determine what within ESP-IDF changed and can develop a suitable patch.
build_src_filter =
${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/stm32wl> -<platform/rp2040> -<mesh/eth/>
@ -38,7 +38,7 @@ lib_deps =
${networking_base.lib_deps}
${environmental_base.lib_deps}
https://github.com/meshtastic/esp32_https_server.git#23665b3adc080a311dcbb586ed5941b5f94d6ea2
h2zero/NimBLE-Arduino@^1.4.0
h2zero/NimBLE-Arduino@^1.4.1
jgromes/RadioLib@^6.1.0
https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6
https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f
@ -57,4 +57,4 @@ lib_ignore =
; customize the partition table
; http://docs.platformio.org/en/latest/platforms/espressif32.html#partition-tables
board_build.partitions = partition-table.csv
board_build.partitions = partition-table.csv

View File

@ -1,7 +1,8 @@
{
"build": {
"arduino": {
"ldscript": "esp32s3_out.ld"
"ldscript": "esp32s3_out.ld",
"memory_type": "qio_opi"
},
"core": "esp32",
"extra_flags": [
@ -13,7 +14,7 @@
],
"f_cpu": "240000000L",
"f_flash": "80000000L",
"flash_mode": "dio",
"flash_mode": "qio",
"hwids": [["0x303A", "0x1001"]],
"mcu": "esp32s3",
"variant": "t-deck"

View File

@ -1,7 +1,8 @@
{
"build": {
"arduino": {
"ldscript": "esp32s3_out.ld"
"ldscript": "esp32s3_out.ld",
"memory_type": "qio_opi"
},
"core": "esp32",
"extra_flags": [
@ -14,7 +15,7 @@
],
"f_cpu": "240000000L",
"f_flash": "80000000L",
"flash_mode": "dio",
"flash_mode": "qio",
"hwids": [["0x303A", "0x1001"]],
"mcu": "esp32s3",
"variant": "t-watch-s3"
@ -31,8 +32,9 @@
"maximum_size": 8388608,
"require_upload_port": true,
"use_1200bps_touch": true,
"wait_for_upload_port": true
"wait_for_upload_port": true,
"speed": 921600
},
"url": "http://www.lilygo.cn/",
"url": "https://www.lilygo.cc/en-pl/products/t-watch-s3",
"vendor": "LilyGo"
}

@ -1 +1 @@
Subproject commit dc28ae3d128b76707c0b87b6f3b2514c7f8514bd
Subproject commit fb28d593526467977cf353959a66e11373928282

View File

@ -0,0 +1,75 @@
#include "configuration.h"
#ifdef HAS_NCP5623
#include <graphics/RAKled.h>
NCP5623 rgb;
#endif
namespace concurrency
{
class AmbientLightingThread : public concurrency::OSThread
{
public:
AmbientLightingThread(ScanI2C::DeviceType type) : OSThread("AmbientLightingThread")
{
// Uncomment to test module
// moduleConfig.ambient_lighting.led_state = true;
// moduleConfig.ambient_lighting.current = 10;
// // Default to a color based on our node number
// moduleConfig.ambient_lighting.red = (myNodeInfo.my_node_num & 0xFF0000) >> 16;
// moduleConfig.ambient_lighting.green = (myNodeInfo.my_node_num & 0x00FF00) >> 8;
// moduleConfig.ambient_lighting.blue = myNodeInfo.my_node_num & 0x0000FF;
#ifdef HAS_NCP5623
_type = type;
if (_type == ScanI2C::DeviceType::NONE) {
LOG_DEBUG("AmbientLightingThread disabling due to no RGB leds found on I2C bus\n");
disable();
return;
}
if (!moduleConfig.ambient_lighting.led_state) {
LOG_DEBUG("AmbientLightingThread disabling due to moduleConfig.ambient_lighting.led_state OFF\n");
disable();
return;
}
LOG_DEBUG("AmbientLightingThread initializing\n");
if (_type == ScanI2C::NCP5623) {
rgb.begin();
setLighting();
}
#endif
}
protected:
int32_t runOnce() override
{
#ifdef HAS_NCP5623
if (_type == ScanI2C::NCP5623 && moduleConfig.ambient_lighting.led_state) {
setLighting();
return 30000; // 30 seconds to reset from any animations that may have been running from Ext. Notification
} else {
return disable();
}
#else
return disable();
#endif
}
private:
ScanI2C::DeviceType _type = ScanI2C::DeviceType::NONE;
void setLighting()
{
#ifdef HAS_NCP5623
rgb.setCurrent(moduleConfig.ambient_lighting.current);
rgb.setRed(moduleConfig.ambient_lighting.red);
rgb.setGreen(moduleConfig.ambient_lighting.green);
rgb.setBlue(moduleConfig.ambient_lighting.blue);
LOG_DEBUG("Initializing Ambient lighting w/ current=%d, red=%d, green=%d, blue=%d\n",
moduleConfig.ambient_lighting.current, moduleConfig.ambient_lighting.red, moduleConfig.ambient_lighting.green,
moduleConfig.ambient_lighting.blue);
#endif
}
};
} // namespace concurrency

View File

@ -164,15 +164,17 @@ class ButtonThread : public concurrency::OSThread
static void userButtonMultiPressed()
{
#if defined(GPS_POWER_TOGGLE)
if (config.position.gps_enabled) {
LOG_DEBUG("Flag set to false for gps power\n");
} else {
LOG_DEBUG("Flag set to true to restore power\n");
if (!config.device.disable_triple_click && (gps != nullptr)) {
config.position.gps_enabled = !(config.position.gps_enabled);
if (config.position.gps_enabled) {
LOG_DEBUG("Flag set to true to restore power\n");
gps->enable();
} else {
LOG_DEBUG("Flag set to false for gps power\n");
gps->disable();
}
}
config.position.gps_enabled = !(config.position.gps_enabled);
doGPSpowersave(config.position.gps_enabled);
#endif
}
static void userButtonPressedLongStart()

View File

@ -16,8 +16,8 @@
#include "buzz/buzz.h"
#include "configuration.h"
#include "main.h"
#include "meshUtils.h"
#include "sleep.h"
#include "utils.h"
#ifdef DEBUG_HEAP_MQTT
#include "mqtt/MQTT.h"
@ -221,10 +221,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
/**
* return true if there is a battery installed in this unit
*/
virtual bool isBatteryConnect() override
{
return getBatteryPercent() != -1;
}
virtual bool isBatteryConnect() override { return getBatteryPercent() != -1; }
/// If we see a battery voltage higher than physics allows - assume charger is pumping
/// in power
@ -245,10 +242,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
/// Assume charging if we have a battery and external power is connected.
/// we can't be smart enough to say 'full'?
virtual bool isCharging() override
{
return isBatteryConnect() && isVbusIn();
}
virtual bool isCharging() override { return isBatteryConnect() && isVbusIn(); }
private:
/// If we see a battery voltage higher than physics allows - assume charger is pumping

View File

@ -8,7 +8,6 @@
* actions to be taken upon entering or exiting each state.
*/
#include "PowerFSM.h"
#include "GPS.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "configuration.h"
@ -137,9 +136,6 @@ static void lsIdle()
static void lsExit()
{
LOG_INFO("Exit state: LS\n");
// setGPSPower(true); // restore GPS power
if (gps)
gps->forceWake(true);
}
static void nbEnter()
@ -158,6 +154,9 @@ static void darkEnter()
{
setBluetoothEnable(true);
screen->setOn(false);
#ifdef KB_POWERON
digitalWrite(KB_POWERON, LOW);
#endif
}
static void serialEnter()
@ -185,6 +184,9 @@ static void powerEnter()
} else {
screen->setOn(true);
setBluetoothEnable(true);
#ifdef KB_POWERON
digitalWrite(KB_POWERON, HIGH);
#endif
// within enter() the function getState() returns the state we came from
if (strcmp(powerFSM.getState()->name, "BOOT") != 0 && strcmp(powerFSM.getState()->name, "POWER") != 0 &&
strcmp(powerFSM.getState()->name, "DARK") != 0) {
@ -215,6 +217,9 @@ static void onEnter()
LOG_DEBUG("Enter state: ON\n");
screen->setOn(true);
setBluetoothEnable(true);
#ifdef KB_POWERON
digitalWrite(KB_POWERON, HIGH);
#endif
}
static void onIdle()
@ -365,10 +370,6 @@ void PowerFSM_setup()
getConfiguredOrDefaultMs(config.power.wait_bluetooth_secs, default_wait_bluetooth_secs),
NULL, "Bluetooth timeout");
}
if (config.power.sds_secs != UINT32_MAX)
powerFSM.add_timed_transition(lowPowerState, &stateSDS, getConfiguredOrDefaultMs(config.power.sds_secs), NULL,
"mesh timeout");
#endif
powerFSM.run_machine(); // run one iteration of the state machine, so we run our on enter tasks for the initial DARK state

View File

@ -18,6 +18,12 @@ NoopPrint noopPrint;
#if HAS_WIFI || HAS_ETHERNET
extern Syslog syslog;
#endif
void RedirectablePrint::rpInit()
{
#ifdef HAS_FREE_RTOS
inDebugPrint = xSemaphoreCreateMutexStatic(&this->_MutexStorageSpace);
#endif
}
void RedirectablePrint::setDestination(Print *_dest)
{
@ -66,9 +72,12 @@ size_t RedirectablePrint::log(const char *logLevel, const char *format, ...)
return 0;
}
size_t r = 0;
#ifdef HAS_FREE_RTOS
if (inDebugPrint != nullptr && xSemaphoreTake(inDebugPrint, portMAX_DELAY) == pdTRUE) {
#else
if (!inDebugPrint) {
inDebugPrint = true;
#endif
va_list arg;
va_start(arg, format);
@ -141,7 +150,11 @@ size_t RedirectablePrint::log(const char *logLevel, const char *format, ...)
va_end(arg);
isContinuationMessage = !hasNewline;
#ifdef HAS_FREE_RTOS
xSemaphoreGive(inDebugPrint);
#else
inDebugPrint = false;
#endif
}
return r;

View File

@ -1,5 +1,6 @@
#pragma once
#include "../freertosinc.h"
#include <Print.h>
#include <stdarg.h>
#include <string>
@ -16,14 +17,19 @@ class RedirectablePrint : public Print
/// Used to allow multiple logDebug messages to appear on a single log line
bool isContinuationMessage = false;
#ifdef HAS_FREE_RTOS
SemaphoreHandle_t inDebugPrint = nullptr;
StaticSemaphore_t _MutexStorageSpace;
#else
volatile bool inDebugPrint = false;
#endif
public:
explicit RedirectablePrint(Print *_dest) : dest(_dest) {}
/**
* Set a new destination
*/
void rpInit();
void setDestination(Print *dest);
virtual size_t write(uint8_t c);
@ -54,4 +60,4 @@ class NoopPrint : public Print
/**
* A printer that doesn't go anywhere
*/
extern NoopPrint noopPrint;
extern NoopPrint noopPrint;

View File

@ -12,6 +12,7 @@ SerialConsole *console;
void consoleInit()
{
new SerialConsole(); // Must be dynamically allocated because we are now inheriting from thread
DEBUG_PORT.rpInit(); // Simply sets up semaphore
}
void consolePrintf(const char *format, ...)

View File

@ -53,7 +53,7 @@ class OSThread : public Thread
static void setup();
int32_t disable();
virtual int32_t disable();
/**
* Wait a specified number msecs starting from the current time (rather than the last time we were run)
@ -87,4 +87,4 @@ extern bool hasBeenSetup;
void assertIsSetup();
} // namespace concurrency
} // namespace concurrency

View File

@ -101,6 +101,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// I2C Keyboards (M5Stack, RAK14004, T-Deck)
#define CARDKB_ADDR 0x5F
#define TDECK_KB_ADDR 0x55
#define BBQ10_KB_ADDR 0x1F
// -----------------------------------------------------------------------------
// SENSOR
@ -144,7 +145,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define GPS_BAUDRATE 9600
#ifndef GPS_THREAD_INTERVAL
#define GPS_THREAD_INTERVAL 100
#define GPS_THREAD_INTERVAL 200
#endif
// convert 24-bit color to 16-bit (56K)

View File

@ -30,8 +30,8 @@ ScanI2C::FoundDevice ScanI2C::firstRTC() const
ScanI2C::FoundDevice ScanI2C::firstKeyboard() const
{
ScanI2C::DeviceType types[] = {CARDKB, TDECKKB, RAK14004};
return firstOfOrNONE(3, types);
ScanI2C::DeviceType types[] = {CARDKB, TDECKKB, BBQ10KB, RAK14004};
return firstOfOrNONE(4, types);
}
ScanI2C::FoundDevice ScanI2C::firstAccelerometer() const

View File

@ -17,6 +17,7 @@ class ScanI2C
RTC_PCF8563,
CARDKB,
TDECKKB,
BBQ10KB,
RAK14004,
PMU_AXP192_AXP2101,
BME_680,

View File

@ -213,6 +213,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port)
break;
SCAN_SIMPLE_CASE(TDECK_KB_ADDR, TDECKKB, "T-Deck keyboard found\n");
SCAN_SIMPLE_CASE(BBQ10_KB_ADDR, BBQ10KB, "BB Q10 keyboard found\n");
SCAN_SIMPLE_CASE(ST7567_ADDRESS, SCREEN_ST7567, "st7567 display found\n");
#ifdef HAS_NCP5623
SCAN_SIMPLE_CASE(NCP5623_ADDR, NCP5623, "NCP5623 RGB LED found\n");

File diff suppressed because it is too large Load Diff

View File

@ -2,7 +2,16 @@
#include "GPSStatus.h"
#include "Observer.h"
#include "TinyGPS++.h"
#include "concurrency/OSThread.h"
#include "input/RotaryEncoderInterruptImpl1.h"
#include "input/UpDownInterruptImpl1.h"
#include "modules/PositionModule.h"
// Allow defining the polarity of the ENABLE output. default is active high
#ifndef GPS_EN_ACTIVE
#define GPS_EN_ACTIVE 1
#endif
struct uBloxGnssModelInfo {
char swVersion[30];
@ -18,6 +27,13 @@ typedef enum {
GNSS_MODEL_UNKNOWN,
} GnssModel_t;
typedef enum {
GNSS_RESPONSE_NONE,
GNSS_RESPONSE_NAK,
GNSS_RESPONSE_FRAME_ERRORS,
GNSS_RESPONSE_OK,
} GPS_RESPONSE;
// Generate a string representation of DOP
const char *getDOPString(uint32_t dop);
@ -28,8 +44,29 @@ const char *getDOPString(uint32_t dop);
*/
class GPS : private concurrency::OSThread
{
TinyGPSPlus reader;
uint8_t fixQual = 0; // fix quality from GPGGA
uint32_t lastChecksumFailCount = 0;
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
// (20210908) TinyGps++ can only read the GPGSA "FIX TYPE" field
// via optional feature "custom fields", currently disabled (bug #525)
TinyGPSCustom gsafixtype; // custom extract fix type from GPGSA
TinyGPSCustom gsapdop; // custom extract PDOP from GPGSA
uint8_t fixType = 0; // fix type from GPGSA
#endif
private:
uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0, lastWhileActiveMsec = 0;
uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0;
const int serialSpeeds[6] = {9600, 4800, 38400, 57600, 115200, 9600};
uint32_t rx_gpio = 0;
uint32_t tx_gpio = 0;
uint32_t en_gpio = 0;
int32_t averageLockTime = 0;
uint32_t GPSCycles = 0;
int speedSelect = 0;
int probeTries = 2;
/**
* hasValidLocation - indicates that the position variables contain a complete
@ -39,15 +76,17 @@ class GPS : private concurrency::OSThread
bool isAwake = false; // true if we want a location right now
bool wakeAllowed = true; // false if gps must be forced to sleep regardless of what time it is
bool isInPowersave = false;
bool shouldPublish = false; // If we've changed GPS state, this will force a publish the next loop()
bool hasGPS = false; // Do we have a GPS we are talking to
bool GPSInitFinished = false; // Init thread finished?
bool GPSInitStarted = false; // Init thread finished?
uint8_t numSatellites = 0;
CallbackObserver<GPS, void *> notifySleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareSleep);
CallbackObserver<GPS, void *> notifyDeepSleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareDeepSleep);
CallbackObserver<GPS, void *> notifyGPSSleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareDeepSleep);
@ -55,6 +94,24 @@ class GPS : private concurrency::OSThread
/** If !NULL we will use this serial port to construct our GPS */
static HardwareSerial *_serial_gps;
static const uint8_t _message_PMREQ[];
static const uint8_t _message_CFG_RXM_PSM[];
static const uint8_t _message_CFG_RXM_ECO[];
static const uint8_t _message_CFG_PM2[];
static const uint8_t _message_GNSS_7[];
static const uint8_t _message_GNSS[];
static const uint8_t _message_JAM[];
static const uint8_t _message_NAVX5[];
static const uint8_t _message_1HZ[];
static const uint8_t _message_GGL[];
static const uint8_t _message_GSA[];
static const uint8_t _message_GSV[];
static const uint8_t _message_VTG[];
static const uint8_t _message_RMC[];
static const uint8_t _message_GGA[];
static const uint8_t _message_PMS[];
static const uint8_t _message_SAVE[];
meshtastic_Position p = meshtastic_Position_init_default;
GPS() : concurrency::OSThread("GPS") {}
@ -69,6 +126,14 @@ class GPS : private concurrency::OSThread
*/
virtual bool setup();
// re-enable the thread
void enable();
// Disable the thread
int32_t disable() override;
void setGPSPower(bool on, bool standbyOnly);
/// Returns true if we have acquired GPS lock.
virtual bool hasLock();
@ -80,71 +145,18 @@ class GPS : private concurrency::OSThread
bool isPowerSaving() const { return !config.position.gps_enabled; }
/**
* Restart our lock attempt - try to get and broadcast a GPS reading ASAP
* called after the CPU wakes from light-sleep state
*
* Or set to false, to disallow any sort of waking
* */
void forceWake(bool on);
// Some GPS modules (ublock) require factory reset
virtual bool factoryReset() { return true; }
// Empty the input buffer as quickly as possible
void clearBuffer();
protected:
/// Do gps chipset specific init, return true for success
virtual bool setupGPS();
// Create a ublox packet for editing in memory
uint8_t makeUBXPacket(uint8_t class_id, uint8_t msg_id, uint8_t payload_size, const uint8_t *msg);
/// If possible force the GPS into sleep/low power mode
virtual void sleep();
// scratch space for creating ublox packets
uint8_t UBXscratch[250] = {0};
/// wake the GPS into normal operation mode
virtual void wake();
/** Subclasses should look for serial rx characters here and feed it to their GPS parser
*
* Return true if we received a valid message from the GPS
*/
virtual bool whileIdle() = 0;
/** Idle processing while GPS is looking for lock, called once per secondish */
virtual void whileActive() {}
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a time
*/
virtual bool lookForTime() = 0;
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a new location
*/
virtual bool lookForLocation() = 0;
/// Record that we have a GPS
void setConnected();
void setNumSatellites(uint8_t n);
private:
/// Prepare the GPS for the cpu entering deep or light sleep, expect to be gone for at least 100s of msecs
/// always returns 0 to indicate okay to sleep
int prepareSleep(void *unused);
/// Prepare the GPS for the cpu entering deep sleep, expect to be gone for at least 100s of msecs
/// always returns 0 to indicate okay to sleep
int prepareDeepSleep(void *unused);
// Calculate checksum
void UBXChecksum(byte *message, size_t length);
int getACK(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t requestedID, uint32_t waitMillis);
GPS_RESPONSE getACK(uint8_t c, uint8_t i, uint32_t waitMillis);
GPS_RESPONSE getACK(const char *message, uint32_t waitMillis);
/**
* Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode
@ -152,6 +164,59 @@ class GPS : private concurrency::OSThread
* calls sleep/wake
*/
void setAwake(bool on);
virtual bool factoryReset();
// Creates an instance of the GPS class.
// Returns the new instance or null if the GPS is not present.
static GPS *createGps();
protected:
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a time
*/
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a new location
*/
/// Record that we have a GPS
void setConnected();
/** Subclasses should look for serial rx characters here and feed it to their GPS parser
*
* Return true if we received a valid message from the GPS
*/
virtual bool whileIdle();
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a time
*/
virtual bool lookForTime();
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a new location
*/
virtual bool lookForLocation();
private:
/// Prepare the GPS for the cpu entering deep sleep, expect to be gone for at least 100s of msecs
/// always returns 0 to indicate okay to sleep
int prepareDeepSleep(void *unused);
// Calculate checksum
void UBXChecksum(uint8_t *message, size_t length);
/** Get how long we should stay looking for each aquisition
*/
@ -161,8 +226,6 @@ class GPS : private concurrency::OSThread
*/
uint32_t getSleepTime() const;
bool getACK(uint8_t c, uint8_t i);
/**
* Tell users we have new GPS readings
*/
@ -172,9 +235,7 @@ class GPS : private concurrency::OSThread
// Get GNSS model
String getNMEA();
GnssModel_t probe();
int getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t requestedID);
GnssModel_t probe(int serialSpeed);
// delay counter to allow more sats before fixed position stops GPS thread
uint8_t fixeddelayCtr = 0;
@ -183,8 +244,4 @@ class GPS : private concurrency::OSThread
GnssModel_t gnssModel = GNSS_MODEL_UNKNOWN;
};
// Creates an instance of the GPS class.
// Returns the new instance or null if the GPS is not present.
GPS *createGps();
extern GPS *gps;

View File

@ -1,272 +0,0 @@
#include "NMEAGPS.h"
#include "RTC.h"
#include "configuration.h"
#include <TinyGPS++.h>
// GPS solutions older than this will be rejected - see TinyGPSDatum::age()
#define GPS_SOL_EXPIRY_MS 5000 // in millis. give 1 second time to combine different sentences. NMEA Frequency isn't higher anyway
#define NMEA_MSG_GXGSA "GNGSA" // GSA message (GPGSA, GNGSA etc)
static int32_t toDegInt(RawDegrees d)
{
int32_t degMult = 10000000; // 1e7
int32_t r = d.deg * degMult + d.billionths / 100;
if (d.negative)
r *= -1;
return r;
}
bool NMEAGPS::factoryReset()
{
#ifdef PIN_GPS_REINIT
// The L76K GNSS on the T-Echo requires the RESET pin to be pulled LOW
digitalWrite(PIN_GPS_REINIT, 0);
pinMode(PIN_GPS_REINIT, OUTPUT);
delay(150); // The L76K datasheet calls for at least 100MS delay
digitalWrite(PIN_GPS_REINIT, 1);
#endif
// send the UBLOX Factory Reset Command regardless of detect state, something is very wrong, just assume it's UBLOX.
// Factory Reset
byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFB, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x17, 0x2B, 0x7E};
_serial_gps->write(_message_reset, sizeof(_message_reset));
delay(1000);
return true;
}
bool NMEAGPS::setupGPS()
{
GPS::setupGPS();
#ifdef PIN_GPS_PPS
// pulse per second
// FIXME - move into shared GPS code
pinMode(PIN_GPS_PPS, INPUT);
#endif
// Currently disabled per issue #525 (TinyGPS++ crash bug)
// when fixed upstream, can be un-disabled to enable 3D FixType and PDOP
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
// see NMEAGPS.h
gsafixtype.begin(reader, NMEA_MSG_GXGSA, 2);
gsapdop.begin(reader, NMEA_MSG_GXGSA, 15);
LOG_DEBUG("Using " NMEA_MSG_GXGSA " for 3DFIX and PDOP\n");
#else
LOG_DEBUG("GxGSA NOT available\n");
#endif
return true;
}
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a new location
*/
bool NMEAGPS::lookForTime()
{
auto ti = reader.time;
auto d = reader.date;
if (ti.isValid() && d.isValid()) { // Note: we don't check for updated, because we'll only be called if needed
/* Convert to unix time
The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of seconds that have elapsed since January 1, 1970
(midnight UTC/GMT), not counting leap seconds (in ISO 8601: 1970-01-01T00:00:00Z).
*/
struct tm t;
t.tm_sec = ti.second();
t.tm_min = ti.minute();
t.tm_hour = ti.hour();
t.tm_mday = d.day();
t.tm_mon = d.month() - 1;
t.tm_year = d.year() - 1900;
t.tm_isdst = false;
if (t.tm_mon > -1) {
LOG_DEBUG("NMEA GPS time %02d-%02d-%02d %02d:%02d:%02d\n", d.year(), d.month(), t.tm_mday, t.tm_hour, t.tm_min,
t.tm_sec);
perhapsSetRTC(RTCQualityGPS, t);
return true;
} else
return false;
} else
return false;
}
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a new location
*/
bool NMEAGPS::lookForLocation()
{
// By default, TinyGPS++ does not parse GPGSA lines, which give us
// the 2D/3D fixType (see NMEAGPS.h)
// At a minimum, use the fixQuality indicator in GPGGA (FIXME?)
fixQual = reader.fixQuality();
#ifndef TINYGPS_OPTION_NO_STATISTICS
if (reader.failedChecksum() > lastChecksumFailCount) {
LOG_WARN("Warning, %u new GPS checksum failures, for a total of %u.\n", reader.failedChecksum() - lastChecksumFailCount,
reader.failedChecksum());
lastChecksumFailCount = reader.failedChecksum();
}
#endif
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
fixType = atoi(gsafixtype.value()); // will set to zero if no data
// LOG_DEBUG("FIX QUAL=%d, TYPE=%d\n", fixQual, fixType);
#endif
// check if GPS has an acceptable lock
if (!hasLock())
return false;
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("AGE: LOC=%d FIX=%d DATE=%d TIME=%d\n", reader.location.age(),
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
gsafixtype.age(),
#else
0,
#endif
reader.date.age(), reader.time.age());
#endif // GPS_EXTRAVERBOSE
// check if a complete GPS solution set is available for reading
// tinyGPSDatum::age() also includes isValid() test
// FIXME
if (!((reader.location.age() < GPS_SOL_EXPIRY_MS) &&
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
(gsafixtype.age() < GPS_SOL_EXPIRY_MS) &&
#endif
(reader.time.age() < GPS_SOL_EXPIRY_MS) && (reader.date.age() < GPS_SOL_EXPIRY_MS))) {
LOG_WARN("SOME data is TOO OLD: LOC %u, TIME %u, DATE %u\n", reader.location.age(), reader.time.age(), reader.date.age());
return false;
}
// Is this a new point or are we re-reading the previous one?
if (!reader.location.isUpdated())
return false;
// We know the solution is fresh and valid, so just read the data
auto loc = reader.location.value();
// Bail out EARLY to avoid overwriting previous good data (like #857)
if (toDegInt(loc.lat) > 900000000) {
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LAT %i\n", toDegInt(loc.lat));
#endif
return false;
}
if (toDegInt(loc.lng) > 1800000000) {
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("Bail out EARLY on LNG %i\n", toDegInt(loc.lng));
#endif
return false;
}
p.location_source = meshtastic_Position_LocSource_LOC_INTERNAL;
// Dilution of precision (an accuracy metric) is reported in 10^2 units, so we need to scale down when we use it
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
p.HDOP = reader.hdop.value();
p.PDOP = TinyGPSPlus::parseDecimal(gsapdop.value());
// LOG_DEBUG("PDOP=%d, HDOP=%d\n", p.PDOP, p.HDOP);
#else
// FIXME! naive PDOP emulation (assumes VDOP==HDOP)
// correct formula is PDOP = SQRT(HDOP^2 + VDOP^2)
p.HDOP = reader.hdop.value();
p.PDOP = 1.41 * reader.hdop.value();
#endif
// Discard incomplete or erroneous readings
if (reader.hdop.value() == 0) {
LOG_WARN("BOGUS hdop.value() REJECTED: %d\n", reader.hdop.value());
return false;
}
p.latitude_i = toDegInt(loc.lat);
p.longitude_i = toDegInt(loc.lng);
p.altitude_geoidal_separation = reader.geoidHeight.meters();
p.altitude_hae = reader.altitude.meters() + p.altitude_geoidal_separation;
p.altitude = reader.altitude.meters();
p.fix_quality = fixQual;
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
p.fix_type = fixType;
#endif
// positional timestamp
struct tm t;
t.tm_sec = reader.time.second();
t.tm_min = reader.time.minute();
t.tm_hour = reader.time.hour();
t.tm_mday = reader.date.day();
t.tm_mon = reader.date.month() - 1;
t.tm_year = reader.date.year() - 1900;
t.tm_isdst = false;
p.timestamp = mktime(&t);
// Nice to have, if available
if (reader.satellites.isUpdated()) {
p.sats_in_view = reader.satellites.value();
}
if (reader.course.isUpdated() && reader.course.isValid()) {
if (reader.course.value() < 36000) { // sanity check
p.ground_track =
reader.course.value() * 1e3; // Scale the heading (in degrees * 10^-2) to match the expected degrees * 10^-5
} else {
LOG_WARN("BOGUS course.value() REJECTED: %d\n", reader.course.value());
}
}
if (reader.speed.isUpdated() && reader.speed.isValid()) {
p.ground_speed = reader.speed.kmph();
}
return true;
}
bool NMEAGPS::hasLock()
{
// Using GPGGA fix quality indicator
if (fixQual >= 1 && fixQual <= 5) {
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
// Use GPGSA fix type 2D/3D (better) if available
if (fixType == 3 || fixType == 0) // zero means "no data received"
#endif
return true;
}
return false;
}
bool NMEAGPS::hasFlow()
{
return reader.passedChecksum() > 0;
}
bool NMEAGPS::whileIdle()
{
bool isValid = false;
#ifdef SERIAL_BUFFER_SIZE
if (_serial_gps->available() >= SERIAL_BUFFER_SIZE - 1) {
LOG_WARN("GPS Buffer full with %u bytes waiting. Flushing to avoid corruption.\n", _serial_gps->available());
clearBuffer();
}
#endif
// if (_serial_gps->available() > 0)
// LOG_DEBUG("GPS Bytes Waiting: %u\n", _serial_gps->available());
// First consume any chars that have piled up at the receiver
while (_serial_gps->available() > 0) {
int c = _serial_gps->read();
// LOG_DEBUG("%c", c);
isValid |= reader.encode(c);
}
return isValid;
}

View File

@ -1,57 +0,0 @@
#pragma once
#include "GPS.h"
#include "Observer.h"
#include "TinyGPS++.h"
/**
* A gps class thatreads from a NMEA GPS stream (and FIXME - eventually keeps the gps powered down except when reading)
*
* When new data is available it will notify observers.
*/
class NMEAGPS : public GPS
{
TinyGPSPlus reader;
uint8_t fixQual = 0; // fix quality from GPGGA
uint32_t lastChecksumFailCount = 0;
#ifndef TINYGPS_OPTION_NO_CUSTOM_FIELDS
// (20210908) TinyGps++ can only read the GPGSA "FIX TYPE" field
// via optional feature "custom fields", currently disabled (bug #525)
TinyGPSCustom gsafixtype; // custom extract fix type from GPGSA
TinyGPSCustom gsapdop; // custom extract PDOP from GPGSA
uint8_t fixType = 0; // fix type from GPGSA
#endif
public:
virtual bool setupGPS() override;
virtual bool factoryReset() override;
protected:
/** Subclasses should look for serial rx characters here and feed it to their GPS parser
*
* Return true if we received a valid message from the GPS
*/
virtual bool whileIdle() override;
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a time
*/
virtual bool lookForTime() override;
/**
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
* Override this method to check for new locations
*
* @return true if we've acquired a new location
*/
virtual bool lookForLocation() override;
virtual bool hasLock() override;
virtual bool hasFlow() override;
};

View File

@ -103,9 +103,8 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
bool shouldSet;
if (q > currentQuality) {
currentQuality = q;
shouldSet = true;
LOG_DEBUG("Upgrading time to RTC %ld secs (quality %d)\n", tv->tv_sec, q);
LOG_DEBUG("Upgrading time to quality %d\n", q);
} else if (q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000UL)) {
// Every 12 hrs we will slam in a new GPS time, to correct for local RTC clock drift
shouldSet = true;
@ -114,12 +113,12 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
shouldSet = false;
if (shouldSet) {
currentQuality = q;
lastSetMsec = now;
// This delta value works on all platforms
timeStartMsec = now;
zeroOffsetSecs = tv->tv_sec;
// If this platform has a setable RTC, set it
#ifdef RV3028_RTC
if (rtc_found.address == RV3028_RTC) {
@ -209,4 +208,4 @@ uint32_t getTime()
uint32_t getValidTime(RTCQuality minQuality)
{
return (currentQuality >= minQuality) ? getTime() : 0;
}
}

192
src/gps/ubx.h Normal file
View File

@ -0,0 +1,192 @@
const uint8_t GPS::_message_PMREQ[] PROGMEM = {
0x00, 0x00, // 4 bytes duration of request task
0x00, 0x00, // (milliseconds)
0x02, 0x00, // Task flag bitfield
0x00, 0x00 // byte index 1 = sleep mode
};
const uint8_t GPS::_message_CFG_RXM_PSM[] PROGMEM = {
0x08, // Reserved
0x01 // Power save mode
};
const uint8_t GPS::_message_CFG_RXM_ECO[] PROGMEM = {
0x08, // Reserved
0x04 // eco mode
};
const uint8_t GPS::_message_CFG_PM2[] PROGMEM = {
0x01, 0x06, 0x00, 0x00, // version, Reserved
0x0e, 0x81, 0x42, 0x01, // flags
0xE8, 0x03, 0x00, 0x00, // update period 1000 ms
0x10, 0x27, 0x00, 0x00, // search period 10s
0x00, 0x00, 0x00, 0x00, // Grod offset 0
0x01, 0x00, // onTime 1 second
0x00, 0x00, // min search time 0
0x2C, 0x01, // reserved
0x00, 0x00, 0x4F, 0xC1, // reserved
0x03, 0x00, 0x87, 0x02, // reserved
0x00, 0x00, 0xFF, 0x00, // reserved
0x01, 0x00, 0xD6, 0x4D // reserved
};
const uint8_t GPS::_message_GNSS_7[] = {
0x00, // msgVer (0 for this version)
0x00, // numTrkChHw (max number of hardware channels, read only, so it's always 0)
0xff, // numTrkChUse (max number of channels to use, 0xff = max available)
0x02, // numConfigBlocks (number of GNSS systems), most modules support maximum 3 GNSS systems
// GNSS config format: gnssId, resTrkCh, maxTrkCh, reserved1, flags
0x00, 0x08, 0x10, 0x00, 0x01, 0x00, 0x00, 0x01, // GPS
0x01, 0x01, 0x03, 0x00, 0x01, 0x00, 0x00, 0x01 // SBAS
};
// It's not critical if the module doesn't acknowledge this configuration.
// The module should operate adequately with its factory or previously saved settings.
// It appears that there is a firmware bug in some GPS modules: When an attempt is made
// to overwrite a saved state with identical values, no ACK/NAK is received, contrary to
// what is specified in the Ublox documentation.
// There is also a possibility that the module may be GPS-only.
const uint8_t GPS::_message_GNSS[] = {
0x00, // msgVer (0 for this version)
0x00, // numTrkChHw (max number of hardware channels, read only, so it's always 0)
0xff, // numTrkChUse (max number of channels to use, 0xff = max available)
0x03, // numConfigBlocks (number of GNSS systems), most modules support maximum 3 GNSS systems
// GNSS config format: gnssId, resTrkCh, maxTrkCh, reserved1, flags
0x00, 0x08, 0x10, 0x00, 0x01, 0x00, 0x01, 0x01, // GPS
0x01, 0x01, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01, // SBAS
0x06, 0x08, 0x0e, 0x00, 0x01, 0x00, 0x01, 0x01 // GLONASS
};
// Enable interference resistance, because we are using LoRa, WiFi and Bluetooth on same board,
// and we need to reduce interference from them
const uint8_t GPS::_message_JAM[] = {
// bbThreshold (Broadband jamming detection threshold) is set to 0x3F (63 in decimal)
// cwThreshold (CW jamming detection threshold) is set to 0x10 (16 in decimal)
// algorithmBits (Reserved algorithm settings) is set to 0x16B156 as recommended
// enable (Enable interference detection) is set to 1 (enabled)
0x3F, 0x10, 0xB1, 0x56, // config: Interference config word
// generalBits (General settings) is set to 0x31E as recommended
// antSetting (Antenna setting, 0=unknown, 1=passive, 2=active) is set to 0 (unknown)
// ToDo: Set to 1 (passive) or 2 (active) if known, for example from UBX-MON-HW, or from board info
// enable2 (Set to 1 to scan auxiliary bands, u-blox 8 / u-blox M8 only, otherwise ignored) is set to 1
// (enabled)
0x1E, 0x03, 0x00, 0x01 // config2: Extra settings for jamming/interference monitor
};
// Configure navigation engine expert settings:
const uint8_t GPS::_message_NAVX5[] = {
0x00, 0x00, // msgVer (0 for this version)
// minMax flag = 1: apply min/max SVs settings
// minCno flag = 1: apply minimum C/N0 setting
// initial3dfix flag = 0: apply initial 3D fix settings
// aop flag = 1: apply aopCfg (useAOP flag) settings (AssistNow Autonomous)
0x1B, 0x00, // mask1 (First parameters bitmask)
// adr flag = 0: apply ADR sensor fusion on/off setting (useAdr flag)
// If firmware is not ADR/UDR, enabling this flag will fail configuration
// ToDo: check this with UBX-MON-VER
0x00, 0x00, 0x00, 0x00, // mask2 (Second parameters bitmask)
0x00, 0x00, // Reserved
0x03, // minSVs (Minimum number of satellites for navigation) = 3
0x10, // maxSVs (Maximum number of satellites for navigation) = 16
0x06, // minCNO (Minimum satellite signal level for navigation) = 6 dBHz
0x00, // Reserved
0x00, // iniFix3D (Initial fix must be 3D) = 0 (disabled)
0x00, 0x00, // Reserved
0x00, // ackAiding (Issue acknowledgements for assistance message input) = 0 (disabled)
0x00, 0x00, // Reserved
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved
0x00, // Reserved
0x01, // aopCfg (AssistNow Autonomous configuration) = 1 (enabled)
0x00, 0x00, // Reserved
0x00, 0x00, // Reserved
0x00, 0x00, 0x00, 0x00, // Reserved
0x00, 0x00, 0x00, // Reserved
0x01, // useAdr (Enable/disable ADR sensor fusion) = 1 (enabled)
};
// Set GPS update rate to 1Hz
// Lowering the update rate helps to save power.
// Additionally, for some new modules like the M9/M10, an update rate lower than 5Hz
// is recommended to avoid a known issue with satellites disappearing.
const uint8_t GPS::_message_1HZ[] = {
0xE8, 0x03, // Measurement Rate (1000ms for 1Hz)
0x01, 0x00, // Navigation rate, always 1 in GPS mode
0x01, 0x00, // Time reference
};
// Disable GGL. GGL - Geographic position (latitude and longitude), which provides the current geographical
// coordinates.
const uint8_t GPS::_message_GGL[] = {
0xF0, 0x01, // NMEA ID for GLL
0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI
0x00, // Disable
0x01, 0x01, 0x01, 0x01 // Reserved
};
// Enable GSA. GSA - GPS DOP and active satellites, used for detailing the satellites used in the positioning and
// the DOP (Dilution of Precision)
const uint8_t GPS::_message_GSA[] = {
0xF0, 0x02, // NMEA ID for GSA
0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI
0x01, // Enable
0x01, 0x01, 0x01, 0x01 // Reserved
};
// Disable GSV. GSV - Satellites in view, details the number and location of satellites in view.
const uint8_t GPS::_message_GSV[] = {
0xF0, 0x03, // NMEA ID for GSV
0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI
0x00, // Disable
0x01, 0x01, 0x01, 0x01 // Reserved
};
// Disable VTG. VTG - Track made good and ground speed, which provides course and speed information relative to
// the ground.
const uint8_t GPS::_message_VTG[] = {
0xF0, 0x05, // NMEA ID for VTG
0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI
0x00, // Disable
0x01, 0x01, 0x01, 0x01 // Reserved
};
// Enable RMC. RMC - Recommended Minimum data, the essential gps pvt (position, velocity, time) data.
const uint8_t GPS::_message_RMC[] = {
0xF0, 0x04, // NMEA ID for RMC
0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI
0x01, // Enable
0x01, 0x01, 0x01, 0x01 // Reserved
};
// Enable GGA. GGA - Global Positioning System Fix Data, which provides 3D location and accuracy data.
const uint8_t GPS::_message_GGA[] = {
0xF0, 0x00, // NMEA ID for GGA
0x01, // I/O Target 0=I/O, 1=UART1, 2=UART2, 3=USB, 4=SPI
0x01, // Enable
0x01, 0x01, 0x01, 0x01 // Reserved
};
// The Power Management configuration allows the GPS module to operate in different power modes for optimized
// power consumption. The modes supported are: 0x00 = Full power: The module operates at full power with no power
// saving. 0x01 = Balanced: The module dynamically adjusts the tracking behavior to balance power consumption.
// 0x02 = Interval: The module operates in a periodic mode, cycling between tracking and power saving states.
// 0x03 = Aggressive with 1 Hz: The module operates in a power saving mode with a 1 Hz update rate.
// 0x04 = Aggressive with 2 Hz: The module operates in a power saving mode with a 2 Hz update rate.
// 0x05 = Aggressive with 4 Hz: The module operates in a power saving mode with a 4 Hz update rate.
// The 'period' field specifies the position update and search period. It is only valid when the powerSetupValue
// is set to Interval; otherwise, it must be set to '0'. The 'onTime' field specifies the duration of the ON phase
// and must be smaller than the period. It is only valid when the powerSetupValue is set to Interval; otherwise,
// it must be set to '0'.
const uint8_t GPS::_message_PMS[] = {
0x00, // Version (0)
0x03, // Power setup value
0x00, 0x00, // period: not applicable, set to 0
0x00, 0x00, // onTime: not applicable, set to 0
0x97, 0x6F // reserved, generated by u-center
};
const uint8_t GPS::_message_SAVE[] = {
0x00, 0x00, 0x00, 0x00, // clearMask: no sections cleared
0xFF, 0xFF, 0x00, 0x00, // saveMask: save all sections
0x00, 0x00, 0x00, 0x00, // loadMask: no sections loaded
0x0F // deviceMask: BBR, Flash, EEPROM, and SPI Flash
};

View File

@ -1,5 +1,3 @@
#include "main.h"
#ifdef HAS_NCP5623
#include <NCP5623.h>
extern NCP5623 rgb;

View File

@ -36,11 +36,11 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#include "mesh-pb-constants.h"
#include "mesh/Channels.h"
#include "mesh/generated/meshtastic/deviceonly.pb.h"
#include "meshUtils.h"
#include "modules/ExternalNotificationModule.h"
#include "modules/TextMessageModule.h"
#include "sleep.h"
#include "target_specific.h"
#include "utils.h"
#ifdef ARCH_ESP32
#include "esp_task_wdt.h"
@ -365,7 +365,7 @@ static void drawCriticalFaultFrame(OLEDDisplay *display, OLEDDisplayUiState *sta
// Ignore messages originating from phone (from the current node 0x0) unless range test or store and forward module are enabled
static bool shouldDrawMessage(const meshtastic_MeshPacket *packet)
{
return packet->from != 0 && !moduleConfig.range_test.enabled && !moduleConfig.store_forward.enabled;
return packet->from != 0 && !moduleConfig.store_forward.enabled;
}
/// Draw the last text message we received

181
src/input/BBQ10Keyboard.cpp Normal file
View File

@ -0,0 +1,181 @@
// Based on arturo182 arduino_bbq10kbd library https://github.com/arturo182/arduino_bbq10kbd
#include <Arduino.h>
#include "BBQ10Keyboard.h"
#define _REG_VER 1
#define _REG_CFG 2
#define _REG_INT 3
#define _REG_KEY 4
#define _REG_BKL 5
#define _REG_DEB 6
#define _REG_FRQ 7
#define _REG_RST 8
#define _REG_FIF 9
#define _WRITE_MASK (1 << 7)
#define CFG_OVERFLOW_ON (1 << 0)
#define CFG_OVERFLOW_INT (1 << 1)
#define CFG_CAPSLOCK_INT (1 << 2)
#define CFG_NUMLOCK_INT (1 << 3)
#define CFG_KEY_INT (1 << 4)
#define CFG_PANIC_INT (1 << 5)
#define CFG_REPORT_MODS (1 << 6)
#define CFG_USE_MODS (1 << 7)
#define INT_OVERFLOW (1 << 0)
#define INT_CAPSLOCK (1 << 1)
#define INT_NUMLOCK (1 << 2)
#define INT_KEY (1 << 3)
#define INT_PANIC (1 << 4)
#define KEY_CAPSLOCK (1 << 5)
#define KEY_NUMLOCK (1 << 6)
#define KEY_COUNT_MASK (0x1F)
BBQ10Keyboard::BBQ10Keyboard() : m_wire(nullptr), m_addr(0), readCallback(nullptr), writeCallback(nullptr) {}
void BBQ10Keyboard::begin(uint8_t addr, TwoWire *wire)
{
m_addr = addr;
m_wire = wire;
m_wire->begin();
reset();
}
void BBQ10Keyboard::begin(i2c_com_fptr_t r, i2c_com_fptr_t w, uint8_t addr)
{
m_addr = addr;
m_wire = nullptr;
writeCallback = w;
readCallback = r;
reset();
}
void BBQ10Keyboard::reset()
{
if (m_wire) {
m_wire->beginTransmission(m_addr);
m_wire->write(_REG_RST);
m_wire->endTransmission();
}
if (writeCallback) {
uint8_t data = 0;
writeCallback(m_addr, _REG_RST, &data, 0);
}
delay(100);
writeRegister(_REG_CFG, readRegister8(_REG_CFG) | CFG_REPORT_MODS);
delay(100);
}
void BBQ10Keyboard::attachInterrupt(uint8_t pin, void (*func)(void)) const
{
pinMode(pin, INPUT_PULLUP);
::attachInterrupt(digitalPinToInterrupt(pin), func, RISING);
}
void BBQ10Keyboard::detachInterrupt(uint8_t pin) const
{
::detachInterrupt(pin);
}
void BBQ10Keyboard::clearInterruptStatus()
{
writeRegister(_REG_INT, 0x00);
}
uint8_t BBQ10Keyboard::status() const
{
return readRegister8(_REG_KEY);
}
uint8_t BBQ10Keyboard::keyCount() const
{
return status() & KEY_COUNT_MASK;
}
BBQ10Keyboard::KeyEvent BBQ10Keyboard::keyEvent() const
{
KeyEvent event = {.key = '\0', .state = StateIdle};
if (keyCount() == 0)
return event;
const uint16_t buf = readRegister16(_REG_FIF);
event.key = buf >> 8;
event.state = KeyState(buf & 0xFF);
return event;
}
float BBQ10Keyboard::backlight() const
{
return readRegister8(_REG_BKL) / 255.0f;
}
void BBQ10Keyboard::setBacklight(float value)
{
writeRegister(_REG_BKL, value * 255);
}
uint8_t BBQ10Keyboard::readRegister8(uint8_t reg) const
{
if (m_wire) {
m_wire->beginTransmission(m_addr);
m_wire->write(reg);
m_wire->endTransmission();
m_wire->requestFrom(m_addr, (uint8_t)1);
if (m_wire->available() < 1)
return 0;
return m_wire->read();
}
if (readCallback) {
uint8_t data;
readCallback(m_addr, reg, &data, 1);
return data;
}
return 0;
}
uint16_t BBQ10Keyboard::readRegister16(uint8_t reg) const
{
uint8_t data[2] = {0};
// uint8_t low = 0, high = 0;
if (m_wire) {
m_wire->beginTransmission(m_addr);
m_wire->write(reg);
m_wire->endTransmission();
m_wire->requestFrom(m_addr, (uint8_t)2);
if (m_wire->available() < 2)
return 0;
data[0] = m_wire->read();
data[1] = m_wire->read();
}
if (readCallback) {
readCallback(m_addr, reg, data, 2);
}
return (data[1] << 8) | data[0];
}
void BBQ10Keyboard::writeRegister(uint8_t reg, uint8_t value)
{
uint8_t data[2];
data[0] = reg | _WRITE_MASK;
data[1] = value;
if (m_wire) {
m_wire->beginTransmission(m_addr);
m_wire->write(data, sizeof(uint8_t) * 2);
m_wire->endTransmission();
}
if (writeCallback) {
writeCallback(m_addr, data[0], &(data[1]), 1);
}
}

51
src/input/BBQ10Keyboard.h Normal file
View File

@ -0,0 +1,51 @@
// Based on arturo182 arduino_bbq10kbd library https://github.com/arturo182/arduino_bbq10kbd
#include "configuration.h"
#include <Wire.h>
#define KEY_MOD_ALT (0x1A)
#define KEY_MOD_SHL (0x1B)
#define KEY_MOD_SHR (0x1C)
#define KEY_MOD_SYM (0x1D)
class BBQ10Keyboard
{
public:
typedef uint8_t (*i2c_com_fptr_t)(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t len);
enum KeyState { StateIdle = 0, StatePress, StateLongPress, StateRelease };
struct KeyEvent {
char key;
KeyState state;
};
BBQ10Keyboard();
void begin(uint8_t addr = BBQ10_KB_ADDR, TwoWire *wire = &Wire);
void begin(i2c_com_fptr_t r, i2c_com_fptr_t w, uint8_t addr = BBQ10_KB_ADDR);
void reset(void);
void attachInterrupt(uint8_t pin, void (*func)(void)) const;
void detachInterrupt(uint8_t pin) const;
void clearInterruptStatus(void);
uint8_t status(void) const;
uint8_t keyCount(void) const;
KeyEvent keyEvent(void) const;
float backlight() const;
void setBacklight(float value);
uint8_t readRegister8(uint8_t reg) const;
uint16_t readRegister16(uint8_t reg) const;
void writeRegister(uint8_t reg, uint8_t value);
private:
TwoWire *m_wire;
uint8_t m_addr;
i2c_com_fptr_t readCallback;
i2c_com_fptr_t writeCallback;
};

View File

@ -5,12 +5,12 @@ RotaryEncoderInterruptImpl1 *rotaryEncoderInterruptImpl1;
RotaryEncoderInterruptImpl1::RotaryEncoderInterruptImpl1() : RotaryEncoderInterruptBase("rotEnc1") {}
void RotaryEncoderInterruptImpl1::init()
bool RotaryEncoderInterruptImpl1::init()
{
if (!moduleConfig.canned_message.rotary1_enabled) {
// Input device is disabled.
disable();
return;
return false;
}
uint8_t pinA = moduleConfig.canned_message.inputbroker_pin_a;
@ -25,6 +25,7 @@ void RotaryEncoderInterruptImpl1::init()
RotaryEncoderInterruptImpl1::handleIntA, RotaryEncoderInterruptImpl1::handleIntB,
RotaryEncoderInterruptImpl1::handleIntPressed);
inputBroker->registerSource(this);
return true;
}
void RotaryEncoderInterruptImpl1::handleIntA()
@ -38,4 +39,4 @@ void RotaryEncoderInterruptImpl1::handleIntB()
void RotaryEncoderInterruptImpl1::handleIntPressed()
{
rotaryEncoderInterruptImpl1->intPressHandler();
}
}

View File

@ -12,7 +12,7 @@ class RotaryEncoderInterruptImpl1 : public RotaryEncoderInterruptBase
{
public:
RotaryEncoderInterruptImpl1();
void init();
bool init();
static void handleIntA();
static void handleIntB();
static void handleIntPressed();

View File

@ -5,12 +5,12 @@ UpDownInterruptImpl1 *upDownInterruptImpl1;
UpDownInterruptImpl1::UpDownInterruptImpl1() : UpDownInterruptBase("upDown1") {}
void UpDownInterruptImpl1::init()
bool UpDownInterruptImpl1::init()
{
if (!moduleConfig.canned_message.updown1_enabled) {
// Input device is disabled.
return;
return false;
}
uint8_t pinUp = moduleConfig.canned_message.inputbroker_pin_a;
@ -24,6 +24,7 @@ void UpDownInterruptImpl1::init()
UpDownInterruptBase::init(pinDown, pinUp, pinPress, eventDown, eventUp, eventPressed, UpDownInterruptImpl1::handleIntDown,
UpDownInterruptImpl1::handleIntUp, UpDownInterruptImpl1::handleIntPressed);
inputBroker->registerSource(this);
return true;
}
void UpDownInterruptImpl1::handleIntDown()
@ -37,4 +38,4 @@ void UpDownInterruptImpl1::handleIntUp()
void UpDownInterruptImpl1::handleIntPressed()
{
upDownInterruptImpl1->intPressHandler();
}
}

View File

@ -5,10 +5,10 @@ class UpDownInterruptImpl1 : public UpDownInterruptBase
{
public:
UpDownInterruptImpl1();
void init();
bool init();
static void handleIntDown();
static void handleIntUp();
static void handleIntPressed();
};
extern UpDownInterruptImpl1 *upDownInterruptImpl1;
extern UpDownInterruptImpl1 *upDownInterruptImpl1;

View File

@ -7,7 +7,7 @@ CardKbI2cImpl::CardKbI2cImpl() : KbI2cBase("cardKB") {}
void CardKbI2cImpl::init()
{
if (cardkb_found.address != CARDKB_ADDR && cardkb_found.address != TDECK_KB_ADDR) {
if (cardkb_found.address == 0x00) {
disable();
return;
}

View File

@ -30,7 +30,7 @@ uint8_t read_from_14004(TwoWire *i2cBus, uint8_t reg, uint8_t *data, uint8_t len
int32_t KbI2cBase::runOnce()
{
if (cardkb_found.address != CARDKB_ADDR && cardkb_found.address != TDECK_KB_ADDR) {
if (cardkb_found.address == 0x00) {
// Input device is not detected.
return INT32_MAX;
}
@ -41,11 +41,19 @@ int32_t KbI2cBase::runOnce()
#ifdef I2C_SDA1
LOG_DEBUG("Using I2C Bus 1 (the second one)\n");
i2cBus = &Wire1;
if (cardkb_found.address == BBQ10_KB_ADDR) {
Q10keyboard.begin(BBQ10_KB_ADDR, &Wire1);
Q10keyboard.setBacklight(0);
}
break;
#endif
case ScanI2C::WIRE:
LOG_DEBUG("Using I2C Bus 0 (the first one)\n");
i2cBus = &Wire;
if (cardkb_found.address == BBQ10_KB_ADDR) {
Q10keyboard.begin(BBQ10_KB_ADDR, &Wire);
Q10keyboard.setBacklight(0);
}
break;
case ScanI2C::NO_I2C:
default:
@ -53,7 +61,105 @@ int32_t KbI2cBase::runOnce()
}
}
if (kb_model == 0x02) {
switch (kb_model) {
case 0x11: { // BB Q10
int keyCount = Q10keyboard.keyCount();
while (keyCount--) {
const BBQ10Keyboard::KeyEvent key = Q10keyboard.keyEvent();
if ((key.key != 0x00) && (key.state == BBQ10Keyboard::StateRelease)) {
InputEvent e;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
e.source = this->_originName;
switch (key.key) {
case 'p': // TAB
case 't': // TAB as well
if (is_sym) {
e.inputEvent = ANYKEY;
e.kbchar = 0x09; // TAB Scancode
is_sym = false; // reset sym state after second keypress
} else {
e.inputEvent = ANYKEY;
e.kbchar = key.key;
}
break;
case 'q': // ESC
if (is_sym) {
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_CANCEL;
e.kbchar = 0x1b;
is_sym = false; // reset sym state after second keypress
} else {
e.inputEvent = ANYKEY;
e.kbchar = key.key;
}
break;
case 0x08: // Back
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_BACK;
e.kbchar = key.key;
break;
case 'e': // sym e
if (is_sym) {
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_UP;
e.kbchar = 0xb5;
is_sym = false; // reset sym state after second keypress
} else {
e.inputEvent = ANYKEY;
e.kbchar = key.key;
}
break;
case 'x': // sym x
if (is_sym) {
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_DOWN;
e.kbchar = 0xb6;
is_sym = false; // reset sym state after second keypress
} else {
e.inputEvent = ANYKEY;
e.kbchar = key.key;
}
break;
case 's': // sym s
if (is_sym) {
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_LEFT;
e.kbchar = 0x00; // tweak for destSelect
is_sym = false; // reset sym state after second keypress
} else {
e.inputEvent = ANYKEY;
e.kbchar = key.key;
}
break;
case 'f': // sym f
if (is_sym) {
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT;
e.kbchar = 0x00; // tweak for destSelect
is_sym = false; // reset sym state after second keypress
} else {
e.inputEvent = ANYKEY;
e.kbchar = key.key;
}
break;
case 0x13: // Code scanner says the SYM key is 0x13
is_sym = !is_sym;
break;
case 0x0a: // apparently Enter on Q10 is a line feed instead of carriage return
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_SELECT;
break;
case 0x00: // nopress
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
break;
default: // all other keys
e.inputEvent = ANYKEY;
e.kbchar = key.key;
is_sym = false; // reset sym state after second keypress
break;
}
if (e.inputEvent != meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE) {
this->notifyObservers(&e);
}
}
}
break;
}
case 0x02: {
// RAK14004
uint8_t rDataBuf[8] = {0};
uint8_t PrintDataBuf = 0;
@ -74,9 +180,12 @@ int32_t KbI2cBase::runOnce()
e.kbchar = PrintDataBuf;
this->notifyObservers(&e);
}
} else if (kb_model == 0x00 || kb_model == 0x10) {
// m5 cardkb and T-Deck
i2cBus->requestFrom(kb_model == 0x00 ? CARDKB_ADDR : TDECK_KB_ADDR, 1);
break;
}
case 0x00: // CARDKB
case 0x10: { // T-DECK
i2cBus->requestFrom((int)cardkb_found.address, 1);
while (i2cBus->available()) {
char c = i2cBus->read();
@ -93,17 +202,19 @@ int32_t KbI2cBase::runOnce()
break;
case 0xb5: // Up
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_UP;
e.kbchar = 0xb5;
break;
case 0xb6: // Down
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_DOWN;
e.kbchar = 0xb6;
break;
case 0xb4: // Left
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_LEFT;
e.kbchar = c;
e.kbchar = 0xb4;
break;
case 0xb7: // Right
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT;
e.kbchar = c;
e.kbchar = 0xb7;
break;
case 0x0d: // Enter
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_SELECT;
@ -121,7 +232,9 @@ int32_t KbI2cBase::runOnce()
this->notifyObservers(&e);
}
}
} else {
break;
}
default:
LOG_WARN("Unknown kb_model 0x%02x\n", kb_model);
}
return 300;

View File

@ -1,5 +1,6 @@
#pragma once
#include "BBQ10Keyboard.h"
#include "InputBroker.h"
#include "Wire.h"
#include "concurrency/OSThread.h"
@ -16,4 +17,7 @@ class KbI2cBase : public Observable<const InputEvent *>, public concurrency::OST
const char *_originName;
TwoWire *i2cBus = 0;
BBQ10Keyboard Q10keyboard;
bool is_sym = false;
};

View File

@ -73,6 +73,7 @@ NRF52Bluetooth *nrf52Bluetooth;
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
#include "AccelerometerThread.h"
#include "AmbientLightingThread.h"
#endif
using namespace concurrency;
@ -169,6 +170,7 @@ static OSThread *buttonThread;
uint32_t ButtonThread::longPressTime = 0;
#endif
static OSThread *accelerometerThread;
static OSThread *ambientLightingThread;
SPISettings spiSettings(4000000, MSBFIRST, SPI_MODE0);
RadioInterface *rIf = NULL;
@ -219,11 +221,6 @@ void setup()
digitalWrite(VEXT_ENABLE, 0); // turn on the display power
#endif
#ifdef VGNSS_CTRL
pinMode(VGNSS_CTRL, OUTPUT);
digitalWrite(VGNSS_CTRL, LOW);
#endif
#if defined(VTFT_CTRL)
pinMode(VTFT_CTRL, OUTPUT);
digitalWrite(VTFT_CTRL, LOW);
@ -387,6 +384,10 @@ void setup()
// assign an arbitrary value to distinguish from other models
kb_model = 0x10;
break;
case ScanI2C::DeviceType::BBQ10KB:
// assign an arbitrary value to distinguish from other models
kb_model = 0x11;
break;
default:
// use this as default since it's also just zero
LOG_WARN("kb_info.type is unknown(0x%02x), setting kb_model=0x00\n", kb_info.type);
@ -405,14 +406,6 @@ void setup()
// Only one supported RGB LED currently
#ifdef HAS_NCP5623
rgb_found = i2cScanner->find(ScanI2C::DeviceType::NCP5623);
// Start the RGB LED at 50%
if (rgb_found.type == ScanI2C::NCP5623) {
rgb.begin();
rgb.setCurrent(10);
rgb.setColor(128, 128, 128);
}
#endif
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
@ -517,6 +510,12 @@ void setup()
}
#endif
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
if (rgb_found.type != ScanI2C::DeviceType::NONE) {
ambientLightingThread = new AmbientLightingThread(rgb_found.type);
}
#endif
#ifdef T_WATCH_S3
drv.begin();
drv.selectLibrary(1);
@ -554,14 +553,12 @@ void setup()
readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time)
gps = createGps();
gps = GPS::createGps();
if (gps) {
gpsStatus->observe(&gps->newStatus);
} else {
LOG_WARN("No GPS found - running without GPS\n");
LOG_DEBUG("Running without GPS.\n");
}
nodeStatus->observe(&nodeDB.newStatus);
service.init();
@ -586,17 +583,6 @@ void setup()
screen->print("Started...\n");
// We have now loaded our saved preferences from flash
// ONCE we will factory reset the GPS for bug #327
if (gps && !devicestate.did_gps_reset) {
LOG_WARN("GPS FactoryReset requested\n");
if (gps->factoryReset()) { // If we don't succeed try again next time
devicestate.did_gps_reset = true;
nodeDB.saveToDisk(SEGMENT_DEVICESTATE);
}
}
#ifdef SX126X_ANT_SW
// make analog PA vs not PA switch on SX126x eval board work properly
pinMode(SX126X_ANT_SW, OUTPUT);
@ -751,7 +737,6 @@ void setup()
PowerFSM_setup(); // we will transition to ON in a couple of seconds, FIXME, only do this for cold boots, not waking from SDS
powerFSMthread = new PowerFSMThread();
// setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state
setCPUFast(false); // 80MHz is fine for our slow peripherals
}

View File

@ -327,21 +327,19 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus)
// load data from GPS object, will add timestamp + battery further down
pos = gps->p;
} else {
// The GPS has lost lock, if we are fixed position we should just keep using
// the old position
// The GPS has lost lock
#ifdef GPS_EXTRAVERBOSE
LOG_DEBUG("onGPSchanged() - lost validLocation\n");
#endif
if (config.position.fixed_position) {
LOG_WARN("Using fixed position\n");
pos = ConvertToPosition(node->position);
}
}
// Used fixed position if configured regalrdless of GPS lock
if (config.position.fixed_position) {
LOG_WARN("Using fixed position\n");
pos = ConvertToPosition(node->position);
}
// Finally add a fresh timestamp and battery level reading
// I KNOW this is redundant with refreshLocalMeshNode() above, but these are
// inexpensive nonblocking calls and can be refactored in due course
pos.time = getValidTime(RTCQualityGPS);
// 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\n", pos.timestamp, pos.time, pos.latitude_i,

View File

@ -48,6 +48,14 @@ class MeshService
uint32_t oldFromNum = 0;
public:
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;
}
/// Called when some new packets have arrived from one of the radios
Observable<uint32_t> fromNumChanged;

View File

@ -169,6 +169,14 @@ void NodeDB::installDefaultConfig()
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET;
config.lora.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST;
config.lora.hop_limit = HOP_RELIABLE;
#ifdef PIN_GPS_EN
config.position.gps_en_gpio = PIN_GPS_EN;
#endif
#ifdef GPS_POWER_TOGGLE
config.device.disable_triple_click = false;
#else
config.device.disable_triple_click = true;
#endif
config.position.gps_enabled = true;
config.position.position_broadcast_smart_enabled = true;
config.position.broadcast_smart_minimum_distance = 100;
@ -190,7 +198,9 @@ void NodeDB::installDefaultConfig()
: meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN;
// for backward compat, default position flags are ALT+MSL
config.position.position_flags =
(meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE | meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE_MSL);
(meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE | meshtastic_Config_PositionConfig_PositionFlags_ALTITUDE_MSL |
meshtastic_Config_PositionConfig_PositionFlags_SPEED | meshtastic_Config_PositionConfig_PositionFlags_HEADING |
meshtastic_Config_PositionConfig_PositionFlags_DOP);
#ifdef T_WATCH_S3
config.display.screen_on_secs = 30;
@ -253,6 +263,13 @@ void NodeDB::installDefaultModuleConfig()
moduleConfig.detection_sensor.detection_triggered_high = true;
moduleConfig.detection_sensor.minimum_broadcast_secs = 45;
moduleConfig.has_ambient_lighting = true;
moduleConfig.ambient_lighting.current = 10;
// Default to a color based on our node number
moduleConfig.ambient_lighting.red = (myNodeInfo.my_node_num & 0xFF0000) >> 16;
moduleConfig.ambient_lighting.green = (myNodeInfo.my_node_num & 0x00FF00) >> 8;
moduleConfig.ambient_lighting.blue = myNodeInfo.my_node_num & 0x0000FF;
initModuleConfigIntervals();
}
@ -295,6 +312,19 @@ void NodeDB::resetNodes()
neighborInfoModule->resetNeighbors();
}
void NodeDB::cleanupMeshDB()
{
int newPos = 0, removed = 0;
for (int i = 0; i < *numMeshNodes; i++) {
if (meshNodes[i].has_user)
meshNodes[newPos++] = meshNodes[i];
else
removed++;
}
*numMeshNodes -= removed;
LOG_DEBUG("cleanupMeshDB purged %d entries\n", removed);
}
void NodeDB::installDefaultDeviceState()
{
LOG_INFO("Installing default DeviceState\n");
@ -324,6 +354,7 @@ void NodeDB::init()
{
LOG_INFO("Initializing NodeDB\n");
loadFromDisk();
cleanupMeshDB();
uint32_t devicestateCRC = crc32Buffer(&devicestate, sizeof(devicestate));
uint32_t configCRC = crc32Buffer(&config, sizeof(config));
@ -379,25 +410,20 @@ void NodeDB::init()
*/
void NodeDB::pickNewNodeNum()
{
NodeNum r = myNodeInfo.my_node_num;
getMacAddr(ourMacAddr); // Make sure ourMacAddr is set
// Pick an initial nodenum based on the macaddr
r = (ourMacAddr[2] << 24) | (ourMacAddr[3] << 16) | (ourMacAddr[4] << 8) | ourMacAddr[5];
if (r == NODENUM_BROADCAST || r < NUM_RESERVED)
r = NUM_RESERVED; // don't pick a reserved node number
NodeNum nodeNum = (ourMacAddr[2] << 24) | (ourMacAddr[3] << 16) | (ourMacAddr[4] << 8) | ourMacAddr[5];
meshtastic_NodeInfoLite *found;
while ((found = getMeshNode(r)) && memcmp(found->user.macaddr, owner.macaddr, sizeof(owner.macaddr))) {
// FIXME: input for random() is int, so NODENUM_BROADCAST becomes -1
NodeNum n = random(NUM_RESERVED, NODENUM_BROADCAST); // try a new random choice
LOG_WARN("NOTE! Our desired nodenum 0x%x is in use, so trying for 0x%x\n", r, n);
r = n;
while ((nodeNum == NODENUM_BROADCAST || nodeNum < NUM_RESERVED) ||
((found = getMeshNode(nodeNum)) && memcmp(found->user.macaddr, owner.macaddr, sizeof(owner.macaddr)) != 0)) {
NodeNum candidate = random(NUM_RESERVED, LONG_MAX); // try a new random choice
LOG_WARN("NOTE! Our desired nodenum 0x%x is invalid or in use, so trying for 0x%x\n", nodeNum, candidate);
nodeNum = candidate;
}
myNodeInfo.my_node_num = r;
myNodeInfo.my_node_num = nodeNum;
}
static const char *prefFileName = "/prefs/db.proto";

View File

@ -146,6 +146,9 @@ class NodeDB
/// 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(), installDefaultChannels(), installDefaultConfig(), installDefaultModuleConfig();
};
@ -209,6 +212,14 @@ inline uint32_t getConfiguredOrDefaultMs(uint32_t configuredInterval, uint32_t d
return defaultInterval * 1000;
}
inline uint32_t getConfiguredOrDefault(uint32_t configured, uint32_t defaultValue)
{
if (configured > 0)
return configured;
return defaultValue;
}
/// Sometimes we will have Position objects that only have a time, so check for
/// valid lat/lon
static inline bool hasValidPosition(const meshtastic_NodeInfoLite *n)

View File

@ -155,11 +155,18 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// app not to send locations on our behalf.
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_my_info_tag;
fromRadioScratch.my_info = myNodeInfo;
state = STATE_SEND_NODEINFO;
state = STATE_SEND_METADATA;
service.refreshLocalMeshNode(); // Update my NodeInfo because the client will be asking for it soon.
break;
case STATE_SEND_METADATA:
LOG_INFO("getFromRadio=STATE_SEND_METADATA\n");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_metadata_tag;
fromRadioScratch.metadata = getDeviceMetadata();
state = STATE_SEND_NODEINFO;
break;
case STATE_SEND_NODEINFO: {
LOG_INFO("getFromRadio=STATE_SEND_NODEINFO\n");
@ -294,15 +301,11 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
config_state++;
// Advance when we have sent all of our ModuleConfig objects
if (config_state > (_meshtastic_AdminMessage_ModuleConfigType_MAX + 1)) {
state = STATE_SEND_METADATA;
state = STATE_SEND_COMPLETE_ID;
config_state = 0;
}
break;
case STATE_SEND_METADATA:
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_metadata_tag;
fromRadioScratch.metadata = getDeviceMetadata();
state = STATE_SEND_COMPLETE_ID;
break;
case STATE_SEND_COMPLETE_ID:
LOG_INFO("getFromRadio=STATE_SEND_COMPLETE_ID\n");
fromRadioScratch.which_payload_variant = meshtastic_FromRadio_config_complete_id_tag;

View File

@ -534,8 +534,8 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p)
h->id = p->id;
h->channel = p->channel;
if (p->hop_limit > HOP_MAX) {
LOG_WARN("hop limit %d is too high, setting to %d\n", p->hop_limit, HOP_MAX);
p->hop_limit = HOP_MAX;
LOG_WARN("hop limit %d is too high, setting to %d\n", p->hop_limit, HOP_RELIABLE);
p->hop_limit = HOP_RELIABLE;
}
h->flags = p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0);

View File

@ -3,7 +3,8 @@
#include "error.h"
#include "mesh/NodeDB.h"
// Particular boards might define a different max power based on what their hardware can do
// 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)
#ifndef SX126X_MAX_POWER
#define SX126X_MAX_POWER 22
#endif
@ -26,20 +27,23 @@ template <typename T> bool SX126xInterface<T>::init()
pinMode(SX126X_POWER_EN, OUTPUT);
#endif
#ifndef SX126X_E22
float tcxoVoltage = 0; // None - we use an XTAL
// FIXME: correct logic to default to not using TCXO if no voltage is specified for SX126X_DIO3_TCXO_VOLTAGE
#if !defined(SX126X_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/SX126x/SX126x.h#L471C26-L471C104
// (DIO3 is free to be used as an IRQ)
LOG_DEBUG("SX126X_DIO3_TCXO_VOLTAGE not defined, not using DIO3 as TCXO reference voltage\n");
#else
// Use DIO3 to power tcxo per https://github.com/jgromes/RadioLib/issues/12#issuecomment-520695575
float tcxoVoltage = 1.8;
float tcxoVoltage = SX126X_DIO3_TCXO_VOLTAGE;
LOG_DEBUG("SX126X_DIO3_TCXO_VOLTAGE defined, using DIO3 as TCXO reference voltage at %f V\n", SX126X_DIO3_TCXO_VOLTAGE);
// (DIO3 is not free to be used as an IRQ)
#endif
// 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();
if (power == 0)
power = SX126X_MAX_POWER;
if (power > SX126X_MAX_POWER) // This chip has lower power limits than some
if (power > SX126X_MAX_POWER) // Clamp power to maximum defined level
power = SX126X_MAX_POWER;
limitPower();
@ -54,49 +58,50 @@ template <typename T> bool SX126xInterface<T>::init()
LOG_INFO("Bandwidth set to %f\n", bw);
LOG_INFO("Power output set to %d\n", power);
// current limit was removed from module' ctor
// override default value (60 mA)
// 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 neccessary, 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\n", currentLimit);
LOG_DEBUG("Current limit set result %d\n", res);
#if defined(SX126X_E22)
// E22 Emulation explicitly requires DIO2 as RF switch, so set it to TRUE again for good measure. In case somebody defines
// SX126X_TX for an E22 Module
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("SX126X_E22 mode enabled. Setting DIO2 as RF Switch\n");
res = lora.setDio2AsRfSwitch(true);
}
#ifdef SX126X_DIO2_AS_RF_SWITCH
LOG_DEBUG("Setting DIO2 as RF switch\n");
bool dio2AsRfSwitch = true;
#else
LOG_DEBUG("Setting DIO2 as not RF switch\n");
bool dio2AsRfSwitch = false;
#endif
if (res == RADIOLIB_ERR_NONE) {
res = lora.setDio2AsRfSwitch(dio2AsRfSwitch);
}
#if defined(SX126X_TXEN) && (SX126X_TXEN != RADIOLIB_NC)
// If SX126X_TXEN is connected to the MCU, we are manually controlling RX and TX.
// But lora.begin (called above) sets Dio2 as RF switch control, which is not true here, so set it back to false.
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("SX126X_TXEN pin defined. Setting RF Switch: RXEN=%i, TXEN=%i\n", SX126X_RXEN, SX126X_TXEN);
res = lora.setDio2AsRfSwitch(false);
lora.setRfSwitchPins(SX126X_RXEN, SX126X_TXEN);
}
#elif defined(SX126X_RXEN) && (SX126X_RXEN != RADIOLIB_NC && defined(E22_TXEN_CONNECTED_TO_DIO2))
// Otherwise, if SX126X_RXEN is connected to the MCU, and E22_TXEN_CONNECTED_TO_DIO2 is defined, we are letting the
// E22 control RX and TX via DIO2. In this configuration, the E22's TXEN and DIO2 pins are connected to each other,
// but not to the MCU.
// However, we must still connect the E22's RXEN pin to the MCU, define SX126X_RXEN accordingly, and then call
// setRfSwitchPins, otherwise RX sensitivity (observed via RSSI) is greatly diminished.
LOG_DEBUG("SX126X_RXEN and E22_TXEN_CONNECTED_TO_DIO2 are defined; value of res: %d", res);
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("SX126X_TXEN is RADIOLIB_NC, but SX126X_RXEN and E22_TXEN_CONNECTED_TO_DIO2 are both defined; calling "
"lora.setRfSwitchPins.");
lora.setRfSwitchPins(SX126X_RXEN, SX126X_TXEN);
}
// 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
#ifndef SX126X_RXEN
#define SX126X_RXEN RADIOLIB_NC
LOG_DEBUG("SX126X_RXEN not defined, defaulting to RADIOLIB_NC\n");
#endif
#ifndef SX126X_TXEN
#define SX126X_TXEN RADIOLIB_NC
LOG_DEBUG("SX126X_TXEN not defined, defaulting to RADIOLIB_NC\n");
#endif
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("Using MCU pin %i as RXEN and pin %i as TXEN to control RF switching\n", SX126X_RXEN, SX126X_TXEN);
lora.setRfSwitchPins(SX126X_RXEN, SX126X_TXEN);
}
if (config.lora.sx126x_rx_boosted_gain) {
uint16_t result = lora.setRxBoostedGainMode(true);
LOG_INFO("Set Rx Boosted Gain mode; result: %d\n", result);
LOG_INFO("Set RX gain to boosted mode; result: %d\n", result);
} else {
uint16_t result = lora.setRxBoostedGainMode(false);
LOG_INFO("Set Rx Power Saving Gain mode; result: %d\n", result);
LOG_INFO("Set RX gain to power saving mode (boosted mode off); result: %d\n", result);
}
#if 0
@ -265,7 +270,7 @@ template <typename T> bool SX126xInterface<T>::isChannelActive()
/** 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
// 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.
uint16_t irq = lora.getIrqStatus();
@ -296,7 +301,7 @@ 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)\n");
LOG_DEBUG("SX126x entering sleep mode (FIXME, don't keep config)\n");
setStandby(); // Stop any pending operations
// turn off TCXO if it was powered
@ -312,4 +317,4 @@ template <typename T> bool SX126xInterface<T>::sleep()
#endif
return true;
}
}

View File

@ -51,8 +51,9 @@ typedef enum _meshtastic_Config_DeviceConfig_RebroadcastMode {
} meshtastic_Config_DeviceConfig_RebroadcastMode;
/* Bit field of boolean configuration options, indicating which optional
fields to include when assembling POSITION messages
Longitude and latitude are always included (also time if GPS-synced)
fields to include when assembling POSITION messages.
Longitude, latitude, altitude, speed, heading, and DOP
are always included (also time if GPS-synced)
NOTE: the more fields are included, the larger the message will be -
leading to longer airtime and a higher risk of packet loss */
typedef enum _meshtastic_Config_PositionConfig_PositionFlags {
@ -236,6 +237,8 @@ typedef struct _meshtastic_Config_DeviceConfig {
/* If true, device is considered to be "managed" by a mesh administrator
Clients should then limit available configuration and administrative options inside the user interface */
bool is_managed;
/* Disables the triple-press of user button to enable or disable GPS */
bool disable_triple_click;
} meshtastic_Config_DeviceConfig;
/* Position Config */
@ -271,6 +274,8 @@ typedef struct _meshtastic_Config_PositionConfig {
uint32_t broadcast_smart_minimum_distance;
/* The minimum number of seconds (since the last send) before we can send a position to the mesh if position_broadcast_smart_enabled */
uint32_t broadcast_smart_minimum_interval_secs;
/* (Re)define PIN_GPS_EN for your board. */
uint32_t gps_en_gpio;
} meshtastic_Config_PositionConfig;
/* Power Config\
@ -398,7 +403,8 @@ typedef struct _meshtastic_Config_LoRaConfig {
/* The region code for the radio (US, CN, EU433, etc...) */
meshtastic_Config_LoRaConfig_RegionCode region;
/* Maximum number of hops. This can't be greater than 7.
Default of 3 */
Default of 3
Attempting to set a value > 7 results in the default */
uint32_t hop_limit;
/* Disable TX from the LoRa radio. Useful for hot-swapping antennas and other tests.
Defaults to false */
@ -529,8 +535,8 @@ extern "C" {
/* Initializer values for message structs */
#define meshtastic_Config_init_default {0, {meshtastic_Config_DeviceConfig_init_default}}
#define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0}
#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0}
#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_PowerConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_NetworkConfig_init_default {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_default, ""}
#define meshtastic_Config_NetworkConfig_IpV4Config_init_default {0, 0, 0, 0}
@ -538,8 +544,8 @@ extern "C" {
#define meshtastic_Config_LoRaConfig_init_default {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}}
#define meshtastic_Config_BluetoothConfig_init_default {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0}
#define meshtastic_Config_init_zero {0, {meshtastic_Config_DeviceConfig_init_zero}}
#define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0}
#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0, 0}
#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_PowerConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_NetworkConfig_init_zero {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_zero, ""}
#define meshtastic_Config_NetworkConfig_IpV4Config_init_zero {0, 0, 0, 0}
@ -557,6 +563,7 @@ extern "C" {
#define meshtastic_Config_DeviceConfig_node_info_broadcast_secs_tag 7
#define meshtastic_Config_DeviceConfig_double_tap_as_button_press_tag 8
#define meshtastic_Config_DeviceConfig_is_managed_tag 9
#define meshtastic_Config_DeviceConfig_disable_triple_click_tag 10
#define meshtastic_Config_PositionConfig_position_broadcast_secs_tag 1
#define meshtastic_Config_PositionConfig_position_broadcast_smart_enabled_tag 2
#define meshtastic_Config_PositionConfig_fixed_position_tag 3
@ -568,6 +575,7 @@ extern "C" {
#define meshtastic_Config_PositionConfig_tx_gpio_tag 9
#define meshtastic_Config_PositionConfig_broadcast_smart_minimum_distance_tag 10
#define meshtastic_Config_PositionConfig_broadcast_smart_minimum_interval_secs_tag 11
#define meshtastic_Config_PositionConfig_gps_en_gpio_tag 12
#define meshtastic_Config_PowerConfig_is_power_saving_tag 1
#define meshtastic_Config_PowerConfig_on_battery_shutdown_after_secs_tag 2
#define meshtastic_Config_PowerConfig_adc_multiplier_override_tag 3
@ -652,7 +660,8 @@ X(a, STATIC, SINGULAR, UINT32, buzzer_gpio, 5) \
X(a, STATIC, SINGULAR, UENUM, rebroadcast_mode, 6) \
X(a, STATIC, SINGULAR, UINT32, node_info_broadcast_secs, 7) \
X(a, STATIC, SINGULAR, BOOL, double_tap_as_button_press, 8) \
X(a, STATIC, SINGULAR, BOOL, is_managed, 9)
X(a, STATIC, SINGULAR, BOOL, is_managed, 9) \
X(a, STATIC, SINGULAR, BOOL, disable_triple_click, 10)
#define meshtastic_Config_DeviceConfig_CALLBACK NULL
#define meshtastic_Config_DeviceConfig_DEFAULT NULL
@ -667,7 +676,8 @@ X(a, STATIC, SINGULAR, UINT32, position_flags, 7) \
X(a, STATIC, SINGULAR, UINT32, rx_gpio, 8) \
X(a, STATIC, SINGULAR, UINT32, tx_gpio, 9) \
X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_distance, 10) \
X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_interval_secs, 11)
X(a, STATIC, SINGULAR, UINT32, broadcast_smart_minimum_interval_secs, 11) \
X(a, STATIC, SINGULAR, UINT32, gps_en_gpio, 12)
#define meshtastic_Config_PositionConfig_CALLBACK NULL
#define meshtastic_Config_PositionConfig_DEFAULT NULL
@ -767,12 +777,12 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg;
/* Maximum encoded size of messages (where known) */
#define meshtastic_Config_BluetoothConfig_size 10
#define meshtastic_Config_DeviceConfig_size 30
#define meshtastic_Config_DeviceConfig_size 32
#define meshtastic_Config_DisplayConfig_size 28
#define meshtastic_Config_LoRaConfig_size 77
#define meshtastic_Config_NetworkConfig_IpV4Config_size 20
#define meshtastic_Config_NetworkConfig_size 195
#define meshtastic_Config_PositionConfig_size 54
#define meshtastic_Config_PositionConfig_size 60
#define meshtastic_Config_PowerConfig_size 40
#define meshtastic_Config_size 198

View File

@ -316,7 +316,7 @@ extern const pb_msgdesc_t meshtastic_NodeRemoteHardwarePin_msg;
#define meshtastic_DeviceState_size 16854
#define meshtastic_NodeInfoLite_size 151
#define meshtastic_NodeRemoteHardwarePin_size 29
#define meshtastic_OEMStore_size 3210
#define meshtastic_OEMStore_size 3218
#define meshtastic_PositionLite_size 28
#ifdef __cplusplus

View File

@ -174,7 +174,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg;
#define meshtastic_LocalModuleConfig_fields &meshtastic_LocalModuleConfig_msg
/* Maximum encoded size of messages (where known) */
#define meshtastic_LocalConfig_size 455
#define meshtastic_LocalConfig_size 463
#define meshtastic_LocalModuleConfig_size 609
#ifdef __cplusplus

View File

@ -111,6 +111,8 @@ typedef enum _meshtastic_HardwareModel {
meshtastic_HardwareModel_T_WATCH_S3 = 51,
/* Bobricius Picomputer with ESP32-S3 CPU, Keyboard and IPS display */
meshtastic_HardwareModel_PICOMPUTER_S3 = 52,
/* Heltec HT-CT62 with ESP32-C3 CPU and SX1262 LoRa */
meshtastic_HardwareModel_HELTEC_HT62 = 53,
/* ------------------------------------------------------------------------------------------------------------------------------------------
Reserved ID For developing private Ports. These will show up in live traffic sparsely, so we can use a high number. Keep it within 8 bits.
------------------------------------------------------------------------------------------------------------------------------------------ */
@ -297,9 +299,8 @@ typedef struct _meshtastic_Position {
/* In meters above MSL (but see issue #359) */
int32_t altitude;
/* This is usually not sent over the mesh (to save space), but it is sent
from the phone so that the local device can set its RTC If it is sent over
the mesh (because there are devices on the mesh without GPS), it will only
be sent by devices which has a hardware GPS clock.
from the phone so that the local device can set its time if it is sent over
the mesh (because there are devices on the mesh without GPS or RTC).
seconds since 1970 */
uint32_t time;
/* TODO: REPLACE */

View File

@ -313,13 +313,14 @@ Initially created for the RAK14001 RGB LED module. */
typedef struct _meshtastic_ModuleConfig_AmbientLightingConfig {
/* Sets LED to on or off. */
bool led_state;
/* Sets the overall current for the LED, firmware side range for the RAK14001 is 1-31, but users should be given a range of 0-100% */
/* Sets the current for the LED output. Default is 10. */
uint8_t current;
uint8_t red; /* Red level */
/* Sets the green level of the LED, firmware side values are 0-255, but users should be given a range of 0-100% */
uint8_t green; /* Green level */
/* Sets the blue level of the LED, firmware side values are 0-255, but users should be given a range of 0-100% */
uint8_t blue; /* Blue level */
/* Sets the red LED level. Values are 0-255. */
uint8_t red;
/* Sets the green LED level. Values are 0-255. */
uint8_t green;
/* Sets the blue LED level. Values are 0-255. */
uint8_t blue;
} meshtastic_ModuleConfig_AmbientLightingConfig;
/* A GPIO pin definition for remote hardware module */

View File

@ -69,6 +69,9 @@ typedef enum _meshtastic_PortNum {
NOTE: audio frames contain a 3 byte header (0xc0 0xde 0xc2) and a one byte marker for the decompressed bitrate.
This marker comes from the 'moduleConfig.audio.bitrate' enum minus one. */
meshtastic_PortNum_AUDIO_APP = 9,
/* Same as Text Message but originating from Detection Sensor Module.
NOTE: This portnum traffic is not sent to the public MQTT starting at firmware version 2.2.9 */
meshtastic_PortNum_DETECTION_SENSOR_APP = 10,
/* Provides a 'ping' service that replies to any packet it receives.
Also serves as a small example module.
ENCODING: ASCII Plaintext */
@ -88,7 +91,8 @@ typedef enum _meshtastic_PortNum {
ENCODING: Protobuf */
meshtastic_PortNum_STORE_FORWARD_APP = 65,
/* Optional port for messages for the range test module.
ENCODING: ASCII Plaintext */
ENCODING: ASCII Plaintext
NOTE: This portnum traffic is not sent to the public MQTT starting at firmware version 2.2.9 */
meshtastic_PortNum_RANGE_TEST_APP = 66,
/* Provides a format to send and receive telemetry data from the Meshtastic network.
Maintained by Charles Crossan (crossan007) : crossan007@gmail.com

View File

@ -101,11 +101,7 @@ typedef struct _meshtastic_AirQualityMetrics {
/* Types of Measurements the telemetry module is equipped to handle */
typedef struct _meshtastic_Telemetry {
/* This is usually not sent over the mesh (to save space), but it is sent
from the phone so that the local device can set its RTC If it is sent over
the mesh (because there are devices on the mesh without GPS), it will only
be sent by devices which has a hardware GPS clock (IE Mobile Phone).
seconds since 1970 */
/* Seconds since 1970 - or 0 for unknown/unset */
uint32_t time;
pb_size_t which_variant;
union {

View File

@ -25,7 +25,7 @@ bool pb_decode_from_bytes(const uint8_t *srcbuf, size_t srcbufsize, const pb_msg
{
pb_istream_t stream = pb_istream_from_buffer(srcbuf, srcbufsize);
if (!pb_decode(&stream, fields, dest_struct)) {
LOG_ERROR("Can't decode protobuf reason='%s', pb_msgdesc 0x%p\n", PB_GET_ERROR(&stream), fields);
LOG_ERROR("Can't decode protobuf reason='%s', pb_msgdesc %p\n", PB_GET_ERROR(&stream), fields);
return false;
} else {
return true;

58
src/meshUtils.cpp Normal file
View File

@ -0,0 +1,58 @@
#include "meshUtils.h"
#include <string.h>
/*
* Find the first occurrence of find in s, where the search is limited to the
* first slen characters of s.
* -
* Copyright (c) 2001 Mike Barcroft <mike@FreeBSD.org>
* Copyright (c) 1990, 1993
* The Regents of the University of California. All rights reserved.
*
* This code is derived from software contributed to Berkeley by
* Chris Torek.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the University nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE REGENTS AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE REGENTS OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
*/
char *strnstr(const char *s, const char *find, size_t slen)
{
char c, sc;
size_t len;
if ((c = *find++) != '\0') {
len = strlen(find);
do {
do {
if (slen-- < 1 || (sc = *s++) == '\0')
return (NULL);
} while (sc != c);
if (len > slen)
return (NULL);
} while (strncmp(s, find, len) != 0);
s--;
}
return ((char *)s);
}

View File

@ -4,4 +4,9 @@
template <class T> constexpr const T &clamp(const T &v, const T &lo, const T &hi)
{
return (v < lo) ? lo : (hi < v) ? hi : v;
}
}
#if (defined(ARCH_PORTDUINO) && !defined(STRNSTR))
#define STRNSTR
char *strnstr(const char *s, const char *find, size_t slen);
#endif

View File

@ -65,8 +65,8 @@ CannedMessageModule::CannedMessageModule()
{
if (moduleConfig.canned_message.enabled || CANNED_MESSAGE_MODULE_ENABLE) {
this->loadProtoForModule();
if ((this->splitConfiguredMessages() <= 0) && (cardkb_found.address != CARDKB_ADDR) &&
(cardkb_found.address != TDECK_KB_ADDR) && !INPUTBROKER_MATRIX_TYPE && !CANNED_MESSAGE_MODULE_ENABLE) {
if ((this->splitConfiguredMessages() <= 0) && (cardkb_found.address == 0x00) && !INPUTBROKER_MATRIX_TYPE &&
!CANNED_MESSAGE_MODULE_ENABLE) {
LOG_INFO("CannedMessageModule: No messages are configured. Module is disabled\n");
this->runState = CANNED_MESSAGE_RUN_STATE_DISABLED;
disable();
@ -171,7 +171,7 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event)
(event->inputEvent == static_cast<char>(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_LEFT)) ||
(event->inputEvent == static_cast<char>(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT))) {
// LOG_DEBUG("Canned message event (%x)\n", event->kbchar);
// tweak for left/right events generated via trackball/touch with empty kbchar
// tweak for left/right events generated via trackball/touch with empty kbchar
if (!event->kbchar) {
if (event->inputEvent == static_cast<char>(meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_LEFT)) {
this->payload = 0xb4;
@ -195,6 +195,7 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event)
this->runState = CANNED_MESSAGE_RUN_STATE_FREETEXT;
}
// pass the pressed key
// LOG_DEBUG("Canned message ANYKEY (%x)\n", event->kbchar);
this->payload = event->kbchar;
this->lastTouchMillis = millis();
validEvent = true;
@ -649,4 +650,4 @@ String CannedMessageModule::drawWithCursor(String text, int cursor)
return result;
}
#endif
#endif

View File

@ -46,10 +46,7 @@ int32_t DetectionSensorModule::runOnce()
if ((millis() - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs) &&
hasDetectionEvent()) {
sendDetectionMessage();
return getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs <
moduleConfig.detection_sensor.state_broadcast_secs
? moduleConfig.detection_sensor.minimum_broadcast_secs
: moduleConfig.detection_sensor.state_broadcast_secs);
return DELAYED_INTERVAL;
}
// Even if we haven't detected an event, broadcast our current state to the mesh on the scheduled interval as a sort
// of heartbeat. We only do this if the minimum broadcast interval is greater than zero, otherwise we'll only broadcast state
@ -57,10 +54,7 @@ int32_t DetectionSensorModule::runOnce()
else if (moduleConfig.detection_sensor.state_broadcast_secs > 0 &&
(millis() - lastSentToMesh) >= getConfiguredOrDefaultMs(moduleConfig.detection_sensor.state_broadcast_secs)) {
sendCurrentStateMessage();
return getConfiguredOrDefaultMs(moduleConfig.detection_sensor.minimum_broadcast_secs <
moduleConfig.detection_sensor.state_broadcast_secs
? moduleConfig.detection_sensor.minimum_broadcast_secs
: moduleConfig.detection_sensor.state_broadcast_secs);
return DELAYED_INTERVAL;
}
return GPIO_POLLING_INTERVAL;
}

View File

@ -5,7 +5,7 @@ class DetectionSensorModule : public SinglePortModule, private concurrency::OSTh
{
public:
DetectionSensorModule()
: SinglePortModule("detection", meshtastic_PortNum_TEXT_MESSAGE_APP), OSThread("DetectionSensorModule")
: SinglePortModule("detection", meshtastic_PortNum_DETECTION_SENSOR_APP), OSThread("DetectionSensorModule")
{
}

View File

@ -27,7 +27,6 @@
#ifdef HAS_NCP5623
#include <graphics/RAKled.h>
NCP5623 rgb;
uint8_t red = 0;
uint8_t green = 0;
@ -128,6 +127,11 @@ int32_t ExternalNotificationModule::runOnce()
}
}
bool ExternalNotificationModule::wantPacket(const meshtastic_MeshPacket *p)
{
return MeshService::isTextPayload(p);
}
/**
* Sets the external notification on for the specified index.
*
@ -212,8 +216,8 @@ void ExternalNotificationModule::stopNow()
}
ExternalNotificationModule::ExternalNotificationModule()
: SinglePortModule("ExternalNotificationModule", meshtastic_PortNum_TEXT_MESSAGE_APP), concurrency::OSThread(
"ExternalNotificationModule")
: SinglePortModule("ExternalNotificationModule", meshtastic_PortNum_TEXT_MESSAGE_APP),
concurrency::OSThread("ExternalNotificationModule")
{
/*
Uncomment the preferences below if you want to use the module

View File

@ -52,6 +52,8 @@ class ExternalNotificationModule : public SinglePortModule, private concurrency:
virtual int32_t runOnce() override;
virtual bool wantPacket(const meshtastic_MeshPacket *p) override;
bool isNagging = false;
virtual AdminMessageHandleResult handleAdminMessageForModule(const meshtastic_MeshPacket &mp,
@ -59,4 +61,4 @@ class ExternalNotificationModule : public SinglePortModule, private concurrency:
meshtastic_AdminMessage *response) override;
};
extern ExternalNotificationModule *externalNotificationModule;
extern ExternalNotificationModule *externalNotificationModule;

View File

@ -31,7 +31,7 @@
#if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)
#include "modules/ExternalNotificationModule.h"
#include "modules/RangeTestModule.h"
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52)) && !defined(CONFIG_IDF_TARGET_ESP32S2)
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2)
#include "modules/SerialModule.h"
#endif
#endif
@ -60,9 +60,15 @@ void setupModules()
new ReplyModule();
#if HAS_BUTTON
rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1();
rotaryEncoderInterruptImpl1->init();
if (!rotaryEncoderInterruptImpl1->init()) {
delete rotaryEncoderInterruptImpl1;
rotaryEncoderInterruptImpl1 = nullptr;
}
upDownInterruptImpl1 = new UpDownInterruptImpl1();
upDownInterruptImpl1->init();
if (!upDownInterruptImpl1->init()) {
delete upDownInterruptImpl1;
upDownInterruptImpl1 = nullptr;
}
cardKbI2cImpl = new CardKbI2cImpl();
cardKbI2cImpl->init();
#ifdef INPUTBROKER_MATRIX_TYPE
@ -86,7 +92,8 @@ void setupModules()
new AirQualityTelemetryModule();
}
#endif
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && !defined(CONFIG_IDF_TARGET_ESP32C3)
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \
!defined(CONFIG_IDF_TARGET_ESP32C3)
new SerialModule();
#endif
#ifdef ARCH_ESP32

View File

@ -15,12 +15,12 @@ NOTE: For debugging only
*/
void NeighborInfoModule::printNeighborInfo(const char *header, const meshtastic_NeighborInfo *np)
{
LOG_DEBUG("%s NEIGHBORINFO PACKET from Node %d to Node %d (last sent by %d)\n", header, np->node_id, nodeDB.getNodeNum(),
np->last_sent_by_id);
LOG_DEBUG("%s NEIGHBORINFO PACKET from Node 0x%x to Node 0x%x (last sent by 0x%x)\n", header, np->node_id,
nodeDB.getNodeNum(), np->last_sent_by_id);
LOG_DEBUG("----------------\n");
LOG_DEBUG("Packet contains %d neighbors\n", np->neighbors_count);
for (int i = 0; i < np->neighbors_count; i++) {
LOG_DEBUG("Neighbor %d: node_id=%d, snr=%.2f\n", i, np->neighbors[i].node_id, np->neighbors[i].snr);
LOG_DEBUG("Neighbor %d: node_id=0x%x, snr=%.2f\n", i, np->neighbors[i].node_id, np->neighbors[i].snr);
}
LOG_DEBUG("----------------\n");
}
@ -31,12 +31,12 @@ NOTE: for debugging only
void NeighborInfoModule::printNodeDBNodes(const char *header)
{
int num_nodes = nodeDB.getNumMeshNodes();
LOG_DEBUG("%s NODEDB SELECTION from Node %d:\n", header, nodeDB.getNodeNum());
LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB.getNodeNum());
LOG_DEBUG("----------------\n");
LOG_DEBUG("DB contains %d nodes\n", num_nodes);
for (int i = 0; i < num_nodes; i++) {
const meshtastic_NodeInfoLite *dbEntry = nodeDB.getMeshNodeByIndex(i);
LOG_DEBUG(" Node %d: node_id=%d, snr=%.2f\n", i, dbEntry->num, dbEntry->snr);
LOG_DEBUG(" Node %d: node_id=0x%x, snr=%.2f\n", i, dbEntry->num, dbEntry->snr);
}
LOG_DEBUG("----------------\n");
}
@ -48,12 +48,12 @@ NOTE: for debugging only
void NeighborInfoModule::printNodeDBNeighbors(const char *header)
{
int num_neighbors = getNumNeighbors();
LOG_DEBUG("%s NODEDB SELECTION from Node %d:\n", header, nodeDB.getNodeNum());
LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB.getNodeNum());
LOG_DEBUG("----------------\n");
LOG_DEBUG("DB contains %d neighbors\n", num_neighbors);
for (int i = 0; i < num_neighbors; i++) {
const meshtastic_Neighbor *dbEntry = getNeighborByIndex(i);
LOG_DEBUG(" Node %d: node_id=%d, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr);
LOG_DEBUG(" Node %d: node_id=0x%x, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr);
}
LOG_DEBUG("----------------\n");
}
@ -66,7 +66,7 @@ NOTE: For debugging only
void NeighborInfoModule::printNodeDBSelection(const char *header, const meshtastic_NeighborInfo *np)
{
int num_neighbors = getNumNeighbors();
LOG_DEBUG("%s NODEDB SELECTION from Node %d:\n", header, nodeDB.getNodeNum());
LOG_DEBUG("%s NODEDB SELECTION from Node 0x%x:\n", header, nodeDB.getNodeNum());
LOG_DEBUG("----------------\n");
LOG_DEBUG("Selected %d neighbors of %d DB neighbors\n", np->neighbors_count, num_neighbors);
for (int i = 0; i < num_neighbors; i++) {
@ -78,9 +78,9 @@ void NeighborInfoModule::printNodeDBSelection(const char *header, const meshtast
}
}
if (!chosen) {
LOG_DEBUG(" Node %d: neighbor=%d, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr);
LOG_DEBUG(" Node %d: neighbor=0x%x, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr);
} else {
LOG_DEBUG("---> Node %d: neighbor=%d, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr);
LOG_DEBUG("---> Node %d: neighbor=0x%x, snr=%.2f\n", i, dbEntry->node_id, dbEntry->snr);
}
}
LOG_DEBUG("----------------\n");
@ -103,16 +103,6 @@ NeighborInfoModule::NeighborInfoModule()
}
}
/*
Allocate a zeroed neighbor info packet
*/
meshtastic_NeighborInfo *NeighborInfoModule::allocateNeighborInfoPacket()
{
meshtastic_NeighborInfo *neighborInfo = (meshtastic_NeighborInfo *)malloc(sizeof(meshtastic_NeighborInfo));
memset(neighborInfo, 0, sizeof(meshtastic_NeighborInfo));
return neighborInfo;
}
/*
Collect neighbor info from the nodeDB's history, capping at a maximum number of entries and max time
Assumes that the neighborInfo packet has been allocated
@ -120,7 +110,7 @@ Assumes that the neighborInfo packet has been allocated
*/
uint32_t NeighborInfoModule::collectNeighborInfo(meshtastic_NeighborInfo *neighborInfo)
{
int my_node_id = nodeDB.getNodeNum();
uint my_node_id = nodeDB.getNodeNum();
neighborInfo->node_id = my_node_id;
neighborInfo->last_sent_by_id = my_node_id;
neighborInfo->node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval;
@ -184,14 +174,14 @@ size_t NeighborInfoModule::cleanUpNeighbors()
/* Send neighbor info to the mesh */
void NeighborInfoModule::sendNeighborInfo(NodeNum dest, bool wantReplies)
{
meshtastic_NeighborInfo *neighborInfo = allocateNeighborInfoPacket();
collectNeighborInfo(neighborInfo);
meshtastic_MeshPacket *p = allocDataProtobuf(*neighborInfo);
meshtastic_NeighborInfo neighborInfo = meshtastic_NeighborInfo_init_zero;
collectNeighborInfo(&neighborInfo);
meshtastic_MeshPacket *p = allocDataProtobuf(neighborInfo);
// send regardless of whether or not we have neighbors in our DB,
// because we want to get neighbors for the next cycle
p->to = dest;
p->decoded.want_response = wantReplies;
printNeighborInfo("SENDING", neighborInfo);
printNeighborInfo("SENDING", &neighborInfo);
service.sendToMesh(p, RX_SRC_LOCAL, true);
}
@ -212,8 +202,10 @@ Pass it to an upper client; do not persist this data on the mesh
*/
bool NeighborInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_NeighborInfo *np)
{
printNeighborInfo("RECEIVED", np);
updateNeighbors(mp, np);
if (enabled) {
printNeighborInfo("RECEIVED", np);
updateNeighbors(mp, np);
}
// Allow others to handle this packet
return false;
}
@ -255,7 +247,7 @@ void NeighborInfoModule::updateNeighbors(const meshtastic_MeshPacket &mp, const
}
meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSender, NodeNum n,
uint32_t node_broadcast_interval_secs, int snr)
uint32_t node_broadcast_interval_secs, float snr)
{
// our node and the phone are the same node (not neighbors)
if (n == 0) {
@ -277,7 +269,7 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen
}
// otherwise, allocate one and assign data to it
// TODO: max memory for the database should take neighbors into account, but currently doesn't
if (*numNeighbors < MAX_NUM_NODES) {
if (*numNeighbors < MAX_NUM_NEIGHBORS) {
(*numNeighbors)++;
}
meshtastic_Neighbor *new_nbr = &neighbors[((*numNeighbors) - 1)];

View File

@ -49,7 +49,7 @@ class NeighborInfoModule : public ProtobufModule<meshtastic_NeighborInfo>, priva
meshtastic_NeighborInfo *allocateNeighborInfoPacket();
// Find a neighbor in our DB, create an empty neighbor if missing
meshtastic_Neighbor *getOrCreateNeighbor(NodeNum originalSender, NodeNum n, uint32_t node_broadcast_interval_secs, int snr);
meshtastic_Neighbor *getOrCreateNeighbor(NodeNum originalSender, NodeNum n, uint32_t node_broadcast_interval_secs, float snr);
/*
* Send info on our node's neighbors into the mesh

View File

@ -11,8 +11,8 @@
PositionModule *positionModule;
PositionModule::PositionModule()
: ProtobufModule("position", meshtastic_PortNum_POSITION_APP, &meshtastic_Position_msg), concurrency::OSThread(
"PositionModule")
: ProtobufModule("position", meshtastic_PortNum_POSITION_APP, &meshtastic_Position_msg),
concurrency::OSThread("PositionModule")
{
isPromiscuous = true; // We always want to update our nodedb, even if we are sniffing on others
setIntervalFromNow(60 * 1000); // Send our initial position 60 seconds after we start (to give GPS time to setup)
@ -33,12 +33,12 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes
// return false;
}
// Log packet size and list of fields
LOG_INFO("POSITION node=%08x l=%d %s%s%s%s%s%s%s%s%s%s%s%s%s\n", getFrom(&mp), mp.decoded.payload.size,
p.latitude_i ? "LAT " : "", p.longitude_i ? "LON " : "", p.altitude ? "MSL " : "", p.altitude_hae ? "HAE " : "",
p.altitude_geoidal_separation ? "GEO " : "", p.PDOP ? "PDOP " : "", p.HDOP ? "HDOP " : "", p.VDOP ? "VDOP " : "",
p.sats_in_view ? "SIV " : "", p.fix_quality ? "FXQ " : "", p.fix_type ? "FXT " : "", p.timestamp ? "PTS " : "",
p.time ? "TIME " : "");
// Log packet size and data fields
LOG_INFO("POSITION node=%08x l=%d latI=%d lonI=%d msl=%d hae=%d geo=%d pdop=%d hdop=%d vdop=%d siv=%d fxq=%d fxt=%d pts=%d "
"time=%d\n",
getFrom(&mp), mp.decoded.payload.size, p.latitude_i, p.longitude_i, p.altitude, p.altitude_hae,
p.altitude_geoidal_separation, p.PDOP, p.HDOP, p.VDOP, p.sats_in_view, p.fix_quality, p.fix_type, p.timestamp,
p.time);
if (p.time) {
struct timeval tv;
@ -65,7 +65,7 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes
meshtastic_MeshPacket *PositionModule::allocReply()
{
if (ignoreRequest) {
return NULL;
return nullptr;
}
meshtastic_NodeInfoLite *node = service.refreshLocalMeshNode(); // should guarantee there is now a position
@ -142,6 +142,11 @@ void PositionModule::sendOurPosition(NodeNum dest, bool wantReplies, uint8_t cha
service.cancelSending(prevPacketId);
meshtastic_MeshPacket *p = allocReply();
if (p == nullptr) {
LOG_WARN("allocReply returned a nullptr");
return;
}
p->to = dest;
p->decoded.want_response = wantReplies;
if (config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER)
@ -188,26 +193,19 @@ int32_t PositionModule::runOnce()
const meshtastic_NodeInfoLite *node2 = service.refreshLocalMeshNode(); // should guarantee there is now a position
if (hasValidPosition(node2)) {
// The minimum distance to travel before we are able to send a new position packet.
const uint32_t distanceTravelThreshold =
config.position.broadcast_smart_minimum_distance > 0 ? config.position.broadcast_smart_minimum_distance : 100;
// The minimum time (in seconds) that would pass before we are able to send a new position packet.
const uint32_t minimumTimeThreshold =
getConfiguredOrDefaultMs(config.position.broadcast_smart_minimum_interval_secs, 30);
// Determine the distance in meters between two points on the globe
float distanceTraveledSinceLastSend =
GeoCoord::latLongToMeter(lastGpsLatitude * 1e-7, lastGpsLongitude * 1e-7, node->position.latitude_i * 1e-7,
node->position.longitude_i * 1e-7);
auto smartPosition = getDistanceTraveledSinceLastSend(node->position);
if ((abs(distanceTraveledSinceLastSend) >= distanceTravelThreshold) && msSinceLastSend >= minimumTimeThreshold) {
if (smartPosition.hasTraveledOverThreshold && msSinceLastSend >= minimumTimeThreshold) {
bool requestReplies = currentGeneration != radioGeneration;
currentGeneration = radioGeneration;
LOG_INFO("Sending smart pos@%x:6 to mesh (distanceTraveled=%fm, minDistanceThreshold=%im, timeElapsed=%ims, "
"minTimeInterval=%ims)\n",
localPosition.timestamp, abs(distanceTraveledSinceLastSend), distanceTravelThreshold,
localPosition.timestamp, smartPosition.distanceTraveled, smartPosition.distanceThreshold,
msSinceLastSend, minimumTimeThreshold);
sendOurPosition(NODENUM_BROADCAST, requestReplies);
@ -225,4 +223,48 @@ int32_t PositionModule::runOnce()
}
return 5000; // to save power only wake for our callback occasionally
}
struct SmartPosition PositionModule::getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition)
{
// The minimum distance to travel before we are able to send a new position packet.
const uint32_t distanceTravelThreshold = getConfiguredOrDefault(config.position.broadcast_smart_minimum_distance, 100);
// Determine the distance in meters between two points on the globe
float distanceTraveledSinceLastSend = GeoCoord::latLongToMeter(
lastGpsLatitude * 1e-7, lastGpsLongitude * 1e-7, currentPosition.latitude_i * 1e-7, currentPosition.longitude_i * 1e-7);
return SmartPosition{.distanceTraveled = abs(distanceTraveledSinceLastSend),
.distanceThreshold = distanceTravelThreshold,
.hasTraveledOverThreshold = abs(distanceTraveledSinceLastSend) >= distanceTravelThreshold};
}
void PositionModule::handleNewPosition()
{
meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum());
const meshtastic_NodeInfoLite *node2 = service.refreshLocalMeshNode(); // should guarantee there is now a position
// We limit our GPS broadcasts to a max rate
uint32_t now = millis();
uint32_t msSinceLastSend = now - lastGpsSend;
if (hasValidPosition(node2)) {
auto smartPosition = getDistanceTraveledSinceLastSend(node->position);
if (smartPosition.hasTraveledOverThreshold) {
bool requestReplies = currentGeneration != radioGeneration;
currentGeneration = radioGeneration;
LOG_INFO("Sending smart pos@%x:6 to mesh (distanceTraveled=%fm, minDistanceThreshold=%im, timeElapsed=%ims)\n",
localPosition.timestamp, smartPosition.distanceTraveled, smartPosition.distanceThreshold, msSinceLastSend);
sendOurPosition(NODENUM_BROADCAST, requestReplies);
// Set the current coords as our last ones, after we've compared distance with current and decided to send
lastGpsLatitude = node->position.latitude_i;
lastGpsLongitude = node->position.longitude_i;
/* Update lastGpsSend to now. This means if the device is stationary, then
getPref_position_broadcast_secs will still apply.
*/
lastGpsSend = now;
}
}
}

View File

@ -31,6 +31,8 @@ class PositionModule : public ProtobufModule<meshtastic_Position>, private concu
*/
void sendOurPosition(NodeNum dest = NODENUM_BROADCAST, bool wantReplies = false, uint8_t channel = 0);
void handleNewPosition();
protected:
/** Called to handle a particular incoming message
@ -44,6 +46,15 @@ class PositionModule : public ProtobufModule<meshtastic_Position>, private concu
/** Does our periodic broadcast */
virtual int32_t runOnce() override;
private:
struct SmartPosition getDistanceTraveledSinceLastSend(meshtastic_PositionLite currentPosition);
};
struct SmartPosition {
float distanceTraveled;
uint32_t distanceThreshold;
bool hasTraveledOverThreshold;
};
extern PositionModule *positionModule;

View File

@ -29,7 +29,7 @@ class RangeTestModuleRadio : public SinglePortModule
uint32_t lastRxID = 0;
public:
RangeTestModuleRadio() : SinglePortModule("RangeTestModuleRadio", meshtastic_PortNum_TEXT_MESSAGE_APP)
RangeTestModuleRadio() : SinglePortModule("RangeTestModuleRadio", meshtastic_PortNum_RANGE_TEST_APP)
{
loopbackOk = true; // Allow locally generated messages to loop back to the client
}

View File

@ -44,9 +44,10 @@
*/
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && !defined(CONFIG_IDF_TARGET_ESP32C3)
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \
!defined(CONFIG_IDF_TARGET_ESP32C3)
#define RX_BUFFER 128
#define RX_BUFFER 256
#define TIMEOUT 250
#define BAUD 38400
#define ACK 1
@ -141,7 +142,12 @@ int32_t SerialModule::runOnce()
}
#elif !defined(TTGO_T_ECHO)
if (moduleConfig.serial.rxd && moduleConfig.serial.txd) {
#ifdef ARCH_RP2040
Serial2.setFIFOSize(RX_BUFFER);
Serial2.setPinout(moduleConfig.serial.txd, moduleConfig.serial.rxd);
#else
Serial2.setPins(moduleConfig.serial.rxd, moduleConfig.serial.txd);
#endif
Serial2.begin(baud, SERIAL_8N1);
Serial2.setTimeout(moduleConfig.serial.timeout > 0 ? moduleConfig.serial.timeout : TIMEOUT);
} else {
@ -182,7 +188,7 @@ int32_t SerialModule::runOnce()
}
}
}
#ifndef TTGO_T_ECHO
#if !defined(TTGO_T_ECHO)
else {
while (Serial2.available()) {
serialPayloadSize = Serial2.readBytes(serialBytes, meshtastic_Constants_DATA_PAYLOAD_LEN);

View File

@ -8,7 +8,8 @@
#include <Arduino.h>
#include <functional>
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && !defined(CONFIG_IDF_TARGET_ESP32C3)
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \
!defined(CONFIG_IDF_TARGET_ESP32C3)
class SerialModule : public StreamAPI, private concurrency::OSThread
{
@ -74,4 +75,4 @@ class SerialModuleRadio : public MeshModule
extern SerialModuleRadio *serialModuleRadio;
#endif
#endif

View File

@ -1,4 +1,5 @@
#include "TextMessageModule.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
@ -22,3 +23,8 @@ ProcessMessage TextMessageModule::handleReceived(const meshtastic_MeshPacket &mp
return ProcessMessage::CONTINUE; // Let others look at this message also if they want
}
bool TextMessageModule::wantPacket(const meshtastic_MeshPacket *p)
{
return MeshService::isTextPayload(p);
}

View File

@ -20,6 +20,7 @@ class TextMessageModule : public SinglePortModule, public Observable<const mesht
it
*/
virtual ProcessMessage handleReceived(const meshtastic_MeshPacket &mp) override;
virtual bool wantPacket(const meshtastic_MeshPacket *p) override;
};
extern TextMessageModule *textMessageModule;
extern TextMessageModule *textMessageModule;

View File

@ -455,6 +455,13 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, ChannelIndex chIndex)
{
auto &ch = channels.getByIndex(chIndex);
if (&mp.decoded && strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 &&
(mp.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP ||
mp.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) {
LOG_DEBUG("MQTT onSend - Ignoring range test or detection sensor message on public mqtt\n");
return;
}
if (ch.settings.uplink_enabled) {
const char *channelId = channels.getGlobalId(chIndex); // FIXME, for now we just use the human name for the channel
@ -656,8 +663,18 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
&scratch)) {
decoded = &scratch;
msgPayload["node_id"] = new JSONValue((uint)decoded->node_id);
msgPayload["node_broadcast_interval_secs"] = new JSONValue((uint)decoded->node_broadcast_interval_secs);
msgPayload["last_sent_by_id"] = new JSONValue((uint)decoded->last_sent_by_id);
msgPayload["neighbors_count"] = new JSONValue(decoded->neighbors_count);
msgPayload["neighbors"] = new JSONValue(decoded->neighbors);
JSONArray neighbors;
for (uint8_t i = 0; i < decoded->neighbors_count; i++) {
JSONObject neighborObj;
neighborObj["node_id"] = new JSONValue((uint)decoded->neighbors[i].node_id);
neighborObj["snr"] = new JSONValue((int)decoded->neighbors[i].snr);
neighbors.push_back(new JSONValue(neighborObj));
}
msgPayload["neighbors"] = new JSONValue(neighbors);
jsonObj["payload"] = new JSONValue(msgPayload);
} else {
LOG_ERROR("Error decoding protobuf for neighborinfo message!\n");
}

View File

@ -119,22 +119,8 @@
#define HW_VENDOR meshtastic_HardwareModel_BETAFPV_900_NANO_TX
#elif defined(PICOMPUTER_S3)
#define HW_VENDOR meshtastic_HardwareModel_PICOMPUTER_S3
#endif
//
// Standard definitions for ESP32 targets
//
#define GPS_SERIAL_NUM 1
#ifndef GPS_RX_PIN
#define GPS_RX_PIN 34
#endif
#ifndef GPS_TX_PIN
#ifdef USE_JTAG
#define GPS_TX_PIN -1
#else
#define GPS_TX_PIN 12
#endif
#elif defined(HELTEC_HT62)
#define HW_VENDOR meshtastic_HardwareModel_HELTEC_HT62
#endif
// -----------------------------------------------------------------------------

View File

@ -9,10 +9,10 @@
#include "BleOta.h"
#include "mesh/http/WiFiAPClient.h"
#include "meshUtils.h"
#include "sleep.h"
#include "soc/rtc.h"
#include "target_specific.h"
#include "utils.h"
#include <Preferences.h>
#include <driver/rtc_io.h>
#include <nvs.h>
@ -220,4 +220,4 @@ void cpuDeepSleep(uint32_t msecToWake)
esp_sleep_enable_timer_wakeup(msecToWake * 1000ULL); // call expects usecs
esp_deep_sleep_start(); // TBD mA sleep current (battery)
}
}

View File

@ -90,33 +90,6 @@ void setLed(bool ledOn)
#endif
}
void setGPSPower(bool on)
{
LOG_INFO("Setting GPS power=%d\n", on);
#ifdef PIN_GPS_EN
digitalWrite(PIN_GPS_EN, on ? 1 : 0);
#endif
#ifdef HAS_PMU
if (pmu_found && PMU) {
uint8_t model = PMU->getChipModel();
if (model == XPOWERS_AXP2101) {
if (HW_VENDOR == meshtastic_HardwareModel_TBEAM) {
// t-beam v1.2 GNSS power channel
on ? PMU->enablePowerOutput(XPOWERS_ALDO3) : PMU->disablePowerOutput(XPOWERS_ALDO3);
} else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE) {
// t-beam-s3-core GNSS power channel
on ? PMU->enablePowerOutput(XPOWERS_ALDO4) : PMU->disablePowerOutput(XPOWERS_ALDO4);
}
} else if (model == XPOWERS_AXP192) {
// t-beam v1.1 GNSS power channel
on ? PMU->enablePowerOutput(XPOWERS_LDO3) : PMU->disablePowerOutput(XPOWERS_LDO3);
}
}
#endif
}
// Perform power on init that we do on each wake from deep sleep
void initDeepSleep()
{
@ -182,30 +155,6 @@ static void waitEnterSleep()
notifySleep.notifyObservers(NULL);
}
void doGPSpowersave(bool on)
{
#if defined(HAS_PMU) || defined(PIN_GPS_EN)
if (on) {
LOG_INFO("Turning GPS back on\n");
gps->forceWake(1);
setGPSPower(1);
} else {
LOG_INFO("Turning off GPS chip\n");
notifyGPSSleep.notifyObservers(NULL);
setGPSPower(0);
}
#endif
#ifdef PIN_GPS_WAKE
if (on) {
LOG_INFO("Waking GPS");
gps->forceWake(1);
} else {
LOG_INFO("GPS entering sleep");
notifyGPSSleep.notifyObservers(NULL);
}
#endif
}
void doDeepSleep(uint32_t msecToWake)
{
if (INCLUDE_vTaskSuspend && (msecToWake == portMAX_DELAY)) {
@ -224,7 +173,7 @@ void doDeepSleep(uint32_t msecToWake)
nodeDB.saveToDisk();
// Kill GPS power completely (even if previously we just had it in sleep mode)
setGPSPower(false);
gps->setGPSPower(false, false);
setLed(false);

View File

@ -18,8 +18,6 @@ extern esp_sleep_source_t wakeCause;
extern XPowersLibInterface *PMU;
#endif
void setGPSPower(bool on);
void doGPSpowersave(bool on);
// Perform power on init that we do on each wake from deep sleep
void initDeepSleep();

View File

@ -47,12 +47,12 @@ extern "C" {
#define PIN_LED2 (0 + 6) // Built in Green P0.06
// Green Built in LED1
//#define PIN_LED1 (0 + 6) // LED1 P1.15
// #define PIN_LED1 (0 + 6) // LED1 P1.15
// RGB NeoPixel LED2
//#define PIN_LED1 (0 + 8) Red
//#define PIN_LED1 (32 + 9) Green
//#define PIN_LED1 (0 + 12) Blue
// #define PIN_LED1 (0 + 8) Red
// #define PIN_LED1 (32 + 9) Green
// #define PIN_LED1 (0 + 12) Blue
#define LED_BUILTIN PIN_LED1
#define LED_CONN PIN_LED2
@ -113,7 +113,7 @@ static const uint8_t SCK = PIN_SPI_SCK;
* eink display pins
*/
//#define PIN_EINK_EN (-1)
// #define PIN_EINK_EN (-1)
#define PIN_EINK_EN (0 + 6) // Turn on the Green built in LED
#define PIN_EINK_CS (32) // EPD_CS
#define PIN_EINK_BUSY (20) // EPD_BUSY
@ -140,7 +140,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define SX126X_RESET (32 + 15) // LORA_RESET P1.15
#define SX126X_TXEN (32 + 13) // TXEN P1.13 NiceRF 868 dont use
#define SX126X_RXEN (32 + 10) // RXEN P1.10 NiceRF 868 dont use
#define SX126X_E22
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#define PIN_GPS_EN (-1)
#define PIN_GPS_PPS (-1) // Pulse per second input from the GPS

View File

@ -73,7 +73,7 @@ static const uint8_t AREF = PIN_AREF;
*/
#define SPI_INTERFACES_COUNT 2
// here
//#define SPI_INTERFACES_COUNT 1
// #define SPI_INTERFACES_COUNT 1
#define PIN_SPI_MISO (0 + 31) // MISO P0.31
#define PIN_SPI_MOSI (0 + 30) // MOSI P0.30
@ -94,7 +94,7 @@ static const uint8_t SCK = PIN_SPI_SCK;
* eink display pins
*/
//#define PIN_EINK_EN (-1)
// #define PIN_EINK_EN (-1)
#define PIN_EINK_CS (0 + 3) // EPD_CS
#define PIN_EINK_BUSY (32 + 11) // EPD_BUSY
#define PIN_EINK_DC (32 + 13) // EPD_D/C
@ -118,8 +118,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define SX128X_CS (0 + 23)
#define SX128X_DIO1 (0 + 4)
#define SX128X_BUSY (0 + 7)
//#define SX128X_TXEN (32 + 9)
//#define SX128X_RXEN (0 + 12)
// #define SX128X_TXEN (32 + 9)
// #define SX128X_RXEN (0 + 12)
#define SX128X_RESET LORA_RESET
#define PIN_GPS_EN (-1)

View File

@ -96,8 +96,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define SX128X_CS (0 + 23)
#define SX128X_DIO1 (0 + 4)
#define SX128X_BUSY (0 + 7)
//#define SX128X_TXEN (32 + 9)
//#define SX128X_RXEN (0 + 12)
// #define SX128X_TXEN (32 + 9)
// #define SX128X_RXEN (0 + 12)
#define SX128X_RESET LORA_RESET
#define PIN_GPS_EN (-1)

View File

@ -23,7 +23,9 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY 10
#define SX126X_RESET LORA_RESET
#define SX126X_E22 // use DIO2 as RF switch
#define SX126X_DIO2_AS_RF_SWITCH // use DIO2 as RF switch
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#define HAS_GPS 0
#undef GPS_RX_PIN

View File

@ -27,11 +27,11 @@ static const uint8_t SCK = 21;
static const uint8_t MOSI = 38;
static const uint8_t SS = 17;
//#define SPI_MOSI (11)
//#define SPI_SCK (14)
//#define SPI_MISO (2)
//#define SPI_CS (13)
// #define SPI_MOSI (11)
// #define SPI_SCK (14)
// #define SPI_MISO (2)
// #define SPI_CS (13)
//#define SDCARD_CS SPI_CS
// #define SDCARD_CS SPI_CS
#endif /* Pins_Arduino_h */
#endif /* Pins_Arduino_h */

View File

@ -2,10 +2,10 @@
#undef GPS_RX_PIN
#undef GPS_TX_PIN
//#define HAS_SCREEN 0
// #define HAS_SCREEN 0
//#define HAS_SDCARD
//#define SDCARD_USE_SPI1
// #define HAS_SDCARD
// #define SDCARD_USE_SPI1
#define USE_SSD1306
#define I2C_SDA 12
@ -14,13 +14,13 @@
#define LED_PIN 46
#define LED_STATE_ON 0 // State when LED is litted
//#define BUTTON_PIN 15 // Pico OLED 1.3 User key 0 - removed User key 1 (17)
// #define BUTTON_PIN 15 // Pico OLED 1.3 User key 0 - removed User key 1 (17)
#define BUTTON_PIN 40
//#define BUTTON_PIN 0 // This is the BOOT button pad at the moment
//#define BUTTON_NEED_PULLUP
// #define BUTTON_PIN 0 // This is the BOOT button pad at the moment
// #define BUTTON_NEED_PULLUP
//#define USE_RF95 // RFM95/SX127x
// #define USE_RF95 // RFM95/SX127x
#undef RF95_SCK
#undef RF95_MISO
@ -43,10 +43,11 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_BUSY
#define SX126X_RESET LORA_RESET
#define SX126X_E22
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#endif
//#define USE_SX1280
// #define USE_SX1280
#ifdef USE_SX1280
#define RF95_MISO 1
#define RF95_SCK 3
@ -61,13 +62,13 @@
#define SX128X_RESET LORA_RESET
#endif
//#define USE_EINK
// #define USE_EINK
/*
* eink display pins
*/
//#define PIN_EINK_CS
//#define PIN_EINK_BUSY
//#define PIN_EINK_DC
//#define PIN_EINK_RES (-1)
//#define PIN_EINK_SCLK 3
//#define PIN_EINK_MOSI 4
// #define PIN_EINK_CS
// #define PIN_EINK_BUSY
// #define PIN_EINK_DC
// #define PIN_EINK_RES (-1)
// #define PIN_EINK_SCLK 3
// #define PIN_EINK_MOSI 4

View File

@ -31,10 +31,13 @@
// PINS FOR THE 900M22S
#define LORA_DIO1 26 // IRQ for SX1262/SX1268
#define LORA_DIO2 22 // BUSY for SX1262/SX1268
#define LORA_TXEN NOT_A_PIN // Input - RF switch TX control, connecting external MCU IO or DIO2, valid in high level
#define LORA_RXEN 17 // Input - RF switch RX control, connecting external MCU IO, valid in high level
#define LORA_DIO1 26 // IRQ for SX1262/SX1268
#define LORA_DIO2 22 // BUSY for SX1262/SX1268
// NOT_A_PIN is treated as RADIOLIB_NC due to how they are defined, best to use RADIOLIB_NC directly
#define LORA_TXEN RADIOLIB_NC // Input - RF switch TX control, connecting external MCU IO or DIO2, valid in high level
// E22_TXEN_CONNECTED_TO_DIO2 wasn't defined, so RXEN wasn't controlled. Commented it out to maintain behavior, but shouldn't be.
// Need to comment out defining SX126X_RXEN as LORA_RXEN too
// #define LORA_RXEN 17 // Input - RF switch RX control, connecting external MCU IO, valid in high level
#undef RF95_NSS
#define RF95_NSS 16
#define SX126X_BUSY 22
@ -53,7 +56,7 @@
*/
// RX/TX for RFM95/SX127x
#define RF95_RXEN LORA_RXEN
// #define RF95_RXEN LORA_RXEN
#define RF95_TXEN LORA_TXEN
// #define RF95_TCXO <GPIO#>
@ -61,12 +64,13 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_RESET LORA_RESET
#define SX126X_RXEN LORA_RXEN
// #define SX126X_RXEN LORA_RXEN
#define SX126X_TXEN LORA_TXEN
// supported modules list
//#define USE_RF95 // RFM95/SX127x
// #define USE_RF95 // RFM95/SX127x
#define USE_SX1262
//#define USE_SX1268
//#define USE_LLCC68
#define SX126X_E22
// #define USE_SX1268
// #define USE_LLCC68
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8

View File

@ -37,8 +37,9 @@
#define SX126X_RESET LORA_RESET
#define SX126X_RXEN 14
#define SX126X_TXEN RADIOLIB_NC
#define E22_TXEN_CONNECTED_TO_DIO2 1
#define SX126X_DIO2_AS_RF_SWITCH
// Set lora.tx_power to 13 for Hydra or other E22 900M30S target due to PA
#define SX126X_MAX_POWER 13
#define SX126X_E22
#define SX126X_DIO3_TCXO_VOLTAGE 1.8

View File

@ -52,5 +52,5 @@
#ifdef EBYTE_E22
// Internally the TTGO module hooks the SX126x-DIO2 in to control the TX/RX switch
// (which is the default for the sx1262interface code)
#define SX126X_E22
#endif
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#endif

View File

@ -53,5 +53,5 @@
#ifdef EBYTE_E22
// Internally the TTGO module hooks the SX126x-DIO2 in to control the TX/RX switch
// (which is the default for the sx1262interface code)
#define SX126X_E22
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#endif

View File

@ -105,7 +105,7 @@ extern "C" {
#ifdef EBYTE_E22
// Internally the TTGO module hooks the SX126x-DIO2 in to control the TX/RX switch
// (which is the default for the sx1262interface code)
#define SX126X_E22
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#endif
#ifdef __cplusplus

View File

@ -0,0 +1,32 @@
#ifndef Pins_Arduino_h
#define Pins_Arduino_h
#include <stdint.h>
#define EXTERNAL_NUM_INTERRUPTS 22
#define NUM_DIGITAL_PINS 22
#define NUM_ANALOG_INPUTS 6
#define analogInputToDigitalPin(p) (((p) < NUM_ANALOG_INPUTS) ? (esp32_adc2gpio[(p)]) : -1)
#define digitalPinToInterrupt(p) (((p) < NUM_DIGITAL_PINS) ? (p) : -1)
#define digitalPinHasPWM(p) (p < EXTERNAL_NUM_INTERRUPTS)
static const uint8_t TX = 21;
static const uint8_t RX = 20;
static const uint8_t SDA = 1;
static const uint8_t SCL = 0;
static const uint8_t SS = 8;
static const uint8_t MOSI = 7;
static const uint8_t MISO = 6;
static const uint8_t SCK = 10;
static const uint8_t A0 = 0;
static const uint8_t A1 = 1;
static const uint8_t A2 = 2;
static const uint8_t A3 = 3;
static const uint8_t A4 = 4;
static const uint8_t A5 = 5;
#endif /* Pins_Arduino_h */

View File

@ -0,0 +1,12 @@
[env:heltec-ht62-esp32c3-sx1262]
extends = esp32c3_base
board = esp32-c3-devkitm-1
board_level = extra
build_flags =
${esp32_base.build_flags}
-D HELTEC_HT62
-I variants/heltec_esp32c3
monitor_speed = 115200
upload_protocol = esptool
upload_port = /dev/ttyUSB0
upload_speed = 921600

View File

@ -0,0 +1,37 @@
#define I2C_SDA 1
#define I2C_SCL 0
#define BUTTON_PIN 9
#define BUTTON_NEED_PULLUP
// LED flashes brighter
// https://resource.heltec.cn/download/HT-CT62/HT-CT62_Reference_Design.pdf
#define LED_PIN 18 // LED
#define LED_INVERTED 1
#define HAS_SCREEN 0
#define HAS_GPS 0
#undef GPS_RX_PIN
#undef GPS_TX_PIN
#undef RF95_SCK
#undef RF95_MISO
#undef RF95_MOSI
#undef RF95_NSS
#define USE_SX1262
#define RF95_SCK 10
#define RF95_MISO 6
#define RF95_MOSI 7
#define RF95_NSS 8
#define LORA_DIO0 RADIOLIB_NC
#define LORA_RESET 5
#define LORA_DIO1 3
#define LORA_DIO2 RADIOLIB_NC
#define LORA_BUSY 4
#define SX126X_CS RF95_NSS
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_BUSY
#define SX126X_RESET LORA_RESET
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8

View File

@ -11,8 +11,6 @@
#define VEXT_ENABLE Vext // active low, powers the oled display and the lora antenna boost
#define BUTTON_PIN 0
#define PIN_GPS_EN 46 // GPS power enable pin
#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC1_GPIO1_CHANNEL
#define ADC_ATTENUATION ADC_ATTEN_DB_2_5 // lower dB for high resistance voltage divider
@ -35,4 +33,6 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_DIO2
#define SX126X_RESET LORA_RESET
#define SX126X_E22
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8

View File

@ -40,4 +40,6 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_DIO2
#define SX126X_RESET LORA_RESET
#define SX126X_E22
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8

View File

@ -5,6 +5,7 @@ upload_protocol = esp-builtin
build_flags =
${esp32s3_base.build_flags} -I variants/heltec_wireless_tracker
-DGPS_POWER_TOGGLE
lib_deps =
${esp32s3_base.lib_deps}

View File

@ -38,6 +38,8 @@
#define PIN_GPS_RESET 35
#define PIN_GPS_PPS 36
#define VGNSS_CTRL 37 // Heltec Tracker needs this pulled low for GPS
#define PIN_GPS_EN VGNSS_CTRL
#define GPS_EN_ACTIVE LOW
#define GPS_RESET_MODE LOW
#define GPS_UC6580
@ -57,4 +59,6 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_DIO2
#define SX126X_RESET LORA_RESET
#define SX126X_E22
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8

View File

@ -32,4 +32,6 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_DIO2
#define SX126X_RESET LORA_RESET
#define SX126X_E22
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8

View File

@ -28,7 +28,7 @@
#define USE_LFXO
//#define USE_SEGGER
// #define USE_SEGGER
// Number of pins defined in PinDescription array
#define PINS_COUNT (16)
@ -88,6 +88,7 @@
#define BATTERY_PIN 3
#define ADC_MULTIPLIER 1.436
#define SX126X_E22 // Not really an E22 but this board clones using DIO3 for tcxo control
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8 // Not really an E22 but this board clones using DIO3 for tcxo control
#endif

View File

@ -134,7 +134,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define SX126X_TXEN (31)
#define SX126X_POWER_EN \
(15) // FIXME, see warning hre https://github.com/BigCorvus/SX1262-LoRa-BLE-Relay/blob/master/LORA_RELAY_NRF52840.ino
#define SX126X_E22 // Indicates this SX1262 is inside of an ebyte E22 module and special config should be done for that
// Indicates this SX1262 is inside of an ebyte E22 module and special config should be done for that
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#define ST7735_RESET (11) // Output
#define ST7735_CS (12)

View File

@ -154,7 +154,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define SX126X_TXEN (31)
#define SX126X_POWER_EN \
(15) // FIXME, see warning hre https://github.com/BigCorvus/SX1262-LoRa-BLE-Relay/blob/master/LORA_RELAY_NRF52840.ino
#define SX126X_E22 // Indicates this SX1262 is inside of an ebyte E22 module and special config should be done for that
// Indicates this SX1262 is inside of an ebyte E22 module and special config should be done for that
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
// ST7565 SPI
#define ST7735_RESET (11) // Output
@ -164,8 +165,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
#define ST7735_SDA (39) // actually spi MOSI
#define ST7735_SCK (37) // actually spi clk
#define PIN_GPS_WAKE 36 // Just kill GPS power when we want it to sleep? FIXME
#define GPS_WAKE_ACTIVE 0 // GPS Power output is active low
#define PIN_GPS_EN 36 // Just kill GPS power when we want it to sleep? FIXME
#define GPS_EN_ACTIVE 0 // GPS Power output is active low
// #define LORA_DISABLE_SENDING // The board can brownout during lora TX if you don't have a battery connected. Disable sending
// to allow USB power only based debugging

View File

@ -4,7 +4,7 @@
#define BUTTON_PIN 3 // M5Stack STAMP C3 built in button
#define BUTTON_NEED_PULLUP
//#define HAS_SCREEN 0
// #define HAS_SCREEN 0
#define HAS_GPS 0
#undef GPS_RX_PIN
#undef GPS_TX_PIN
@ -28,45 +28,46 @@
// WaveShare Core1262-868M OK
// https://www.waveshare.com/wiki/Core1262-868M
//#define USE_SX1262
//#define RF95_SCK 4
//#define RF95_MISO 5
//#define RF95_MOSI 6
//#define RF95_NSS 7
//#define LORA_DIO0 RADIOLIB_NC
//#define LORA_RESET 8
//#define LORA_DIO1 10
//#define LORA_DIO2 RADIOLIB_NC
//#define LORA_BUSY 18
//#define SX126X_CS RF95_NSS
//#define SX126X_DIO1 LORA_DIO1
//#define SX126X_BUSY LORA_BUSY
//#define SX126X_RESET LORA_RESET
//#define SX126X_E22
// #define USE_SX1262
// #define RF95_SCK 4
// #define RF95_MISO 5
// #define RF95_MOSI 6
// #define RF95_NSS 7
// #define LORA_DIO0 RADIOLIB_NC
// #define LORA_RESET 8
// #define LORA_DIO1 10
// #define LORA_DIO2 RADIOLIB_NC
// #define LORA_BUSY 18
// #define SX126X_CS RF95_NSS
// #define SX126X_DIO1 LORA_DIO1
// #define SX126X_BUSY LORA_BUSY
// #define SX126X_RESET LORA_RESET
// #define SX126X_DIO2_AS_RF_SWITCH
// #define SX126X_DIO3_TCXO_VOLTAGE 1.8
// SX128X 2.4 Ghz LoRa module Not OK - RadioLib issue ? still to confirm
//#define USE_SX1280
//#define RF95_SCK 4
//#define RF95_MISO 5
//#define RF95_MOSI 6
//#define RF95_NSS 7
//#define LORA_DIO0 -1
//#define LORA_DIO1 10
//#define LORA_DIO2 21
//#define LORA_RESET 8
//#define LORA_BUSY 1
//#define SX128X_CS RF95_NSS
//#define SX128X_DIO1 LORA_DIO1
//#define SX128X_BUSY LORA_BUSY
//#define SX128X_RESET LORA_RESET
//#define SX128X_MAX_POWER 10
// #define USE_SX1280
// #define RF95_SCK 4
// #define RF95_MISO 5
// #define RF95_MOSI 6
// #define RF95_NSS 7
// #define LORA_DIO0 -1
// #define LORA_DIO1 10
// #define LORA_DIO2 21
// #define LORA_RESET 8
// #define LORA_BUSY 1
// #define SX128X_CS RF95_NSS
// #define SX128X_DIO1 LORA_DIO1
// #define SX128X_BUSY LORA_BUSY
// #define SX128X_RESET LORA_RESET
// #define SX128X_MAX_POWER 10
// Not yet tested
//#define USE_EINK
//#define PIN_EINK_EN -1 // N/C
//#define PIN_EINK_CS 9 // EPD_CS
//#define PIN_EINK_BUSY 18 // EPD_BUSY
//#define PIN_EINK_DC 19 // EPD_D/C
//#define PIN_EINK_RES -1 // Connected but not needed
//#define PIN_EINK_SCLK 4 // EPD_SCLK
//#define PIN_EINK_MOSI 6 // EPD_MOSI
// #define USE_EINK
// #define PIN_EINK_EN -1 // N/C
// #define PIN_EINK_CS 9 // EPD_CS
// #define PIN_EINK_BUSY 18 // EPD_BUSY
// #define PIN_EINK_DC 19 // EPD_D/C
// #define PIN_EINK_RES -1 // Connected but not needed
// #define PIN_EINK_SCLK 4 // EPD_SCLK
// #define PIN_EINK_MOSI 6 // EPD_MOSI

View File

@ -4,7 +4,7 @@
#define I2C_SCL 22
// #define BUTTON_PIN 39 // 38, 37
//#define BUTTON_PIN 0
// #define BUTTON_PIN 0
#define BUTTON_NEED_PULLUP
// #define EXT_NOTIFY_OUT 13 // Default pin to use for Ext Notify Plugin.

View File

@ -3,8 +3,8 @@
#define I2C_SCL 22
// 7-07-2023 Or enable Secondary I2C Bus
//#define I2C_SDA1 32
//#define I2C_SCL1 33
// #define I2C_SDA1 32
// #define I2C_SCL1 33
#define HAS_GPS 1
#undef GPS_RX_PIN
@ -39,7 +39,7 @@
#undef RF95_MOSI
#undef RF95_NSS
#define USE_RF95
//#define USE_SX1280
// #define USE_SX1280
#ifdef USE_RF95
#define RF95_SCK 18

View File

@ -64,7 +64,7 @@ extern "C" {
* Buttons
*/
//#define PIN_BUTTON1 9 // Pin for button on E-ink button module or IO expansion
// #define PIN_BUTTON1 9 // Pin for button on E-ink button module or IO expansion
#define BUTTON_NEED_PULLUP
#define PIN_BUTTON2 12
#define PIN_BUTTON3 24
@ -191,7 +191,9 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG
// #define SX126X_TXEN (39)
// #define SX126X_RXEN (37)
#define SX126X_POWER_EN (37)
#define SX126X_E22 // DIO2 controlls an antenna switch and the TCXO voltage is controlled by DIO3
#define SX126X_DIO2_AS_RF_SWITCH // DIO2 controlls an antenna switch and the TCXO voltage is controlled by DIO3
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#define PIN_GPS_RESET (34) // Must be P1.02
// #define PIN_GPS_EN
@ -220,7 +222,7 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG
#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB
#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x)
//#define HAS_RTC 1
// #define HAS_RTC 1
#define HAS_ETHERNET 1
@ -237,4 +239,4 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG
* Arduino objects - C++ only
*----------------------------------------------------------------------------*/
#endif
#endif

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