This commit is contained in:
2025-06-18 09:21:10 +08:00
commit b2b79996d7
478 changed files with 82728 additions and 0 deletions

View File

@ -0,0 +1,154 @@
/*
Get the high precision geodetic solution for latitude and longitude
By: Nathan Seidle
Modified by: Steven Rowland and Paul Clark
SparkFun Electronics
Date: April 17th, 2020
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example shows how to inspect the accuracy of the high-precision
positional solution. Please see below for information about the units.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
Hardware Connections:
Plug a Qwiic cable into the GPS and a BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
void setup()
{
Serial.begin(115200);
while (!Serial); //Wait for user to open terminal
Wire.begin();
//myGPS.enableDebugging(Serial);
if (myGPS.begin(Wire) == false) //Connect to the Ublox module using Wire port
{
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1);
}
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
myGPS.setNavigationFrequency(20); //Set output to 20 times a second
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
Serial.print("Current update rate: ");
Serial.println(rate);
//myGPS.saveConfiguration(); //Save the current settings to flash and BBR
}
void loop()
{
//Query module only every second. Doing it more often will just cause I2C traffic.
//The module only responds when a new position is available
if (millis() - lastTime > 1000)
{
lastTime = millis(); //Update the timer
// getHighResLatitude: returns the latitude from HPPOSLLH as an int32_t in degrees * 10^-7
// getHighResLatitudeHp: returns the high resolution component of latitude from HPPOSLLH as an int8_t in degrees * 10^-9
// getHighResLongitude: returns the longitude from HPPOSLLH as an int32_t in degrees * 10^-7
// getHighResLongitudeHp: returns the high resolution component of longitude from HPPOSLLH as an int8_t in degrees * 10^-9
// getElipsoid: returns the height above ellipsoid as an int32_t in mm
// getElipsoidHp: returns the high resolution component of the height above ellipsoid as an int8_t in mm * 10^-1
// getMeanSeaLevel: returns the height above mean sea level as an int32_t in mm
// getMeanSeaLevelHp: returns the high resolution component of the height above mean sea level as an int8_t in mm * 10^-1
// getHorizontalAccuracy: returns the horizontal accuracy estimate from HPPOSLLH as an uint32_t in mm * 10^-1
// If you want to use the high precision latitude and longitude with the full 9 decimal places
// you will need to use a 64-bit double - which is not supported on all platforms
// To allow this example to run on standard platforms, we cheat by converting lat and lon to integer and fractional degrees
// The high resolution altitudes can be converted into standard 32-bit float
// First, let's collect the position data
int32_t latitude = myGPS.getHighResLatitude();
int8_t latitudeHp = myGPS.getHighResLatitudeHp();
int32_t longitude = myGPS.getHighResLongitude();
int8_t longitudeHp = myGPS.getHighResLongitudeHp();
int32_t ellipsoid = myGPS.getElipsoid();
int8_t ellipsoidHp = myGPS.getElipsoidHp();
int32_t msl = myGPS.getMeanSeaLevel();
int8_t mslHp = myGPS.getMeanSeaLevelHp();
uint32_t accuracy = myGPS.getHorizontalAccuracy();
// Defines storage for the lat and lon units integer and fractional parts
int32_t lat_int; // Integer part of the latitude in degrees
int32_t lat_frac; // Fractional part of the latitude
int32_t lon_int; // Integer part of the longitude in degrees
int32_t lon_frac; // Fractional part of the longitude
// Calculate the latitude and longitude integer and fractional parts
lat_int = latitude / 10000000; // Convert latitude from degrees * 10^-7 to Degrees
lat_frac = latitude - (lat_int * 10000000); // Calculate the fractional part of the latitude
lat_frac = (lat_frac * 100) + latitudeHp; // Now add the high resolution component
if (lat_frac < 0) // If the fractional part is negative, remove the minus sign
{
lat_frac = 0 - lat_frac;
}
lon_int = longitude / 10000000; // Convert latitude from degrees * 10^-7 to Degrees
lon_frac = longitude - (lon_int * 10000000); // Calculate the fractional part of the longitude
lon_frac = (lon_frac * 100) + longitudeHp; // Now add the high resolution component
if (lon_frac < 0) // If the fractional part is negative, remove the minus sign
{
lon_frac = 0 - lon_frac;
}
// Print the lat and lon
Serial.print("Lat (deg): ");
Serial.print(lat_int); // Print the integer part of the latitude
Serial.print(".");
Serial.print(lat_frac); // Print the fractional part of the latitude
Serial.print(", Lon (deg): ");
Serial.print(lon_int); // Print the integer part of the latitude
Serial.print(".");
Serial.println(lon_frac); // Print the fractional part of the latitude
// Now define float storage for the heights and accuracy
float f_ellipsoid;
float f_msl;
float f_accuracy;
// Calculate the height above ellipsoid in mm * 10^-1
f_ellipsoid = (ellipsoid * 10) + ellipsoidHp;
// Now convert to m
f_ellipsoid = f_ellipsoid / 10000.0; // Convert from mm * 10^-1 to m
// Calculate the height above mean sea level in mm * 10^-1
f_msl = (msl * 10) + mslHp;
// Now convert to m
f_msl = f_msl / 10000.0; // Convert from mm * 10^-1 to m
// Convert the horizontal accuracy (mm * 10^-1) to a float
f_accuracy = accuracy;
// Now convert to m
f_accuracy = f_accuracy / 10000.0; // Convert from mm * 10^-1 to m
// Finally, do the printing
Serial.print("Ellipsoid (m): ");
Serial.print(f_ellipsoid, 4); // Print the ellipsoid with 4 decimal places
Serial.print(", Mean Sea Level(m): ");
Serial.print(f_msl, 4); // Print the mean sea level with 4 decimal places
Serial.print(", Accuracy (m): ");
Serial.println(f_accuracy, 4); // Print the accuracy with 4 decimal places
}
}

View File

@ -0,0 +1,146 @@
/*
Get the high precision geodetic solution for latitude and longitude using double
By: Nathan Seidle
Modified by: Paul Clark (PaulZC)
SparkFun Electronics
Date: April 17th, 2020
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example shows how to inspect the accuracy of the high-precision
positional solution. Please see below for information about the units.
** This example will only work correctly on platforms which support 64-bit double **
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
Hardware Connections:
Plug a Qwiic cable into the GPS and (e.g.) a Redboard Artemis https://www.sparkfun.com/products/15444
or an Artemis Thing Plus https://www.sparkfun.com/products/15574
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> // Needed for I2C to GPS
#define myWire Wire // This will work on the Redboard Artemis and the Artemis Thing Plus using Qwiic
//#define myWire Wire1 // Uncomment this line if you are using the extra SCL1/SDA1 pins (D17 and D16) on the Thing Plus
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
void setup()
{
Serial.begin(115200);
while (!Serial); //Wait for user to open terminal
myWire.begin();
//myGPS.enableDebugging(Serial); // Uncomment this line to enable debug messages
if (myGPS.begin(myWire) == false) //Connect to the Ublox module using Wire port
{
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1)
;
}
// Check that this platform supports 64-bit (8 byte) double
if (sizeof(double) < 8)
{
Serial.println(F("Warning! Your platform does not support 64-bit double."));
Serial.println(F("The latitude and longitude will be inaccurate."));
}
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
//myGPS.setNavigationFrequency(20); //Set output to 20 times a second
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
Serial.print("Current update rate: ");
Serial.println(rate);
//myGPS.saveConfiguration(); //Save the current settings to flash and BBR
}
void loop()
{
//Query module only every second.
//The module only responds when a new position is available.
if (millis() - lastTime > 1000)
{
lastTime = millis(); //Update the timer
// getHighResLatitude: returns the latitude from HPPOSLLH as an int32_t in degrees * 10^-7
// getHighResLatitudeHp: returns the high resolution component of latitude from HPPOSLLH as an int8_t in degrees * 10^-9
// getHighResLongitude: returns the longitude from HPPOSLLH as an int32_t in degrees * 10^-7
// getHighResLongitudeHp: returns the high resolution component of longitude from HPPOSLLH as an int8_t in degrees * 10^-9
// getElipsoid: returns the height above ellipsoid as an int32_t in mm
// getElipsoidHp: returns the high resolution component of the height above ellipsoid as an int8_t in mm * 10^-1
// getMeanSeaLevel: returns the height above mean sea level as an int32_t in mm
// getMeanSeaLevelHp: returns the high resolution component of the height above mean sea level as an int8_t in mm * 10^-1
// getHorizontalAccuracy: returns the horizontal accuracy estimate from HPPOSLLH as an uint32_t in mm * 10^-1
// First, let's collect the position data
int32_t latitude = myGPS.getHighResLatitude();
int8_t latitudeHp = myGPS.getHighResLatitudeHp();
int32_t longitude = myGPS.getHighResLongitude();
int8_t longitudeHp = myGPS.getHighResLongitudeHp();
int32_t ellipsoid = myGPS.getElipsoid();
int8_t ellipsoidHp = myGPS.getElipsoidHp();
int32_t msl = myGPS.getMeanSeaLevel();
int8_t mslHp = myGPS.getMeanSeaLevelHp();
uint32_t accuracy = myGPS.getHorizontalAccuracy();
// Defines storage for the lat and lon as double
double d_lat; // latitude
double d_lon; // longitude
// Assemble the high precision latitude and longitude
d_lat = ((double)latitude) / 10000000.0; // Convert latitude from degrees * 10^-7 to degrees
d_lat += ((double)latitudeHp) / 1000000000.0; // Now add the high resolution component (degrees * 10^-9 )
d_lon = ((double)longitude) / 10000000.0; // Convert longitude from degrees * 10^-7 to degrees
d_lon += ((double)longitudeHp) / 1000000000.0; // Now add the high resolution component (degrees * 10^-9 )
// Print the lat and lon
Serial.print("Lat (deg): ");
Serial.print(d_lat, 9);
Serial.print(", Lon (deg): ");
Serial.print(d_lon, 9);
// Now define float storage for the heights and accuracy
float f_ellipsoid;
float f_msl;
float f_accuracy;
// Calculate the height above ellipsoid in mm * 10^-1
f_ellipsoid = (ellipsoid * 10) + ellipsoidHp;
// Now convert to m
f_ellipsoid = f_ellipsoid / 10000.0; // Convert from mm * 10^-1 to m
// Calculate the height above mean sea level in mm * 10^-1
f_msl = (msl * 10) + mslHp;
// Now convert to m
f_msl = f_msl / 10000.0; // Convert from mm * 10^-1 to m
// Convert the horizontal accuracy (mm * 10^-1) to a float
f_accuracy = accuracy;
// Now convert to m
f_accuracy = f_accuracy / 10000.0; // Convert from mm * 10^-1 to m
// Finally, do the printing
Serial.print(", Ellipsoid (m): ");
Serial.print(f_ellipsoid, 4); // Print the ellipsoid with 4 decimal places
Serial.print(", Mean Sea Level (m): ");
Serial.print(f_msl, 4); // Print the mean sea level with 4 decimal places
Serial.print(", Accuracy (m): ");
Serial.println(f_accuracy, 4); // Print the accuracy with 4 decimal places
}
}

View File

@ -0,0 +1,73 @@
/*
Set the static position of the receiver.
By: SparkFun Electronics / Nathan Seidle
Date: September 26th, 2020
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example shows how to set the static position of a receiver
using an Earth-Centered, Earth-Fixed (ECEF) location. This is the
output from a long (24 hour+) survey-in. Setting the static position
immediately causes the receiver to begin outputting RTCM data (if
enabled), perfect for setting up your own RTCM NTRIP caster or CORS.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
Hardware Connections:
Plug a Qwiic cable into the GPS and a BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
void setup()
{
Serial.begin(115200); // You may need to increase this for high navigation rates!
while (!Serial)
; //Wait for user to open terminal
Serial.println(F("SparkFun u-blox Example"));
Wire.begin();
//myGPS.enableDebugging(); // Uncomment this line to enable debug messages
if (myGPS.begin() == false) //Connect to the u-blox module using Wire port
{
Serial.println(F("u-blox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1)
;
}
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
//-1280208.308,-4716803.847,4086665.811 is SparkFun HQ so...
//Units are cm so 1234 = 12.34m
//myGPS.setStaticPosition(-128020831, -471680385, 408666581);
//Units are cm with a high precision extension so -1234.5678 should be called: (-123456, -78)
myGPS.setStaticPosition(-128020830, -80, -471680384, -70, 408666581, 10); //With high precision 0.1mm parts
//We can also set via lat/long
//40.09029751,-105.18507900,1560.238
//myGPS.setStaticPosition(400902975, -1051850790, 156024, true); //True at end enables lat/long input
//myGPS.setStaticPosition(400902975, 10, -1051850790, 0, 156023, 80, true);
//Now let's use getVals to read back the data
//long ecefX = myGPS.getVal32(0x40030003);
//Serial.print("ecefX: ");
//Serial.println(ecefX);
Serial.println(F("Done!"));
}
void loop()
{
}

View File

@ -0,0 +1,119 @@
/*
Configuring the GPS to automatically send HPPOSLLH position reports over I2C
By: Paul Clark
Date: October 27th 2020
Based on an earlier example:
By: Nathan Seidle and Thorsten von Eicken
SparkFun Electronics
Date: January 3rd, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example shows how to configure the U-Blox GPS the send navigation reports automatically
and retrieving the latest one via getHPPOSLLH. This eliminates the blocking in getHPPOSLLH while the GPS
produces a fresh navigation solution at the expense of returning a slighly old solution.
This can be used over serial or over I2C, this example shows the I2C use. With serial the GPS
simply outputs the UBX_NAV_HPPOSLLH packet. With I2C it queues it into its internal I2C buffer (4KB in
size?) where it can be retrieved in the next I2C poll.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
Hardware Connections:
Plug a Qwiic cable into the GPS and a BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include <SparkFun_Ublox_Arduino_Library.h> //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
void setup()
{
Serial.begin(115200);
while (!Serial); //Wait for user to open terminal
Serial.println("SparkFun Ublox Example");
Wire.begin();
//myGPS.enableDebugging(); // Uncomment this line to enable lots of helpful debug messages
//myGPS.enableDebugging(Serial, true); // Uncomment this line to enable the minimum of helpful debug messages
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
{
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1);
}
// Uncomment the next line if you want to reset your module back to the default settings with 1Hz navigation rate
//myGPS.factoryDefault(); delay(5000);
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
myGPS.saveConfigSelective(VAL_CFG_SUBSEC_IOPORT); //Save the communications port settings to flash and BBR
myGPS.setNavigationFrequency(1); //Produce one solution per second
// The acid test: all four of these combinations should work seamlessly :-)
//myGPS.setAutoPVT(false); // Library will poll each reading
//myGPS.setAutoHPPOSLLH(false); // Library will poll each reading
//myGPS.setAutoPVT(true); // Tell the GPS to "send" each solution automatically
//myGPS.setAutoHPPOSLLH(false); // Library will poll each reading
//myGPS.setAutoPVT(false); // Library will poll each reading
//myGPS.setAutoHPPOSLLH(true); // Tell the GPS to "send" each hi res solution automatically
myGPS.setAutoPVT(true); // Tell the GPS to "send" each solution automatically
myGPS.setAutoHPPOSLLH(true); // Tell the GPS to "send" each hi res solution automatically
}
void loop()
{
// Calling getHPPOSLLH returns true if there actually is a fresh navigation solution available.
// Calling getPVT returns true if there actually is a fresh navigation solution available.
if ((myGPS.getHPPOSLLH()) || (myGPS.getPVT()))
{
Serial.println();
long highResLatitude = myGPS.getHighResLatitude();
Serial.print(F("Hi Res Lat: "));
Serial.print(highResLatitude);
int highResLatitudeHp = myGPS.getHighResLatitudeHp();
Serial.print(F(" "));
Serial.print(highResLatitudeHp);
long highResLongitude = myGPS.getHighResLongitude();
Serial.print(F(" Hi Res Long: "));
Serial.print(highResLongitude);
int highResLongitudeHp = myGPS.getHighResLongitudeHp();
Serial.print(F(" "));
Serial.print(highResLongitudeHp);
unsigned long horizAccuracy = myGPS.getHorizontalAccuracy();
Serial.print(F(" Horiz accuracy: "));
Serial.print(horizAccuracy);
long latitude = myGPS.getLatitude();
Serial.print(F(" Lat: "));
Serial.print(latitude);
long longitude = myGPS.getLongitude();
Serial.print(F(" Long: "));
Serial.println(longitude);
}
else
{
Serial.print(".");
delay(50);
}
}

View File

@ -0,0 +1,274 @@
/*
Use ESP32 WiFi to push RTCM data to RTK2Go (caster) as a Server
By: SparkFun Electronics / Nathan Seidle
Date: December 14th, 2020
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example shows how to gather RTCM data over I2C and push it to a casting service over WiFi.
It's confusing, but the Arduino is acting as a 'server' to a 'caster'. In this case we will
use RTK2Go.com as our caster because it is free. A rover (car, surveyor stick, etc) can
then connect to RTK2Go as a 'client' and get the RTCM data it needs.
You will need to register your mountpoint here: http://www.rtk2go.com/new-reservation/
(They'll probably block the credentials we include in this example)
To see if your mountpoint is active go here: http://rtk2go.com:2101/
This is a proof of concept. Serving RTCM to a caster over WiFi is useful when you need to
set up a high-precision base station.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/16481
RTK Surveyor: https://www.sparkfun.com/products/17369
Hardware Connections:
Plug a Qwiic cable into the GPS and a ESP32 Thing Plus
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <WiFi.h>
#include "secrets.h"
WiFiClient client;
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
//Basic Connection settings to RTK2Go NTRIP Caster - See secrets for mount specific credentials
//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
const uint16_t casterPort = 2101;
const char * casterHost = "rtk2go.com";
const char * ntrip_server_name = "SparkFun_RTK_Surveyor";
long lastSentRTCM_ms = 0; //Time of last data pushed to socket
int maxTimeBeforeHangup_ms = 10000; //If we fail to get a complete RTCM frame after 10s, then disconnect from caster
uint32_t serverBytesSent = 0; //Just a running total
//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
long lastReport_ms = 0; //Time of last report of bytes sent
void setup()
{
Serial.begin(115200); // You may need to increase this for high navigation rates!
while (!Serial)
; //Wait for user to open terminal
Serial.println(F("SparkFun u-blox Example"));
Wire.begin();
//myGPS.enableDebugging(); // Uncomment this line to enable debug messages
if (myGPS.begin() == false) //Connect to the u-blox module using Wire port
{
Serial.println(F("u-blox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1)
;
}
Serial.print("Connecting to local WiFi");
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Serial.print("\nWiFi connected with IP: ");
Serial.println(WiFi.localIP());
myGPS.setI2COutput(COM_TYPE_UBX | COM_TYPE_NMEA | COM_TYPE_RTCM3); //UBX+RTCM3 is not a valid option so we enable all three.
myGPS.setNavigationFrequency(1); //Set output in Hz. RTCM rarely benefits from >1Hz.
//Disable all NMEA sentences
bool response = true;
response &= myGPS.disableNMEAMessage(UBX_NMEA_GGA, COM_PORT_I2C);
response &= myGPS.disableNMEAMessage(UBX_NMEA_GSA, COM_PORT_I2C);
response &= myGPS.disableNMEAMessage(UBX_NMEA_GSV, COM_PORT_I2C);
response &= myGPS.disableNMEAMessage(UBX_NMEA_RMC, COM_PORT_I2C);
response &= myGPS.disableNMEAMessage(UBX_NMEA_GST, COM_PORT_I2C);
response &= myGPS.disableNMEAMessage(UBX_NMEA_GLL, COM_PORT_I2C);
response &= myGPS.disableNMEAMessage(UBX_NMEA_VTG, COM_PORT_I2C);
if (response == false)
{
Serial.println(F("Failed to disable NMEA. Freezing..."));
while (1);
}
else
Serial.println(F("NMEA disabled"));
//Enable necessary RTCM sentences
response &= myGPS.enableRTCMmessage(UBX_RTCM_1005, COM_PORT_I2C, 1); //Enable message 1005 to output through UART2, message every second
response &= myGPS.enableRTCMmessage(UBX_RTCM_1074, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1084, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1094, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1124, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1230, COM_PORT_I2C, 10); //Enable message every 10 seconds
if (response == false)
{
Serial.println(F("Failed to enable RTCM. Freezing..."));
while (1);
}
else
Serial.println(F("RTCM sentences enabled"));
//-1280208.308,-4716803.847,4086665.811 is SparkFun HQ so...
//Units are cm with a high precision extension so -1234.5678 should be called: (-123456, -78)
//For more infomation see Example12_setStaticPosition
//Note: If you leave these coordinates in place and setup your antenna *not* at SparkFun, your receiver
//will be very confused and fail to generate correction data because, well, you aren't at SparkFun...
//See this tutorial on getting PPP coordinates: https://learn.sparkfun.com/tutorials/how-to-build-a-diy-gnss-reference-station/all
response &= myGPS.setStaticPosition(-128020830, -80, -471680384, -70, 408666581, 10); //With high precision 0.1mm parts
if (response == false)
{
Serial.println(F("Failed to enter static position. Freezing..."));
while (1);
}
else
Serial.println(F("Static position set"));
//You could instead do a survey-in but it takes much longer to start generating RTCM data. See Example4_BaseWithLCD
//myGPS.enableSurveyMode(60, 5.000); //Enable Survey in, 60 seconds, 5.0m
if (myGPS.saveConfiguration() == false) //Save the current settings to flash and BBR
Serial.println(F("Module failed to save."));
Serial.println(F("Module configuration complete"));
}
void loop()
{
if (Serial.available()) beginServing();
Serial.println(F("Press any key to start serving."));
delay(1000);
}
void beginServing()
{
Serial.println("Xmit to RTK2Go. Press any key to stop");
delay(10); //Wait for any serial to arrive
while (Serial.available()) Serial.read(); //Flush
while (Serial.available() == 0)
{
//Connect if we are not already
if (client.connected() == false)
{
Serial.printf("Opening socket to %s\n", casterHost);
if (client.connect(casterHost, casterPort) == true) //Attempt connection
{
Serial.printf("Connected to %s:%d\n", casterHost, casterPort);
const int SERVER_BUFFER_SIZE = 512;
char serverBuffer[SERVER_BUFFER_SIZE];
snprintf(serverBuffer, SERVER_BUFFER_SIZE, "SOURCE %s /%s\r\nSource-Agent: NTRIP %s/%s\r\n\r\n",
mntpnt_pw, mntpnt, ntrip_server_name, "App Version 1.0");
Serial.printf("Sending credentials:\n%s\n", serverBuffer);
client.write(serverBuffer, strlen(serverBuffer));
//Wait for response
unsigned long timeout = millis();
while (client.available() == 0)
{
if (millis() - timeout > 5000)
{
Serial.println(">>> Client Timeout !");
client.stop();
return;
}
delay(10);
}
//Check reply
bool connectionSuccess = false;
char response[512];
int responseSpot = 0;
while (client.available())
{
response[responseSpot++] = client.read();
if (strstr(response, "200") > 0) //Look for 'ICY 200 OK'
connectionSuccess = true;
if (responseSpot == 512 - 1) break;
}
response[responseSpot] = '\0';
if (connectionSuccess == false)
{
Serial.printf("Failed to connect to RTK2Go: %s", response);
}
} //End attempt to connect
else
{
Serial.println("Connection to host failed");
}
} //End connected == false
if (client.connected() == true)
{
delay(10);
while (Serial.available()) Serial.read(); //Flush any endlines or carriage returns
lastReport_ms = millis();
lastSentRTCM_ms = millis();
//This is the main sending loop. We scan for new ublox data but processRTCM() is where the data actually gets sent out.
while (1)
{
if (Serial.available()) break;
myGPS.checkUblox(); //See if new data is available. Process bytes as they come in.
//Close socket if we don't have new data for 10s
//RTK2Go will ban your IP address if you abuse it. See http://www.rtk2go.com/how-to-get-your-ip-banned/
//So let's not leave the socket open/hanging without data
if (millis() - lastSentRTCM_ms > maxTimeBeforeHangup_ms)
{
Serial.println("RTCM timeout. Disconnecting...");
client.stop();
return;
}
delay(10);
//Report some statistics every 250
if (millis() - lastReport_ms > 250)
{
lastReport_ms += 250;
Serial.printf("Total sent: %d\n", serverBytesSent);
}
}
}
delay(10);
}
Serial.println("User pressed a key");
Serial.println("Disconnecting...");
client.stop();
delay(10);
while (Serial.available()) Serial.read(); //Flush any endlines or carriage returns
}
//This function gets called from the SparkFun u-blox Arduino Library.
//As each RTCM byte comes in you can specify what to do with it
//Useful for passing the RTCM correction data to a radio, Ntrip broadcaster, etc.
void SFE_UBLOX_GPS::processRTCM(uint8_t incoming)
{
if (client.connected() == true)
{
client.write(incoming); //Send this byte to socket
serverBytesSent++;
lastSentRTCM_ms = millis();
}
}

View File

@ -0,0 +1,7 @@
//Your WiFi credentials
const char* ssid = "TRex";
const char* password = "hasBigTeeth";
//Your RTK2GO mount point credentials
const char* mntpnt_pw = "WR5wRo4H";
const char* mntpnt = "bldr_dwntwn2";

View File

@ -0,0 +1,77 @@
/*
Get the high position accuracy of the RTK enhanced position
By: Nathan Seidle
SparkFun Electronics
Date: January 3rd, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example shows how to inspect the accuracy of the high-precision
positional solution.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
SAM-M8Q: https://www.sparkfun.com/products/15106
Hardware Connections:
Plug a Qwiic cable into the GPS and a BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
void setup()
{
Serial.begin(115200);
while (!Serial); //Wait for user to open terminal
Serial.println("SparkFun Ublox Example");
Wire.begin();
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
{
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1);
}
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
}
void loop()
{
//Query module only every second. Doing it more often will just cause I2C traffic.
//The module only responds when a new position is available
if (millis() - lastTime > 1000)
{
lastTime = millis(); //Update the timer
long latitude = myGPS.getLatitude();
Serial.print(F("Lat: "));
Serial.print(latitude);
long longitude = myGPS.getLongitude();
Serial.print(F(" Long: "));
Serial.print(longitude);
Serial.print(F(" (degrees * 10^-7)"));
long altitude = myGPS.getAltitude();
Serial.print(F(" Alt: "));
Serial.print(altitude);
Serial.print(F(" (mm)"));
long accuracy = myGPS.getPositionAccuracy();
Serial.print(F(" 3D Positional Accuracy: "));
Serial.print(accuracy);
Serial.println(F("mm"));
}
}

View File

@ -0,0 +1,60 @@
/*
Configuring Ublox Module using new VALGET / VALSET / VALDEL methods
By: Nathan Seidle
SparkFun Electronics
Date: January 3rd, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
Ublox depricated many -CFG messages and replaced them with new
VALGET, VALSET, VALDEL methods. This shows the basics of how to use
these methods.
Leave NMEA parsing behind. Now you can simply ask the module for the datums you want!
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
SAM-M8Q: https://www.sparkfun.com/products/15106
Hardware Connections:
Plug a Qwiic cable into the GPS and a BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
void setup()
{
Serial.begin(115200);
while (!Serial); //Wait for user to open terminal
Serial.println("SparkFun Ublox Example");
Wire.begin();
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
{
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1);
}
byte response;
response = myGPS.getVal8(VAL_GROUP_I2C, VAL_ID_I2C_ADDRESS, VAL_GROUP_I2C_SIZE, VAL_LAYER_RAM);
Serial.print(F("I2C Address: 0x"));
Serial.println(response >> 1, HEX); //We have to shift by 1 to get the common '7-bit' I2C address format
response = myGPS.getVal8(VAL_GROUP_I2COUTPROT, VAL_ID_I2COUTPROT_NMEA, VAL_GROUP_I2COUTPROT_SIZE, VAL_LAYER_RAM);
Serial.print(F("Output NMEA over I2C port: 0x"));
Serial.print(response, HEX);
}
void loop()
{
}

View File

@ -0,0 +1,176 @@
/*
Send UBX binary commands to enable RTCM sentences on Ublox ZED-F9P module
By: Nathan Seidle
SparkFun Electronics
Date: January 9th, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example does all steps to configure and enable a ZED-F9P as a base station:
Begin Survey-In
Once we've achieved 2m accuracy and 300s have passed, survey is complete
Enable six RTCM messages
Begin outputting RTCM bytes
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
SAM-M8Q: https://www.sparkfun.com/products/15106
Hardware Connections:
Plug a Qwiic cable into the GPS and a BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
//#define USE_SERIAL1 // Uncomment this line to push the RTCM data to Serial1
void setup()
{
Serial.begin(115200);
while (!Serial); //Wait for user to open terminal
Serial.println("Ublox Base station example");
#ifdef USE_SERIAL1
// If our board supports it, we can output the RTCM data on Serial1
Serial1.begin(115200);
#endif
Wire.begin();
Wire.setClock(400000); //Increase I2C clock speed to 400kHz
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
{
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1);
}
// Uncomment the next line if you want to reset your module back to the default settings with 1Hz navigation rate
//myGPS.factoryDefault(); delay(5000);
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
myGPS.saveConfigSelective(VAL_CFG_SUBSEC_IOPORT); //Save the communications port settings to flash and BBR
while (Serial.available()) Serial.read(); //Clear any latent chars in serial buffer
Serial.println("Press any key to send commands to begin Survey-In");
while (Serial.available() == 0) ; //Wait for user to press a key
boolean response = true;
response &= myGPS.enableRTCMmessage(UBX_RTCM_1005, COM_PORT_I2C, 1); //Enable message 1005 to output through I2C port, message every second
response &= myGPS.enableRTCMmessage(UBX_RTCM_1074, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1084, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1094, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1124, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1230, COM_PORT_I2C, 10); //Enable message every 10 seconds
//Use COM_PORT_UART1 for the above six messages to direct RTCM messages out UART1
//COM_PORT_UART2, COM_PORT_USB, COM_PORT_SPI are also available
//For example: response &= myGPS.enableRTCMmessage(UBX_RTCM_1005, COM_PORT_UART1, 10);
if (response == true)
{
Serial.println("RTCM messages enabled");
}
else
{
Serial.println("RTCM failed to enable. Are you sure you have an ZED-F9P?");
while (1); //Freeze
}
//Check if Survey is in Progress before initiating one
response = myGPS.getSurveyStatus(2000); //Query module for SVIN status with 2000ms timeout (request can take a long time)
if (response == false)
{
Serial.println("Failed to get Survey In status");
while (1); //Freeze
}
if (myGPS.svin.active == true)
{
Serial.print("Survey already in progress.");
}
else
{
//Start survey
//The ZED-F9P is slightly different than the NEO-M8P. See the Integration manual 3.5.8 for more info.
//response = myGPS.enableSurveyMode(300, 2.000); //Enable Survey in on NEO-M8P, 300 seconds, 2.0m
response = myGPS.enableSurveyMode(60, 5.000); //Enable Survey in, 60 seconds, 5.0m
if (response == false)
{
Serial.println("Survey start failed");
while (1);
}
Serial.println("Survey started. This will run until 60s has passed and less than 5m accuracy is achieved.");
}
while(Serial.available()) Serial.read(); //Clear buffer
//Begin waiting for survey to complete
while (myGPS.svin.valid == false)
{
if(Serial.available())
{
byte incoming = Serial.read();
if(incoming == 'x')
{
//Stop survey mode
response = myGPS.disableSurveyMode(); //Disable survey
Serial.println("Survey stopped");
break;
}
}
response = myGPS.getSurveyStatus(2000); //Query module for SVIN status with 2000ms timeout (req can take a long time)
if (response == true)
{
Serial.print("Press x to end survey - ");
Serial.print("Time elapsed: ");
Serial.print((String)myGPS.svin.observationTime);
Serial.print(" Accuracy: ");
Serial.print((String)myGPS.svin.meanAccuracy);
Serial.println();
}
else
{
Serial.println("SVIN request failed");
}
delay(1000);
}
Serial.println("Survey valid!");
Serial.println("Base survey complete! RTCM now broadcasting.");
myGPS.setI2COutput(COM_TYPE_UBX | COM_TYPE_RTCM3); //Set the I2C port to output UBX and RTCM sentences (not really an option, turns on NMEA as well)
}
void loop()
{
myGPS.checkUblox(); //See if new data is available. Process bytes as they come in.
delay(250); //Don't pound too hard on the I2C bus
}
//This function gets called from the SparkFun Ublox Arduino Library.
//As each RTCM byte comes in you can specify what to do with it
//Useful for passing the RTCM correction data to a radio, Ntrip broadcaster, etc.
void SFE_UBLOX_GPS::processRTCM(uint8_t incoming)
{
#ifdef USE_SERIAL1
//Push the RTCM data to Serial1
Serial1.write(incoming);
#endif
//Pretty-print the HEX values to Serial
if (myGPS.rtcmFrameCounter % 16 == 0) Serial.println();
Serial.print(" ");
if (incoming < 0x10) Serial.print("0");
Serial.print(incoming, HEX);
}

View File

@ -0,0 +1,200 @@
/*
Send UBX binary commands to enable RTCM sentences on Ublox ZED-F9P module
By: Nathan Seidle
SparkFun Electronics
Date: January 9th, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example does all steps to configure and enable a ZED-F9P as a base station:
Begin Survey-In
Once we've achieved 2m accuracy and 300s have passed, survey is complete
Enable six RTCM messages
Begin outputting RTCM bytes
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
SAM-M8Q: https://www.sparkfun.com/products/15106
Hardware Connections:
Plug a Qwiic cable into the GPS and a BlackBoard
Plug a SerLCD onto the Qwiic bus
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Watch the output on the LCD or open the serial monitor at 115200 baud to see the output
*/
#define STAT_LED 13
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
#include <SerLCD.h> //http://librarymanager/All#SparkFun_SerLCD
SerLCD lcd; // Initialize the library with default I2C address 0x72
void setup()
{
Serial.begin(115200);
while (!Serial)
; //Wait for user to open terminal
Serial.println("Ublox GPS I2C Test");
Wire.begin();
pinMode(STAT_LED, OUTPUT);
digitalWrite(STAT_LED, LOW);
lcd.begin(Wire); //Set up the LCD for Serial communication at 9600bps
lcd.setBacklight(0x4B0082); //indigo, a kind of dark purplish blue
lcd.clear();
lcd.print(F("LCD Ready"));
myGPS.begin(Wire);
if (myGPS.isConnected() == false)
{
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
lcd.setCursor(0, 1);
lcd.print(F("No GPS detected"));
while (1)
;
}
Wire.setClock(400000); //Increase I2C clock speed to 400kHz
lcd.setCursor(0, 1);
lcd.print("GPS Detected");
//myGPS.setI2COutput(COM_TYPE_RTCM3); //Set the I2C port to output RTCM3 sentences (turn off NMEA noise)
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX sentences (turn off NMEA noise)
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
boolean response = true;
response &= myGPS.enableRTCMmessage(UBX_RTCM_1005, COM_PORT_I2C, 1); //Enable message 1005 to output through I2C port, message every second
response &= myGPS.enableRTCMmessage(UBX_RTCM_1074, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1084, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1094, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1124, COM_PORT_I2C, 1);
response &= myGPS.enableRTCMmessage(UBX_RTCM_1230, COM_PORT_I2C, 10); //Enable message every 10 seconds
if (response == true)
{
Serial.println(F("RTCM messages enabled"));
}
else
{
Serial.println(F("RTCM failed to enable. Are you sure you have an ZED-F9P? Freezing."));
while (1)
; //Freeze
}
//Check if Survey is in Progress before initiating one
response = myGPS.getSurveyStatus(2000); //Query module for SVIN status with 2000ms timeout (request can take a long time)
if (response == false)
{
Serial.println(F("Failed to get Survey In status. Freezing."));
while (1)
; //Freeze
}
if (myGPS.svin.active == true)
{
Serial.print(F("Survey already in progress."));
lcd.setCursor(0, 2);
lcd.print(F("Survey already going"));
}
else
{
//Start survey
response = myGPS.enableSurveyMode(60, 5.000); //Enable Survey in, 60 seconds, 5.0m
if (response == false)
{
Serial.println(F("Survey start failed"));
lcd.setCursor(0, 3);
lcd.print(F("Survey start failed. Freezing."));
while (1)
;
}
Serial.println(F("Survey started. This will run until 60s has passed and less than 5m accuracy is achieved."));
}
while (Serial.available())
Serial.read(); //Clear buffer
lcd.clear();
lcd.print(F("Survey in progress"));
//Begin waiting for survey to complete
while (myGPS.svin.valid == false)
{
if (Serial.available())
{
byte incoming = Serial.read();
if (incoming == 'x')
{
//Stop survey mode
response = myGPS.disableSurveyMode(); //Disable survey
Serial.println(F("Survey stopped"));
break;
}
}
response = myGPS.getSurveyStatus(2000); //Query module for SVIN status with 2000ms timeout (req can take a long time)
if (response == true)
{
Serial.print(F("Press x to end survey - "));
Serial.print(F("Time elapsed: "));
Serial.print((String)myGPS.svin.observationTime);
lcd.setCursor(0, 1);
lcd.print(F("Elapsed: "));
lcd.print((String)myGPS.svin.observationTime);
Serial.print(F(" Accuracy: "));
Serial.print((String)myGPS.svin.meanAccuracy);
Serial.println();
lcd.setCursor(0, 2);
lcd.print(F("Accuracy: "));
lcd.print((String)myGPS.svin.meanAccuracy);
}
else
{
Serial.println(F("SVIN request failed"));
}
delay(1000);
}
Serial.println(F("Survey valid!"));
Serial.println(F("Base survey complete! RTCM now broadcasting."));
lcd.clear();
lcd.print(F("Transmitting RTCM"));
myGPS.setI2COutput(COM_TYPE_UBX | COM_TYPE_RTCM3); //Set the I2C port to output UBX and RTCM sentences (not really an option, turns on NMEA as well)
}
void loop()
{
myGPS.checkUblox(); //See if new data is available. Process bytes as they come in.
//Do anything you want. Call checkUblox() every second. ZED-F9P has TX buffer of 4k bytes.
delay(250); //Don't pound too hard on the I2C bus
}
//This function gets called from the SparkFun Ublox Arduino Library.
//As each RTCM byte comes in you can specify what to do with it
//Useful for passing the RTCM correction data to a radio, Ntrip broadcaster, etc.
void SFE_UBLOX_GPS::processRTCM(uint8_t incoming)
{
//Let's just pretty-print the HEX values for now
if (myGPS.rtcmFrameCounter % 16 == 0)
Serial.println();
Serial.print(" ");
if (incoming < 0x10)
Serial.print("0");
Serial.print(incoming, HEX);
}

View File

@ -0,0 +1,161 @@
/*
Send UBX binary commands to enable RTCM sentences on Ublox ZED-F9P module
By: Nathan Seidle
SparkFun Electronics
Date: January 9th, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example shows how to query the module for RELPOS information in the NED frame.
It assumes you already have RTCM correction data being fed to the receiver.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
SAM-M8Q: https://www.sparkfun.com/products/15106
Hardware Connections:
Plug a Qwiic cable into the GPS and a RedBoard Qwiic or BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
//#define USE_SERIAL1 // Uncomment this line to push the RTCM data from Serial1 to the module via I2C
size_t numBytes = 0; // Record the number os bytes received from Serial1
void setup()
{
Serial.begin(115200);
while (!Serial); //Wait for user to open terminal
Serial.println("Ublox Base station example");
#ifdef USE_SERIAL1
// If our board supports it, we can receive the RTCM data on Serial1
Serial1.begin(115200);
#endif
Wire.begin();
Wire.setClock(400000); //Increase I2C clock speed to 400kHz
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
{
Serial.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1);
}
// Uncomment the next line if you want to reset your module back to the default settings with 1Hz navigation rate
//myGPS.factoryDefault(); delay(5000);
#ifdef USE_SERIAL1
Serial.print(F("Enabling UBX and RTCM input on I2C. Result: "));
Serial.print(myGPS.setPortInput(COM_PORT_I2C, COM_TYPE_UBX | COM_TYPE_RTCM3)); //Enable UBX and RTCM input on I2C
myGPS.saveConfigSelective(VAL_CFG_SUBSEC_IOPORT); //Save the communications port settings to flash and BBR
#endif
}
void loop()
{
if (myGPS.getRELPOSNED() == true)
{
Serial.print("relPosN: ");
Serial.println(myGPS.relPosInfo.relPosN, 4);
Serial.print("relPosE: ");
Serial.println(myGPS.relPosInfo.relPosE, 4);
Serial.print("relPosD: ");
Serial.println(myGPS.relPosInfo.relPosD, 4);
Serial.print("relPosLength: ");
Serial.println(myGPS.relPosInfo.relPosLength);
Serial.print("relPosHeading: ");
Serial.println(myGPS.relPosInfo.relPosHeading);
Serial.print("relPosHPN: ");
Serial.println(myGPS.relPosInfo.relPosHPN);
Serial.print("relPosHPE: ");
Serial.println(myGPS.relPosInfo.relPosHPE);
Serial.print("relPosHPD: ");
Serial.println(myGPS.relPosInfo.relPosHPD);
Serial.print("relPosHPLength: ");
Serial.println(myGPS.relPosInfo.relPosHPLength);
Serial.print("accN: ");
Serial.println(myGPS.relPosInfo.accN, 4);
Serial.print("accE: ");
Serial.println(myGPS.relPosInfo.accE, 4);
Serial.print("accD: ");
Serial.println(myGPS.relPosInfo.accD, 4);
Serial.print("gnssFixOk: ");
if (myGPS.relPosInfo.gnssFixOk == true)
Serial.println("x");
else
Serial.println("");
Serial.print("diffSolution: ");
if (myGPS.relPosInfo.diffSoln == true)
Serial.println("x");
else
Serial.println("");
Serial.print("relPosValid: ");
if (myGPS.relPosInfo.relPosValid == true)
Serial.println("x");
else
Serial.println("");
Serial.print("carrier Solution Type: ");
if (myGPS.relPosInfo.carrSoln == 0)
Serial.println("None");
else if (myGPS.relPosInfo.carrSoln == 1)
Serial.println("Float");
else if (myGPS.relPosInfo.carrSoln == 2)
Serial.println("Fixed");
Serial.print("isMoving: ");
if (myGPS.relPosInfo.isMoving == true)
Serial.println("x");
else
Serial.println("");
Serial.print("refPosMiss: ");
if (myGPS.relPosInfo.refPosMiss == true)
Serial.println("x");
else
Serial.println("");
Serial.print("refObsMiss: ");
if (myGPS.relPosInfo.refObsMiss == true)
Serial.println("x");
else
Serial.println("");
}
else
Serial.println("RELPOS request failed");
for (int i = 0; i < 500; i++)
{
#ifdef USE_SERIAL1
uint8_t store[256];
while ((Serial1.available()) && (numBytes < 256)) // Check if data has been received
{
store[numBytes++] = Serial1.read(); // Read a byte from Serial1 and store it
}
if (numBytes > 0) // Check if data was received
{
//Serial.print("Pushing ");
//Serial.print(numBytes);
//Serial.println(" bytes via I2C");
myGPS.pushRawData(((uint8_t *)&store), numBytes); // Push the RTCM data via I2C
numBytes = 0; // Reset numBytes
}
#endif
delay(10);
}
}

View File

@ -0,0 +1,88 @@
/*
Get a device's I2C address using advanced getVal method
By: Nathan Seidle
SparkFun Electronics
Date: January 9th, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
u-blox changed how to configure their modules in 2019. As of version 23 of the UBX protocol the
UBX-CFG commands are deprecated; they still work, they just recommend using VALSET, VALGET, and VALDEL
commands instead. This example shows how to use this new command structure.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
SAM-M8Q: https://www.sparkfun.com/products/15106
Hardware Connections:
Plug a Qwiic cable into the GPS and a RedBoard Qwiic or BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
void setup()
{
Serial.begin(115200);
while (!Serial)
; //Wait for user to open terminal
Serial.println("u-blox getVal example");
Wire.begin();
Wire.setClock(400000); //Increase I2C clock speed to 400kHz
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
{
Serial.println(F("u-blox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1)
;
}
myGPS.enableDebugging(); //Enable debug messages over Serial (default)
//myGPS.enableDebugging(SerialUSB); //Enable debug messages over Serial USB
uint8_t currentI2Caddress = myGPS.getVal8(UBLOX_CFG_I2C_ADDRESS);
Serial.print("Current I2C address (should be 0x42): 0x");
Serial.println(currentI2Caddress >> 1, HEX); //Ublox module returns a shifted 8-bit address. Make it 7-bit unshifted.
while (1)
;
}
void loop()
{
//Query module only every second. Doing it more often will just cause I2C traffic.
//The module only responds when a new position is available
if (millis() - lastTime > 1000)
{
lastTime = millis(); //Update the timer
long latitude = myGPS.getLatitude();
Serial.print(F("Lat: "));
Serial.print(latitude);
long longitude = myGPS.getLongitude();
Serial.print(F(" Long: "));
Serial.print(longitude);
Serial.print(F(" (degrees * 10^-7)"));
long altitude = myGPS.getAltitude();
Serial.print(F(" Alt: "));
Serial.print(altitude);
Serial.print(F(" (mm)"));
byte SIV = myGPS.getSIV();
Serial.print(F(" SIV: "));
Serial.print(SIV);
Serial.println();
}
}

View File

@ -0,0 +1,76 @@
/*
Send UBX binary commands to enable RTCM sentences on u-blox ZED-F9P module
By: Nathan Seidle
SparkFun Electronics
Date: January 9th, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
u-blox changed how to configure their modules in 2019. As of version 23 of the UBX protocol the
UBX-CFG commands are deprecated; they still work, they just recommend using VALSET, VALGET, and VALDEL
commands instead. This example shows how to use this new command structure.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
SAM-M8Q: https://www.sparkfun.com/products/15106
Hardware Connections:
Plug a Qwiic cable into the GPS and a RedBoard Qwiic or BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to u-blox module.
void setup()
{
Serial.begin(115200);
while (!Serial)
; //Wait for user to open terminal
Serial.println("u-blox getVal example");
Wire.begin();
Wire.setClock(400000); //Increase I2C clock speed to 400kHz
if (myGPS.begin() == false) //Connect to the u-blox module using Wire port
{
Serial.println(F("u-blox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1)
;
}
myGPS.enableDebugging(); //Enable debug messages over Serial (default)
//myGPS.enableDebugging(SerialUSB); //Enable debug messages over Serial USB
bool setValueSuccess;
//These key values are hard coded and defined in u-blox_config_keys.h.
//You can obtain them from the ZED-F9P interface description doc
//or from u-center's Messages->CFG->VALSET window. Keys must be 32-bit.
//setValueSuccess = myGPS.setVal(UBLOX_CFG_NMEA_HIGHPREC, 0); //Enable high precision NMEA
setValueSuccess = myGPS.setVal(UBLOX_CFG_RATE_MEAS, 100); //Set measurement rate to 100ms (10Hz update rate)
//setValueSuccess = myGPS.setVal(UBLOX_CFG_RATE_MEAS, 1000); //Set measurement rate to 1000ms (1Hz update rate)
//Below is the original way we enabled the RTCM message on the I2C port. After that, we show how to do the same
//but with setVal().
//Original: myGPS.enableRTCMmessage(UBX_RTCM_1005, COM_PORT_I2C, 1); //Enable message 1005 to output through I2C port, message every second
//setValueSuccess = myGPS.setVal(0x209102bd, 1); //Set output rate of msg 1005 over the I2C port to once per second
if (setValueSuccess == true)
{
Serial.println("Value was successfully set");
}
else
Serial.println("Value set failed");
}
void loop()
{
}

View File

@ -0,0 +1,98 @@
/*
Configuring port settings using the newer getVal/setVal methods
By: Nathan Seidle
SparkFun Electronics
Date: October 23rd, 2020
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
This example shows how to query a u-blox module for its UART1 settings and
then change them if the settings aren't what we want.
Note: getVal/setVal/delVal are only support in u-blox protocol versions 27 and higher.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
Hardware Connections:
Plug a Qwiic cable into the GPS and a RedBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
void setup()
{
Serial.begin(115200);
while (!Serial)
; //Wait for user to open terminal
Serial.println("SparkFun u-blox Example");
Wire.begin();
if (myGPS.begin() == false) //Connect to the u-blox module using Wire port
{
Serial.println(F("u-blox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1)
;
}
bool response = true;
//Read the settings from RAM (what the module is running right now, not BBR, Flash, or default)
uint8_t currentUART1Setting_ubx = myGPS.getVal8(UBLOX_CFG_UART1INPROT_UBX);
uint8_t currentUART1Setting_nmea = myGPS.getVal8(UBLOX_CFG_UART1INPROT_NMEA);
uint8_t currentUART1Setting_rtcm3 = myGPS.getVal8(UBLOX_CFG_UART1INPROT_RTCM3X);
Serial.print("currentUART1Setting_ubx: ");
Serial.println(currentUART1Setting_ubx);
Serial.print("currentUART1Setting_nmea: ");
Serial.println(currentUART1Setting_nmea);
Serial.print("currentUART1Setting_rtcm3: ");
Serial.println(currentUART1Setting_rtcm3);
//Check if NMEA and RTCM are enabled for UART1
if (currentUART1Setting_ubx == 0 || currentUART1Setting_nmea == 0)
{
Serial.println("Updating UART1 configuration");
//setVal sets the values for RAM, BBR, and Flash automatically so no .saveConfiguration() is needed
response &= myGPS.setVal8(UBLOX_CFG_UART1INPROT_UBX, 1); //Enable UBX on UART1 Input
response &= myGPS.setVal8(UBLOX_CFG_UART1INPROT_NMEA, 1); //Enable NMEA on UART1 Input
response &= myGPS.setVal8(UBLOX_CFG_UART1INPROT_RTCM3X, 0); //Disable RTCM on UART1 Input
if (response == false)
Serial.println("SetVal failed");
else
Serial.println("SetVal succeeded");
}
else
Serial.println("No port change needed");
//Change speed of UART2
uint32_t currentUART2Baud = myGPS.getVal32(UBLOX_CFG_UART2_BAUDRATE);
Serial.print("currentUART2Baud: ");
Serial.println(currentUART2Baud);
if (currentUART2Baud != 57600)
{
response &= myGPS.setVal32(UBLOX_CFG_UART2_BAUDRATE, 57600);
if (response == false)
Serial.println("SetVal failed");
else
Serial.println("SetVal succeeded");
}
else
Serial.println("No baud change needed");
Serial.println("Done");
}
void loop()
{
}

View File

@ -0,0 +1,90 @@
/*
Send UBX binary commands to enable RTCM sentences on u-blox ZED-F9P module
Based on Example7 By: Nathan Seidle
SparkFun Electronics
Updated by Paul Clark to demonstrate setVal8/16/32, newCfgValset8/16/32, addCfgValset8/16/32 and sendCfgValset8/16/32
Date: July 1st, 2019
License: MIT. See license file for more information but you can
basically do whatever you want with this code.
u-blox changed how to configure their modules in 2019. As of version 23 of the UBX protocol the
UBX-CFG commands are deprecated; they still work, they just recommend using VALSET, VALGET, and VALDEL
commands instead. This example shows how to use this new command structure.
Feel like supporting open source hardware?
Buy a board from SparkFun!
ZED-F9P RTK2: https://www.sparkfun.com/products/15136
NEO-M8P RTK: https://www.sparkfun.com/products/15005
SAM-M8Q: https://www.sparkfun.com/products/15106
Hardware Connections:
Plug a Qwiic cable into the GPS and a RedBoard Qwiic or BlackBoard
If you don't have a platform with a Qwiic connection use the SparkFun Qwiic Breadboard Jumper (https://www.sparkfun.com/products/14425)
Open the serial monitor at 115200 baud to see the output
*/
#include <Wire.h> //Needed for I2C to GPS
#include "SparkFun_Ublox_Arduino_Library.h" //http://librarymanager/All#SparkFun_u-blox_GNSS
SFE_UBLOX_GPS myGPS;
void setup()
{
Serial.begin(115200);
while (!Serial)
; //Wait for user to open terminal
Serial.println("u-blox multi setVal example");
Wire.begin();
Wire.setClock(400000); //Increase I2C clock speed to 400kHz
if (myGPS.begin() == false) //Connect to the u-blox module using Wire port
{
Serial.println(F("u-blox GPS not detected at default I2C address. Please check wiring. Freezing."));
while (1)
;
}
myGPS.enableDebugging(); //Enable debug messages over Serial (default)
//myGPS.enableDebugging(SerialUSB); //Enable debug messages over Serial USB
bool setValueSuccess = true;
//These key values are hard coded. You can obtain them from the ZED-F9P interface description doc
//or from u-center's Messages->CFG->VALSET window. Keys must be 32-bit.
//Choose setVal8, setVal16 or setVal32 depending on the required value data width (1, 2 or 4 bytes)
//L, U1, I1, E1 and X1 values are 8-bit
//U2, I2, E2 and X2 values are 16-bit
//U4, I4, R4, E4, X4 values are 32-bit
setValueSuccess &= myGPS.setVal8(UBLOX_CFG_NMEA_HIGHPREC, 0); //Enable high precision NMEA (value is 8-bit (L / U1))
//setValueSuccess &= myGPS.setVal16(UBLOX_CFG_RATE_MEAS, 200); //Set measurement rate to 100ms (10Hz update rate) (value is 16-bit (U2))
//setValueSuccess &= myGPS.setVal16(UBLOX_CFG_RATE_MEAS, 200, 1); //Set rate setting in RAM instead of BBR
setValueSuccess &= myGPS.setVal16(UBLOX_CFG_RATE_MEAS, 1000); //Set measurement rate to 1000ms (1Hz update rate) (value is 16-bit (U2))
//Below is the original way we enabled a single RTCM message on the I2C port. After that, we show how to do the same
//but with multiple messages all in one go using newCfgValset, addCfgValset and sendCfgValset.
//Original: myGPS.enableRTCMmessage(UBX_RTCM_1005, COM_PORT_I2C, 1); //Enable message 1005 to output through I2C port, message every second
//Begin with newCfgValset8/16/32
setValueSuccess &= myGPS.newCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_I2C, 1); //Set output rate of msg 1005 over the I2C port to once per measurement (value is 8-bit (U1))
//setValueSuccess &= myGPS.newCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1005_I2C, 1, VAL_LAYER_RAM); //Set this and the following settings in RAM only instead of Flash/RAM/BBR
//Add extra keyIDs and values using addCfgValset8/16/32
setValueSuccess &= myGPS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1077_I2C, 1); //Set output rate of msg 1077 over the I2C port to once per measurement (value is 8-bit (U1))
setValueSuccess &= myGPS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1087_I2C, 1); //Set output rate of msg 1087 over the I2C port to once per measurement (value is 8-bit (U1))
setValueSuccess &= myGPS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1127_I2C, 1); //Set output rate of msg 1127 over the I2C port to once per measurement (value is 8-bit (U1))
setValueSuccess &= myGPS.addCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1097_I2C, 1); //Set output rate of msg 1097 over the I2C port to once per measurement (value is 8-bit (U1))
// Add the final value and send the packet using sendCfgValset8/16/32
setValueSuccess &= myGPS.sendCfgValset8(UBLOX_CFG_MSGOUT_RTCM_3X_TYPE1230_I2C, 10); //Set output rate of msg 1230 over the I2C port to once every 10 measurements (value is 8-bit (U1))
if (setValueSuccess == true)
{
Serial.println("Values were successfully set");
}
else
Serial.println("Value set failed");
}
void loop()
{
}