#376 use power off command instead of killing gps power per manual 9.5

pull/456/head
Kevin Hester 2020-10-07 11:44:30 +08:00
rodzic 4ccd03623f
commit 044cc26340
3 zmienionych plików z 50 dodań i 6 usunięć

Wyświetl plik

@ -6,8 +6,48 @@ bin/run.sh --set region 8
time only mode
./bin/run.sh --set gps_operation 3
increase acquisition time until ublox power management can be improved see 9.3.1
ublox parsing failure
record power measurements and update spreadsheet
wait to sleep loop problem
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
Can not send yet, busyRx
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
vs normal run
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
radio wait to sleep, txEmpty=0
Starting low level send (id=0x53fe1dd0 Fr0xe5 To0xff, WantAck0, HopLim3 encrypted)
Completed sending (id=0x53fe1dd0 Fr0xe5 To0xff, WantAck0, HopLim3 encrypted)
fix has_gps based on new logic
don't send locations if the user has forbidden that (lie to phone so phone won't either)

Wyświetl plik

@ -151,7 +151,7 @@ uint32_t GPS::getWakeTime() const
return t; // already maxint
if (t == 0)
t = 2 * 60; // default to 2 mins
t = 5 * 60; // Allow up to 5 mins for each attempt (probably will be much less if we can find sats)
t *= 1000; // msecs
@ -223,6 +223,7 @@ void GPS::loop()
// Once we get a location we no longer desperately want an update
// 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 || tooLong || (gotTime && getGpsOp() == GpsOperation_GpsOpTimeOnly)) {
if (gotLoc)
hasValidLocation = true;

Wyświetl plik

@ -31,7 +31,7 @@ bool UBloxGPS::setupGPS()
#else
_serial_gps->begin(GPS_BAUDRATE);
#endif
// _serial_gps.setRxBufferSize(1024); // the default is 256
_serial_gps->setRxBufferSize(1024); // the default is 256
}
// uncomment to see debug info
@ -202,15 +202,18 @@ bool UBloxGPS::whileIdle()
/// Note: ublox doesn't need a wake method, because as soon as we send chars to the GPS it will wake up
void UBloxGPS::sleep()
{
// won't work on 6M
// ublox.powerOff();
setGPSPower(false);
// Tell GPS to power down until we send it characters on serial port (we leave vcc connected)
ublox.powerOff();
// setGPSPower(false);
}
void UBloxGPS::wake()
{
fixType = 0; // assume we hace no fix yet
setGPSPower(true);
// Note: no delay needed because now we leave gps power on always and instead use ublox.powerOff()
// Give time for the GPS to boot
delay(200);
// delay(200);
}