Skip to content
This repository was archived by the owner on Jan 28, 2021. It is now read-only.

Commit e0eb2b3

Browse files
authoredAug 7, 2019
Merge branch 'master' into multiSetVal-revisited-(Issue-#20-#21-#23)
·
v1.8.11v1.6.0
2 parents 61ab2e9 + 50e2af8 commit e0eb2b3

File tree

11 files changed

+730
-161
lines changed

11 files changed

+730
-161
lines changed
 

‎ISSUE_TEMPLATE.md

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
### Subject of the issue
2+
Describe your issue here. If you reference a datasheet please specify which one and in which section (ie, the protocol manual, section 5.1.2). Additionally, screenshots are easy to paste into github.
3+
4+
### Your workbench
5+
* What development board or microcontroller are you using?
6+
* What version of hardware or breakout board are you using?
7+
* How is the breakout board wired to your microcontroller?
8+
* How is everything being powered?
9+
* Are there any additional details that may help us help you?
10+
11+
### Steps to reproduce
12+
Tell us how to reproduce this issue. Please post stripped down example code demonstrating your issue.
13+
14+
### Expected behavior
15+
Tell us what should happen
16+
17+
### Actual behavior
18+
Tell us what happens instead

‎examples/Example14_DebugOutput/Example14_DebugOutput.ino

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,19 @@ void loop()
7575
Serial.print(F(" SIV: "));
7676
Serial.print(SIV);
7777

78+
Serial.println();
79+
Serial.print(myGPS.getYear());
80+
Serial.print("-");
81+
Serial.print(myGPS.getMonth());
82+
Serial.print("-");
83+
Serial.print(myGPS.getDay());
84+
Serial.print(" ");
85+
Serial.print(myGPS.getHour());
86+
Serial.print(":");
87+
Serial.print(myGPS.getMinute());
88+
Serial.print(":");
89+
Serial.println(myGPS.getSecond());
90+
7891
Serial.println();
7992
}
8093
}

‎examples/Example15_GetDateTime/Example15_GetDateTime.ino

Lines changed: 56 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@
77
basically do whatever you want with this code.
88
99
This example shows how to query a Ublox module for the current time and date. We also
10-
turn off the NMEA output on the I2C port. This decreases the amount of I2C traffic
10+
turn off the NMEA output on the I2C port. This decreases the amount of I2C traffic
1111
dramatically.
1212
1313
Leave NMEA parsing behind. Now you can simply ask the module for the datums you want!
@@ -33,63 +33,63 @@ long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox m
3333

3434
void setup()
3535
{
36-
Serial.begin(115200);
37-
while (!Serial)
38-
; //Wait for user to open terminal
39-
Serial.println("SparkFun Ublox Example");
40-
41-
Wire.begin();
42-
43-
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
44-
{
45-
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
46-
while (1)
47-
;
48-
}
49-
50-
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
51-
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
36+
Serial.begin(115200);
37+
while (!Serial)
38+
; //Wait for user to open terminal
39+
Serial.println("SparkFun Ublox Example");
40+
41+
Wire.begin();
42+
43+
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
44+
{
45+
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
46+
while (1)
47+
;
48+
}
49+
50+
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
51+
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
5252
}
5353

5454
void loop()
5555
{
56-
//Query module only every second. Doing it more often will just cause I2C traffic.
57-
//The module only responds when a new position is available
58-
if (millis() - lastTime > 1000)
59-
{
60-
lastTime = millis(); //Update the timer
61-
62-
long latitude = myGPS.getLatitude();
63-
Serial.print(F("Lat: "));
64-
Serial.print(latitude);
65-
66-
long longitude = myGPS.getLongitude();
67-
Serial.print(F(" Long: "));
68-
Serial.print(longitude);
69-
Serial.print(F(" (degrees * 10^-7)"));
70-
71-
long altitude = myGPS.getAltitude();
72-
Serial.print(F(" Alt: "));
73-
Serial.print(altitude);
74-
Serial.print(F(" (mm)"));
75-
76-
byte SIV = myGPS.getSIV();
77-
Serial.print(F(" SIV: "));
78-
Serial.print(SIV);
79-
80-
Serial.println();
81-
Serial.print(myGPS.getYear());
82-
Serial.print("-");
83-
Serial.print(myGPS.getMonth());
84-
Serial.print("-");
85-
Serial.print(myGPS.getDay());
86-
Serial.print(" ");
87-
Serial.print(myGPS.getHour());
88-
Serial.print(":");
89-
Serial.print(myGPS.getMinute());
90-
Serial.print(":");
91-
Serial.println(myGPS.getSecond());
92-
93-
Serial.println();
94-
}
56+
//Query module only every second. Doing it more often will just cause I2C traffic.
57+
//The module only responds when a new position is available
58+
if (millis() - lastTime > 1000)
59+
{
60+
lastTime = millis(); //Update the timer
61+
62+
long latitude = myGPS.getLatitude();
63+
Serial.print(F("Lat: "));
64+
Serial.print(latitude);
65+
66+
long longitude = myGPS.getLongitude();
67+
Serial.print(F(" Long: "));
68+
Serial.print(longitude);
69+
Serial.print(F(" (degrees * 10^-7)"));
70+
71+
long altitude = myGPS.getAltitude();
72+
Serial.print(F(" Alt: "));
73+
Serial.print(altitude);
74+
Serial.print(F(" (mm)"));
75+
76+
byte SIV = myGPS.getSIV();
77+
Serial.print(F(" SIV: "));
78+
Serial.print(SIV);
79+
80+
Serial.println();
81+
Serial.print(myGPS.getYear());
82+
Serial.print("-");
83+
Serial.print(myGPS.getMonth());
84+
Serial.print("-");
85+
Serial.print(myGPS.getDay());
86+
Serial.print(" ");
87+
Serial.print(myGPS.getHour());
88+
Serial.print(":");
89+
Serial.print(myGPS.getMinute());
90+
Serial.print(":");
91+
Serial.println(myGPS.getSecond());
92+
93+
Serial.println();
94+
}
9595
}
Lines changed: 98 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,98 @@
1+
/*
2+
Configuring the GPS to automatically send position reports over I2C, with explicit data parsing calls
3+
By: Nathan Seidle Thorsten von Eicken and Felix Jirka
4+
SparkFun Electronics
5+
Date: July 1st, 2019
6+
License: MIT. See license file for more information but you can
7+
basically do whatever you want with this code.
8+
9+
This example shows how to configure the U-Blox GPS the send navigation reports automatically
10+
and retrieving the latest one via checkUblox when available.
11+
This eliminates the implicit update in getPVT when accessing data fields twice.
12+
Also this reduces the memory overhead of a separate buffer while introducing a slight error by inconsistencies because of the unsynchronized updates (on a multi core system).
13+
14+
This can be used over serial or over I2C, this example shows the I2C use. With serial the GPS
15+
simply outputs the UBX_NAV_PVT packet. With I2C it queues it into its internal I2C buffer (4KB in
16+
size?) where it can be retrieved in the next I2C poll.
17+
18+
Feel like supporting open source hardware?
19+
Buy a board from SparkFun!
20+
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
21+
NEO-M8P RTK: https://www.sparkfun.com/products/15005
22+
SAM-M8Q: https://www.sparkfun.com/products/15106
23+
24+
Hardware Connections:
25+
Plug a Qwiic cable into the GPS and a BlackBoard
26+
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
27+
Open the serial monitor at 115200 baud to see the output
28+
*/
29+
30+
#include <Wire.h> //Needed for I2C to GPS
31+
32+
#include <SparkFun_Ublox_Arduino_Library.h> //http://librarymanager/All#SparkFun_Ublox_GPS
33+
SFE_UBLOX_GPS myGPS;
34+
35+
void setup()
36+
{
37+
Serial.begin(115200);
38+
while (!Serial); //Wait for user to open terminal
39+
Serial.println("SparkFun Ublox Example");
40+
41+
Wire.begin();
42+
43+
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
44+
{
45+
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
46+
while (1);
47+
}
48+
49+
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
50+
myGPS.setNavigationFrequency(2); //Produce two solutions per second
51+
myGPS.setAutoPVT(true, false); //Tell the GPS to "send" each solution and the lib not to update stale data implicitly
52+
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
53+
}
54+
55+
/*
56+
Calling getPVT would return false now (compare to Example 13 where it would return true), so we just use the data provided
57+
If you are using a threaded OS eg. FreeRTOS on an ESP32, the explicit mode of autoPVT allows you to use the data provided on both cores and inside multiple threads
58+
The data update in background creates an inconsistent state, but that should not cause issues for most applications as they usually won't change the GPS location significantly within a 2Hz - 5Hz update rate.
59+
Also you could oversample (10Hz - 20Hz) the data to smooth out such issues...
60+
*/
61+
void loop()
62+
{
63+
static uint16_t counter = 0;
64+
65+
if (counter % 10 == 0) {
66+
// update your AHRS filter here for a ~100Hz update rate
67+
// GPS data will be quasi static but data from your IMU will be changing
68+
}
69+
// debug output each half second
70+
if (counter % 500 == 0) {
71+
Serial.println();
72+
long latitude = myGPS.getLatitude();
73+
Serial.print(F("Lat: "));
74+
Serial.print(latitude);
75+
76+
long longitude = myGPS.getLongitude();
77+
Serial.print(F(" Long: "));
78+
Serial.print(longitude);
79+
Serial.print(F(" (degrees * 10^-7)"));
80+
81+
long altitude = myGPS.getAltitude();
82+
Serial.print(F(" Alt: "));
83+
Serial.print(altitude);
84+
Serial.print(F(" (mm)"));
85+
86+
byte SIV = myGPS.getSIV();
87+
Serial.print(F(" SIV: "));
88+
Serial.print(SIV);
89+
90+
Serial.println();
91+
}
92+
// call checkUblox all 50ms to capture the gps data
93+
if (counter % 50 == 0) {
94+
myGPS.checkUblox();
95+
}
96+
delay(1);
97+
counter++;
98+
}
Lines changed: 105 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
/*
2+
Getting time and date using Ublox commands
3+
By: davidallenmann
4+
SparkFun Electronics
5+
Date: April 16th, 2019
6+
License: MIT. See license file for more information but you can
7+
basically do whatever you want with this code.
8+
9+
This example shows how to query a Ublox module for the current time and date. We also
10+
turn off the NMEA output on the I2C port. This decreases the amount of I2C traffic
11+
dramatically.
12+
13+
Leave NMEA parsing behind. Now you can simply ask the module for the datums you want!
14+
15+
Feel like supporting open source hardware?
16+
Buy a board from SparkFun!
17+
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
18+
NEO-M8P RTK: https://www.sparkfun.com/products/15005
19+
SAM-M8Q: https://www.sparkfun.com/products/15106
20+
21+
Hardware Connections:
22+
Plug a Qwiic cable into the GPS and a BlackBoard
23+
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
24+
Open the serial monitor at 115200 baud to see the output
25+
*/
26+
27+
#include <Wire.h> //Needed for I2C to GPS
28+
29+
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_Ublox_GPS
30+
SFE_UBLOX_GPS myGPS;
31+
32+
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
33+
34+
void setup()
35+
{
36+
Serial.begin(500000); //Increase serial speed to maximize
37+
while (!Serial)
38+
; //Wait for user to open terminal
39+
Serial.println("SparkFun Ublox Example");
40+
41+
Wire.begin();
42+
Wire.setClock(400000);
43+
44+
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
45+
{
46+
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
47+
while (1)
48+
;
49+
}
50+
51+
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
52+
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
53+
54+
//myGPS.enableDebugging(); //Enable debug messages over Serial (default)
55+
56+
myGPS.setNavigationFrequency(10); //Set output to 10 times a second
57+
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
58+
Serial.print("Current update rate:");
59+
Serial.println(rate);
60+
61+
}
62+
63+
void loop()
64+
{
65+
//Query module only every second. Doing it more often will just cause I2C traffic.
66+
//The module only responds when a new position is available
67+
if (millis() - lastTime > 10)
68+
{
69+
lastTime = millis(); //Update the timer
70+
71+
long latitude = myGPS.getLatitude();
72+
Serial.print(F("Lat: "));
73+
Serial.print(latitude);
74+
75+
long longitude = myGPS.getLongitude();
76+
Serial.print(F(" Long: "));
77+
Serial.print(longitude);
78+
Serial.print(F(" (degrees * 10^-7)"));
79+
80+
long altitude = myGPS.getAltitude();
81+
Serial.print(F(" Alt: "));
82+
Serial.print(altitude);
83+
Serial.print(F(" (mm)"));
84+
85+
byte SIV = myGPS.getSIV();
86+
Serial.print(F(" SIV: "));
87+
Serial.print(SIV);
88+
89+
Serial.print(myGPS.getYear());
90+
Serial.print("-");
91+
Serial.print(myGPS.getMonth());
92+
Serial.print("-");
93+
Serial.print(myGPS.getDay());
94+
Serial.print(" ");
95+
Serial.print(myGPS.getHour());
96+
Serial.print(":");
97+
Serial.print(myGPS.getMinute());
98+
Serial.print(":");
99+
Serial.print(myGPS.getSecond());
100+
Serial.print(".");
101+
Serial.print(myGPS.getNanosecond());
102+
103+
Serial.println();
104+
}
105+
}
Lines changed: 114 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,114 @@
1+
/*
2+
Getting time and date using Ublox commands
3+
By: Nathan Seidle
4+
SparkFun Electronics
5+
Date: April 16th, 2019
6+
License: MIT. See license file for more information but you can
7+
basically do whatever you want with this code.
8+
9+
This example shows how to use the Millisecond and Nanosecond output as well as increase the
10+
I2C speed (100 to 400kHz), and serial output (115200 to 500kbps).
11+
12+
Leave NMEA parsing behind. Now you can simply ask the module for the datums you want!
13+
14+
Feel like supporting open source hardware?
15+
Buy a board from SparkFun!
16+
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
17+
NEO-M8P RTK: https://www.sparkfun.com/products/15005
18+
SAM-M8Q: https://www.sparkfun.com/products/15106
19+
20+
Hardware Connections:
21+
Plug a Qwiic cable into the GPS and a BlackBoard
22+
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
23+
Open the serial monitor at 115200 baud to see the output
24+
*/
25+
26+
#include <Wire.h> //Needed for I2C to GPS
27+
28+
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_Ublox_GPS
29+
SFE_UBLOX_GPS myGPS;
30+
31+
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
32+
33+
void setup()
34+
{
35+
Serial.begin(500000); //Increase serial speed to maximize
36+
while (!Serial)
37+
; //Wait for user to open terminal
38+
Serial.println("SparkFun Ublox Example");
39+
40+
Wire.begin();
41+
Wire.setClock(400000);
42+
43+
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
44+
{
45+
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
46+
while (1)
47+
;
48+
}
49+
50+
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
51+
52+
//myGPS.enableDebugging(); //Enable debug messages over Serial (default)
53+
54+
myGPS.setNavigationFrequency(10); //Set output to 10 times a second
55+
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
56+
Serial.print("Current update rate:");
57+
Serial.println(rate);
58+
59+
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
60+
61+
pinMode(2, OUTPUT); //For debug capture
62+
digitalWrite(2, HIGH);
63+
}
64+
65+
void loop()
66+
{
67+
//Query module very often to get max update rate
68+
if (millis() - lastTime > 10)
69+
{
70+
lastTime = millis(); //Update the timer
71+
72+
long latitude = myGPS.getLatitude();
73+
Serial.print(F("Lat: "));
74+
Serial.print(latitude);
75+
76+
long longitude = myGPS.getLongitude();
77+
Serial.print(F(" Long: "));
78+
Serial.print(longitude);
79+
Serial.print(F(" (degrees * 10^-7)"));
80+
81+
long altitude = myGPS.getAltitude();
82+
Serial.print(F(" Alt: "));
83+
Serial.print(altitude);
84+
Serial.print(F(" (mm)"));
85+
86+
byte SIV = myGPS.getSIV();
87+
Serial.print(F(" SIV: "));
88+
Serial.print(SIV);
89+
90+
Serial.print(" ");
91+
Serial.print(myGPS.getYear());
92+
Serial.print("-");
93+
Serial.print(myGPS.getMonth());
94+
Serial.print("-");
95+
Serial.print(myGPS.getDay());
96+
Serial.print(" ");
97+
Serial.print(myGPS.getHour());
98+
Serial.print(":");
99+
Serial.print(myGPS.getMinute());
100+
Serial.print(":");
101+
Serial.print(myGPS.getSecond());
102+
Serial.print(".");
103+
//Pretty print leading zeros
104+
int mseconds = myGPS.getMillisecond();
105+
if(mseconds < 100) Serial.print("0");
106+
if(mseconds < 10) Serial.print("0");
107+
Serial.print(mseconds);
108+
109+
Serial.print(" nanoSeconds: ");
110+
Serial.print(myGPS.getNanosecond());
111+
112+
Serial.println();
113+
}
114+
}
Lines changed: 79 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
/*
2+
Reading lat and long via UBX binary commands using an RX-only UART
3+
By: Nathan Seidle, Adapted from Example11 by Felix Jirka
4+
SparkFun Electronics
5+
Date: July 2nd, 2019
6+
License: MIT. See license file for more information but you can
7+
basically do whatever you want with this code.
8+
9+
This example shows how to configure the library for serial port use with a single wire connection using the assumeAutoPVT method.
10+
Saving your pins for other stuff :-)
11+
12+
Leave NMEA parsing behind. Now you can simply ask the module for the datums you want!
13+
14+
Feel like supporting open source hardware?
15+
Buy a board from SparkFun!
16+
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
17+
NEO-M8P RTK: https://www.sparkfun.com/products/15005
18+
SAM-M8Q: https://www.sparkfun.com/products/15106
19+
20+
Preconditions:
21+
U-Blox module is configured to send cyclical PVT message
22+
Hardware Connections:
23+
Connect the U-Blox serial TX pin to Rx of Serial2 (default: GPIO16) on your ESP32
24+
Open the serial monitor at 115200 baud to see the output
25+
*/
26+
27+
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_Ublox_GPS
28+
SFE_UBLOX_GPS myGPS;
29+
30+
void setup()
31+
{
32+
Serial.begin(115200);
33+
while (!Serial); //Wait for user to open terminal
34+
Serial.println("SparkFun Ublox Example 17");
35+
36+
//Use any Serial port with at least a Rx Pin connected or a receive only version of SoftwareSerial here
37+
//Assume that the U-Blox GPS is running at 9600 baud (the default)
38+
Serial2.begin(9600);
39+
// no need to check return value as internal call to isConnected() will not succeed
40+
myGPS.begin(Serial2);
41+
42+
// tell lib, we are expecting the module to send PVT messages by itself to our Rx pin
43+
// you can set second parameter to "false" if you want to control the parsing and eviction of the data (need to call checkUblox cyclically)
44+
myGPS.assumeAutoPVT(true, true);
45+
46+
}
47+
48+
void loop()
49+
{
50+
// if implicit updates are allowed, this will trigger parsing the incoming messages
51+
// and be true once a PVT message has been parsed
52+
// In case you want to use explicit updates, wrap this in a timer and call checkUblox as often as needed, not to overflow your UART buffers
53+
if (myGPS.getPVT())
54+
{
55+
long latitude = myGPS.getLatitude();
56+
Serial.print(F("Lat: "));
57+
Serial.print(latitude);
58+
59+
long longitude = myGPS.getLongitude();
60+
Serial.print(F(" Long: "));
61+
Serial.print(longitude);
62+
Serial.print(F(" (degrees * 10^-7)"));
63+
64+
long altitude = myGPS.getAltitude();
65+
Serial.print(F(" Alt: "));
66+
Serial.print(altitude);
67+
Serial.print(F(" (mm)"));
68+
69+
byte SIV = myGPS.getSIV();
70+
Serial.print(F(" SIV: "));
71+
Serial.print(SIV);
72+
73+
Serial.println();
74+
}
75+
else {
76+
Serial.println(F("Wait for GPS data"));
77+
delay(500);
78+
}
79+
}

‎keywords.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,16 +95,21 @@ getRELPOSNED KEYWORD2
9595

9696
enableDebugging KEYWORD2
9797
disableDebugging KEYWORD2
98+
debugPrint KEYWORD2
99+
debugPrintln KEYWORD2
98100

99101
factoryReset KEYWORD2
100102
setAutoPVT KEYWORD2
103+
assumeAutoPVT KEYWORD2
101104

102105
getYear KEYWORD2
103106
getMonth KEYWORD2
104107
getDay KEYWORD2
105108
getHour KEYWORD2
106109
getMinute KEYWORD2
107110
getSecond KEYWORD2
111+
getMillisecond KEYWORD2
112+
getNanosecond KEYWORD2
108113

109114
getHPPOSLLH KEYWORD2
110115
getTimeOfWeek KEYWORD2

‎library.properties

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
name=SparkFun Ublox Arduino Library
2-
version=1.4.2
2+
version=1.5.0
33
author=SparkFun Electronics <techsupport@sparkfun.com>
44
maintainer=SparkFun Electronics <sparkfun.com>
55
sentence=Library for I2C and Serial Communication with Ublox modules

‎src/SparkFun_Ublox_Arduino_Library.cpp

Lines changed: 173 additions & 52 deletions
Large diffs are not rendered by default.

‎src/SparkFun_Ublox_Arduino_Library.h

Lines changed: 68 additions & 52 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@
7676

7777
//The catch-all default is 32
7878
#define I2C_BUFFER_LENGTH 32
79+
//#define I2C_BUFFER_LENGTH 16 //For testing on Artemis
7980

8081
#endif
8182
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
@@ -238,10 +239,12 @@ class SFE_UBLOX_GPS
238239

239240
boolean waitForResponse(uint8_t requestedClass, uint8_t requestedID, uint16_t maxTime = 250); //Poll the module until and ack is received
240241

242+
boolean assumeAutoPVT(boolean enabled, boolean implicitUpdate = true); //In case no config access to the GPS is possible and PVT is send cyclically already
241243
boolean setAutoPVT(boolean enabled, uint16_t maxWait = 250); //Enable/disable automatic PVT reports at the navigation frequency
242244
boolean getPVT(uint16_t maxWait = 1000); //Query module for latest group of datums and load global vars: lat, long, alt, speed, SIV, accuracies, etc. If autoPVT is disabled, performs an explicit poll and waits, if enabled does not block. Retruns true if new PVT is available.
243-
boolean getHPPOSLLH(uint16_t maxWait = 1000); //Query module for latest group of datums and load global vars: lat, long, alt, speed, SIV, accuracies, etc. If autoPVT is disabled, performs an explicit poll and waits, if enabled does not block. Retruns true if new PVT is available.
244-
245+
boolean setAutoPVT(boolean enabled, boolean implicitUpdate, uint16_t maxWait = 250); //Enable/disable automatic PVT reports at the navigation frequency, with implicitUpdate == false accessing stale data will not issue parsing of data in the rxbuffer of your interface, instead you have to call checkUblox when you want to perform an update
246+
boolean getHPPOSLLH(uint16_t maxWait = 1000); //Query module for latest group of datums and load global vars: lat, long, alt, speed, SIV, accuracies, etc. If autoPVT is disabled, performs an explicit poll and waits, if enabled does not block. Retruns true if new PVT is available.
247+
245248
int32_t getLatitude(uint16_t maxWait = 250); //Returns the current latitude in degrees * 10^-7. Auto selects between HighPrecision and Regular depending on ability of module.
246249
int32_t getLongitude(uint16_t maxWait = 250); //Returns the current longitude in degrees * 10-7. Auto selects between HighPrecision and Regular depending on ability of module.
247250
int32_t getAltitude(uint16_t maxWait = 250); //Returns the current altitude in mm above ellipsoid
@@ -258,15 +261,17 @@ class SFE_UBLOX_GPS
258261
uint8_t getHour(uint16_t maxWait = 250);
259262
uint8_t getMinute(uint16_t maxWait = 250);
260263
uint8_t getSecond(uint16_t maxWait = 250);
261-
262-
uint32_t getTimeOfWeek(uint16_t maxWait = 250);
263-
int32_t getHighResLatitude(uint16_t maxWait = 250);
264-
int32_t getHighResLongitude(uint16_t maxWait = 250);
265-
int32_t getElipsoid(uint16_t maxWait = 250);
266-
int32_t getMeanSeaLevel(uint16_t maxWait = 250);
267-
int32_t getGeoidSeparation(uint16_t maxWait = 250);
268-
uint32_t getHorizontalAccuracy(uint16_t maxWait = 250);
269-
uint32_t getVerticalAccuracy(uint16_t maxWait = 250);
264+
uint16_t getMillisecond(uint16_t maxWait = 250);
265+
int32_t getNanosecond(uint16_t maxWait = 250);
266+
267+
uint32_t getTimeOfWeek(uint16_t maxWait = 250);
268+
int32_t getHighResLatitude(uint16_t maxWait = 250);
269+
int32_t getHighResLongitude(uint16_t maxWait = 250);
270+
int32_t getElipsoid(uint16_t maxWait = 250);
271+
int32_t getMeanSeaLevel(uint16_t maxWait = 250);
272+
int32_t getGeoidSeparation(uint16_t maxWait = 250);
273+
uint32_t getHorizontalAccuracy(uint16_t maxWait = 250);
274+
uint32_t getVerticalAccuracy(uint16_t maxWait = 250);
270275

271276
//Port configurations
272277
boolean setPortOutput(uint8_t portID, uint8_t comSettings, uint16_t maxWait = 250); //Configure a given port to output UBX, NMEA, RTCM3 or a combination thereof
@@ -315,7 +320,9 @@ class SFE_UBLOX_GPS
315320
boolean getRELPOSNED(uint16_t maxWait = 1000); //Get Relative Positioning Information of the NED frame
316321

317322
void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages
318-
void disableDebugging(void);
323+
void disableDebugging(void); //Turn off debug statements
324+
void debugPrint(char *message); //Safely print debug statements
325+
void debugPrintln(char *message); //Safely print debug statements
319326

320327
//Survey-in specific controls
321328
struct svinStructure
@@ -363,6 +370,8 @@ class SFE_UBLOX_GPS
363370
uint8_t gpsHour;
364371
uint8_t gpsMinute;
365372
uint8_t gpsSecond;
373+
uint16_t gpsMillisecond;
374+
int32_t gpsNanosecond;
366375

367376
int32_t latitude; //Degrees * 10^-7 (more accurate than floats)
368377
int32_t longitude; //Degrees * 10^-7 (more accurate than floats)
@@ -377,14 +386,14 @@ class SFE_UBLOX_GPS
377386
uint8_t versionLow; //Loaded from getProtocolVersion().
378387
uint8_t versionHigh;
379388

380-
uint32_t timeOfWeek;
381-
int32_t highResLatitude;
382-
int32_t highResLongitude;
383-
int32_t elipsoid;
384-
int32_t meanSeaLevel;
385-
int32_t geoidSeparation;
386-
uint32_t horizontalAccuracy;
387-
uint32_t verticalAccuracy;
389+
uint32_t timeOfWeek;
390+
int32_t highResLatitude;
391+
int32_t highResLongitude;
392+
int32_t elipsoid;
393+
int32_t meanSeaLevel;
394+
int32_t geoidSeparation;
395+
uint32_t horizontalAccuracy;
396+
uint32_t verticalAccuracy;
388397

389398
uint16_t rtcmFrameCounter = 0; //Tracks the type of incoming byte inside RTCM frame
390399

@@ -438,9 +447,14 @@ class SFE_UBLOX_GPS
438447
ubxPacket packetAck = {0, 0, 0, 0, 0, payloadAck, 0, 0, false};
439448
ubxPacket packetCfg = {0, 0, 0, 0, 0, payloadCfg, 0, 0, false};
440449

441-
const uint8_t I2C_POLLING_WAIT_MS = 25; //Limit checking of new characters to every X ms
450+
//Limit checking of new data to every X ms
451+
//If we are expecting an update every X Hz then we should check every half that amount of time
452+
//Otherwise we may block ourselves from seeing new data
453+
uint8_t i2cPollingWait = 100; //Default to 100ms. Adjusted when user calls setNavigationFrequency()
454+
442455
unsigned long lastCheck = 0;
443456
boolean autoPVT = false; //Whether autoPVT is enabled or not
457+
boolean autoPVTImplicitUpdate = true; // Whether autoPVT is triggered by accessing stale data (=true) or by a call to checkUblox (=false)
444458
boolean commandAck = false; //This goes true after we send a command and it's ack'd
445459
uint8_t ubxFrameCounter;
446460

@@ -453,39 +467,41 @@ class SFE_UBLOX_GPS
453467
//depending on update rate
454468
struct
455469
{
456-
uint16_t gpsYear : 1;
457-
uint16_t gpsMonth : 1;
458-
uint16_t gpsDay : 1;
459-
uint16_t gpsHour : 1;
460-
uint16_t gpsMinute : 1;
461-
uint16_t gpsSecond : 1;
462-
463-
uint16_t all : 1;
464-
uint16_t longitude : 1;
465-
uint16_t latitude : 1;
466-
uint16_t altitude : 1;
467-
uint16_t altitudeMSL : 1;
468-
uint16_t SIV : 1;
469-
uint16_t fixType : 1;
470-
uint16_t carrierSolution : 1;
471-
uint16_t groundSpeed : 1;
472-
uint16_t headingOfMotion : 1;
473-
uint16_t pDOP : 1;
474-
uint16_t versionNumber : 1;
470+
uint32_t gpsiTOW : 1;
471+
uint32_t gpsYear : 1;
472+
uint32_t gpsMonth : 1;
473+
uint32_t gpsDay : 1;
474+
uint32_t gpsHour : 1;
475+
uint32_t gpsMinute : 1;
476+
uint32_t gpsSecond : 1;
477+
uint32_t gpsNanosecond : 1;
478+
479+
uint32_t all : 1;
480+
uint32_t longitude : 1;
481+
uint32_t latitude : 1;
482+
uint32_t altitude : 1;
483+
uint32_t altitudeMSL : 1;
484+
uint32_t SIV : 1;
485+
uint32_t fixType : 1;
486+
uint32_t carrierSolution : 1;
487+
uint32_t groundSpeed : 1;
488+
uint32_t headingOfMotion : 1;
489+
uint32_t pDOP : 1;
490+
uint32_t versionNumber : 1;
475491
} moduleQueried;
476492

477-
struct
478-
{
479-
uint16_t all : 1;
480-
uint16_t timeOfWeek : 1;
481-
uint16_t highResLatitude : 1;
482-
uint16_t highResLongitude : 1;
483-
uint16_t elipsoid : 1;
484-
uint16_t meanSeaLevel : 1;
485-
uint16_t geoidSeparation : 1;
486-
uint16_t horizontalAccuracy : 1;
487-
uint16_t verticalAccuracy : 1;
488-
} highResModuleQueried;
493+
struct
494+
{
495+
uint16_t all : 1;
496+
uint16_t timeOfWeek : 1;
497+
uint16_t highResLatitude : 1;
498+
uint16_t highResLongitude : 1;
499+
uint16_t elipsoid : 1;
500+
uint16_t meanSeaLevel : 1;
501+
uint16_t geoidSeparation : 1;
502+
uint16_t horizontalAccuracy : 1;
503+
uint16_t verticalAccuracy : 1;
504+
} highResModuleQueried;
489505

490506
uint16_t rtcmLen = 0;
491507
};

0 commit comments

Comments
 (0)
This repository has been archived.