Compare commits

...

42 Commits

Author SHA1 Message Date
Ben Meadors
8255128eae Trunk finally spilled the beans about what it's upset about 2023-09-09 19:40:57 -05:00
Ric In New Mexico
d7a98519f4 Update variant.h (#2778)
* Update variant.h

Add second i2c channel on external connector for Station G1

* Create trunk-check.yml

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2023-09-09 19:37:35 -05:00
github-actions[bot]
e256520336 [create-pull-request] automated change (#2782)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2023-09-08 14:34:58 -05:00
Ben Meadors
fcf798df98 Experiment with moving gps init (#2780)
* Move it move it

* Moving to the end of the main setup method

* NimBLE version
2023-09-07 16:01:35 -05:00
Ben Meadors
dcdf9b64de Ambient lighting (#2779)
* This was already defined and throwing a ton of warnings

* Ambient lighting module feature

* Use local instance type
2023-09-07 12:24:47 -05:00
Jonathan Bennett
fd563e41f1 Add ubx-cfg-rxm and cfg-pm2 for ublock 6 powersave (#2777) 2023-09-07 12:24:21 -05:00
Jonathan Bennett
0fa3685161 Fix crash in GPS setup when GPS is disabled 2023-09-06 12:38:58 -05:00
code8buster
899f9dd7bf Merge pull request #2775 from GUVWAF/disabledNeighbor
Only update neighbors when module is enabled
2023-09-05 23:43:09 +00:00
GUVWAF
9af4ecf48f Remove unnecessary line when disabled 2023-09-05 21:42:39 +02:00
GUVWAF
cfb6a1394c Only update neighbors when module is enabled 2023-09-05 19:56:42 +02:00
code8buster
1254031f7d Merge pull request #2772 from meshtastic/ubx-pmreq
UBX-RXM-PMREQ soft-off implemented
2023-09-05 17:15:12 +00:00
code8buster
c91e306659 Move packet scratch declaration to header 2023-09-05 11:59:34 -04:00
code8buster
4ff343b20f no byte... just 8 unsigned bits please 2023-09-05 00:32:53 -04:00
code8buster
134fc75b67 UBX-RXM-PMREQ soft-off implemented 2023-09-05 00:26:42 -04:00
Ben Meadors
fb23e479ac Update ESP32 platform (#2770) 2023-09-04 20:20:20 -05:00
github-actions[bot]
5a61695016 [create-pull-request] automated change (#2769)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2023-09-04 19:45:46 -05:00
github-actions[bot]
3bcab0e223 [create-pull-request] automated change (#2768)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2023-09-04 18:38:58 -05:00
GUVWAF
17617ce031 Fix possible memory leak in NeighborInfo Module (#2765)
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2023-09-04 18:38:16 -05:00
Jonathan Bennett
97f0c734e0 Fix Neighborinfo crash
neighbors object wasn't initialized when module disabled, this
initializes it to a safe, empty object.
2023-09-04 18:15:27 -05:00
Jonathan Bennett
e943fffe8c GPS fixes
Work aroung Serial reset issue on ESP32
Don't send unsupported command to G60xx GPS
2023-09-04 15:00:05 -05:00
tropho23
ffcb131171 GPS toggle for RAK4631 (patch 2 of 2) (#2764)
* Added triple-press GPS toggle button changes

* Revert edits to extensions.json

* comma'd

* Update variant.h

Added the line:

// Define pin to enable GPS toggle (set GPIO to LOW) via user button triple press
#define PIN_GPS_EN 34 // GPS power enable pin

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
Co-authored-by: code8buster <communismisgreat@national.shitposting.agency>
2023-09-04 13:17:01 -05:00
tropho23
bb1fe7cad3 GPS toggle for RAK4631 (patch 1 of 2) (#2763)
* Added triple-press GPS toggle button changes

* Revert edits to extensions.json

* comma'd

* Update platformio.ini

Added line:

-DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely.

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
Co-authored-by: code8buster <communismisgreat@national.shitposting.agency>
2023-09-04 13:16:39 -05:00
Ben Meadors
ad40493a39 Add speed, heading, and DOP to default position flags (#2759)
* Add speed and heading

* Add DOP
2023-09-04 06:46:27 -05:00
Jonathan Bennett
ac62330e1c Found lost byte dropped from moduleinfo
Attempt to fix CFG-GNSS for neo-6m
2023-09-03 22:38:03 -05:00
code8buster
53f6a43661 Merge pull request #2752 from meshtastic/nmea-rate
Adds GPS Serial Speed scanning, fixes ublox GNSS setup errors
2023-09-03 21:57:51 +00:00
Jonathan Bennett
7ad94da1c6 Add more to GPS_DEBUG and fix ubx7 CFG-GNSS 2023-09-03 16:20:01 -05:00
Jonathan Bennett
ecdb75aae0 Correct UBX-CFG-PMS message 2023-09-03 02:16:29 -05:00
Jonathan Bennett
7c98445ca3 Cleanup in prep for commiting
Fix some compilation warnings
gate debug code behind GPS_DEBUG
minor fix in u-blox protocol detection
Begin to gate GPS messages based on protover
2023-09-03 01:50:11 -05:00
Jonathan Bennett
b21368ecfa Add delay and debug code for GPS probe 2023-09-02 20:35:38 -05:00
Jonathan Bennett
1a178c7d33 Add check for GPS Frame Errors message 2023-09-02 04:29:48 -05:00
Jonathan Bennett
5d6f0ea6c4 Fix possible edge case in GPS detection 2023-09-01 16:24:28 -05:00
Ben Meadors
5bd861f3d8 Merge branch 'master' into nmea-rate 2023-09-01 15:08:32 -05:00
GUVWAF
6d93fab495 Add neighbor IDs to MQTT JSON (#2756)
* Add neighbor IDs to JSON

* Limit #neighbors to what we can actually save

* Put neighbor IDs in an array

* Add SNR to neighbors in nested objects
2023-09-01 14:35:57 -05:00
Jonathan Bennett
6803fd7949 More fixes for GPS chips with unexpected baud 2023-09-01 12:11:39 -05:00
Jonathan Bennett
a61f969773 Increase GPS detection timeout slightly 2023-08-31 22:19:50 -05:00
Jonathan Bennett
79cfc4b725 Avoid Serial output mangling with RTOS. 2023-08-31 20:40:01 -05:00
Jonathan Bennett
cf762bbd42 Cut down delay times for GPS probe and init 2023-08-31 20:39:23 -05:00
code8buster
3d2c419d0d Remove leftover debug msg 2023-08-30 16:24:56 -04:00
Jonathan Bennett
903f619609 Add GPS serial speed scan 2023-08-28 19:01:14 -05:00
Jonathan Bennett
2e3f762d3d Catch a nullptr return rather than crash 2023-08-28 04:05:45 -05:00
Jonathan Bennett
a42266f74b GPS: Fix checksum and remove spurious returns 2023-08-28 04:05:45 -05:00
github-actions[bot]
a605c69eb4 [create-pull-request] automated change (#2748)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2023-08-26 07:36:04 -05:00
26 changed files with 653 additions and 235 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

View File

@@ -1,7 +1,7 @@
; Common settings for ESP targes, mixin with extends = esp32_base ; Common settings for ESP targes, mixin with extends = esp32_base
[esp32_base] [esp32_base]
extends = arduino_base extends = arduino_base
platform = platformio/espressif32@^6.3.2 platform = platformio/espressif32@^6.4.0
build_src_filter = build_src_filter =
${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/stm32wl> -<platform/rp2040> -<mesh/eth/> ${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/stm32wl> -<platform/rp2040> -<mesh/eth/>
@@ -38,7 +38,7 @@ lib_deps =
${networking_base.lib_deps} ${networking_base.lib_deps}
${environmental_base.lib_deps} ${environmental_base.lib_deps}
https://github.com/meshtastic/esp32_https_server.git#23665b3adc080a311dcbb586ed5941b5f94d6ea2 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 jgromes/RadioLib@^6.1.0
https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6 https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6
https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f

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

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

View File

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

View File

@@ -12,6 +12,7 @@ SerialConsole *console;
void consoleInit() void consoleInit()
{ {
new SerialConsole(); // Must be dynamically allocated because we are now inheriting from thread 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, ...) void consolePrintf(const char *format, ...)

View File

@@ -3,6 +3,11 @@
#include "RTC.h" #include "RTC.h"
#include "configuration.h" #include "configuration.h"
#include "sleep.h" #include "sleep.h"
#include "ubx.h"
#ifdef ARCH_PORTDUINO
#include "meshUtils.h"
#endif
#ifndef GPS_RESET_MODE #ifndef GPS_RESET_MODE
#define GPS_RESET_MODE HIGH #define GPS_RESET_MODE HIGH
@@ -28,7 +33,7 @@ static bool didSerialInit;
struct uBloxGnssModelInfo info; struct uBloxGnssModelInfo info;
uint8_t uBloxProtocolVersion; uint8_t uBloxProtocolVersion;
void GPS::UBXChecksum(byte *message, size_t length) void GPS::UBXChecksum(uint8_t *message, size_t length)
{ {
uint8_t CK_A = 0, CK_B = 0; uint8_t CK_A = 0, CK_B = 0;
@@ -43,13 +48,71 @@ void GPS::UBXChecksum(byte *message, size_t length)
message[length - 1] = CK_B; message[length - 1] = CK_B;
} }
bool GPS::getACK(uint8_t class_id, uint8_t msg_id) // Function to create a ublox packet for editing in memory
uint8_t GPS::makeUBXPacket(uint8_t class_id, uint8_t msg_id, uint8_t payload_size, const uint8_t *msg)
{
// Construct the UBX packet
UBXscratch[0] = 0xB5; // header
UBXscratch[1] = 0x62; // header
UBXscratch[2] = class_id; // class
UBXscratch[3] = msg_id; // id
UBXscratch[4] = payload_size; // length
UBXscratch[5] = 0x00;
UBXscratch[6 + payload_size] = 0x00; // CK_A
UBXscratch[7 + payload_size] = 0x00; // CK_B
for (int i = 0; i < payload_size; i++) {
UBXscratch[6 + i] = pgm_read_byte(&msg[i]);
}
UBXChecksum(UBXscratch, (payload_size + 8));
return (payload_size + 8);
}
GPS_RESPONSE GPS::getACK(const char *message, uint32_t waitMillis)
{
uint8_t buffer[768] = {0};
uint8_t b;
int bytesRead = 0;
uint32_t startTimeout = millis() + waitMillis;
while (millis() < startTimeout) {
if (_serial_gps->available()) {
b = _serial_gps->read();
buffer[bytesRead] = b;
bytesRead++;
if ((bytesRead == 767) || (b == '\r')) {
if (strnstr((char *)buffer, message, bytesRead) != nullptr) {
#ifdef GPS_DEBUG
buffer[bytesRead] = '\0';
LOG_DEBUG("%s\r", (char *)buffer);
#endif
return GNSS_RESPONSE_OK;
} else {
#ifdef GPS_DEBUG
buffer[bytesRead] = '\0';
LOG_INFO("Bytes read:%s\n", (char *)buffer);
#endif
bytesRead = 0;
}
}
}
}
#ifdef GPS_DEBUG
buffer[bytesRead] = '\0';
LOG_INFO("Bytes read:%s\n", (char *)buffer);
#endif
return GNSS_RESPONSE_NONE;
}
GPS_RESPONSE GPS::getACK(uint8_t class_id, uint8_t msg_id, uint32_t waitMillis)
{ {
uint8_t b; uint8_t b;
uint8_t ack = 0; uint8_t ack = 0;
const uint8_t ackP[2] = {class_id, msg_id}; const uint8_t ackP[2] = {class_id, msg_id};
uint8_t buf[10] = {0xB5, 0x62, 0x05, 0x01, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00}; uint8_t buf[10] = {0xB5, 0x62, 0x05, 0x01, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00};
unsigned long startTime = millis(); uint32_t startTime = millis();
const char frame_errors[] = "More than 100 frame errors";
int sCounter = 0;
for (int j = 2; j < 6; j++) { for (int j = 2; j < 6; j++) {
buf[8] += buf[j]; buf[8] += buf[j];
@@ -62,28 +125,46 @@ bool GPS::getACK(uint8_t class_id, uint8_t msg_id)
buf[9] += buf[8]; buf[9] += buf[8];
} }
while (1) { while (millis() - startTime < waitMillis) {
if (ack > 9) { if (ack > 9) {
// LOG_INFO("Got ACK for class %02X message %02X\n", class_id, msg_id); #ifdef GPS_DEBUG
return true; // ACK received LOG_DEBUG("\n");
} LOG_INFO("Got ACK for class %02X message %02X in %d millis.\n", class_id, msg_id, millis() - startTime);
if (millis() - startTime > 3000) { #endif
LOG_WARN("No response for class %02X message %02X\n", class_id, msg_id); return GNSS_RESPONSE_OK; // ACK received
return false; // No response received within 3 seconds
} }
if (_serial_gps->available()) { if (_serial_gps->available()) {
b = _serial_gps->read(); b = _serial_gps->read();
if (b == frame_errors[sCounter]) {
sCounter++;
if (sCounter == 26) {
return GNSS_RESPONSE_FRAME_ERRORS;
}
} else {
sCounter = 0;
}
#ifdef GPS_DEBUG
LOG_DEBUG("%02X", b);
#endif
if (b == buf[ack]) { if (b == buf[ack]) {
ack++; ack++;
} else { } else {
ack = 0; // Reset the acknowledgement counter if (ack == 3 && b == 0x00) { // UBX-ACK-NAK message
if (buf[3] == 0x00) { // UBX-ACK-NAK message #ifdef GPS_DEBUG
LOG_DEBUG("\n");
#endif
LOG_WARN("Got NAK for class %02X message %02X\n", class_id, msg_id); LOG_WARN("Got NAK for class %02X message %02X\n", class_id, msg_id);
return false; // NAK received return GNSS_RESPONSE_NAK; // NAK received
} }
ack = 0; // Reset the acknowledgement counter
} }
} }
} }
#ifdef GPS_DEBUG
LOG_DEBUG("\n");
LOG_WARN("No response for class %02X message %02X\n", class_id, msg_id);
#endif
return GNSS_RESPONSE_NONE; // No response received within timeout
} }
/** /**
@@ -95,14 +176,14 @@ bool GPS::getACK(uint8_t class_id, uint8_t msg_id)
* @param requestedID: request message ID constant * @param requestedID: request message ID constant
* @retval length of payload message * @retval length of payload message
*/ */
int GPS::getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t requestedID) int GPS::getACK(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t requestedID, uint32_t waitMillis)
{ {
uint16_t ubxFrameCounter = 0; uint16_t ubxFrameCounter = 0;
uint32_t startTime = millis(); uint32_t startTime = millis();
uint16_t needRead; uint16_t needRead;
while (millis() - startTime < 1200) { while (millis() - startTime < waitMillis) {
while (_serial_gps->available()) { if (_serial_gps->available()) {
int c = _serial_gps->read(); int c = _serial_gps->read();
switch (ubxFrameCounter) { switch (ubxFrameCounter) {
case 0: case 0:
@@ -144,8 +225,6 @@ int GPS::getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
// Payload length msb // Payload length msb
needRead |= (c << 8); needRead |= (c << 8);
ubxFrameCounter++; ubxFrameCounter++;
break;
case 6:
// Check for buffer overflow // Check for buffer overflow
if (needRead >= size) { if (needRead >= size) {
ubxFrameCounter = 0; ubxFrameCounter = 0;
@@ -155,6 +234,10 @@ int GPS::getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
ubxFrameCounter = 0; ubxFrameCounter = 0;
} else { } else {
// return payload length // return payload length
#ifdef GPS_DEBUG
LOG_INFO("Got ACK for class %02X message %02X in %d millis.\n", requestedClass, requestedID,
millis() - startTime);
#endif
return needRead; return needRead;
} }
break; break;
@@ -164,6 +247,7 @@ int GPS::getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
} }
} }
} }
// LOG_WARN("No response for class %02X message %02X\n", requestedClass, requestedID);
return 0; return 0;
} }
@@ -188,8 +272,8 @@ bool GPS::setupGPS()
config.position.tx_gpio = GPS_TX_PIN; config.position.tx_gpio = GPS_TX_PIN;
#endif #endif
//#define BAUD_RATE 115200 // #define BAUD_RATE 115200
// ESP32 has a special set of parameters vs other arduino ports // ESP32 has a special set of parameters vs other arduino ports
#if defined(ARCH_ESP32) #if defined(ARCH_ESP32)
if (config.position.rx_gpio) { if (config.position.rx_gpio) {
LOG_DEBUG("Using GPIO%d for GPS RX\n", config.position.rx_gpio); LOG_DEBUG("Using GPIO%d for GPS RX\n", config.position.rx_gpio);
@@ -203,7 +287,21 @@ bool GPS::setupGPS()
/* /*
* T-Beam-S3-Core will be preset to use gps Probe here, and other boards will not be changed first * T-Beam-S3-Core will be preset to use gps Probe here, and other boards will not be changed first
*/ */
gnssModel = probe(); #if defined(GPS_UC6580)
_serial_gps->updateBaudRate(115200);
gnssModel = GNSS_MODEL_UC6850;
#else
for (int serialSpeed : {9600, 4800, 38400, 57600, 115200}) {
LOG_DEBUG("Probing for GPS at %d \n", serialSpeed);
gnssModel = probe(serialSpeed);
if (gnssModel != GNSS_MODEL_UNKNOWN)
break;
}
if (gnssModel == GNSS_MODEL_UNKNOWN) {
LOG_DEBUG("No GPS found, retrying at 9600 baud.\n");
gnssModel = probe(9600);
}
#endif
if (gnssModel == GNSS_MODEL_MTK) { if (gnssModel == GNSS_MODEL_MTK) {
/* /*
@@ -228,51 +326,93 @@ bool GPS::setupGPS()
_serial_gps->write("$CFGSYS,h15\r\n"); _serial_gps->write("$CFGSYS,h15\r\n");
delay(250); delay(250);
} else if (gnssModel == GNSS_MODEL_UBLOX) { } else if (gnssModel == GNSS_MODEL_UBLOX) {
/*
uint8_t buffer[768] = {0};
uint8_t _message_GNSS[8] = {0xb5, 0x62, // Sync message for UBX protocol
0x06, 0x3e, // Message class and ID (UBX-CFG-GNSS)
0x00, 0x00, // Length of payload (28 bytes)
0x00, 0x00};
UBXChecksum(_message_GNSS, sizeof(_message_GNSS));
// Send the message to the module
_serial_gps->write(_message_GNSS, sizeof(_message_GNSS));
int ackLen = getACK(buffer, sizeof(buffer), 0x06, 0x3e, 2000);
LOG_DEBUG("monver reply size = %d\n", ackLen);
LOG_DEBUG("Ack: ");
for (int i = 0; i < ackLen; i++) {
LOG_DEBUG("%02X", buffer[i]);
}
LOG_DEBUG("\n"); */
// Configure GNSS system to GPS+SBAS+GLONASS (Module may restart after this command) // Configure GNSS system to GPS+SBAS+GLONASS (Module may restart after this command)
// We need set it because by default it is GPS only, and we want to use GLONASS too // We need set it because by default it is GPS only, and we want to use GLONASS too
// Also we need SBAS for better accuracy and extra features // Also we need SBAS for better accuracy and extra features
// ToDo: Dynamic configure GNSS systems depending of LoRa region // ToDo: Dynamic configure GNSS systems depending of LoRa region
byte _message_GNSS[36] = {
0xb5, 0x62, // Sync message for UBX protocol
0x06, 0x3e, // Message class and ID (UBX-CFG-GNSS)
0x1c, 0x00, // Length of payload (28 bytes)
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
0x00, 0x00 // Checksum (to be calculated below)
};
// Calculate the checksum and update the message. if (strncmp(info.hwVersion, "00040007", 8) !=
UBXChecksum(_message_GNSS, sizeof(_message_GNSS)); 0) { // The original ublox 6 is GPS only and doesn't support the UBX-CFG-GNSS message
if (strncmp(info.hwVersion, "00070000", 8) == 0) { // Max7 seems to only support GPS *or* GLONASS
LOG_DEBUG("Setting GPS+SBAS\n");
uint8_t _message_GNSS[28] = {
0xb5, 0x62, // Sync message for UBX protocol
0x06, 0x3e, // Message class and ID (UBX-CFG-GNSS)
0x14, 0x00, // Length of payload (28 bytes)
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
0x00, 0x00 // Checksum (to be calculated below)
};
// Calculate the checksum and update the message.
UBXChecksum(_message_GNSS, sizeof(_message_GNSS));
// Send the message to the module
_serial_gps->write(_message_GNSS, sizeof(_message_GNSS));
} else {
uint8_t _message_GNSS[36] = {
0xb5, 0x62, // Sync message for UBX protocol
0x06, 0x3e, // Message class and ID (UBX-CFG-GNSS)
0x1c, 0x00, // Length of payload (28 bytes)
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
0x00, 0x00 // Checksum (to be calculated below)
};
// Calculate the checksum and update the message.
UBXChecksum(_message_GNSS, sizeof(_message_GNSS));
// Send the message to the module
_serial_gps->write(_message_GNSS, sizeof(_message_GNSS));
}
// Send the message to the module if (getACK(0x06, 0x3e, 800) == GNSS_RESPONSE_NAK) {
_serial_gps->write(_message_GNSS, sizeof(_message_GNSS)); // It's not critical if the module doesn't acknowledge this configuration.
// The module should operate adequately with its factory or previously saved settings.
if (!getACK(0x06, 0x3e)) { // It appears that there is a firmware bug in some GPS modules: When an attempt is made
// It's not critical if the module doesn't acknowledge this configuration. // to overwrite a saved state with identical values, no ACK/NAK is received, contrary to
// The module should operate adequately with its factory or previously saved settings. // what is specified in the Ublox documentation.
// It appears that there is a firmware bug in some GPS modules: When an attempt is made // There is also a possibility that the module may be GPS-only.
// to overwrite a saved state with identical values, no ACK/NAK is received, contrary to LOG_INFO("Unable to reconfigure GNSS - defaults maintained. Is this module GPS-only?\n");
// what is specified in the Ublox documentation. } else {
// There is also a possibility that the module may be GPS-only. if (strncmp(info.hwVersion, "00070000", 8) == 0) {
LOG_INFO("Unable to reconfigure GNSS - defaults maintained. Is this module GPS-only?\n"); LOG_INFO("GNSS configured for GPS+SBAS. Pause for 0.75s before sending next command.\n");
return true; } else {
} else { LOG_INFO("GNSS configured for GPS+SBAS+GLONASS. Pause for 0.75s before sending next command.\n");
LOG_INFO("GNSS configured for GPS+SBAS+GLONASS. Pause for 0.75s before sending next command.\n"); }
// Documentation say, we need wait atleast 0.5s after reconfiguration of GNSS module, before sending next commands // Documentation say, we need wait atleast 0.5s after reconfiguration of GNSS module, before sending next
delay(750); // commands
return true; delay(750);
}
} }
// Enable interference resistance, because we are using LoRa, WiFi and Bluetooth on same board, // Enable interference resistance, because we are using LoRa, WiFi and Bluetooth on same board,
// and we need to reduce interference from them // and we need to reduce interference from them
byte _message_JAM[16] = { uint8_t _message_JAM[16] = {
0xB5, 0x62, // UBX protocol sync characters 0xB5, 0x62, // UBX protocol sync characters
0x06, 0x39, // Message class and ID (UBX-CFG-ITFM) 0x06, 0x39, // Message class and ID (UBX-CFG-ITFM)
0x08, 0x00, // Length of payload (8 bytes) 0x08, 0x00, // Length of payload (8 bytes)
@@ -296,13 +436,12 @@ bool GPS::setupGPS()
// Send the message to the module // Send the message to the module
_serial_gps->write(_message_JAM, sizeof(_message_JAM)); _serial_gps->write(_message_JAM, sizeof(_message_JAM));
if (!getACK(0x06, 0x39)) { if (getACK(0x06, 0x39, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to enable interference resistance.\n"); LOG_WARN("Unable to enable interference resistance.\n");
return true;
} }
// Configure navigation engine expert settings: // Configure navigation engine expert settings:
byte _message_NAVX5[48] = { uint8_t _message_NAVX5[48] = {
0xb5, 0x62, // UBX protocol sync characters 0xb5, 0x62, // UBX protocol sync characters
0x06, 0x23, // Message class and ID (UBX-CFG-NAVX5) 0x06, 0x23, // Message class and ID (UBX-CFG-NAVX5)
0x28, 0x00, // Length of payload (40 bytes) 0x28, 0x00, // Length of payload (40 bytes)
@@ -342,32 +481,17 @@ bool GPS::setupGPS()
// Send the message to the module // Send the message to the module
_serial_gps->write(_message_NAVX5, sizeof(_message_NAVX5)); _serial_gps->write(_message_NAVX5, sizeof(_message_NAVX5));
if (!getACK(0x06, 0x23)) { if (getACK(0x06, 0x23, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to configure extra settings.\n"); LOG_WARN("Unable to configure extra settings.\n");
return true;
} }
/*
tips: NMEA Only should not be set here, otherwise initializing Ublox gnss module again after
setting will not output command messages in UART1, resulting in unrecognized module information
// Set the UART port to output NMEA only
byte _message_nmea[] = {0xB5, 0x62, 0x06, 0x00, 0x14, 0x00, 0x01, 0x00, 0x00, 0x00, 0xC0, 0x08, 0x00, 0x00,
0x80, 0x25, 0x00, 0x00, 0x07, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x91, 0xAF};
_serial_gps->write(_message_nmea, sizeof(_message_nmea));
if (!getACK(0x06, 0x00)) {
LOG_WARN("Unable to enable NMEA Mode.\n");
return true;
}
*/
// ublox-M10S can be compatible with UBLOX traditional protocol, so the following sentence settings are also valid // ublox-M10S can be compatible with UBLOX traditional protocol, so the following sentence settings are also valid
// Set GPS update rate to 1Hz // Set GPS update rate to 1Hz
// Lowering the update rate helps to save power. // Lowering the update rate helps to save power.
// Additionally, for some new modules like the M9/M10, an update rate lower than 5Hz // 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. // is recommended to avoid a known issue with satellites disappearing.
byte _message_1Hz[] = { uint8_t _message_1Hz[] = {
0xB5, 0x62, // UBX protocol sync characters 0xB5, 0x62, // UBX protocol sync characters
0x06, 0x08, // Message class and ID (UBX-CFG-RATE) 0x06, 0x08, // Message class and ID (UBX-CFG-RATE)
0x06, 0x00, // Length of payload (6 bytes) 0x06, 0x00, // Length of payload (6 bytes)
@@ -383,14 +507,13 @@ bool GPS::setupGPS()
// Send the message to the module // Send the message to the module
_serial_gps->write(_message_1Hz, sizeof(_message_1Hz)); _serial_gps->write(_message_1Hz, sizeof(_message_1Hz));
if (!getACK(0x06, 0x08)) { if (getACK(0x06, 0x08, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to set GPS update rate.\n"); LOG_WARN("Unable to set GPS update rate.\n");
return true;
} }
// Disable GGL. GGL - Geographic position (latitude and longitude), which provides the current geographical // Disable GGL. GGL - Geographic position (latitude and longitude), which provides the current geographical
// coordinates. // coordinates.
byte _message_GGL[] = { uint8_t _message_GGL[] = {
0xB5, 0x62, // UBX sync characters 0xB5, 0x62, // UBX sync characters
0x06, 0x01, // Message class and ID (UBX-CFG-MSG) 0x06, 0x01, // Message class and ID (UBX-CFG-MSG)
0x08, 0x00, // Length of payload (8 bytes) 0x08, 0x00, // Length of payload (8 bytes)
@@ -407,14 +530,13 @@ bool GPS::setupGPS()
// Send the message to the module // Send the message to the module
_serial_gps->write(_message_GGL, sizeof(_message_GGL)); _serial_gps->write(_message_GGL, sizeof(_message_GGL));
if (!getACK(0x06, 0x01)) { if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to disable NMEA GGL.\n"); LOG_WARN("Unable to disable NMEA GGL.\n");
return true;
} }
// Enable GSA. GSA - GPS DOP and active satellites, used for detailing the satellites used in the positioning and // Enable GSA. GSA - GPS DOP and active satellites, used for detailing the satellites used in the positioning and
// the DOP (Dilution of Precision) // the DOP (Dilution of Precision)
byte _message_GSA[] = { uint8_t _message_GSA[] = {
0xB5, 0x62, // UBX sync characters 0xB5, 0x62, // UBX sync characters
0x06, 0x01, // Message class and ID (UBX-CFG-MSG) 0x06, 0x01, // Message class and ID (UBX-CFG-MSG)
0x08, 0x00, // Length of payload (8 bytes) 0x08, 0x00, // Length of payload (8 bytes)
@@ -426,13 +548,12 @@ bool GPS::setupGPS()
}; };
UBXChecksum(_message_GSA, sizeof(_message_GSA)); UBXChecksum(_message_GSA, sizeof(_message_GSA));
_serial_gps->write(_message_GSA, sizeof(_message_GSA)); _serial_gps->write(_message_GSA, sizeof(_message_GSA));
if (!getACK(0x06, 0x01)) { if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to Enable NMEA GSA.\n"); LOG_WARN("Unable to Enable NMEA GSA.\n");
return true;
} }
// Disable GSV. GSV - Satellites in view, details the number and location of satellites in view. // Disable GSV. GSV - Satellites in view, details the number and location of satellites in view.
byte _message_GSV[] = { uint8_t _message_GSV[] = {
0xB5, 0x62, // UBX sync characters 0xB5, 0x62, // UBX sync characters
0x06, 0x01, // Message class and ID (UBX-CFG-MSG) 0x06, 0x01, // Message class and ID (UBX-CFG-MSG)
0x08, 0x00, // Length of payload (8 bytes) 0x08, 0x00, // Length of payload (8 bytes)
@@ -444,14 +565,13 @@ bool GPS::setupGPS()
}; };
UBXChecksum(_message_GSV, sizeof(_message_GSV)); UBXChecksum(_message_GSV, sizeof(_message_GSV));
_serial_gps->write(_message_GSV, sizeof(_message_GSV)); _serial_gps->write(_message_GSV, sizeof(_message_GSV));
if (!getACK(0x06, 0x01)) { if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to disable NMEA GSV.\n"); LOG_WARN("Unable to disable NMEA GSV.\n");
return true;
} }
// Disable VTG. VTG - Track made good and ground speed, which provides course and speed information relative to // Disable VTG. VTG - Track made good and ground speed, which provides course and speed information relative to
// the ground. // the ground.
byte _message_VTG[] = { uint8_t _message_VTG[] = {
0xB5, 0x62, // UBX sync characters 0xB5, 0x62, // UBX sync characters
0x06, 0x01, // Message class and ID (UBX-CFG-MSG) 0x06, 0x01, // Message class and ID (UBX-CFG-MSG)
0x08, 0x00, // Length of payload (8 bytes) 0x08, 0x00, // Length of payload (8 bytes)
@@ -463,13 +583,12 @@ bool GPS::setupGPS()
}; };
UBXChecksum(_message_VTG, sizeof(_message_VTG)); UBXChecksum(_message_VTG, sizeof(_message_VTG));
_serial_gps->write(_message_VTG, sizeof(_message_VTG)); _serial_gps->write(_message_VTG, sizeof(_message_VTG));
if (!getACK(0x06, 0x01)) { if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to disable NMEA VTG.\n"); LOG_WARN("Unable to disable NMEA VTG.\n");
return true;
} }
// Enable RMC. RMC - Recommended Minimum data, the essential gps pvt (position, velocity, time) data. // Enable RMC. RMC - Recommended Minimum data, the essential gps pvt (position, velocity, time) data.
byte _message_RMC[] = { uint8_t _message_RMC[] = {
0xB5, 0x62, // UBX sync characters 0xB5, 0x62, // UBX sync characters
0x06, 0x01, // Message class and ID (UBX-CFG-MSG) 0x06, 0x01, // Message class and ID (UBX-CFG-MSG)
0x08, 0x00, // Length of payload (8 bytes) 0x08, 0x00, // Length of payload (8 bytes)
@@ -481,13 +600,12 @@ bool GPS::setupGPS()
}; };
UBXChecksum(_message_RMC, sizeof(_message_RMC)); UBXChecksum(_message_RMC, sizeof(_message_RMC));
_serial_gps->write(_message_RMC, sizeof(_message_RMC)); _serial_gps->write(_message_RMC, sizeof(_message_RMC));
if (!getACK(0x06, 0x01)) { if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to enable NMEA RMC.\n"); LOG_WARN("Unable to enable NMEA RMC.\n");
return true;
} }
// Enable GGA. GGA - Global Positioning System Fix Data, which provides 3D location and accuracy data. // Enable GGA. GGA - Global Positioning System Fix Data, which provides 3D location and accuracy data.
byte _message_GGA[] = { uint8_t _message_GGA[] = {
0xB5, 0x62, // UBX sync characters 0xB5, 0x62, // UBX sync characters
0x06, 0x01, // Message class and ID (UBX-CFG-MSG) 0x06, 0x01, // Message class and ID (UBX-CFG-MSG)
0x08, 0x00, // Length of payload (8 bytes) 0x08, 0x00, // Length of payload (8 bytes)
@@ -499,9 +617,8 @@ bool GPS::setupGPS()
}; };
UBXChecksum(_message_GGA, sizeof(_message_GGA)); UBXChecksum(_message_GGA, sizeof(_message_GGA));
_serial_gps->write(_message_GGA, sizeof(_message_GGA)); _serial_gps->write(_message_GGA, sizeof(_message_GGA));
if (!getACK(0x06, 0x01)) { if (getACK(0x06, 0x01, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to enable NMEA GGA.\n"); LOG_WARN("Unable to enable NMEA GGA.\n");
return true;
} }
// The Power Management configuration allows the GPS module to operate in different power modes for optimized power // The Power Management configuration allows the GPS module to operate in different power modes for optimized power
@@ -517,29 +634,49 @@ bool GPS::setupGPS()
// set to Interval; otherwise, it must be set to '0'. The 'onTime' field specifies the duration of the ON phase and // 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 // must be smaller than the period. It is only valid when the powerSetupValue is set to Interval; otherwise, it must
// be set to '0'. // be set to '0'.
byte UBX_CFG_PMS[14] = { if (uBloxProtocolVersion >= 18) {
0xB5, 0x62, // UBX sync characters byte UBX_CFG_PMS[16] = {
0x06, 0x86, // Message class and ID (UBX-CFG-PMS) 0xB5, 0x62, // UBX sync characters
0x06, 0x00, // Length of payload (6 bytes) 0x06, 0x86, // Message class and ID (UBX-CFG-PMS)
0x00, // Version (0) 0x08, 0x00, // Length of payload (6 bytes)
0x03, // Power setup value 0x00, // Version (0)
0x00, 0x00, // period: not applicable, set to 0 0x03, // Power setup value
0x00, 0x00, // onTime: not applicable, set to 0 0x00, 0x00, // period: not applicable, set to 0
0x00, 0x00 // Placeholder for checksum, will be calculated next 0x00, 0x00, // onTime: not applicable, set to 0
}; 0x97, 0x6F, // reserved, generated by u-center
0x00, 0x00 // Placeholder for checksum, will be calculated next
};
// Calculate the checksum and update the message // Calculate the checksum and update the message
UBXChecksum(UBX_CFG_PMS, sizeof(UBX_CFG_PMS)); UBXChecksum(UBX_CFG_PMS, sizeof(UBX_CFG_PMS));
// Send the message to the module // Send the message to the module
_serial_gps->write(UBX_CFG_PMS, sizeof(UBX_CFG_PMS)); _serial_gps->write(UBX_CFG_PMS, sizeof(UBX_CFG_PMS));
if (!getACK(0x06, 0x86)) { if (getACK(0x06, 0x86, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to enable powersaving for GPS.\n"); LOG_WARN("Unable to enable powersaving for GPS.\n");
return true; }
} else {
if (strncmp(info.hwVersion, "00040007", 8) == 0) { // This PSM mode has only been tested on this hardware
int msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_PSM);
_serial_gps->write(UBXscratch, msglen);
if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to enable powersaving mode for GPS.\n");
}
msglen = makeUBXPacket(0x06, 0x3B, 44, _message_CFG_PM2);
_serial_gps->write(UBXscratch, msglen);
if (getACK(0x06, 0x3B, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to enable powersaving details for GPS.\n");
}
} else {
int msglen = makeUBXPacket(0x06, 0x11, 0x2, _message_CFG_RXM_ECO);
_serial_gps->write(UBXscratch, msglen);
if (getACK(0x06, 0x11, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to enable powersaving ECO mode for GPS.\n");
}
}
} }
// We need save configuration to flash to make our config changes persistent // We need save configuration to flash to make our config changes persistent
byte _message_SAVE[21] = { uint8_t _message_SAVE[21] = {
0xB5, 0x62, // UBX protocol header 0xB5, 0x62, // UBX protocol header
0x06, 0x09, // UBX class ID (Configuration Input Messages), message ID (UBX-CFG-CFG) 0x06, 0x09, // UBX class ID (Configuration Input Messages), message ID (UBX-CFG-CFG)
0x0D, 0x00, // Length of payload (13 bytes) 0x0D, 0x00, // Length of payload (13 bytes)
@@ -556,12 +693,10 @@ bool GPS::setupGPS()
// Send the message to the module // Send the message to the module
_serial_gps->write(_message_SAVE, sizeof(_message_SAVE)); _serial_gps->write(_message_SAVE, sizeof(_message_SAVE));
if (!getACK(0x06, 0x09)) { if (getACK(0x06, 0x09, 300) != GNSS_RESPONSE_OK) {
LOG_WARN("Unable to save GNSS module configuration.\n"); LOG_WARN("Unable to save GNSS module configuration.\n");
return true;
} else { } else {
LOG_INFO("GNSS module configuration saved!\n"); LOG_INFO("GNSS module configuration saved!\n");
return true;
} }
} }
} }
@@ -599,7 +734,6 @@ bool GPS::setup()
if (config.position.gps_enabled == false && config.position.fixed_position == false) { if (config.position.gps_enabled == false && config.position.fixed_position == false) {
setAwake(false); setAwake(false);
doGPSpowersave(false);
} }
return ok; return ok;
} }
@@ -675,6 +809,7 @@ void GPS::setAwake(bool on)
if (isAwake != on) { if (isAwake != on) {
LOG_DEBUG("WANT GPS=%d\n", on); LOG_DEBUG("WANT GPS=%d\n", on);
if (on) { if (on) {
clearBuffer(); // drop any old data waiting in the buffer
lastWakeStartMsec = millis(); lastWakeStartMsec = millis();
wake(); wake();
} else { } else {
@@ -854,52 +989,74 @@ int GPS::prepareDeepSleep(void *unused)
return 0; return 0;
} }
GnssModel_t GPS::probe() GnssModel_t GPS::probe(int serialSpeed)
{ {
memset(&info, 0, sizeof(struct uBloxGnssModelInfo)); #if defined(ARCH_NRF52) || defined(ARCH_PORTDUINO) || defined(ARCH_RP2040)
// return immediately if the model is set by the variant.h file _serial_gps->end();
//#ifdef GPS_UBLOX (unless it's a ublox, because we might want to know the module info! _serial_gps->begin(serialSpeed);
// return GNSS_MODEL_UBLOX; think about removing this macro and return)
#if defined(GPS_L76K)
return GNSS_MODEL_MTK;
#elif defined(GPS_UC6580)
_serial_gps->updateBaudRate(115200);
return GNSS_MODEL_UC6850;
#else #else
uint8_t buffer[384] = {0}; if (_serial_gps->baudRate() != serialSpeed) {
LOG_DEBUG("Setting Baud to %i\n", serialSpeed);
_serial_gps->updateBaudRate(serialSpeed);
}
#endif
#ifdef GPS_DEBUG
for (int i = 0; i < 20; i++) {
getACK("$GP", 200);
}
#endif
memset(&info, 0, sizeof(struct uBloxGnssModelInfo));
uint8_t buffer[768] = {0};
delay(100);
// Close all NMEA sentences , Only valid for MTK platform // Close all NMEA sentences , Only valid for MTK platform
_serial_gps->write("$PCAS03,0,0,0,0,0,0,0,0,0,0,,,0,0*02\r\n"); _serial_gps->write("$PCAS03,0,0,0,0,0,0,0,0,0,0,,,0,0*02\r\n");
delay(20); delay(20);
// Get version information // Get version information
clearBuffer();
_serial_gps->write("$PCAS06,0*1B\r\n"); _serial_gps->write("$PCAS06,0*1B\r\n");
uint32_t startTimeout = millis() + 500; if (getACK("$GPTXT,01,01,02,SW=", 500) == GNSS_RESPONSE_OK) {
while (millis() < startTimeout) { LOG_INFO("L76K GNSS init succeeded, using L76K GNSS Module\n");
if (_serial_gps->available()) { return GNSS_MODEL_MTK;
String ver = _serial_gps->readStringUntil('\r');
// Get module info , If the correct header is returned,
// it can be determined that it is the MTK chip
int index = ver.indexOf("$");
if (index != -1) {
ver = ver.substring(index);
if (ver.startsWith("$GPTXT,01,01,02,SW=")) {
LOG_INFO("L76K GNSS init succeeded, using L76K GNSS Module\n");
return GNSS_MODEL_MTK;
}
}
}
} }
uint8_t cfg_rate[] = {0xB5, 0x62, 0x06, 0x08, 0x00, 0x00, 0x0E, 0x30}; uint8_t cfg_rate[] = {0xB5, 0x62, 0x06, 0x08, 0x00, 0x00, 0x00, 0x00};
UBXChecksum(cfg_rate, sizeof(cfg_rate));
clearBuffer();
_serial_gps->write(cfg_rate, sizeof(cfg_rate)); _serial_gps->write(cfg_rate, sizeof(cfg_rate));
// Check that the returned response class and message ID are correct // Check that the returned response class and message ID are correct
if (!getAck(buffer, 384, 0x06, 0x08)) { GPS_RESPONSE response = getACK(0x06, 0x08, 750);
LOG_WARN("Failed to find UBlox & MTK GNSS Module\n"); if (response == GNSS_RESPONSE_NONE) {
LOG_WARN("Failed to find UBlox & MTK GNSS Module using baudrate %d\n", serialSpeed);
return GNSS_MODEL_UNKNOWN; return GNSS_MODEL_UNKNOWN;
} else if (response == GNSS_RESPONSE_FRAME_ERRORS) {
LOG_INFO("UBlox Frame Errors using baudrate %d\n", serialSpeed);
} else if (response == GNSS_RESPONSE_OK) {
LOG_INFO("Found a UBlox Module using baudrate %d\n", serialSpeed);
} }
// tips: NMEA Only should not be set here, otherwise initializing Ublox gnss module again after
// setting will not output command messages in UART1, resulting in unrecognized module information
if (serialSpeed != 9600) {
// Set the UART port to 9600
uint8_t _message_prt[] = {0xB5, 0x62, 0x06, 0x00, 0x14, 0x00, 0x01, 0x00, 0x00, 0x00, 0xD0, 0x08, 0x00, 0x00,
0x80, 0x25, 0x00, 0x00, 0x07, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
UBXChecksum(_message_prt, sizeof(_message_prt));
_serial_gps->write(_message_prt, sizeof(_message_prt));
delay(500);
serialSpeed = 9600;
#if defined(ARCH_NRF52) || defined(ARCH_PORTDUINO) || defined(ARCH_RP2040)
_serial_gps->end();
_serial_gps->begin(serialSpeed);
#else
_serial_gps->updateBaudRate(serialSpeed);
#endif
delay(200);
}
memset(buffer, 0, sizeof(buffer)); memset(buffer, 0, sizeof(buffer));
byte _message_MONVER[8] = { uint8_t _message_MONVER[8] = {
0xB5, 0x62, // Sync message for UBX protocol 0xB5, 0x62, // Sync message for UBX protocol
0x0A, 0x04, // Message class and ID (UBX-MON-VER) 0x0A, 0x04, // Message class and ID (UBX-MON-VER)
0x00, 0x00, // Length of payload (we're asking for an answer, so no payload) 0x00, 0x00, // Length of payload (we're asking for an answer, so no payload)
@@ -907,9 +1064,10 @@ GnssModel_t GPS::probe()
}; };
// Get Ublox gnss module hardware and software info // Get Ublox gnss module hardware and software info
UBXChecksum(_message_MONVER, sizeof(_message_MONVER)); UBXChecksum(_message_MONVER, sizeof(_message_MONVER));
clearBuffer();
_serial_gps->write(_message_MONVER, sizeof(_message_MONVER)); _serial_gps->write(_message_MONVER, sizeof(_message_MONVER));
uint16_t len = getAck(buffer, 384, 0x0A, 0x04); uint16_t len = getACK(buffer, sizeof(buffer), 0x0A, 0x04, 1200);
if (len) { if (len) {
// LOG_DEBUG("monver reply size = %d\n", len); // LOG_DEBUG("monver reply size = %d\n", len);
uint16_t position = 0; uint16_t position = 0;
@@ -918,13 +1076,13 @@ GnssModel_t GPS::probe()
position++; position++;
} }
for (int i = 0; i < 10; i++) { for (int i = 0; i < 10; i++) {
info.hwVersion[i] = buffer[position - 1]; info.hwVersion[i] = buffer[position];
position++; position++;
} }
while (len >= position + 30) { while (len >= position + 30) {
for (int i = 0; i < 30; i++) { for (int i = 0; i < 30; i++) {
info.extension[info.extensionNo][i] = buffer[position - 1]; info.extension[info.extensionNo][i] = buffer[position];
position++; position++;
} }
info.extensionNo++; info.extensionNo++;
@@ -934,7 +1092,6 @@ GnssModel_t GPS::probe()
LOG_DEBUG("Module Info : \n"); LOG_DEBUG("Module Info : \n");
LOG_DEBUG("Soft version: %s\n", info.swVersion); LOG_DEBUG("Soft version: %s\n", info.swVersion);
LOG_DEBUG("first char is %c\n", (char)info.swVersion[0]);
LOG_DEBUG("Hard version: %s\n", info.hwVersion); LOG_DEBUG("Hard version: %s\n", info.hwVersion);
LOG_DEBUG("Extensions:%d\n", info.extensionNo); LOG_DEBUG("Extensions:%d\n", info.extensionNo);
for (int i = 0; i < info.extensionNo; i++) { for (int i = 0; i < info.extensionNo; i++) {
@@ -953,7 +1110,7 @@ GnssModel_t GPS::probe()
} else { } else {
LOG_INFO("UBlox GNSS init succeeded, using UBlox GNSS Module\n"); LOG_INFO("UBlox GNSS init succeeded, using UBlox GNSS Module\n");
} }
} else if (!strncmp(info.extension[i], "PROTVER=", 8)) { } else if (!strncmp(info.extension[i], "PROTVER", 7)) {
char *ptr = nullptr; char *ptr = nullptr;
memset(buffer, 0, sizeof(buffer)); memset(buffer, 0, sizeof(buffer));
strncpy((char *)buffer, &(info.extension[i][8]), sizeof(buffer)); strncpy((char *)buffer, &(info.extension[i][8]), sizeof(buffer));
@@ -969,7 +1126,6 @@ GnssModel_t GPS::probe()
} }
return GNSS_MODEL_UBLOX; return GNSS_MODEL_UBLOX;
#endif
} }
#if HAS_GPS #if HAS_GPS

View File

@@ -18,6 +18,13 @@ typedef enum {
GNSS_MODEL_UNKNOWN, GNSS_MODEL_UNKNOWN,
} GnssModel_t; } 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 // Generate a string representation of DOP
const char *getDOPString(uint32_t dop); const char *getDOPString(uint32_t dop);
@@ -55,6 +62,10 @@ class GPS : private concurrency::OSThread
/** If !NULL we will use this serial port to construct our GPS */ /** If !NULL we will use this serial port to construct our GPS */
static HardwareSerial *_serial_gps; static HardwareSerial *_serial_gps;
static const uint8_t _message_PMREQ[8];
static const uint8_t _message_CFG_RXM_PSM[2];
static const uint8_t _message_CFG_RXM_ECO[2];
static const uint8_t _message_CFG_PM2[44];
meshtastic_Position p = meshtastic_Position_init_default; meshtastic_Position p = meshtastic_Position_init_default;
GPS() : concurrency::OSThread("GPS") {} GPS() : concurrency::OSThread("GPS") {}
@@ -94,6 +105,12 @@ class GPS : private concurrency::OSThread
// Empty the input buffer as quickly as possible // Empty the input buffer as quickly as possible
void clearBuffer(); void clearBuffer();
// 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);
// scratch space for creating ublox packets
uint8_t UBXscratch[250] = {0};
protected: protected:
/// Do gps chipset specific init, return true for success /// Do gps chipset specific init, return true for success
virtual bool setupGPS(); virtual bool setupGPS();
@@ -144,7 +161,7 @@ class GPS : private concurrency::OSThread
int prepareDeepSleep(void *unused); int prepareDeepSleep(void *unused);
// Calculate checksum // Calculate checksum
void UBXChecksum(byte *message, size_t length); void UBXChecksum(uint8_t *message, size_t length);
/** /**
* Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode * Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode
@@ -161,8 +178,6 @@ class GPS : private concurrency::OSThread
*/ */
uint32_t getSleepTime() const; uint32_t getSleepTime() const;
bool getACK(uint8_t c, uint8_t i);
/** /**
* Tell users we have new GPS readings * Tell users we have new GPS readings
*/ */
@@ -172,10 +187,11 @@ class GPS : private concurrency::OSThread
// Get GNSS model // Get GNSS model
String getNMEA(); String getNMEA();
GnssModel_t probe(); GnssModel_t probe(int serialSpeed);
int getAck(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t requestedID);
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);
// delay counter to allow more sats before fixed position stops GPS thread // delay counter to allow more sats before fixed position stops GPS thread
uint8_t fixeddelayCtr = 0; uint8_t fixeddelayCtr = 0;

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

@@ -0,0 +1,31 @@
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
};

View File

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

View File

@@ -73,6 +73,7 @@ NRF52Bluetooth *nrf52Bluetooth;
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
#include "AccelerometerThread.h" #include "AccelerometerThread.h"
#include "AmbientLightingThread.h"
#endif #endif
using namespace concurrency; using namespace concurrency;
@@ -169,6 +170,7 @@ static OSThread *buttonThread;
uint32_t ButtonThread::longPressTime = 0; uint32_t ButtonThread::longPressTime = 0;
#endif #endif
static OSThread *accelerometerThread; static OSThread *accelerometerThread;
static OSThread *ambientLightingThread;
SPISettings spiSettings(4000000, MSBFIRST, SPI_MODE0); SPISettings spiSettings(4000000, MSBFIRST, SPI_MODE0);
RadioInterface *rIf = NULL; RadioInterface *rIf = NULL;
@@ -409,14 +411,6 @@ void setup()
// Only one supported RGB LED currently // Only one supported RGB LED currently
#ifdef HAS_NCP5623 #ifdef HAS_NCP5623
rgb_found = i2cScanner->find(ScanI2C::DeviceType::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 #endif
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
@@ -521,6 +515,12 @@ void setup()
} }
#endif #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 #ifdef T_WATCH_S3
drv.begin(); drv.begin();
drv.selectLibrary(1); drv.selectLibrary(1);
@@ -558,14 +558,6 @@ void setup()
readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time) readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time)
gps = createGps();
if (gps) {
gpsStatus->observe(&gps->newStatus);
} else {
LOG_WARN("No GPS found - running without GPS\n");
}
nodeStatus->observe(&nodeDB.newStatus); nodeStatus->observe(&nodeDB.newStatus);
service.init(); service.init();
@@ -590,17 +582,6 @@ void setup()
screen->print("Started...\n"); 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 #ifdef SX126X_ANT_SW
// make analog PA vs not PA switch on SX126x eval board work properly // make analog PA vs not PA switch on SX126x eval board work properly
pinMode(SX126X_ANT_SW, OUTPUT); pinMode(SX126X_ANT_SW, OUTPUT);
@@ -755,6 +736,26 @@ 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 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(); powerFSMthread = new PowerFSMThread();
gps = createGps();
if (gps) {
gpsStatus->observe(&gps->newStatus);
if (config.position.gps_enabled == false && config.position.fixed_position == false) {
doGPSpowersave(false);
}
} else {
LOG_WARN("No GPS found - running without GPS\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);
}
}
// setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state // setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state
setCPUFast(false); // 80MHz is fine for our slow peripherals setCPUFast(false); // 80MHz is fine for our slow peripherals
} }

View File

@@ -190,7 +190,9 @@ void NodeDB::installDefaultConfig()
: meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN; : meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN;
// for backward compat, default position flags are ALT+MSL // for backward compat, default position flags are ALT+MSL
config.position.position_flags = 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 #ifdef T_WATCH_S3
config.display.screen_on_secs = 30; config.display.screen_on_secs = 30;
@@ -253,6 +255,13 @@ void NodeDB::installDefaultModuleConfig()
moduleConfig.detection_sensor.detection_triggered_high = true; moduleConfig.detection_sensor.detection_triggered_high = true;
moduleConfig.detection_sensor.minimum_broadcast_secs = 45; 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(); initModuleConfigIntervals();
} }

View File

@@ -51,8 +51,9 @@ typedef enum _meshtastic_Config_DeviceConfig_RebroadcastMode {
} meshtastic_Config_DeviceConfig_RebroadcastMode; } meshtastic_Config_DeviceConfig_RebroadcastMode;
/* Bit field of boolean configuration options, indicating which optional /* Bit field of boolean configuration options, indicating which optional
fields to include when assembling POSITION messages fields to include when assembling POSITION messages.
Longitude and latitude are always included (also time if GPS-synced) 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 - NOTE: the more fields are included, the larger the message will be -
leading to longer airtime and a higher risk of packet loss */ leading to longer airtime and a higher risk of packet loss */
typedef enum _meshtastic_Config_PositionConfig_PositionFlags { typedef enum _meshtastic_Config_PositionConfig_PositionFlags {

View File

@@ -313,13 +313,14 @@ Initially created for the RAK14001 RGB LED module. */
typedef struct _meshtastic_ModuleConfig_AmbientLightingConfig { typedef struct _meshtastic_ModuleConfig_AmbientLightingConfig {
/* Sets LED to on or off. */ /* Sets LED to on or off. */
bool led_state; 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 current;
uint8_t red; /* Red level */ /* Sets the red LED level. Values are 0-255. */
/* 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 red;
uint8_t green; /* Green level */ /* Sets the green LED level. Values are 0-255. */
/* 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 green;
uint8_t blue; /* Blue level */ /* Sets the blue LED level. Values are 0-255. */
uint8_t blue;
} meshtastic_ModuleConfig_AmbientLightingConfig; } meshtastic_ModuleConfig_AmbientLightingConfig;
/* A GPIO pin definition for remote hardware module */ /* A GPIO pin definition for remote hardware module */

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) template <class T> constexpr const T &clamp(const T &v, const T &lo, const T &hi)
{ {
return (v < lo) ? lo : (hi < v) ? hi : v; 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

@@ -27,7 +27,6 @@
#ifdef HAS_NCP5623 #ifdef HAS_NCP5623
#include <graphics/RAKled.h> #include <graphics/RAKled.h>
NCP5623 rgb;
uint8_t red = 0; uint8_t red = 0;
uint8_t green = 0; uint8_t green = 0;

View File

@@ -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 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 Assumes that the neighborInfo packet has been allocated
@@ -184,14 +174,14 @@ size_t NeighborInfoModule::cleanUpNeighbors()
/* Send neighbor info to the mesh */ /* Send neighbor info to the mesh */
void NeighborInfoModule::sendNeighborInfo(NodeNum dest, bool wantReplies) void NeighborInfoModule::sendNeighborInfo(NodeNum dest, bool wantReplies)
{ {
meshtastic_NeighborInfo *neighborInfo = allocateNeighborInfoPacket(); meshtastic_NeighborInfo neighborInfo = meshtastic_NeighborInfo_init_zero;
collectNeighborInfo(neighborInfo); collectNeighborInfo(&neighborInfo);
meshtastic_MeshPacket *p = allocDataProtobuf(*neighborInfo); meshtastic_MeshPacket *p = allocDataProtobuf(neighborInfo);
// send regardless of whether or not we have neighbors in our DB, // send regardless of whether or not we have neighbors in our DB,
// because we want to get neighbors for the next cycle // because we want to get neighbors for the next cycle
p->to = dest; p->to = dest;
p->decoded.want_response = wantReplies; p->decoded.want_response = wantReplies;
printNeighborInfo("SENDING", neighborInfo); printNeighborInfo("SENDING", &neighborInfo);
service.sendToMesh(p, RX_SRC_LOCAL, true); 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) bool NeighborInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_NeighborInfo *np)
{ {
printNeighborInfo("RECEIVED", np); if (enabled) {
updateNeighbors(mp, np); printNeighborInfo("RECEIVED", np);
updateNeighbors(mp, np);
}
// Allow others to handle this packet // Allow others to handle this packet
return false; return false;
} }
@@ -277,7 +269,7 @@ meshtastic_Neighbor *NeighborInfoModule::getOrCreateNeighbor(NodeNum originalSen
} }
// otherwise, allocate one and assign data to it // otherwise, allocate one and assign data to it
// TODO: max memory for the database should take neighbors into account, but currently doesn't // 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)++; (*numNeighbors)++;
} }
meshtastic_Neighbor *new_nbr = &neighbors[((*numNeighbors) - 1)]; meshtastic_Neighbor *new_nbr = &neighbors[((*numNeighbors) - 1)];

View File

@@ -11,8 +11,8 @@
PositionModule *positionModule; PositionModule *positionModule;
PositionModule::PositionModule() PositionModule::PositionModule()
: ProtobufModule("position", meshtastic_PortNum_POSITION_APP, &meshtastic_Position_msg), concurrency::OSThread( : ProtobufModule("position", meshtastic_PortNum_POSITION_APP, &meshtastic_Position_msg),
"PositionModule") concurrency::OSThread("PositionModule")
{ {
isPromiscuous = true; // We always want to update our nodedb, even if we are sniffing on others 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) setIntervalFromNow(60 * 1000); // Send our initial position 60 seconds after we start (to give GPS time to setup)
@@ -65,7 +65,7 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes
meshtastic_MeshPacket *PositionModule::allocReply() meshtastic_MeshPacket *PositionModule::allocReply()
{ {
if (ignoreRequest) { if (ignoreRequest) {
return NULL; return nullptr;
} }
meshtastic_NodeInfoLite *node = service.refreshLocalMeshNode(); // should guarantee there is now a position 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); service.cancelSending(prevPacketId);
meshtastic_MeshPacket *p = allocReply(); meshtastic_MeshPacket *p = allocReply();
if (p == nullptr) {
LOG_WARN("allocReply returned a nullptr");
return;
}
p->to = dest; p->to = dest;
p->decoded.want_response = wantReplies; p->decoded.want_response = wantReplies;
if (config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER) if (config.device.role == meshtastic_Config_DeviceConfig_Role_TRACKER)

View File

@@ -656,8 +656,18 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
&scratch)) { &scratch)) {
decoded = &scratch; decoded = &scratch;
msgPayload["node_id"] = new JSONValue((uint)decoded->node_id); 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_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 { } else {
LOG_ERROR("Error decoding protobuf for neighborinfo message!\n"); LOG_ERROR("Error decoding protobuf for neighborinfo message!\n");
} }

View File

@@ -204,6 +204,19 @@ void doGPSpowersave(bool on)
notifyGPSSleep.notifyObservers(NULL); notifyGPSSleep.notifyObservers(NULL);
} }
#endif #endif
#if !(defined(HAS_PMU) || defined(PIN_GPS_EN) || defined(PIN_GPS_WAKE))
if (!on) {
uint8_t msglen;
notifyGPSSleep.notifyObservers(NULL);
msglen = gps->makeUBXPacket(0x02, 0x41, 0x08, gps->_message_PMREQ);
for (int i = 0; i < msglen; i++) {
gps->_serial_gps->write(gps->UBXscratch, msglen);
}
} else {
gps->forceWake(1);
gps->_serial_gps->write(0xFF);
}
#endif
} }
void doDeepSleep(uint32_t msecToWake) void doDeepSleep(uint32_t msecToWake)

View File

@@ -4,6 +4,7 @@ extends = nrf52840_base
board = wiscore_rak4631 board = wiscore_rak4631
build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631 -D RAK_4631 build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631 -D RAK_4631
-L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard" -L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard"
-DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely.
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631> +<mesh/eth/> +<mesh/api/> +<mqtt/> build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631> +<mesh/eth/> +<mesh/api/> +<mqtt/>
lib_deps = lib_deps =
${nrf52840_base.lib_deps} ${nrf52840_base.lib_deps}
@@ -13,4 +14,4 @@ lib_deps =
rakwireless/RAKwireless NCP5623 RGB LED library@^1.0.2 rakwireless/RAKwireless NCP5623 RGB LED library@^1.0.2
debug_tool = jlink debug_tool = jlink
; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm) ; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm)
;upload_protocol = jlink ;upload_protocol = jlink

View File

@@ -227,6 +227,8 @@ SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG
#define GPS_RX_PIN PIN_SERIAL1_RX #define GPS_RX_PIN PIN_SERIAL1_RX
#define GPS_TX_PIN PIN_SERIAL1_TX #define GPS_TX_PIN PIN_SERIAL1_TX
// Define pin to enable GPS toggle (set GPIO to LOW) via user button triple press
// RAK12002 RTC Module // RAK12002 RTC Module
#define RV3028_RTC (uint8_t)0b1010010 #define RV3028_RTC (uint8_t)0b1010010

View File

@@ -3,9 +3,12 @@
#define I2C_SDA 21 #define I2C_SDA 21
#define I2C_SCL 22 #define I2C_SCL 22
#define I2C_SDA1 14 // Second i2c channel on external IO connector
#define I2C_SCL1 15 // Second i2c channel on external IO connector
#define BUTTON_PIN 36 // The middle button GPIO on the Nano G1 #define BUTTON_PIN 36 // The middle button GPIO on the Nano G1
//#define BUTTON_PIN_ALT 13 // Alternate GPIO for an external button if needed. Does anyone use this? It is not documented // #define BUTTON_PIN_ALT 13 // Alternate GPIO for an external button if needed. Does anyone use this? It is not documented
// anywhere. // anywhere.
#define EXT_NOTIFY_OUT 13 // Default pin to use for Ext Notify Module. #define EXT_NOTIFY_OUT 13 // Default pin to use for Ext Notify Module.
// common pinout for their SX1262 vs RF95 modules - both can be enabled and we will probe at runtime for RF95 and if // common pinout for their SX1262 vs RF95 modules - both can be enabled and we will probe at runtime for RF95 and if
@@ -24,9 +27,9 @@
#define SX126X_DIO1 LORA_DIO1 #define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_DIO2 #define SX126X_BUSY LORA_DIO2
#define SX126X_RESET LORA_RESET #define SX126X_RESET LORA_RESET
//#define SX126X_E22 // Not really an E22 // #define SX126X_E22 // Not really an E22
// Internally the module hooks the SX1262-DIO2 in to control the TX/RX switch (which is the default for the sx1262interface // Internally the module hooks the SX1262-DIO2 in to control the TX/RX switch (which is the default for the sx1262interface
// code) // code)
#define SX126X_MAX_POWER \ #define SX126X_MAX_POWER \
16 // Ensure the PA does not exceed the saturation output power. More 16 // Ensure the PA does not exceed the saturation output power. More
// Info:https://uniteng.com/wiki/doku.php?id=meshtastic:station#rf_design_-_lora_station_edition_g1 // Info:https://uniteng.com/wiki/doku.php?id=meshtastic:station#rf_design_-_lora_station_edition_g1
@@ -42,4 +45,4 @@
#define BAT_NOBATVOLT 6690 #define BAT_NOBATVOLT 6690
// different screen // different screen
#define USE_SH1106 #define USE_SH1106

View File

@@ -1,4 +1,4 @@
[VERSION] [VERSION]
major = 2 major = 2
minor = 2 minor = 2
build = 3 build = 5