Skip to content
This repository was archived by the owner on Jan 28, 2021. It is now read-only.
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit a284616

Browse files
committedJul 25, 2019
Merge branch 'master' into pr/18
2 parents 8f1b20b + 21b708a commit a284616

File tree

11 files changed

+887
-168
lines changed

11 files changed

+887
-168
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: 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+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
/*
2+
Get the high precision geodetic solution for latituude and longitude
3+
By: Nathan Seidle
4+
Modified by: Steven Rowland
5+
SparkFun Electronics
6+
Date: January 3rd, 2019
7+
License: MIT. See license file for more information but you can
8+
basically do whatever you want with this code.
9+
10+
This example shows how to inspect the accuracy of the high-precision
11+
positional solution.
12+
13+
Feel like supporting open source hardware?
14+
Buy a board from SparkFun!
15+
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
16+
NEO-M8P RTK: https://www.sparkfun.com/products/15005
17+
SAM-M8Q: https://www.sparkfun.com/products/15106
18+
19+
Hardware Connections:
20+
Plug a Qwiic cable into the GPS and a BlackBoard
21+
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
22+
Open the serial monitor at 115200 baud to see the output
23+
*/
24+
25+
#include <Wire.h> //Needed for I2C to GPS
26+
27+
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_Ublox_GPS
28+
SFE_UBLOX_GPS myGPS;
29+
30+
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
31+
32+
void setup()
33+
{
34+
Serial.begin(115200);
35+
while (!Serial); //Wait for user to open terminal
36+
37+
Wire.begin();
38+
39+
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
40+
{
41+
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
42+
while (1);
43+
}
44+
45+
//myGPS.enableDebugging(Serial);
46+
47+
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
48+
myGPS.setNavigationFrequency(20); //Set output to 20 times a second
49+
50+
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
51+
Serial.print("Current update rate:");
52+
Serial.println(rate);
53+
54+
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
55+
}
56+
57+
void loop()
58+
{
59+
//Query module only every second. Doing it more often will just cause I2C traffic.
60+
//The module only responds when a new position is available
61+
if (millis() - lastTime > 1000)
62+
{
63+
lastTime = millis(); //Update the timer
64+
Serial.print("HP Lat: ");
65+
int32_t latitude = myGPS.getHighResLatitude();
66+
Serial.print(latitude);
67+
Serial.print(", HP Lon: ");
68+
69+
int32_t longitude = myGPS.getHighResLongitude();
70+
Serial.print(longitude);
71+
Serial.print(", Accuracy: ");
72+
73+
uint32_t accuracy = myGPS.getHorizontalAccuracy();
74+
Serial.println(accuracy);
75+
}
76+
77+
}
Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
/*
2+
Get the high precision geodetic solution
3+
By: Nathan Seidle
4+
Modified by: Steven Rowland
5+
SparkFun Electronics
6+
Date: January 3rd, 2019
7+
License: MIT. See license file for more information but you can
8+
basically do whatever you want with this code.
9+
10+
This example shows how to inspect the accuracy of the high-precision
11+
positional solution.
12+
13+
Feel like supporting open source hardware?
14+
Buy a board from SparkFun!
15+
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
16+
NEO-M8P RTK: https://www.sparkfun.com/products/15005
17+
SAM-M8Q: https://www.sparkfun.com/products/15106
18+
19+
Hardware Connections:
20+
Plug a Qwiic cable into the GPS and a BlackBoard
21+
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
22+
Open the serial monitor at 115200 baud to see the output
23+
*/
24+
25+
#include <Wire.h> //Needed for I2C to GPS
26+
27+
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_Ublox_GPS
28+
SFE_UBLOX_GPS myGPS;
29+
30+
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
31+
32+
void setup()
33+
{
34+
Serial.begin(115200);
35+
while (!Serial); //Wait for user to open terminal
36+
37+
Wire.begin();
38+
39+
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
40+
{
41+
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
42+
while (1);
43+
}
44+
45+
//myGPS.enableDebugging(Serial);
46+
47+
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
48+
myGPS.setNavigationFrequency(20); //Set output to 20 times a second
49+
50+
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
51+
Serial.print("Current update rate:");
52+
Serial.println(rate);
53+
54+
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
55+
}
56+
57+
void loop()
58+
{
59+
//Query module only every second. Doing it more often will just cause I2C traffic.
60+
//The module only responds when a new position is available
61+
if (millis() - lastTime > 1000)
62+
{
63+
lastTime = millis(); //Update the timer
64+
Serial.print("HP Lat: ");
65+
int32_t latitude = myGPS.getHighResLatitude();
66+
Serial.print(latitude);
67+
Serial.print(", HP Lon: ");
68+
69+
int32_t longitude = myGPS.getHighResLongitude();
70+
Serial.print(longitude);
71+
Serial.print(", 2D Accuracy(MM): ");
72+
73+
uint32_t accuracy = myGPS.getHorizontalAccuracy();
74+
Serial.println(accuracy);
75+
Serial.print(", Vertical Accuracy(MM): ");
76+
77+
uint32_t verticalAccuracy = myGPS.getVerticalAccuracy();
78+
Serial.println(verticalAccuracy);
79+
Serial.print(", Elipsoid(MM): ");
80+
81+
int32_t elipsoid = myGPS.getElipsoid();
82+
Serial.println(elipsoid);
83+
Serial.print(", Mean Sea Level(MM): ");
84+
85+
int32_t meanSeaLevel = myGPS.getMeanSeaLevel();
86+
Serial.println(meanSeaLevel);
87+
Serial.print(", Geoid Separation(MM): ");
88+
89+
int32_t geoidSeparation = myGPS.getGeoidSeparation();
90+
Serial.println(geoidSeparation);
91+
Serial.print(", Time of Week(Millis): ");
92+
93+
uint32_t timeOfWeek = myGPS.getTimeOfWeek();
94+
Serial.println(timeOfWeek);
95+
Serial.print(",");
96+
97+
}
98+
99+
}

‎keywords.txt

Lines changed: 32 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ setUSBOutput KEYWORD2
6262
setSPIOutput KEYWORD2
6363

6464
getVal8 KEYWORD2
65-
setVal KEYWORD2
65+
setVal KEYWORD2
6666

6767
getSurveyMode KEYWORD2
6868
setSurveyMode KEYWORD2
@@ -77,24 +77,37 @@ getPositionAccuracy KEYWORD2
7777

7878
getProtocolVersionHigh KEYWORD2
7979
getProtocolVersionLow KEYWORD2
80-
getProtocolVersion KEYWORD2
81-
82-
getRELPOSNED KEYWORD2
83-
84-
enableDebugging KEYWORD2
85-
disableDebugging KEYWORD2
86-
87-
factoryReset KEYWORD2
88-
89-
setAutoPVT KEYWORD2
90-
assumeAutoPVT KEYWORD2
91-
92-
getYear KEYWORD2
93-
getMonth KEYWORD2
94-
getDay KEYWORD2
95-
getHour KEYWORD2
96-
getMinute KEYWORD2
97-
getSecond KEYWORD2
80+
getProtocolVersion KEYWORD2
81+
82+
getRELPOSNED KEYWORD2
83+
84+
enableDebugging KEYWORD2
85+
disableDebugging KEYWORD2
86+
debugPrint KEYWORD2
87+
debugPrintln KEYWORD2
88+
89+
factoryReset KEYWORD2
90+
setAutoPVT KEYWORD2
91+
assumeAutoPVT KEYWORD2
92+
93+
getYear KEYWORD2
94+
getMonth KEYWORD2
95+
getDay KEYWORD2
96+
getHour KEYWORD2
97+
getMinute KEYWORD2
98+
getSecond KEYWORD2
99+
getMillisecond KEYWORD2
100+
getNanosecond KEYWORD2
101+
102+
getHPPOSLLH KEYWORD2
103+
getTimeOfWeek KEYWORD2
104+
getHighResLatitude KEYWORD2
105+
getHighResLongitude KEYWORD2
106+
getElipsoid KEYWORD2
107+
getMeanSeaLevel KEYWORD2
108+
getGeoidSeparation KEYWORD2
109+
getHorizontalAccuracy KEYWORD2
110+
getVerticalAccuracy KEYWORD2
98111

99112
#######################################
100113
# Constants (LITERAL1)

‎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.1
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: 293 additions & 66 deletions
Large diffs are not rendered by default.

‎src/SparkFun_Ublox_Arduino_Library.h

Lines changed: 79 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,13 @@
2121
- Added support for parsing date and time
2222
- Added functions getYear(), getMonth(), getDay(), getHour(), getMinute(), getSecond()
2323
24+
Modified by Steven Rowland, June 11th, 2019
25+
- Added functionality for reading HPPOSLLH (High Precision Geodetic Position)
26+
- Added getTimeOfWeek(), getHighResLatitude(). getHighResLongitude(), getElipsoid(),
27+
getMeanSeaLevel(), getHorizontalAccuracy(), getVerticalAccuracy(), getHPPOSLLH()
28+
- Modified ProcessUBXPacket to parse HPPOSLLH packet
29+
- Added query staleness verification for HPPOSLLH data
30+
2431
This program is distributed in the hope that it will be useful,
2532
but WITHOUT ANY WARRANTY; without even the implied warranty of
2633
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
@@ -64,6 +71,7 @@
6471

6572
//The catch-all default is 32
6673
#define I2C_BUFFER_LENGTH 32
74+
//#define I2C_BUFFER_LENGTH 16 //For testing on Artemis
6775

6876
#endif
6977
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
@@ -141,10 +149,10 @@ const uint8_t VAL_SIZE_16 = 0x03; //Two bytes
141149
const uint8_t VAL_SIZE_32 = 0x04; //Four bytes
142150
const uint8_t VAL_SIZE_64 = 0x05; //Eight bytes
143151

144-
const uint8_t VAL_LAYER_RAM = 0;
145-
const uint8_t VAL_LAYER_BBR = 1;
146-
const uint8_t VAL_LAYER_FLASH = 2;
147-
const uint8_t VAL_LAYER_DEFAULT = 7;
152+
//These are the Bitfield layers definitions for the UBX-CFG-VALSET message (not to be confused with Bitfield deviceMask in UBX-CFG-CFG)
153+
const uint8_t VAL_LAYER_RAM = (1 << 0);
154+
const uint8_t VAL_LAYER_BBR = (1 << 1);
155+
const uint8_t VAL_LAYER_FLASH = (1 << 2);
148156

149157
//Below are various Groups, IDs, and sizes for various settings
150158
//These can be used to call getVal/setVal/delVal
@@ -162,7 +170,8 @@ const uint8_t VAL_ID_I2C_ADDRESS = 0x01;
162170

163171
#ifndef MAX_PAYLOAD_SIZE
164172

165-
#define MAX_PAYLOAD_SIZE 64 //Some commands are larger than 64 bytes but this covers most
173+
//Payload size must be big enough to cover the commands we want to get responses from
174+
#define MAX_PAYLOAD_SIZE 128 //Increased to 128 to cover the PVT packet
166175

167176
#endif
168177

@@ -227,8 +236,9 @@ class SFE_UBLOX_GPS
227236

228237
boolean assumeAutoPVT(boolean enabled, boolean implicitUpdate = true); //In case no config access to the GPS is possible and PVT is send cyclically already
229238
boolean setAutoPVT(boolean enabled, uint16_t maxWait = 250); //Enable/disable automatic PVT reports at the navigation frequency
239+
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.
230240
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
231-
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.
241+
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.
232242

233243
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.
234244
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.
@@ -246,6 +256,17 @@ class SFE_UBLOX_GPS
246256
uint8_t getHour(uint16_t maxWait = 250);
247257
uint8_t getMinute(uint16_t maxWait = 250);
248258
uint8_t getSecond(uint16_t maxWait = 250);
259+
uint16_t getMillisecond(uint16_t maxWait = 250);
260+
int32_t getNanosecond(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);
249270

250271
//Port configurations
251272
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
@@ -282,7 +303,9 @@ class SFE_UBLOX_GPS
282303
boolean getRELPOSNED(uint16_t maxWait = 1000); //Get Relative Positioning Information of the NED frame
283304

284305
void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages
285-
void disableDebugging(void);
306+
void disableDebugging(void); //Turn off debug statements
307+
void debugPrint(char *message); //Safely print debug statements
308+
void debugPrintln(char *message); //Safely print debug statements
286309

287310
//Survey-in specific controls
288311
struct svinStructure
@@ -330,6 +353,8 @@ class SFE_UBLOX_GPS
330353
uint8_t gpsHour;
331354
uint8_t gpsMinute;
332355
uint8_t gpsSecond;
356+
uint16_t gpsMillisecond;
357+
int32_t gpsNanosecond;
333358

334359
int32_t latitude; //Degrees * 10^-7 (more accurate than floats)
335360
int32_t longitude; //Degrees * 10^-7 (more accurate than floats)
@@ -344,6 +369,15 @@ class SFE_UBLOX_GPS
344369
uint8_t versionLow; //Loaded from getProtocolVersion().
345370
uint8_t versionHigh;
346371

372+
uint32_t timeOfWeek;
373+
int32_t highResLatitude;
374+
int32_t highResLongitude;
375+
int32_t elipsoid;
376+
int32_t meanSeaLevel;
377+
int32_t geoidSeparation;
378+
uint32_t horizontalAccuracy;
379+
uint32_t verticalAccuracy;
380+
347381
uint16_t rtcmFrameCounter = 0; //Tracks the type of incoming byte inside RTCM frame
348382

349383
private:
@@ -396,7 +430,11 @@ class SFE_UBLOX_GPS
396430
ubxPacket packetAck = {0, 0, 0, 0, 0, payloadAck, 0, 0, false};
397431
ubxPacket packetCfg = {0, 0, 0, 0, 0, payloadCfg, 0, 0, false};
398432

399-
const uint8_t I2C_POLLING_WAIT_MS = 25; //Limit checking of new characters to every X ms
433+
//Limit checking of new data to every X ms
434+
//If we are expecting an update every X Hz then we should check every half that amount of time
435+
//Otherwise we may block ourselves from seeing new data
436+
uint8_t i2cPollingWait = 100; //Default to 100ms. Adjusted when user calls setNavigationFrequency()
437+
400438
unsigned long lastCheck = 0;
401439
boolean autoPVT = false; //Whether autoPVT is enabled or not
402440
boolean autoPVTImplicitUpdate = true; // Whether autoPVT is triggered by accessing stale data (=true) or by a call to checkUblox (=false)
@@ -412,26 +450,41 @@ class SFE_UBLOX_GPS
412450
//depending on update rate
413451
struct
414452
{
415-
uint16_t gpsYear : 1;
416-
uint16_t gpsMonth : 1;
417-
uint16_t gpsDay : 1;
418-
uint16_t gpsHour : 1;
419-
uint16_t gpsMinute : 1;
420-
uint16_t gpsSecond : 1;
453+
uint32_t gpsiTOW : 1;
454+
uint32_t gpsYear : 1;
455+
uint32_t gpsMonth : 1;
456+
uint32_t gpsDay : 1;
457+
uint32_t gpsHour : 1;
458+
uint32_t gpsMinute : 1;
459+
uint32_t gpsSecond : 1;
460+
uint32_t gpsNanosecond : 1;
461+
462+
uint32_t all : 1;
463+
uint32_t longitude : 1;
464+
uint32_t latitude : 1;
465+
uint32_t altitude : 1;
466+
uint32_t altitudeMSL : 1;
467+
uint32_t SIV : 1;
468+
uint32_t fixType : 1;
469+
uint32_t carrierSolution : 1;
470+
uint32_t groundSpeed : 1;
471+
uint32_t headingOfMotion : 1;
472+
uint32_t pDOP : 1;
473+
uint32_t versionNumber : 1;
474+
} moduleQueried;
421475

476+
struct
477+
{
422478
uint16_t all : 1;
423-
uint16_t longitude : 1;
424-
uint16_t latitude : 1;
425-
uint16_t altitude : 1;
426-
uint16_t altitudeMSL : 1;
427-
uint16_t SIV : 1;
428-
uint16_t fixType : 1;
429-
uint16_t carrierSolution : 1;
430-
uint16_t groundSpeed : 1;
431-
uint16_t headingOfMotion : 1;
432-
uint16_t pDOP : 1;
433-
uint16_t versionNumber : 1;
434-
} moduleQueried;
479+
uint16_t timeOfWeek : 1;
480+
uint16_t highResLatitude : 1;
481+
uint16_t highResLongitude : 1;
482+
uint16_t elipsoid : 1;
483+
uint16_t meanSeaLevel : 1;
484+
uint16_t geoidSeparation : 1;
485+
uint16_t horizontalAccuracy : 1;
486+
uint16_t verticalAccuracy : 1;
487+
} highResModuleQueried;
435488

436489
uint16_t rtcmLen = 0;
437490
};

0 commit comments

Comments
 (0)
This repository has been archived.