wip gps power fixes #376

This commit is contained in:
geeksville
2020-10-01 09:11:54 -07:00
parent 56d4250197
commit bacc6caf04
8 changed files with 333 additions and 190 deletions

View File

@@ -1,6 +1,7 @@
#include "GPS.h"
#include "configuration.h"
#include "sleep.h"
#include <assert.h>
#include <time.h>
@@ -86,19 +87,99 @@ uint32_t getValidTime()
return timeSetFromGPS ? getTime() : 0;
}
bool GPS::setup()
{
notifySleepObserver.observe(&notifySleep);
return true;
}
/**
* Switch the GPS into a mode where we are actively looking for a lock, or alternatively switch GPS into a low power mode
*
* calls sleep/wake
*/
void GPS::setWantLocation(bool on)
void GPS::setAwake(bool on)
{
if (wantNewLocation != on) {
wantNewLocation = on;
if(!wakeAllowed && on) {
DEBUG_MSG("Inhibiting because !wakeAllowed\n");
on = false;
}
if (isAwake != on) {
DEBUG_MSG("WANT GPS=%d\n", on);
if (on)
wake();
else
sleep();
isAwake = on;
}
}
void GPS::loop()
{
if (whileIdle()) {
// if we have received valid NMEA claim we are connected
isConnected = true;
}
// If we are overdue for an update, turn on the GPS and at least publish the current status
uint32_t now = millis();
bool mustPublishUpdate = false;
if ((now - lastUpdateMsec) > 30 * 1000 && !isAwake) {
// We now want to be awake - so wake up the GPS
setAwake(true);
mustPublishUpdate =
true; // Even if we don't have an update this time, we at least want to occasionally publish the current state
}
// While we are awake
if (isAwake) {
DEBUG_MSG("looking for location\n");
bool gotTime = lookForTime();
bool gotLoc = lookForLocation();
if (gotLoc)
hasValidLocation = true;
mustPublishUpdate |= gotLoc;
// Once we get a location we no longer desperately want an update
if (gotLoc) {
lastUpdateMsec = now;
setAwake(false);
}
}
}
if (mustPublishUpdate) {
DEBUG_MSG("publishing GPS lock=%d\n", hasLock());
// Notify any status instances that are observing us
const meshtastic::GPSStatus status =
meshtastic::GPSStatus(hasLock(), isConnected, latitude, longitude, altitude, dop, heading, numSatellites);
newStatus.notifyObservers(&status);
}
}
void GPS::forceWake(bool on)
{
if (on) {
DEBUG_MSG("Looking for GPS lock\n");
lastUpdateMsec = 0; // Force an update ASAP
wakeAllowed = true;
} else {
wakeAllowed = false;
setAwake(false);
}
}
/// 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)
{
forceWake(false);
return 0;
}