sforkowany z mirror/meshtastic-firmware
begin testing native ublox api
rodzic
4999da0824
commit
9bbd658b9d
|
@ -2,6 +2,7 @@
|
|||
|
||||
Items to complete soon (next couple of alpha releases).
|
||||
|
||||
* make girts gps work again with SparkFun Ublox Arduino Library_ID5746/examples/Example13_PVT/Example3_AssumeAutoPVTviaUart/Example3_AssumeAutoPVTviaUart.ino
|
||||
* turn on gps https://github.com/sparkfun/SparkFun_Ublox_Arduino_Library/blob/master/examples/Example18_PowerSaveMode/Example18_PowerSaveMode.ino
|
||||
* switch gps to 38400 baud https://github.com/sparkfun/SparkFun_Ublox_Arduino_Library/blob/master/examples/Example11_ResetModule/Example2_FactoryDefaultsviaSerial/Example2_FactoryDefaultsviaSerial.ino
|
||||
* Use Neo-M8M API to put it in sleep mode
|
||||
|
|
|
@ -59,7 +59,6 @@ debug_init_break = tbreak setup
|
|||
; names.
|
||||
lib_deps =
|
||||
https://github.com/meshtastic/RadioHead.git
|
||||
1655 ; TinyGPSPlus
|
||||
https://github.com/meshtastic/esp8266-oled-ssd1306.git ; ESP8266_SSD1306
|
||||
AXP202X_Library
|
||||
SPI
|
||||
|
|
52
src/GPS.cpp
52
src/GPS.cpp
|
@ -4,7 +4,6 @@
|
|||
#include <sys/time.h>
|
||||
#include "configuration.h"
|
||||
|
||||
|
||||
HardwareSerial _serial_gps(GPS_SERIAL_NUM);
|
||||
|
||||
RTC_DATA_ATTR bool timeSetFromGPS; // We only reset our time once per _boot_ after that point just run from the internal clock (even across sleeps)
|
||||
|
@ -28,23 +27,36 @@ void GPS::setup()
|
|||
|
||||
#ifdef GPS_RX_PIN
|
||||
_serial_gps.begin(GPS_BAUDRATE, SERIAL_8N1, GPS_RX_PIN, GPS_TX_PIN);
|
||||
ublox.enableDebugging(Serial);
|
||||
// ublox.enableDebugging(Serial);
|
||||
|
||||
#if 0
|
||||
// note: the lib's implementation has the wrong docs for what the return val is
|
||||
// it is not a bool, it returns zero for success
|
||||
bool errCode = ublox.begin(_serial_gps);
|
||||
assert(!errCode); // FIXME, report hw failure on screen
|
||||
isConnected = ublox.begin(_serial_gps);
|
||||
if (isConnected)
|
||||
{
|
||||
DEBUG_MSG("Connected to GPS successfully\n");
|
||||
|
||||
bool ok = ublox.setUART1Output(COM_TYPE_UBX); // Use native API
|
||||
assert(ok);
|
||||
ok = ublox.setNavigationFrequency(1); //Produce one solutions per second
|
||||
assert(ok);
|
||||
ok = ublox.setAutoPVT(true);
|
||||
assert(ok);
|
||||
// ublox.saveConfiguration();
|
||||
assert(ok);
|
||||
#endif
|
||||
bool ok = ublox.setUART1Output(COM_TYPE_UBX); // Use native API
|
||||
assert(ok);
|
||||
ok = ublox.setNavigationFrequency(1); //Produce one solutions per second
|
||||
assert(ok);
|
||||
ok = ublox.setAutoPVT(false);
|
||||
assert(ok);
|
||||
ok = ublox.setDynamicModel(DYN_MODEL_BIKE); // probably PEDESTRIAN but just in case assume bike speeds
|
||||
assert(ok);
|
||||
ok = ublox.saveConfiguration();
|
||||
assert(ok);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Some boards might have only the TX line from the GPS connected, in that case, we can't configure it at all. Just
|
||||
// assume NEMA at 9600 baud.
|
||||
DEBUG_MSG("ERROR: No bidirectional GPS found, hoping that it still might work\n");
|
||||
|
||||
// tell lib, we are expecting the module to send PVT messages by itself to our Rx pin
|
||||
// you can set second parameter to "false" if you want to control the parsing and eviction of the data (need to call checkUblox cyclically)
|
||||
ublox.assumeAutoPVT(true, true);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -109,17 +121,19 @@ void GPS::doTask()
|
|||
#ifdef GPS_RX_PIN
|
||||
// Consume all characters that have arrived
|
||||
|
||||
#if 0
|
||||
ublox.checkUblox(); //See if new data is available. Process bytes as they come in.
|
||||
// getPVT automatically calls checkUblox
|
||||
// ublox.checkUblox(); //See if new data is available. Process bytes as they come in.
|
||||
DEBUG_MSG("numsat %d, sec %d\n", ublox.getSIV(), ublox.getSecond());
|
||||
|
||||
#if 0
|
||||
if (ublox.getPVT())
|
||||
{ // we only notify if position has changed
|
||||
isConnected = true; // We just received a packet, so we must have a GPS
|
||||
|
||||
if (!timeSetFromGPS)
|
||||
{
|
||||
struct timeval tv;
|
||||
|
||||
DEBUG_MSG("Got time from GPS month=%d, year=%d\n", ublox.getMonth(), ublox.getYear());
|
||||
|
||||
/* 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).
|
||||
*/
|
||||
|
@ -135,6 +149,8 @@ void GPS::doTask()
|
|||
tv.tv_sec = res;
|
||||
tv.tv_usec = 0; // time.centisecond() * (10 / 1000);
|
||||
|
||||
DEBUG_MSG("Got time from GPS month=%d, year=%d, unixtime=%ld\n", ublox.getMonth(), ublox.getYear(), tv.tv_sec);
|
||||
|
||||
// FIXME
|
||||
// perhapsSetRTC(&tv);
|
||||
}
|
||||
|
|
|
@ -17,6 +17,7 @@ class GPS : public PeriodicTask, public Observable
|
|||
public:
|
||||
double latitude, longitude;
|
||||
uint32_t altitude;
|
||||
bool isConnected; // Do we have a GPS we are talking to
|
||||
|
||||
GPS();
|
||||
|
||||
|
@ -50,6 +51,3 @@ private:
|
|||
|
||||
extern GPS gps;
|
||||
|
||||
// Temporary support for the one TTGO in the world with a busted serial rx line (my old devboard)
|
||||
extern HardwareSerial _serial_gps;
|
||||
extern RTC_DATA_ATTR bool timeSetFromGPS;
|
156
src/GPSNema.cpp
156
src/GPSNema.cpp
|
@ -1,156 +0,0 @@
|
|||
|
||||
#include "GPSNema.h"
|
||||
#include "time.h"
|
||||
#include <sys/time.h>
|
||||
#include "configuration.h"
|
||||
#include "GPS.h"
|
||||
|
||||
// GPSNema gps;
|
||||
|
||||
// stuff that really should be in in the instance instead...
|
||||
static uint32_t timeStartMsec; // Once we have a GPS lock, this is where we hold the initial msec clock that corresponds to that time
|
||||
static uint64_t zeroOffsetSecs; // GPS based time in secs since 1970 - only updated once on initial lock
|
||||
|
||||
static bool hasValidLocation; // default to false, until we complete our first read
|
||||
static bool wantNewLocation = true;
|
||||
|
||||
GPSNema::GPSNema() : PeriodicTask()
|
||||
{
|
||||
}
|
||||
|
||||
void GPSNema::setup()
|
||||
{
|
||||
readFromRTC();
|
||||
|
||||
#ifdef GPS_RX_PIN
|
||||
_serial_gps.begin(GPS_BAUDRATE, SERIAL_8N1, GPS_RX_PIN, GPS_TX_PIN);
|
||||
#endif
|
||||
}
|
||||
|
||||
void GPSNema::readFromRTC()
|
||||
{
|
||||
struct timeval tv; /* btw settimeofday() is helpfull here too*/
|
||||
|
||||
if (!gettimeofday(&tv, NULL))
|
||||
{
|
||||
uint32_t now = millis();
|
||||
|
||||
DEBUG_MSG("Read RTC time as %ld (cur millis %u) valid=%d\n", tv.tv_sec, now, timeSetFromGPS);
|
||||
timeStartMsec = now;
|
||||
zeroOffsetSecs = tv.tv_sec;
|
||||
}
|
||||
}
|
||||
|
||||
/// If we haven't yet set our RTC this boot, set it from a GPS derived time
|
||||
void GPSNema::perhapsSetRTC(const struct timeval *tv)
|
||||
{
|
||||
if (!timeSetFromGPS)
|
||||
{
|
||||
timeSetFromGPS = true;
|
||||
DEBUG_MSG("Setting RTC %ld secs\n", tv->tv_sec);
|
||||
settimeofday(tv, NULL);
|
||||
readFromRTC();
|
||||
}
|
||||
}
|
||||
|
||||
#include <time.h>
|
||||
|
||||
// for the time being we need to rapidly read from the serial port to prevent overruns
|
||||
void GPSNema::loop()
|
||||
{
|
||||
PeriodicTask::loop();
|
||||
}
|
||||
|
||||
uint32_t GPSNema::getTime()
|
||||
{
|
||||
return ((millis() - timeStartMsec) / 1000) + zeroOffsetSecs;
|
||||
}
|
||||
|
||||
uint32_t GPSNema::getValidTime()
|
||||
{
|
||||
return timeSetFromGPS ? getTime() : 0;
|
||||
}
|
||||
|
||||
/// Returns true if we think the board can enter deep or light sleep now (we might be trying to get a GPS lock)
|
||||
bool GPSNema::canSleep()
|
||||
{
|
||||
return !wantNewLocation;
|
||||
}
|
||||
|
||||
/// Prepare the GPS for the cpu entering deep or light sleep, expect to be gone for at least 100s of msecs
|
||||
void GPSNema::prepareSleep()
|
||||
{
|
||||
// discard all rx serial bytes so we don't try to parse them when we come back
|
||||
while (_serial_gps.available())
|
||||
{
|
||||
_serial_gps.read();
|
||||
}
|
||||
|
||||
// make the parser bail on whatever it was parsing
|
||||
encode('\n');
|
||||
}
|
||||
|
||||
void GPSNema::doTask()
|
||||
{
|
||||
#ifdef GPS_RX_PIN
|
||||
// Consume all characters that have arrived
|
||||
|
||||
while (_serial_gps.available())
|
||||
{
|
||||
encode(_serial_gps.read());
|
||||
// DEBUG_MSG("Got GPS response\n");
|
||||
}
|
||||
|
||||
if (!timeSetFromGPS && time.isValid() && date.isValid())
|
||||
{
|
||||
struct timeval tv;
|
||||
|
||||
DEBUG_MSG("Got time from GPS\n");
|
||||
|
||||
/* 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 = time.second();
|
||||
t.tm_min = time.minute();
|
||||
t.tm_hour = time.hour();
|
||||
t.tm_mday = date.day();
|
||||
t.tm_mon = date.month() - 1;
|
||||
t.tm_year = date.year() - 1900;
|
||||
t.tm_isdst = false;
|
||||
time_t res = mktime(&t);
|
||||
tv.tv_sec = res;
|
||||
tv.tv_usec = 0; // time.centisecond() * (10 / 1000);
|
||||
|
||||
perhapsSetRTC(&tv);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (location.isValid() && location.isUpdated())
|
||||
{ // we only notify if position has changed
|
||||
// DEBUG_MSG("new gps pos\n");
|
||||
hasValidLocation = true;
|
||||
wantNewLocation = false;
|
||||
notifyObservers();
|
||||
}
|
||||
else // we didn't get a location update, go back to sleep and hope the characters show up
|
||||
wantNewLocation = true;
|
||||
|
||||
// Once we have sent a location once we only poll the GPS rarely, otherwise check back every 100ms until we have something over the serial
|
||||
setPeriod(hasValidLocation && !wantNewLocation ? 30 * 1000 : 100);
|
||||
}
|
||||
|
||||
void GPSNema::startLock()
|
||||
{
|
||||
DEBUG_MSG("Looking for GPS lock\n");
|
||||
wantNewLocation = true;
|
||||
setPeriod(1);
|
||||
}
|
||||
|
||||
String GPSNema::getTimeStr()
|
||||
{
|
||||
static char t[12]; // used to sprintf for Serial output
|
||||
|
||||
snprintf(t, sizeof(t), "%02d:%02d:%02d", time.hour(), time.minute(), time.second());
|
||||
return t;
|
||||
}
|
|
@ -1,48 +0,0 @@
|
|||
#pragma once
|
||||
|
||||
#include <TinyGPS++.h>
|
||||
#include "PeriodicTask.h"
|
||||
#include "Observer.h"
|
||||
#include "sys/time.h"
|
||||
|
||||
/**
|
||||
* A gps class that only reads from the GPS periodically (and FIXME - eventually keeps the gps powered down except when reading)
|
||||
*
|
||||
* When new data is available it will notify observers.
|
||||
*/
|
||||
class GPSNema : public PeriodicTask, public Observable, public TinyGPSPlus
|
||||
{
|
||||
public:
|
||||
GPSNema();
|
||||
|
||||
/// Return time since 1970 in secs. Until we have a GPS lock we will be returning time based at zero
|
||||
uint32_t getTime();
|
||||
|
||||
/// Return time since 1970 in secs. If we don't have a GPS lock return zero
|
||||
uint32_t getValidTime();
|
||||
|
||||
String getTimeStr();
|
||||
|
||||
void setup();
|
||||
|
||||
virtual void loop();
|
||||
|
||||
virtual void doTask();
|
||||
|
||||
/// If we haven't yet set our RTC this boot, set it from a GPS derived time
|
||||
void perhapsSetRTC(const struct timeval *tv);
|
||||
|
||||
/// Returns true if we think the board can enter deep or light sleep now (we might be trying to get a GPS lock)
|
||||
bool canSleep();
|
||||
|
||||
/// Prepare the GPS for the cpu entering deep or light sleep, expect to be gone for at least 100s of msecs
|
||||
void prepareSleep();
|
||||
|
||||
/// Restart our lock attempt - try to get and broadcast a GPS reading ASAP
|
||||
void startLock();
|
||||
|
||||
private:
|
||||
void readFromRTC();
|
||||
};
|
||||
|
||||
// extern GPSNema gps;
|
|
@ -32,8 +32,8 @@ static void lsEnter()
|
|||
|
||||
gps.prepareSleep(); // abandon in-process parsing
|
||||
|
||||
if (!isUSBPowered) // FIXME - temp hack until we can put gps in sleep mode, if we have AC when we go to sleep then leave GPS on
|
||||
setGPSPower(false); // kill GPS power
|
||||
//if (!isUSBPowered) // FIXME - temp hack until we can put gps in sleep mode, if we have AC when we go to sleep then leave GPS on
|
||||
// setGPSPower(false); // kill GPS power
|
||||
}
|
||||
|
||||
static void lsIdle()
|
||||
|
@ -76,7 +76,7 @@ static void lsIdle()
|
|||
|
||||
static void lsExit()
|
||||
{
|
||||
setGPSPower(true); // restore GPS power
|
||||
// setGPSPower(true); // restore GPS power
|
||||
gps.startLock();
|
||||
}
|
||||
|
||||
|
|
Ładowanie…
Reference in New Issue