Skip to content

Commit

Permalink
Merge pull request #463 from geeksville/dev
Browse files Browse the repository at this point in the history
fix #462 publish immediately on any GPS state change
  • Loading branch information
geeksville authored Oct 11, 2020
2 parents 514ebdf + c3beca3 commit 87f2673
Show file tree
Hide file tree
Showing 6 changed files with 73 additions and 30 deletions.
51 changes: 41 additions & 10 deletions src/gps/GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,23 @@ bool GPS::setup()
return ok;
}

/// Record that we have a GPS
void GPS::setConnected()
{
if (!hasGPS) {
hasGPS = true;
shouldPublish = true;
}
}

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
*
Expand Down Expand Up @@ -114,19 +131,23 @@ uint32_t GPS::getSleepTime() const

void GPS::publishUpdate()
{
DEBUG_MSG("publishing GPS lock=%d\n", hasLock());
if (shouldPublish) {
shouldPublish = false;

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);
// 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::loop()
{
if (whileIdle()) {
// if we have received valid NMEA claim we are connected
isConnected = true;
setConnected();
}

// If we are overdue for an update, turn on the GPS and at least publish the current status
Expand All @@ -147,8 +168,17 @@ void GPS::loop()
}

// If we've already set time from the GPS, no need to ask the GPS
bool gotTime = (getRTCQuality() >= RTCQualityGPS) || lookForTime();
bool gotTime = (getRTCQuality() >= RTCQualityGPS);
if (!gotTime && lookForTime()) { // Note: we count on this && short-circuiting and not resetting the RTC time
gotTime = true;
shouldPublish = true;
}

bool gotLoc = lookForLocation();
if (gotLoc && !hasValidLocation) { // declare that we have location ASAP
hasValidLocation = true;
shouldPublish = true;
}

// We've been awake too long - force sleep
auto wakeTime = getWakeTime();
Expand All @@ -158,18 +188,19 @@ void GPS::loop()
// or if we got a time and we are in GpsOpTimeOnly mode
// DEBUG_MSG("gotLoc %d, tooLong %d, gotTime %d\n", gotLoc, tooLong, gotTime);
if ((gotLoc && gotTime) || tooLong || (gotTime && getGpsOp() == GpsOperation_GpsOpTimeOnly)) {
if (gotLoc)
hasValidLocation = true;

if (tooLong) {
// we didn't get a location during this ack window, therefore declare loss of lock
hasValidLocation = false;
}

setAwake(false);
publishUpdate(); // publish our update for this just finished acquisition window
shouldPublish = true; // publish our update for this just finished acquisition window
}
}

// If state has changed do a publish
publishUpdate();
}

void GPS::forceWake(bool on)
Expand Down
18 changes: 14 additions & 4 deletions src/gps/GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,14 @@ class GPS

bool wakeAllowed = true; // false if gps must be forced to sleep regardless of what time it is

bool shouldPublish = false; // If we've changed GPS state, this will force a publish the next loop()

bool hasGPS = false; // Do we have a GPS we are talking to

uint8_t numSatellites = 0;

CallbackObserver<GPS, void *> notifySleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareSleep);

protected:
public:
/** If !NULL we will use this serial port to construct our GPS */
static HardwareSerial *_serial_gps;
Expand All @@ -37,9 +42,6 @@ class GPS
uint32_t dop = 0; // Diminution of position; PDOP where possible (UBlox), HDOP otherwise (TinyGPS) in 10^2 units (needs
// scaling before use)
uint32_t heading = 0; // Heading of motion, in degrees * 10^-5
uint32_t numSatellites = 0;

bool isConnected = false; // Do we have a GPS we are talking to

virtual ~GPS() {} // FIXME, we really should unregister our sleep observer

Expand All @@ -56,6 +58,9 @@ class GPS
/// Returns ture if we have acquired GPS lock.
bool hasLock() const { return hasValidLocation; }

/// Return true if we are connected to a GPS
bool isConnected() const { return hasGPS; }

/**
* Restart our lock attempt - try to get and broadcast a GPS reading ASAP
* called after the CPU wakes from light-sleep state
Expand Down Expand Up @@ -99,6 +104,11 @@ class GPS
*/
virtual bool lookForLocation() = 0;

/// Record that we have a GPS
void setConnected();

void setNumSatellites(uint8_t n);

private:
/// Prepare the GPS for the cpu entering deep or light sleep, expect to be gone for at least 100s of msecs
/// always returns 0 to indicate okay to sleep
Expand Down
2 changes: 1 addition & 1 deletion src/gps/NMEAGPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ bool NMEAGPS::lookForLocation()
heading = reader.course.value() * 1e3; // Scale the heading (in degrees * 10^-2) to match the expected degrees * 10^-5
}
if (reader.satellites.isValid()) {
numSatellites = reader.satellites.value();
setNumSatellites(reader.satellites.value());
}

// expect gps pos lat=37.520825, lon=-122.309162, alt=158
Expand Down
26 changes: 14 additions & 12 deletions src/gps/UBloxGPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,20 +8,23 @@ UBloxGPS::UBloxGPS() {}

bool UBloxGPS::tryConnect()
{
isConnected = false;
bool c = false;

if (_serial_gps)
isConnected = ublox.begin(*_serial_gps);
c = ublox.begin(*_serial_gps);

if (!isConnected && i2cAddress) {
if (!c && i2cAddress) {
extern bool neo6M; // Super skanky - if we are talking to the device i2c we assume it is a neo7 on a RAK815, which
// supports the newer API
neo6M = true;

isConnected = ublox.begin(Wire, i2cAddress);
c = ublox.begin(Wire, i2cAddress);
}

return isConnected;
if (c)
setConnected();

return c;
}

bool UBloxGPS::setupGPS()
Expand All @@ -45,7 +48,7 @@ bool UBloxGPS::setupGPS()
for (int i = 0; (i < 3) && !tryConnect(); i++)
delay(500);

if (isConnected) {
if (isConnected()) {
DEBUG_MSG("Connected to UBLOX GPS successfully\n");

if (!setUBXMode())
Expand Down Expand Up @@ -106,8 +109,8 @@ bool UBloxGPS::factoryReset()
for (int i = 0; (i < 3) && !tryConnect(); i++)
delay(500);

DEBUG_MSG("GPS Factory reset success=%d\n", isConnected);
if (isConnected)
DEBUG_MSG("GPS Factory reset success=%d\n", isConnected());
if (isConnected())
ok = setUBXMode();

return ok;
Expand All @@ -127,7 +130,7 @@ void UBloxGPS::whileActive()
// Update fixtype
if (ublox.moduleQueried.fixType) {
fixType = ublox.getFixType(0);
DEBUG_MSG("GPS fix type %d, numSats %d\n", fixType, numSatellites);
// DEBUG_MSG("GPS fix type %d, numSats %d\n", fixType, numSatellites);
}
}

Expand Down Expand Up @@ -170,7 +173,7 @@ bool UBloxGPS::lookForLocation()
bool foundLocation = false;

if (ublox.moduleQueried.SIV)
numSatellites = ublox.getSIV(0);
setNumSatellites(ublox.getSIV(0));

if (ublox.moduleQueried.pDOP)
dop = ublox.getPDOP(0); // PDOP (an accuracy metric) is reported in 10^2 units so we have to scale down when we use it
Expand All @@ -189,8 +192,7 @@ bool UBloxGPS::lookForLocation()

// bogus lat lon is reported as 0 or 0 (can be bogus just for one)
// Also: apparently when the GPS is initially reporting lock it can output a bogus latitude > 90 deg!
foundLocation =
(latitude != 0) && (longitude != 0) && (latitude <= 900000000 && latitude >= -900000000) && (numSatellites > 0);
foundLocation = (latitude != 0) && (longitude != 0) && (latitude <= 900000000 && latitude >= -900000000);
}
}

Expand Down
4 changes: 2 additions & 2 deletions src/mesh/MeshService.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -247,10 +247,10 @@ void MeshService::sendToMesh(MeshPacket *p)
nodeDB.updateFrom(*p); // update our local DB for this packet (because phone might have sent position packets etc...)

// Strip out any time information before sending packets to other nodes - to keep the wire size small (and because other
// nodes shouldn't trust it anyways) Note: for now, we allow a device with a local GPS to include the time, so that gpsless
// nodes shouldn't trust it anyways) Note: we allow a device with a local GPS to include the time, so that gpsless
// devices can get time.
if (p->which_payload == MeshPacket_decoded_tag && p->decoded.which_payload == SubPacket_position_tag) {
if (!gps->isConnected) {
if (getRTCQuality() < RTCQualityGPS) {
DEBUG_MSG("Stripping time %u from position send\n", p->decoded.position.time);
p->decoded.position.time = 0;
} else
Expand Down
2 changes: 1 addition & 1 deletion src/mesh/PhoneAPI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ size_t PhoneAPI::getFromRadio(uint8_t *buf)
// app not to send locations on our behalf.
myNodeInfo.has_gps = (radioConfig.preferences.location_share == LocationSharing_LocDisabled)
? true
: (gps && gps->isConnected); // Update with latest GPS connect info
: (gps && gps->isConnected()); // Update with latest GPS connect info
fromRadioScratch.which_variant = FromRadio_my_info_tag;
fromRadioScratch.variant.my_info = myNodeInfo;
state = STATE_SEND_RADIO;
Expand Down

0 comments on commit 87f2673

Please sign in to comment.