mirror of
https://github.com/meshtastic/firmware.git
synced 2025-06-08 14:12:05 +00:00
Gps cleanup and powersave (#2807)
* Refactor GPS to not probe if pins not defined * Use Named Constructor to clean up code * Move doGPSPowerSave to GPS class * Make sure to set GPS awake on triple-click * Cleanup and remove dead code * Rename GPS_PIN_WAKE to GPS_PIN_STANDBY * Actually put GPS to sleep between fixes * add GPS_POWER_TOGGLE for heltec-tracker and t-deck * Change GPS_THREAD_INTERVAL to 200 ms * More dead code, compiler warnings, and add returns * Add Number of sats to log output * Add pgs enable and triple-click config * Track average GPS fix time to judge low-power time * Feed PositionModule on GPS fix * Don't turn off the 3v3_s line on RAK4631 when the rotary is present. * Add GPS power standbyOnly option * Delay setting time currentQuality to avoid strange log message. * Typos, comments, and remove unused variable * Short-circuit the setAwake logic on GPS disable * heltec-tracker 0.3 GPS power saving * set en_gpio to defined state * Fix fixed_position logic with GPS disabled * Don't process GPS serial when not isAwake * Add quirk for Heltec Tracker GPS powersave --------- Co-authored-by: Ben Meadors <benmmeadors@gmail.com> Co-authored-by: mverch67 <manuel.verch@gmx.de> Co-authored-by: Manuel <71137295+mverch67@users.noreply.github.com>
This commit is contained in:
parent
7eff5e7bcb
commit
1a2c7f00e1
@ -1 +1 @@
|
||||
Subproject commit 524819facebc70ad381f765fedc36003f6994783
|
||||
Subproject commit 60f1f15743f5232cdcae6c160e8fa52951f62880
|
@ -164,17 +164,17 @@ class ButtonThread : public concurrency::OSThread
|
||||
|
||||
static void userButtonMultiPressed()
|
||||
{
|
||||
#if defined(GPS_POWER_TOGGLE)
|
||||
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");
|
||||
}
|
||||
if (!config.device.disable_triple_click && (gps != nullptr)) {
|
||||
config.position.gps_enabled = !(config.position.gps_enabled);
|
||||
gps->doGPSpowersave(config.position.gps_enabled);
|
||||
if (config.position.gps_enabled) {
|
||||
LOG_DEBUG("Flag set to true to restore power\n");
|
||||
gps->enable();
|
||||
|
||||
} else {
|
||||
LOG_DEBUG("Flag set to false for gps power\n");
|
||||
gps->disable();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
static void userButtonPressedLongStart()
|
||||
|
@ -8,7 +8,6 @@
|
||||
* actions to be taken upon entering or exiting each state.
|
||||
*/
|
||||
#include "PowerFSM.h"
|
||||
#include "GPS.h"
|
||||
#include "MeshService.h"
|
||||
#include "NodeDB.h"
|
||||
#include "configuration.h"
|
||||
@ -137,9 +136,6 @@ static void lsIdle()
|
||||
static void lsExit()
|
||||
{
|
||||
LOG_INFO("Exit state: LS\n");
|
||||
// setGPSPower(true); // restore GPS power
|
||||
if (gps)
|
||||
gps->forceWake(true);
|
||||
}
|
||||
|
||||
static void nbEnter()
|
||||
|
@ -53,7 +53,7 @@ class OSThread : public Thread
|
||||
|
||||
static void setup();
|
||||
|
||||
int32_t disable();
|
||||
virtual int32_t disable();
|
||||
|
||||
/**
|
||||
* Wait a specified number msecs starting from the current time (rather than the last time we were run)
|
||||
@ -87,4 +87,4 @@ extern bool hasBeenSetup;
|
||||
|
||||
void assertIsSetup();
|
||||
|
||||
} // namespace concurrency
|
||||
} // namespace concurrency
|
@ -145,7 +145,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
#define GPS_BAUDRATE 9600
|
||||
|
||||
#ifndef GPS_THREAD_INTERVAL
|
||||
#define GPS_THREAD_INTERVAL 100
|
||||
#define GPS_THREAD_INTERVAL 200
|
||||
#endif
|
||||
|
||||
// convert 24-bit color to 16-bit (56K)
|
||||
|
271
src/gps/GPS.cpp
271
src/gps/GPS.cpp
@ -2,6 +2,7 @@
|
||||
#include "NodeDB.h"
|
||||
#include "RTC.h"
|
||||
#include "configuration.h"
|
||||
#include "main.h" // pmu_found
|
||||
#include "sleep.h"
|
||||
#include "ubx.h"
|
||||
|
||||
@ -420,43 +421,77 @@ bool GPS::setup()
|
||||
didSerialInit = true;
|
||||
}
|
||||
|
||||
notifySleepObserver.observe(¬ifySleep);
|
||||
notifyDeepSleepObserver.observe(¬ifyDeepSleep);
|
||||
notifyGPSSleepObserver.observe(¬ifyGPSSleep);
|
||||
|
||||
if (config.position.gps_enabled == false && config.position.fixed_position == false) {
|
||||
setAwake(false);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
GPS::~GPS()
|
||||
{
|
||||
// we really should unregister our sleep observer
|
||||
notifySleepObserver.unobserve(¬ifySleep);
|
||||
notifyDeepSleepObserver.unobserve(¬ifyDeepSleep);
|
||||
notifyGPSSleepObserver.observe(¬ifyGPSSleep);
|
||||
}
|
||||
|
||||
// Allow defining the polarity of the WAKE output. default is active high
|
||||
#ifndef GPS_WAKE_ACTIVE
|
||||
#define GPS_WAKE_ACTIVE 1
|
||||
#endif
|
||||
|
||||
void GPS::wake()
|
||||
void GPS::setGPSPower(bool on, bool standbyOnly)
|
||||
{
|
||||
#ifdef PIN_GPS_WAKE
|
||||
digitalWrite(PIN_GPS_WAKE, GPS_WAKE_ACTIVE);
|
||||
pinMode(PIN_GPS_WAKE, OUTPUT);
|
||||
LOG_INFO("Setting GPS power=%d\n", on);
|
||||
if (on) {
|
||||
clearBuffer(); // drop any old data waiting in the buffer before re-enabling
|
||||
if (en_gpio)
|
||||
digitalWrite(en_gpio, on ? GPS_EN_ACTIVE : !GPS_EN_ACTIVE); // turn this on if defined, every time
|
||||
}
|
||||
isInPowersave = !on;
|
||||
if (!standbyOnly && en_gpio != 0 &&
|
||||
!(HW_VENDOR == meshtastic_HardwareModel_RAK4631 && (rotaryEncoderInterruptImpl1 || upDownInterruptImpl1))) {
|
||||
LOG_DEBUG("GPS powerdown using GPS_EN_ACTIVE\n");
|
||||
digitalWrite(en_gpio, on ? GPS_EN_ACTIVE : !GPS_EN_ACTIVE);
|
||||
return;
|
||||
}
|
||||
#ifdef HAS_PMU // We only have PMUs on the T-Beam, and that board has a tiny battery to save GPS ephemera, so treat as a standby.
|
||||
if (pmu_found && PMU) {
|
||||
uint8_t model = PMU->getChipModel();
|
||||
if (model == XPOWERS_AXP2101) {
|
||||
if (HW_VENDOR == meshtastic_HardwareModel_TBEAM) {
|
||||
// t-beam v1.2 GNSS power channel
|
||||
on ? PMU->enablePowerOutput(XPOWERS_ALDO3) : PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
} else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE) {
|
||||
// t-beam-s3-core GNSS power channel
|
||||
on ? PMU->enablePowerOutput(XPOWERS_ALDO4) : PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
}
|
||||
} else if (model == XPOWERS_AXP192) {
|
||||
// t-beam v1.1 GNSS power channel
|
||||
on ? PMU->enablePowerOutput(XPOWERS_LDO3) : PMU->disablePowerOutput(XPOWERS_LDO3);
|
||||
}
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void GPS::sleep()
|
||||
{
|
||||
#ifdef PIN_GPS_WAKE
|
||||
digitalWrite(PIN_GPS_WAKE, GPS_WAKE_ACTIVE ? 0 : 1);
|
||||
pinMode(PIN_GPS_WAKE, OUTPUT);
|
||||
#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76K and clones
|
||||
if (on) {
|
||||
LOG_INFO("Waking GPS");
|
||||
digitalWrite(PIN_GPS_STANDBY, 1);
|
||||
pinMode(PIN_GPS_STANDBY, OUTPUT);
|
||||
return;
|
||||
} else {
|
||||
LOG_INFO("GPS entering sleep");
|
||||
// notifyGPSSleep.notifyObservers(NULL);
|
||||
digitalWrite(PIN_GPS_STANDBY, 0);
|
||||
pinMode(PIN_GPS_STANDBY, OUTPUT);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
if (!on) {
|
||||
if (gnssModel == GNSS_MODEL_UBLOX) {
|
||||
uint8_t msglen;
|
||||
msglen = gps->makeUBXPacket(0x02, 0x41, 0x08, gps->_message_PMREQ);
|
||||
gps->_serial_gps->write(gps->UBXscratch, msglen);
|
||||
}
|
||||
} else {
|
||||
if (gnssModel == GNSS_MODEL_UBLOX) {
|
||||
gps->_serial_gps->write(0xFF);
|
||||
clearBuffer(); // This often returns old data, so drop it
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// Record that we have a GPS
|
||||
@ -468,14 +503,6 @@ void GPS::setConnected()
|
||||
}
|
||||
}
|
||||
|
||||
void GPS::setNumSatellites(uint8_t n)
|
||||
{
|
||||
if (n != numSatellites) {
|
||||
numSatellites = n;
|
||||
shouldPublish = true;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode
|
||||
*
|
||||
@ -483,23 +510,38 @@ void GPS::setNumSatellites(uint8_t n)
|
||||
*/
|
||||
void GPS::setAwake(bool on)
|
||||
{
|
||||
if (!wakeAllowed && on) {
|
||||
LOG_WARN("Inhibiting because !wakeAllowed\n");
|
||||
on = false;
|
||||
}
|
||||
|
||||
if (isAwake != on) {
|
||||
LOG_DEBUG("WANT GPS=%d\n", on);
|
||||
if (on) {
|
||||
clearBuffer(); // drop any old data waiting in the buffer
|
||||
lastWakeStartMsec = millis();
|
||||
wake();
|
||||
} else {
|
||||
lastSleepStartMsec = millis();
|
||||
sleep();
|
||||
isAwake = on;
|
||||
if (!enabled) { // short circuit if the user has disabled GPS
|
||||
setGPSPower(false, false);
|
||||
return;
|
||||
}
|
||||
|
||||
isAwake = on;
|
||||
if (on) {
|
||||
lastWakeStartMsec = millis();
|
||||
} else {
|
||||
lastSleepStartMsec = millis();
|
||||
if (GPSCycles == 1) { // Skipping initial lock time, as it will likely be much longer than average
|
||||
averageLockTime = lastSleepStartMsec - lastWakeStartMsec;
|
||||
} else if (GPSCycles > 1) {
|
||||
averageLockTime += ((int32_t)(lastSleepStartMsec - lastWakeStartMsec) - averageLockTime) / (int32_t)GPSCycles;
|
||||
}
|
||||
GPSCycles++;
|
||||
LOG_DEBUG("GPS Lock took %d, average %d\n", (lastSleepStartMsec - lastWakeStartMsec) / 1000, averageLockTime / 1000);
|
||||
}
|
||||
if ((int32_t)getSleepTime() - averageLockTime >
|
||||
15 * 60 * 1000) { // 15 minutes is probably long enough to make a complete poweroff worth it.
|
||||
setGPSPower(on, false);
|
||||
} else if ((int32_t)getSleepTime() - averageLockTime > 10000) { // 10 seconds is enough for standby
|
||||
#ifdef GPS_UC6580
|
||||
setGPSPower(on, false);
|
||||
#else
|
||||
setGPSPower(on, true);
|
||||
#endif
|
||||
} else if (averageLockTime > 20000) {
|
||||
averageLockTime -= 1000; // eventually want to sleep again.
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -519,10 +561,9 @@ uint32_t GPS::getWakeTime() const
|
||||
uint32_t GPS::getSleepTime() const
|
||||
{
|
||||
uint32_t t = config.position.gps_update_interval;
|
||||
bool gps_enabled = config.position.gps_enabled;
|
||||
|
||||
// We'll not need the GPS thread to wake up again after first acq. with fixed position.
|
||||
if (!gps_enabled || config.position.fixed_position)
|
||||
if (!config.position.gps_enabled || config.position.fixed_position)
|
||||
t = UINT32_MAX; // Sleep forever now
|
||||
|
||||
if (t == UINT32_MAX)
|
||||
@ -537,11 +578,14 @@ void GPS::publishUpdate()
|
||||
shouldPublish = false;
|
||||
|
||||
// In debug logs, identify position by @timestamp:stage (stage 2 = publish)
|
||||
LOG_DEBUG("publishing pos@%x:2, hasVal=%d, GPSlock=%d\n", p.timestamp, hasValidLocation, hasLock());
|
||||
LOG_DEBUG("publishing pos@%x:2, hasVal=%d, Sats=%d, GPSlock=%d\n", p.timestamp, hasValidLocation, p.sats_in_view,
|
||||
hasLock());
|
||||
|
||||
// Notify any status instances that are observing us
|
||||
const meshtastic::GPSStatus status = meshtastic::GPSStatus(hasValidLocation, isConnected(), isPowerSaving(), p);
|
||||
newStatus.notifyObservers(&status);
|
||||
if (config.position.gps_enabled)
|
||||
positionModule->handleNewPosition();
|
||||
}
|
||||
}
|
||||
|
||||
@ -554,7 +598,9 @@ int32_t GPS::runOnce()
|
||||
return 2000; // Setup failed, re-run in two seconds
|
||||
|
||||
// We have now loaded our saved preferences from flash
|
||||
|
||||
if (config.position.gps_enabled == false && config.position.fixed_position == false) {
|
||||
return disable();
|
||||
}
|
||||
// ONCE we will factory reset the GPS for bug #327
|
||||
if (!devicestate.did_gps_reset) {
|
||||
LOG_WARN("GPS FactoryReset requested\n");
|
||||
@ -564,17 +610,12 @@ int32_t GPS::runOnce()
|
||||
}
|
||||
}
|
||||
GPSInitFinished = true;
|
||||
if (config.position.gps_enabled == false) {
|
||||
doGPSpowersave(false);
|
||||
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)
|
||||
disable();
|
||||
if (config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER) {
|
||||
return disable();
|
||||
}
|
||||
|
||||
if (whileIdle()) {
|
||||
// if we have received valid NMEA claim we are connected
|
||||
@ -582,20 +623,22 @@ int32_t GPS::runOnce()
|
||||
} else {
|
||||
if ((config.position.gps_enabled == 1) && (gnssModel == GNSS_MODEL_UBLOX)) {
|
||||
// reset the GPS on next bootup
|
||||
if (devicestate.did_gps_reset && (millis() > 60000) && !hasFlow()) {
|
||||
if (devicestate.did_gps_reset && (millis() - lastWakeStartMsec > 60000) && !hasFlow()) {
|
||||
LOG_DEBUG("GPS is not communicating, trying factory reset on next bootup.\n");
|
||||
devicestate.did_gps_reset = false;
|
||||
nodeDB.saveDeviceStateToDisk();
|
||||
disable(); // Stop the GPS thread as it can do nothing useful until next reboot.
|
||||
return disable(); // Stop the GPS thread as it can do nothing useful until next reboot.
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// If we are overdue for an update, turn on the GPS and at least publish the current status
|
||||
uint32_t now = millis();
|
||||
uint32_t timeAsleep = now - lastSleepStartMsec;
|
||||
|
||||
auto sleepTime = getSleepTime();
|
||||
if (!isAwake && sleepTime != UINT32_MAX && (now - lastSleepStartMsec) > sleepTime) {
|
||||
if (!isAwake && (sleepTime != UINT32_MAX) &&
|
||||
((timeAsleep > sleepTime) || (isInPowersave && timeAsleep > (sleepTime - averageLockTime)))) {
|
||||
// We now want to be awake - so wake up the GPS
|
||||
setAwake(true);
|
||||
}
|
||||
@ -603,11 +646,6 @@ int32_t GPS::runOnce()
|
||||
// While we are awake
|
||||
if (isAwake) {
|
||||
// LOG_DEBUG("looking for location\n");
|
||||
if ((now - lastWhileActiveMsec) > 5000) {
|
||||
lastWhileActiveMsec = now;
|
||||
whileActive();
|
||||
}
|
||||
|
||||
// If we've already set time from the GPS, no need to ask the GPS
|
||||
bool gotTime = (getRTCQuality() >= RTCQualityGPS);
|
||||
if (!gotTime && lookForTime()) { // Note: we count on this && short-circuiting and not resetting the RTC time
|
||||
@ -622,7 +660,6 @@ int32_t GPS::runOnce()
|
||||
shouldPublish = true;
|
||||
}
|
||||
|
||||
// We've been awake too long - force sleep
|
||||
now = millis();
|
||||
auto wakeTime = getWakeTime();
|
||||
bool tooLong = wakeTime != UINT32_MAX && (now - lastWakeStartMsec) > wakeTime;
|
||||
@ -647,26 +684,15 @@ int32_t GPS::runOnce()
|
||||
|
||||
// If state has changed do a publish
|
||||
publishUpdate();
|
||||
|
||||
if (config.position.gps_enabled == false) // This should trigger if GPS is disabled but fixed_position is true
|
||||
return disable();
|
||||
|
||||
// 9600bps is approx 1 byte per msec, so considering our buffer size we never need to wake more often than 200ms
|
||||
// if not awake we can run super infrquently (once every 5 secs?) to see if we need to wake.
|
||||
return isAwake ? GPS_THREAD_INTERVAL : 5000;
|
||||
}
|
||||
|
||||
void GPS::forceWake(bool on)
|
||||
{
|
||||
if (on) {
|
||||
LOG_DEBUG("Allowing GPS lock\n");
|
||||
// lastSleepStartMsec = 0; // Force an update ASAP
|
||||
wakeAllowed = true;
|
||||
} else {
|
||||
wakeAllowed = false;
|
||||
|
||||
// Note: if the gps was already awake, we DO NOT shut it down, because we want to allow it to complete its lock
|
||||
// attempt even if we are in light sleep. Once the attempt succeeds (or times out) we'll then shut it down.
|
||||
// setAwake(false);
|
||||
}
|
||||
}
|
||||
|
||||
// clear the GPS rx buffer as quickly as possible
|
||||
void GPS::clearBuffer()
|
||||
{
|
||||
@ -675,22 +701,11 @@ void GPS::clearBuffer()
|
||||
_serial_gps->read();
|
||||
}
|
||||
|
||||
/// Prepare the GPS for the cpu entering deep or light sleep, expect to be gone for at least 100s of msecs
|
||||
int GPS::prepareSleep(void *unused)
|
||||
{
|
||||
LOG_INFO("GPS prepare sleep!\n");
|
||||
forceWake(false);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/// Prepare the GPS for the cpu entering deep or light sleep, expect to be gone for at least 100s of msecs
|
||||
int GPS::prepareDeepSleep(void *unused)
|
||||
{
|
||||
LOG_INFO("GPS deep sleep!\n");
|
||||
|
||||
// For deep sleep we also want abandon any lock attempts (because we want minimum power)
|
||||
getSleepTime();
|
||||
setAwake(false);
|
||||
|
||||
return 0;
|
||||
@ -835,11 +850,11 @@ GnssModel_t GPS::probe(int serialSpeed)
|
||||
return GNSS_MODEL_UBLOX;
|
||||
}
|
||||
|
||||
// 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;
|
||||
int8_t _en_gpio = config.position.gps_en_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;
|
||||
@ -851,6 +866,10 @@ GPS *GPS::createGps()
|
||||
#if defined(GPS_TX_PIN)
|
||||
if (!_tx_gpio)
|
||||
_tx_gpio = GPS_TX_PIN;
|
||||
#endif
|
||||
#if defined(PIN_GPS_EN)
|
||||
if (!_en_gpio)
|
||||
_en_gpio = PIN_GPS_EN;
|
||||
#endif
|
||||
if (!_rx_gpio || !_serial_gps) // Configured to have no GPS at all
|
||||
return nullptr;
|
||||
@ -858,6 +877,13 @@ GPS *GPS::createGps()
|
||||
GPS *new_gps = new GPS;
|
||||
new_gps->rx_gpio = _rx_gpio;
|
||||
new_gps->tx_gpio = _tx_gpio;
|
||||
new_gps->en_gpio = _en_gpio;
|
||||
|
||||
if (_en_gpio != 0) {
|
||||
LOG_DEBUG("Setting %d to output.\n", _en_gpio);
|
||||
digitalWrite(_en_gpio, !GPS_EN_ACTIVE);
|
||||
pinMode(_en_gpio, OUTPUT);
|
||||
}
|
||||
|
||||
#ifdef PIN_GPS_PPS
|
||||
// pulse per second
|
||||
@ -873,14 +899,9 @@ GPS *GPS::createGps()
|
||||
LOG_DEBUG("Using " NMEA_MSG_GXGSA " for 3DFIX and PDOP\n");
|
||||
#endif
|
||||
|
||||
#if defined(HAS_PMU) || defined(PIN_GPS_EN)
|
||||
if (config.position.gps_enabled) {
|
||||
#ifdef PIN_GPS_EN
|
||||
pinMode(PIN_GPS_EN, OUTPUT);
|
||||
#endif
|
||||
setGPSPower(true);
|
||||
new_gps->setGPSPower(true, false);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef PIN_GPS_RESET
|
||||
digitalWrite(PIN_GPS_RESET, GPS_RESET_MODE); // assert for 10ms
|
||||
@ -1137,6 +1158,10 @@ bool GPS::hasFlow()
|
||||
bool GPS::whileIdle()
|
||||
{
|
||||
bool isValid = false;
|
||||
if (!isAwake) {
|
||||
clearBuffer();
|
||||
return isAwake;
|
||||
}
|
||||
#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());
|
||||
@ -1154,44 +1179,18 @@ bool GPS::whileIdle()
|
||||
|
||||
return isValid;
|
||||
}
|
||||
|
||||
void GPS::doGPSpowersave(bool on)
|
||||
void GPS::enable()
|
||||
{
|
||||
#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
|
||||
enabled = true;
|
||||
setInterval(GPS_THREAD_INTERVAL);
|
||||
setAwake(true);
|
||||
}
|
||||
|
||||
int32_t GPS::disable()
|
||||
{
|
||||
enabled = false;
|
||||
setInterval(INT32_MAX);
|
||||
setAwake(false);
|
||||
|
||||
return INT32_MAX;
|
||||
}
|
@ -4,6 +4,14 @@
|
||||
#include "Observer.h"
|
||||
#include "TinyGPS++.h"
|
||||
#include "concurrency/OSThread.h"
|
||||
#include "input/RotaryEncoderInterruptImpl1.h"
|
||||
#include "input/UpDownInterruptImpl1.h"
|
||||
#include "modules/PositionModule.h"
|
||||
|
||||
// Allow defining the polarity of the ENABLE output. default is active high
|
||||
#ifndef GPS_EN_ACTIVE
|
||||
#define GPS_EN_ACTIVE 1
|
||||
#endif
|
||||
|
||||
struct uBloxGnssModelInfo {
|
||||
char swVersion[30];
|
||||
@ -48,11 +56,14 @@ class GPS : private concurrency::OSThread
|
||||
uint8_t fixType = 0; // fix type from GPGSA
|
||||
#endif
|
||||
private:
|
||||
uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0, lastWhileActiveMsec = 0;
|
||||
uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0;
|
||||
const int serialSpeeds[6] = {9600, 4800, 38400, 57600, 115200, 9600};
|
||||
|
||||
uint32_t rx_gpio = 0;
|
||||
uint32_t tx_gpio = 0;
|
||||
uint32_t en_gpio = 0;
|
||||
int32_t averageLockTime = 0;
|
||||
uint32_t GPSCycles = 0;
|
||||
|
||||
int speedSelect = 0;
|
||||
int probeTries = 2;
|
||||
@ -65,7 +76,7 @@ class GPS : private concurrency::OSThread
|
||||
|
||||
bool isAwake = false; // true if we want a location right now
|
||||
|
||||
bool wakeAllowed = true; // false if gps must be forced to sleep regardless of what time it is
|
||||
bool isInPowersave = false;
|
||||
|
||||
bool shouldPublish = false; // If we've changed GPS state, this will force a publish the next loop()
|
||||
|
||||
@ -76,7 +87,6 @@ class GPS : private concurrency::OSThread
|
||||
|
||||
uint8_t numSatellites = 0;
|
||||
|
||||
CallbackObserver<GPS, void *> notifySleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareSleep);
|
||||
CallbackObserver<GPS, void *> notifyDeepSleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareDeepSleep);
|
||||
CallbackObserver<GPS, void *> notifyGPSSleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareDeepSleep);
|
||||
|
||||
@ -116,6 +126,14 @@ class GPS : private concurrency::OSThread
|
||||
*/
|
||||
virtual bool setup();
|
||||
|
||||
// re-enable the thread
|
||||
void enable();
|
||||
|
||||
// Disable the thread
|
||||
int32_t disable() override;
|
||||
|
||||
void setGPSPower(bool on, bool standbyOnly);
|
||||
|
||||
/// Returns true if we have acquired GPS lock.
|
||||
virtual bool hasLock();
|
||||
|
||||
@ -127,14 +145,6 @@ class GPS : private concurrency::OSThread
|
||||
|
||||
bool isPowerSaving() const { return !config.position.gps_enabled; }
|
||||
|
||||
/**
|
||||
* Restart our lock attempt - try to get and broadcast a GPS reading ASAP
|
||||
* called after the CPU wakes from light-sleep state
|
||||
*
|
||||
* Or set to false, to disallow any sort of waking
|
||||
* */
|
||||
void forceWake(bool on);
|
||||
|
||||
// Empty the input buffer as quickly as possible
|
||||
void clearBuffer();
|
||||
|
||||
@ -154,7 +164,6 @@ 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.
|
||||
@ -162,20 +171,6 @@ class GPS : private concurrency::OSThread
|
||||
static GPS *createGps();
|
||||
|
||||
protected:
|
||||
/// If possible force the GPS into sleep/low power mode
|
||||
virtual void sleep();
|
||||
|
||||
/// wake the GPS into normal operation mode
|
||||
virtual void wake();
|
||||
|
||||
/** Subclasses should look for serial rx characters here and feed it to their GPS parser
|
||||
*
|
||||
* Return true if we received a valid message from the GPS
|
||||
*/
|
||||
|
||||
/** Idle processing while GPS is looking for lock, called once per secondish */
|
||||
virtual void whileActive() {}
|
||||
|
||||
/**
|
||||
* Perform any processing that should be done only while the GPS is awake and looking for a fix.
|
||||
* Override this method to check for new locations
|
||||
@ -193,8 +188,6 @@ class GPS : private concurrency::OSThread
|
||||
/// 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
|
||||
@ -218,10 +211,6 @@ class GPS : private concurrency::OSThread
|
||||
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
|
||||
int prepareSleep(void *unused);
|
||||
|
||||
/// Prepare the GPS for the cpu entering deep sleep, expect to be gone for at least 100s of msecs
|
||||
/// always returns 0 to indicate okay to sleep
|
||||
int prepareDeepSleep(void *unused);
|
||||
|
@ -103,9 +103,8 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
|
||||
|
||||
bool shouldSet;
|
||||
if (q > currentQuality) {
|
||||
currentQuality = q;
|
||||
shouldSet = true;
|
||||
LOG_DEBUG("Upgrading time to RTC %ld secs (quality %d)\n", tv->tv_sec, q);
|
||||
LOG_DEBUG("Upgrading time to quality %d\n", q);
|
||||
} else if (q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000UL)) {
|
||||
// Every 12 hrs we will slam in a new GPS time, to correct for local RTC clock drift
|
||||
shouldSet = true;
|
||||
@ -114,12 +113,12 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
|
||||
shouldSet = false;
|
||||
|
||||
if (shouldSet) {
|
||||
currentQuality = q;
|
||||
lastSetMsec = now;
|
||||
|
||||
// This delta value works on all platforms
|
||||
timeStartMsec = now;
|
||||
zeroOffsetSecs = tv->tv_sec;
|
||||
|
||||
// If this platform has a setable RTC, set it
|
||||
#ifdef RV3028_RTC
|
||||
if (rtc_found.address == RV3028_RTC) {
|
||||
@ -209,4 +208,4 @@ uint32_t getTime()
|
||||
uint32_t getValidTime(RTCQuality minQuality)
|
||||
{
|
||||
return (currentQuality >= minQuality) ? getTime() : 0;
|
||||
}
|
||||
}
|
@ -5,12 +5,12 @@ RotaryEncoderInterruptImpl1 *rotaryEncoderInterruptImpl1;
|
||||
|
||||
RotaryEncoderInterruptImpl1::RotaryEncoderInterruptImpl1() : RotaryEncoderInterruptBase("rotEnc1") {}
|
||||
|
||||
void RotaryEncoderInterruptImpl1::init()
|
||||
bool RotaryEncoderInterruptImpl1::init()
|
||||
{
|
||||
if (!moduleConfig.canned_message.rotary1_enabled) {
|
||||
// Input device is disabled.
|
||||
disable();
|
||||
return;
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t pinA = moduleConfig.canned_message.inputbroker_pin_a;
|
||||
@ -25,6 +25,7 @@ void RotaryEncoderInterruptImpl1::init()
|
||||
RotaryEncoderInterruptImpl1::handleIntA, RotaryEncoderInterruptImpl1::handleIntB,
|
||||
RotaryEncoderInterruptImpl1::handleIntPressed);
|
||||
inputBroker->registerSource(this);
|
||||
return true;
|
||||
}
|
||||
|
||||
void RotaryEncoderInterruptImpl1::handleIntA()
|
||||
@ -38,4 +39,4 @@ void RotaryEncoderInterruptImpl1::handleIntB()
|
||||
void RotaryEncoderInterruptImpl1::handleIntPressed()
|
||||
{
|
||||
rotaryEncoderInterruptImpl1->intPressHandler();
|
||||
}
|
||||
}
|
@ -12,7 +12,7 @@ class RotaryEncoderInterruptImpl1 : public RotaryEncoderInterruptBase
|
||||
{
|
||||
public:
|
||||
RotaryEncoderInterruptImpl1();
|
||||
void init();
|
||||
bool init();
|
||||
static void handleIntA();
|
||||
static void handleIntB();
|
||||
static void handleIntPressed();
|
||||
|
@ -5,12 +5,12 @@ UpDownInterruptImpl1 *upDownInterruptImpl1;
|
||||
|
||||
UpDownInterruptImpl1::UpDownInterruptImpl1() : UpDownInterruptBase("upDown1") {}
|
||||
|
||||
void UpDownInterruptImpl1::init()
|
||||
bool UpDownInterruptImpl1::init()
|
||||
{
|
||||
|
||||
if (!moduleConfig.canned_message.updown1_enabled) {
|
||||
// Input device is disabled.
|
||||
return;
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t pinUp = moduleConfig.canned_message.inputbroker_pin_a;
|
||||
@ -24,6 +24,7 @@ void UpDownInterruptImpl1::init()
|
||||
UpDownInterruptBase::init(pinDown, pinUp, pinPress, eventDown, eventUp, eventPressed, UpDownInterruptImpl1::handleIntDown,
|
||||
UpDownInterruptImpl1::handleIntUp, UpDownInterruptImpl1::handleIntPressed);
|
||||
inputBroker->registerSource(this);
|
||||
return true;
|
||||
}
|
||||
|
||||
void UpDownInterruptImpl1::handleIntDown()
|
||||
@ -37,4 +38,4 @@ void UpDownInterruptImpl1::handleIntUp()
|
||||
void UpDownInterruptImpl1::handleIntPressed()
|
||||
{
|
||||
upDownInterruptImpl1->intPressHandler();
|
||||
}
|
||||
}
|
@ -5,10 +5,10 @@ class UpDownInterruptImpl1 : public UpDownInterruptBase
|
||||
{
|
||||
public:
|
||||
UpDownInterruptImpl1();
|
||||
void init();
|
||||
bool init();
|
||||
static void handleIntDown();
|
||||
static void handleIntUp();
|
||||
static void handleIntPressed();
|
||||
};
|
||||
|
||||
extern UpDownInterruptImpl1 *upDownInterruptImpl1;
|
||||
extern UpDownInterruptImpl1 *upDownInterruptImpl1;
|
@ -221,11 +221,6 @@ void setup()
|
||||
digitalWrite(VEXT_ENABLE, 0); // turn on the display power
|
||||
#endif
|
||||
|
||||
#ifdef VGNSS_CTRL
|
||||
pinMode(VGNSS_CTRL, OUTPUT);
|
||||
digitalWrite(VGNSS_CTRL, LOW);
|
||||
#endif
|
||||
|
||||
#if defined(VTFT_CTRL)
|
||||
pinMode(VTFT_CTRL, OUTPUT);
|
||||
digitalWrite(VTFT_CTRL, LOW);
|
||||
|
@ -169,6 +169,14 @@ void NodeDB::installDefaultConfig()
|
||||
config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET;
|
||||
config.lora.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST;
|
||||
config.lora.hop_limit = HOP_RELIABLE;
|
||||
#ifdef PIN_GPS_EN
|
||||
config.position.gps_en_gpio = PIN_GPS_EN;
|
||||
#endif
|
||||
#ifdef GPS_POWER_TOGGLE
|
||||
config.device.disable_triple_click = false;
|
||||
#else
|
||||
config.device.disable_triple_click = true;
|
||||
#endif
|
||||
config.position.gps_enabled = true;
|
||||
config.position.position_broadcast_smart_enabled = true;
|
||||
config.position.broadcast_smart_minimum_distance = 100;
|
||||
|
@ -237,8 +237,8 @@ typedef struct _meshtastic_Config_DeviceConfig {
|
||||
/* If true, device is considered to be "managed" by a mesh administrator
|
||||
Clients should then limit available configuration and administrative options inside the user interface */
|
||||
bool is_managed;
|
||||
/* Enables the triple-press of user button to enable or disable GPS */
|
||||
bool enable_triple_click;
|
||||
/* Disables the triple-press of user button to enable or disable GPS */
|
||||
bool disable_triple_click;
|
||||
} meshtastic_Config_DeviceConfig;
|
||||
|
||||
/* Position Config */
|
||||
@ -563,7 +563,7 @@ extern "C" {
|
||||
#define meshtastic_Config_DeviceConfig_node_info_broadcast_secs_tag 7
|
||||
#define meshtastic_Config_DeviceConfig_double_tap_as_button_press_tag 8
|
||||
#define meshtastic_Config_DeviceConfig_is_managed_tag 9
|
||||
#define meshtastic_Config_DeviceConfig_enable_triple_click_tag 10
|
||||
#define meshtastic_Config_DeviceConfig_disable_triple_click_tag 10
|
||||
#define meshtastic_Config_PositionConfig_position_broadcast_secs_tag 1
|
||||
#define meshtastic_Config_PositionConfig_position_broadcast_smart_enabled_tag 2
|
||||
#define meshtastic_Config_PositionConfig_fixed_position_tag 3
|
||||
@ -661,7 +661,7 @@ X(a, STATIC, SINGULAR, UENUM, rebroadcast_mode, 6) \
|
||||
X(a, STATIC, SINGULAR, UINT32, node_info_broadcast_secs, 7) \
|
||||
X(a, STATIC, SINGULAR, BOOL, double_tap_as_button_press, 8) \
|
||||
X(a, STATIC, SINGULAR, BOOL, is_managed, 9) \
|
||||
X(a, STATIC, SINGULAR, BOOL, enable_triple_click, 10)
|
||||
X(a, STATIC, SINGULAR, BOOL, disable_triple_click, 10)
|
||||
#define meshtastic_Config_DeviceConfig_CALLBACK NULL
|
||||
#define meshtastic_Config_DeviceConfig_DEFAULT NULL
|
||||
|
||||
@ -790,4 +790,4 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg;
|
||||
} /* extern "C" */
|
||||
#endif
|
||||
|
||||
#endif
|
||||
#endif
|
@ -60,9 +60,15 @@ void setupModules()
|
||||
new ReplyModule();
|
||||
#if HAS_BUTTON
|
||||
rotaryEncoderInterruptImpl1 = new RotaryEncoderInterruptImpl1();
|
||||
rotaryEncoderInterruptImpl1->init();
|
||||
if (!rotaryEncoderInterruptImpl1->init()) {
|
||||
delete rotaryEncoderInterruptImpl1;
|
||||
rotaryEncoderInterruptImpl1 = nullptr;
|
||||
}
|
||||
upDownInterruptImpl1 = new UpDownInterruptImpl1();
|
||||
upDownInterruptImpl1->init();
|
||||
if (!upDownInterruptImpl1->init()) {
|
||||
delete upDownInterruptImpl1;
|
||||
upDownInterruptImpl1 = nullptr;
|
||||
}
|
||||
cardKbI2cImpl = new CardKbI2cImpl();
|
||||
cardKbI2cImpl->init();
|
||||
#ifdef INPUTBROKER_MATRIX_TYPE
|
||||
|
@ -230,4 +230,41 @@ int32_t PositionModule::runOnce()
|
||||
}
|
||||
|
||||
return 5000; // to save power only wake for our callback occasionally
|
||||
}
|
||||
|
||||
void PositionModule::handleNewPosition()
|
||||
{
|
||||
meshtastic_NodeInfoLite *node = nodeDB.getMeshNode(nodeDB.getNodeNum());
|
||||
const meshtastic_NodeInfoLite *node2 = service.refreshLocalMeshNode(); // should guarantee there is now a position
|
||||
// We limit our GPS broadcasts to a max rate
|
||||
uint32_t now = millis();
|
||||
uint32_t msSinceLastSend = now - lastGpsSend;
|
||||
|
||||
if (hasValidPosition(node2)) {
|
||||
// The minimum distance to travel before we are able to send a new position packet.
|
||||
const uint32_t distanceTravelThreshold =
|
||||
config.position.broadcast_smart_minimum_distance > 0 ? config.position.broadcast_smart_minimum_distance : 100;
|
||||
|
||||
// Determine the distance in meters between two points on the globe
|
||||
float distanceTraveledSinceLastSend = GeoCoord::latLongToMeter(
|
||||
lastGpsLatitude * 1e-7, lastGpsLongitude * 1e-7, node->position.latitude_i * 1e-7, node->position.longitude_i * 1e-7);
|
||||
|
||||
if ((abs(distanceTraveledSinceLastSend) >= distanceTravelThreshold)) {
|
||||
bool requestReplies = currentGeneration != radioGeneration;
|
||||
currentGeneration = radioGeneration;
|
||||
|
||||
LOG_INFO("Sending smart pos@%x:6 to mesh (distanceTraveled=%fm, minDistanceThreshold=%im, timeElapsed=%ims)\n",
|
||||
localPosition.timestamp, abs(distanceTraveledSinceLastSend), distanceTravelThreshold, msSinceLastSend);
|
||||
sendOurPosition(NODENUM_BROADCAST, requestReplies);
|
||||
|
||||
// Set the current coords as our last ones, after we've compared distance with current and decided to send
|
||||
lastGpsLatitude = node->position.latitude_i;
|
||||
lastGpsLongitude = node->position.longitude_i;
|
||||
|
||||
/* Update lastGpsSend to now. This means if the device is stationary, then
|
||||
getPref_position_broadcast_secs will still apply.
|
||||
*/
|
||||
lastGpsSend = now;
|
||||
}
|
||||
}
|
||||
}
|
@ -31,6 +31,8 @@ class PositionModule : public ProtobufModule<meshtastic_Position>, private concu
|
||||
*/
|
||||
void sendOurPosition(NodeNum dest = NODENUM_BROADCAST, bool wantReplies = false, uint8_t channel = 0);
|
||||
|
||||
void handleNewPosition();
|
||||
|
||||
protected:
|
||||
/** Called to handle a particular incoming message
|
||||
|
||||
|
@ -90,33 +90,6 @@ void setLed(bool ledOn)
|
||||
#endif
|
||||
}
|
||||
|
||||
void setGPSPower(bool on)
|
||||
{
|
||||
LOG_INFO("Setting GPS power=%d\n", on);
|
||||
|
||||
#ifdef PIN_GPS_EN
|
||||
digitalWrite(PIN_GPS_EN, on ? 1 : 0);
|
||||
#endif
|
||||
|
||||
#ifdef HAS_PMU
|
||||
if (pmu_found && PMU) {
|
||||
uint8_t model = PMU->getChipModel();
|
||||
if (model == XPOWERS_AXP2101) {
|
||||
if (HW_VENDOR == meshtastic_HardwareModel_TBEAM) {
|
||||
// t-beam v1.2 GNSS power channel
|
||||
on ? PMU->enablePowerOutput(XPOWERS_ALDO3) : PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
} else if (HW_VENDOR == meshtastic_HardwareModel_LILYGO_TBEAM_S3_CORE) {
|
||||
// t-beam-s3-core GNSS power channel
|
||||
on ? PMU->enablePowerOutput(XPOWERS_ALDO4) : PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
}
|
||||
} else if (model == XPOWERS_AXP192) {
|
||||
// t-beam v1.1 GNSS power channel
|
||||
on ? PMU->enablePowerOutput(XPOWERS_LDO3) : PMU->disablePowerOutput(XPOWERS_LDO3);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// Perform power on init that we do on each wake from deep sleep
|
||||
void initDeepSleep()
|
||||
{
|
||||
@ -200,7 +173,7 @@ void doDeepSleep(uint32_t msecToWake)
|
||||
nodeDB.saveToDisk();
|
||||
|
||||
// Kill GPS power completely (even if previously we just had it in sleep mode)
|
||||
setGPSPower(false);
|
||||
gps->setGPSPower(false, false);
|
||||
|
||||
setLed(false);
|
||||
|
||||
|
@ -18,8 +18,6 @@ extern esp_sleep_source_t wakeCause;
|
||||
extern XPowersLibInterface *PMU;
|
||||
#endif
|
||||
|
||||
void setGPSPower(bool on);
|
||||
|
||||
// Perform power on init that we do on each wake from deep sleep
|
||||
void initDeepSleep();
|
||||
|
||||
|
@ -5,6 +5,7 @@ upload_protocol = esp-builtin
|
||||
|
||||
build_flags =
|
||||
${esp32s3_base.build_flags} -I variants/heltec_wireless_tracker
|
||||
-DGPS_POWER_TOGGLE
|
||||
|
||||
lib_deps =
|
||||
${esp32s3_base.lib_deps}
|
||||
|
@ -38,6 +38,8 @@
|
||||
#define PIN_GPS_RESET 35
|
||||
#define PIN_GPS_PPS 36
|
||||
#define VGNSS_CTRL 37 // Heltec Tracker needs this pulled low for GPS
|
||||
#define PIN_GPS_EN VGNSS_CTRL
|
||||
#define GPS_EN_ACTIVE LOW
|
||||
#define GPS_RESET_MODE LOW
|
||||
#define GPS_UC6580
|
||||
|
||||
|
@ -164,8 +164,8 @@ static const uint8_t SCK = PIN_SPI_SCK;
|
||||
#define ST7735_SDA (39) // actually spi MOSI
|
||||
#define ST7735_SCK (37) // actually spi clk
|
||||
|
||||
#define PIN_GPS_WAKE 36 // Just kill GPS power when we want it to sleep? FIXME
|
||||
#define GPS_WAKE_ACTIVE 0 // GPS Power output is active low
|
||||
#define PIN_GPS_EN 36 // Just kill GPS power when we want it to sleep? FIXME
|
||||
#define GPS_EN_ACTIVE 0 // GPS Power output is active low
|
||||
|
||||
// #define LORA_DISABLE_SENDING // The board can brownout during lora TX if you don't have a battery connected. Disable sending
|
||||
// to allow USB power only based debugging
|
||||
|
@ -23,7 +23,7 @@
|
||||
#define VARIANT_MCK (64000000ul)
|
||||
|
||||
#define USE_LFXO // Board uses 32khz crystal for LF
|
||||
//#define USE_LFRC // Board uses 32khz RC for LF
|
||||
// #define USE_LFRC // Board uses 32khz RC for LF
|
||||
|
||||
/*----------------------------------------------------------------------------
|
||||
* Headers
|
||||
@ -54,7 +54,7 @@ extern "C" {
|
||||
#define LED_CONN PIN_GREEN
|
||||
|
||||
#define LED_STATE_ON 0 // State when LED is lit
|
||||
//#define LED_INVERTED 1
|
||||
// #define LED_INVERTED 1
|
||||
|
||||
/*
|
||||
* Buttons
|
||||
@ -114,7 +114,7 @@ External serial flash W25Q16JV_IQ
|
||||
#define SX126X_CS (32 + 13) // FIXME - we really should define LORA_CS instead
|
||||
#define SX126X_DIO1 (32 + 10)
|
||||
// Note DIO2 is attached internally to the module to an analog switch for TX/RX switching
|
||||
//#define SX1262_DIO3 (0 + 21)
|
||||
// #define SX1262_DIO3 (0 + 21)
|
||||
// This is used as an *output* from the sx1262 and connected internally to power the tcxo, do not drive from the main CPU?
|
||||
#define SX126X_BUSY (32 + 11)
|
||||
#define SX126X_RESET (32 + 15)
|
||||
@ -130,11 +130,11 @@ External serial flash W25Q16JV_IQ
|
||||
|
||||
#define GPS_L76K
|
||||
|
||||
#define PIN_GPS_WAKE (0 + 13) // An output to wake GPS, low means allow sleep, high means force wake
|
||||
#define PIN_GPS_TX (0 + 9) // This is for bits going TOWARDS the CPU
|
||||
#define PIN_GPS_RX (0 + 10) // This is for bits going TOWARDS the GPS
|
||||
#define PIN_GPS_STANDBY (0 + 13) // An output to wake GPS, low means allow sleep, high means force wake STANDBY
|
||||
#define PIN_GPS_TX (0 + 9) // This is for bits going TOWARDS the CPU
|
||||
#define PIN_GPS_RX (0 + 10) // This is for bits going TOWARDS the GPS
|
||||
|
||||
//#define GPS_THREAD_INTERVAL 50
|
||||
// #define GPS_THREAD_INTERVAL 50
|
||||
|
||||
#define PIN_SERIAL1_RX PIN_GPS_TX
|
||||
#define PIN_SERIAL1_TX PIN_GPS_RX
|
||||
@ -152,7 +152,7 @@ External serial flash W25Q16JV_IQ
|
||||
#define PIN_SPI_MOSI (0 + 11)
|
||||
#define PIN_SPI_SCK (0 + 12)
|
||||
|
||||
//#define PIN_PWR_EN (0 + 6)
|
||||
// #define PIN_PWR_EN (0 + 6)
|
||||
|
||||
// To debug via the segger JLINK console rather than the CDC-ACM serial device
|
||||
// #define USE_SEGGER
|
||||
|
@ -8,6 +8,7 @@ debug_tool = esp-builtin
|
||||
build_flags = ${esp32_base.build_flags}
|
||||
-DT_DECK
|
||||
-DBOARD_HAS_PSRAM
|
||||
-DGPS_POWER_TOGGLE
|
||||
-Ivariants/t-deck
|
||||
|
||||
lib_deps = ${esp32s3_base.lib_deps}
|
||||
|
@ -85,9 +85,9 @@ static const uint8_t A0 = PIN_A0;
|
||||
/*
|
||||
No longer populated on PCB
|
||||
*/
|
||||
//#define PIN_SERIAL2_RX (0 + 6)
|
||||
//#define PIN_SERIAL2_TX (0 + 8)
|
||||
// #define PIN_SERIAL2_EN (0 + 17)
|
||||
// #define PIN_SERIAL2_RX (0 + 6)
|
||||
// #define PIN_SERIAL2_TX (0 + 8)
|
||||
// #define PIN_SERIAL2_EN (0 + 17)
|
||||
|
||||
/**
|
||||
Wire Interfaces
|
||||
@ -171,7 +171,7 @@ External serial flash WP25R1635FZUIL0
|
||||
#define GPS_L76K
|
||||
#define PIN_GPS_REINIT (32 + 5) // An output to reset L76K GPS. As per datasheet, low for > 100ms will reset the L76K
|
||||
|
||||
#define PIN_GPS_WAKE (32 + 2) // An output to wake GPS, low means allow sleep, high means force wake
|
||||
#define PIN_GPS_STANDBY (32 + 2) // An output to wake GPS, low means allow sleep, high means force wake
|
||||
// Seems to be missing on this new board
|
||||
// #define PIN_GPS_PPS (32 + 4) // Pulse per second input from the GPS
|
||||
#define PIN_GPS_TX (32 + 9) // This is for bits going TOWARDS the CPU
|
||||
|
Loading…
Reference in New Issue
Block a user