refactor and avoid needless probe (#2799)

* Use UINT32_MAX to indicate no configured GPS

* Refactor GPS to not probe if pins not defined

* Minor cleanups related to rework

* Use Named Constructor to clean up code

* Actually disable the GPS thread

* Don't actually disable the GPS thread

* Move doGPSPowerSave to GPS class

* Make sure to set GPS awake on triple-click

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
This commit is contained in:
Jonathan Bennett 2023-09-16 23:10:10 -05:00 committed by GitHub
parent 822c150e0d
commit 8b82ae6fe3
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
15 changed files with 397 additions and 443 deletions

View File

@ -165,13 +165,15 @@ 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 (gps != nullptr) {
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");
}
config.position.gps_enabled = !(config.position.gps_enabled);
gps->doGPSpowersave(config.position.gps_enabled);
}
config.position.gps_enabled = !(config.position.gps_enabled);
doGPSpowersave(config.position.gps_enabled);
#endif
}

View File

@ -13,12 +13,7 @@
#define GPS_RESET_MODE HIGH
#endif
// If we have a serial GPS port it will not be null
#ifdef GPS_SERIAL_NUM
HardwareSerial _serial_gps_real(GPS_SERIAL_NUM);
HardwareSerial *GPS::_serial_gps = &_serial_gps_real;
#elif defined(NRF52840_XXAA) || defined(NRF52833_XXAA)
// Assume NRF52840
#if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32)
HardwareSerial *GPS::_serial_gps = &Serial1;
#else
HardwareSerial *GPS::_serial_gps = NULL;
@ -32,6 +27,8 @@ static bool didSerialInit;
struct uBloxGnssModelInfo info;
uint8_t uBloxProtocolVersion;
#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)
void GPS::UBXChecksum(uint8_t *message, size_t length)
{
@ -257,17 +254,21 @@ bool GPS::setup()
if (_serial_gps && !didSerialInit) {
#if !defined(GPS_UC6580)
LOG_DEBUG("Probing for GPS at %d \n", serialSpeeds[speedSelect]);
gnssModel = probe(serialSpeeds[speedSelect]);
if (gnssModel == GNSS_MODEL_UNKNOWN) {
if (++speedSelect == sizeof(serialSpeeds) / sizeof(int)) {
speedSelect = 0;
if (--probeTries == 0) {
LOG_WARN("Giving up on GPS probe and setting to 9600.\n");
return true;
if (tx_gpio) {
LOG_DEBUG("Probing for GPS at %d \n", serialSpeeds[speedSelect]);
gnssModel = probe(serialSpeeds[speedSelect]);
if (gnssModel == GNSS_MODEL_UNKNOWN) {
if (++speedSelect == sizeof(serialSpeeds) / sizeof(int)) {
speedSelect = 0;
if (--probeTries == 0) {
LOG_WARN("Giving up on GPS probe and setting to 9600.\n");
return true;
}
}
return false;
}
return false;
} else {
gnssModel = GNSS_MODEL_UNKNOWN;
}
#else
gnssModel = GNSS_MODEL_UC6850;
@ -437,16 +438,6 @@ GPS::~GPS()
notifyGPSSleepObserver.observe(&notifyGPSSleep);
}
bool GPS::hasLock()
{
return hasValidLocation;
}
bool GPS::hasFlow()
{
return hasGPS;
}
// Allow defining the polarity of the WAKE output. default is active high
#ifndef GPS_WAKE_ACTIVE
#define GPS_WAKE_ACTIVE 1
@ -563,7 +554,7 @@ int32_t GPS::runOnce()
// 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) {
if (!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;
@ -576,6 +567,8 @@ int32_t GPS::runOnce()
return 0;
}
}
if (config.position.gps_enabled == false)
return 0;
// Repeaters have no need for GPS
if (config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER)
@ -840,18 +833,30 @@ GnssModel_t GPS::probe(int serialSpeed)
return GNSS_MODEL_UBLOX;
}
#if HAS_GPS
#include "NMEAGPS.h"
#endif
GPS *createGps()
// GPS::GPS(uint32_t _rx_gpio, uint32_t _tx_gpio) : concurrency::OSThread("GPS")
GPS *GPS::createGps()
{
int8_t _rx_gpio = config.position.rx_gpio;
int8_t _tx_gpio = config.position.tx_gpio;
#if defined(HAS_GPS) && !defined(ARCH_ESP32)
_rx_gpio = 1; // We only specify GPS serial ports on ESP32. Otherwise, these are just flags.
_tx_gpio = 1;
#endif
#if defined(GPS_RX_PIN)
if (!_rx_gpio)
_rx_gpio = GPS_RX_PIN;
#endif
#if defined(GPS_TX_PIN)
if (!_tx_gpio)
_tx_gpio = GPS_TX_PIN;
#endif
if (!_rx_gpio) // Configured to have no GPS at all
return nullptr;
GPS *new_gps = new GPS;
new_gps->rx_gpio = _rx_gpio;
new_gps->tx_gpio = _tx_gpio;
#if !HAS_GPS
return nullptr;
#else
GPS *new_gps = new NMEAGPS();
// Master power for the GPS
#ifdef PIN_GPS_PPS
// pulse per second
pinMode(PIN_GPS_PPS, INPUT);
@ -883,42 +888,308 @@ GPS *createGps()
#endif
new_gps->setAwake(true); // Wake GPS power before doing any init
if (new_gps->_serial_gps) {
if (_serial_gps) {
#ifdef ARCH_ESP32
// In esp32 framework, setRxBufferSize needs to be initialized before Serial
new_gps->_serial_gps->setRxBufferSize(SERIAL_BUFFER_SIZE); // the default is 256
_serial_gps->setRxBufferSize(SERIAL_BUFFER_SIZE); // the default is 256
#endif
// if the overrides are not dialled in, set them from the board definitions, if they exist
#if defined(GPS_RX_PIN)
if (!config.position.rx_gpio)
config.position.rx_gpio = GPS_RX_PIN;
#endif
#if defined(GPS_TX_PIN)
if (!config.position.tx_gpio)
config.position.tx_gpio = GPS_TX_PIN;
#endif
// #define BAUD_RATE 115200
// ESP32 has a special set of parameters vs other arduino ports
#if defined(ARCH_ESP32)
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 TX\n", config.position.tx_gpio);
new_gps->_serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, config.position.rx_gpio, config.position.tx_gpio);
}
LOG_DEBUG("Using GPIO%d for GPS RX\n", new_gps->rx_gpio);
LOG_DEBUG("Using GPIO%d for GPS TX\n", new_gps->tx_gpio);
_serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, new_gps->rx_gpio, new_gps->tx_gpio);
#else
new_gps->_serial_gps->begin(GPS_BAUDRATE);
_serial_gps->begin(GPS_BAUDRATE);
#endif
/*
* T-Beam-S3-Core will be preset to use gps Probe here, and other boards will not be changed first
*/
#if defined(GPS_UC6580)
new_gps->_serial_gps->updateBaudRate(115200);
_serial_gps->updateBaudRate(115200);
#endif
}
return new_gps;
}
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 GPS::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;
}
/**
* 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 GPS::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 GPS::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 GPS::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 GPS::hasFlow()
{
return reader.passedChecksum() > 0;
}
bool GPS::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;
}
void GPS::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);
setAwake(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);
setAwake(1);
} else {
LOG_INFO("GPS entering sleep");
notifyGPSSleep.notifyObservers(NULL);
}
#endif
#if !(defined(HAS_PMU) || defined(PIN_GPS_EN) || defined(PIN_GPS_WAKE))
if (!on) {
notifyGPSSleep.notifyObservers(NULL);
if (gnssModel == GNSS_MODEL_UBLOX) {
uint8_t msglen;
msglen = gps->makeUBXPacket(0x02, 0x41, 0x08, gps->_message_PMREQ);
gps->_serial_gps->write(gps->UBXscratch, msglen);
}
setAwake(1);
} else {
gps->forceWake(1);
if (gnssModel == GNSS_MODEL_UBLOX)
gps->_serial_gps->write(0xFF);
}
#endif
}

View File

@ -2,6 +2,7 @@
#include "GPSStatus.h"
#include "Observer.h"
#include "TinyGPS++.h"
#include "concurrency/OSThread.h"
struct uBloxGnssModelInfo {
@ -35,10 +36,24 @@ 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;
const int serialSpeeds[6] = {9600, 4800, 38400, 57600, 115200, 9600};
uint32_t rx_gpio = 0;
uint32_t tx_gpio = 0;
int speedSelect = 0;
int probeTries = 2;
@ -120,9 +135,6 @@ class GPS : private concurrency::OSThread
* */
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();
@ -142,6 +154,12 @@ class GPS : private concurrency::OSThread
* calls sleep/wake
*/
void setAwake(bool on);
void doGPSpowersave(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:
/// If possible force the GPS into sleep/low power mode
@ -154,7 +172,6 @@ class GPS : private concurrency::OSThread
*
* 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() {}
@ -165,7 +182,6 @@ class GPS : private concurrency::OSThread
*
* @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.
@ -173,13 +189,34 @@ class GPS : private concurrency::OSThread
*
* @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);
/** 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 or light sleep, expect to be gone for at least 100s of msecs
/// always returns 0 to indicate okay to sleep
@ -218,8 +255,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,248 +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;
}
/**
* 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,55 +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 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

@ -557,9 +557,13 @@ void setup()
screen = new graphics::Screen(screen_found, screen_model, screen_geometry);
readFromRTC(); // read the main CPU RTC at first (in case we can't get GPS time)
gps = createGps();
if (gps)
gps = GPS::createGps();
if (gps) {
gpsStatus->observe(&gps->newStatus);
} else {
LOG_DEBUG("Running without GPS.\n");
}
nodeStatus->observe(&nodeDB.newStatus);
service.init();

View File

@ -123,22 +123,6 @@
#define HW_VENDOR meshtastic_HardwareModel_HELTEC_HT62
#endif
//
// Standard definitions for ESP32 targets
//
#define GPS_SERIAL_NUM 1
#ifndef GPS_RX_PIN
#define GPS_RX_PIN 34
#endif
#ifndef GPS_TX_PIN
#ifdef USE_JTAG
#define GPS_TX_PIN -1
#else
#define GPS_TX_PIN 12
#endif
#endif
// -----------------------------------------------------------------------------
// LoRa SPI
// -----------------------------------------------------------------------------
@ -151,4 +135,4 @@
#define RF95_NSS 18
#endif
#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32
#define SERIAL0_RX_GPIO 3 // Always GPIO3 on ESP32

View File

@ -182,41 +182,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
#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);
gps->_serial_gps->write(gps->UBXscratch, msglen);
} else {
gps->forceWake(1);
gps->_serial_gps->write(0xFF);
}
#endif
}
void doDeepSleep(uint32_t msecToWake)
{
if (INCLUDE_vTaskSuspend && (msecToWake == portMAX_DELAY)) {

View File

@ -19,7 +19,7 @@ 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

@ -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,4 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_DIO2
#define SX126X_RESET LORA_RESET
#define SX126X_E22
#define SX126X_E22

View File

@ -11,8 +11,6 @@
#undef ECB
#define ECB 0
#undef GPS_SERIAL_NUM
#define LED_CONN PIN_LED2
#define LED_PIN LED_BUILTIN

View File

@ -11,9 +11,7 @@
#undef ECB
#define ECB 0
#define NO_GPS 1
#define USE_SH1106 1
#undef GPS_SERIAL_NUM
// default I2C pins:
// SDA = 4

View File

@ -11,9 +11,7 @@
#undef ECB
#define ECB 0
#define NO_GPS 1
#define USE_SH1106 1
#undef GPS_SERIAL_NUM
// default I2C pins:
// SDA = 4

View File

@ -46,3 +46,7 @@
// different screen
#define USE_SH1106
// Station may not have GPS installed, but it has a labeled GPS pinout
#define GPS_RX_PIN 34
#define GPS_TX_PIN 12

View File

@ -4,8 +4,8 @@
#define I2C_SCL 22
#define BUTTON_PIN 38 // The middle button GPIO on the T-Beam
//#define BUTTON_PIN_ALT 13 // Alternate GPIO for an external button if needed. Does anyone use this? It is not documented
// anywhere.
// #define BUTTON_PIN_ALT 13 // Alternate GPIO for an external button if needed. Does anyone use this? It is not documented
// anywhere.
#define EXT_NOTIFY_OUT 13 // Default pin to use for Ext Notify Module.
#define LED_INVERTED 1
@ -37,4 +37,6 @@
// and waking from light sleep
// #define PMU_IRQ 35
#define HAS_AXP192
#define GPS_UBLOX
#define GPS_UBLOX
#define GPS_RX_PIN 34
#define GPS_TX_PIN 12