Skip to content

Commit

Permalink
Merge pull request #777 from sparkfun/release_candidate
Browse files Browse the repository at this point in the history
Add support for multiple NTRIP Servers
  • Loading branch information
nseidle authored Jul 22, 2024
2 parents 7e8fd85 + 40607b9 commit ef0bac1
Show file tree
Hide file tree
Showing 28 changed files with 3,520 additions and 2,459 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/compile-rtk-firmware.yml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ on:
env:
FILENAME_PREFIX: RTK_Surveyor_Firmware
FIRMWARE_VERSION_MAJOR: 4
FIRMWARE_VERSION_MINOR: 0
FIRMWARE_VERSION_MINOR: 1
POINTPERFECT_TOKEN: ${{ secrets.POINTPERFECT_TOKEN }}

jobs:
Expand Down
252 changes: 158 additions & 94 deletions Firmware/RTK_Surveyor/AP-Config/index.html

Large diffs are not rendered by default.

236 changes: 141 additions & 95 deletions Firmware/RTK_Surveyor/AP-Config/src/main.js

Large diffs are not rendered by default.

158 changes: 88 additions & 70 deletions Firmware/RTK_Surveyor/Base.ino
Original file line number Diff line number Diff line change
Expand Up @@ -239,76 +239,92 @@ bool surveyInReset()
bool startFixedBase()
{
bool response = true;
int retries = 0;
uint16_t maxWait = 1100;

if (settings.fixedBaseCoordinateType == COORD_TYPE_ECEF)
{
// Break ECEF into main and high precision parts
// The type casting should not effect rounding of original double cast coordinate
long majorEcefX = floor((settings.fixedEcefX * 100.0) + 0.5);
long minorEcefX = floor((((settings.fixedEcefX * 100.0) - majorEcefX) * 100.0) + 0.5);
long majorEcefY = floor((settings.fixedEcefY * 100) + 0.5);
long minorEcefY = floor((((settings.fixedEcefY * 100.0) - majorEcefY) * 100.0) + 0.5);
long majorEcefZ = floor((settings.fixedEcefZ * 100) + 0.5);
long minorEcefZ = floor((((settings.fixedEcefZ * 100.0) - majorEcefZ) * 100.0) + 0.5);

// systemPrintf("fixedEcefY (should be -4716808.5807): %0.04f\r\n", settings.fixedEcefY);
// systemPrintf("major (should be -471680858): %ld\r\n", majorEcefY);
// systemPrintf("minor (should be -7): %ld\r\n", minorEcefY);

// Units are cm with a high precision extension so -1234.5678 should be called: (-123456, -78)
//-1280208.308,-4716803.847,4086665.811 is SparkFun HQ so...

response &= theGNSS.newCfgValset();
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_MODE, 2); // Fixed
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_POS_TYPE, 0); // Position in ECEF
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_X, majorEcefX);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_X_HP, minorEcefX);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_Y, majorEcefY);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_Y_HP, minorEcefY);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_Z, majorEcefZ);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_Z_HP, minorEcefZ);
response &= theGNSS.sendCfgValset();
}
else if (settings.fixedBaseCoordinateType == COORD_TYPE_GEODETIC)
{
// Add height of instrument (HI) to fixed altitude
// https://www.e-education.psu.edu/geog862/node/1853
// For example, if HAE is at 100.0m, + 2m stick + 73mm ARP = 102.073
float totalFixedAltitude =
settings.fixedAltitude + (settings.antennaHeight / 1000.0) + (settings.antennaReferencePoint / 1000.0);

// Break coordinates into main and high precision parts
// The type casting should not effect rounding of original double cast coordinate
int64_t majorLat = settings.fixedLat * 10000000;
int64_t minorLat = ((settings.fixedLat * 10000000) - majorLat) * 100;
int64_t majorLong = settings.fixedLong * 10000000;
int64_t minorLong = ((settings.fixedLong * 10000000) - majorLong) * 100;
int32_t majorAlt = totalFixedAltitude * 100;
int32_t minorAlt = ((totalFixedAltitude * 100) - majorAlt) * 100;

// systemPrintf("fixedLong (should be -105.184774720): %0.09f\r\n", settings.fixedLong);
// systemPrintf("major (should be -1051847747): %lld\r\n", majorLat);
// systemPrintf("minor (should be -20): %lld\r\n", minorLat);
//
// systemPrintf("fixedLat (should be 40.090335429): %0.09f\r\n", settings.fixedLat);
// systemPrintf("major (should be 400903354): %lld\r\n", majorLong);
// systemPrintf("minor (should be 29): %lld\r\n", minorLong);
//
// systemPrintf("fixedAlt (should be 1560.2284): %0.04f\r\n", settings.fixedAltitude);
// systemPrintf("major (should be 156022): %ld\r\n", majorAlt);
// systemPrintf("minor (should be 84): %ld\r\n", minorAlt);
do {
if (settings.fixedBaseCoordinateType == COORD_TYPE_ECEF)
{
// Break ECEF into main and high precision parts
// The type casting should not effect rounding of original double cast coordinate
long majorEcefX = floor((settings.fixedEcefX * 100.0) + 0.5);
long minorEcefX = floor((((settings.fixedEcefX * 100.0) - majorEcefX) * 100.0) + 0.5);
long majorEcefY = floor((settings.fixedEcefY * 100) + 0.5);
long minorEcefY = floor((((settings.fixedEcefY * 100.0) - majorEcefY) * 100.0) + 0.5);
long majorEcefZ = floor((settings.fixedEcefZ * 100) + 0.5);
long minorEcefZ = floor((((settings.fixedEcefZ * 100.0) - majorEcefZ) * 100.0) + 0.5);

// systemPrintf("fixedEcefY (should be -4716808.5807): %0.04f\r\n", settings.fixedEcefY);
// systemPrintf("major (should be -471680858): %ld\r\n", majorEcefY);
// systemPrintf("minor (should be -7): %ld\r\n", minorEcefY);

// Units are cm with a high precision extension so -1234.5678 should be called: (-123456, -78)
//-1280208.308,-4716803.847,4086665.811 is SparkFun HQ so...

response &= theGNSS.newCfgValset();
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_MODE, 2); // Fixed
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_POS_TYPE, 0); // Position in ECEF
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_X, majorEcefX);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_X_HP, minorEcefX);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_Y, majorEcefY);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_Y_HP, minorEcefY);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_Z, majorEcefZ);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_ECEF_Z_HP, minorEcefZ);
response &= theGNSS.sendCfgValset();
}
else if (settings.fixedBaseCoordinateType == COORD_TYPE_GEODETIC)
{
// Add height of instrument (HI) to fixed altitude
// https://www.e-education.psu.edu/geog862/node/1853
// For example, if HAE is at 100.0m, + 2m stick + 73mm ARP = 102.073
float totalFixedAltitude =
settings.fixedAltitude + (settings.antennaHeight / 1000.0) + (settings.antennaReferencePoint / 1000.0);

// Break coordinates into main and high precision parts
// The type casting should not effect rounding of original double cast coordinate
int64_t majorLat = settings.fixedLat * 10000000;
int64_t minorLat = ((settings.fixedLat * 10000000) - majorLat) * 100;
int64_t majorLong = settings.fixedLong * 10000000;
int64_t minorLong = ((settings.fixedLong * 10000000) - majorLong) * 100;
int32_t majorAlt = totalFixedAltitude * 100;
int32_t minorAlt = ((totalFixedAltitude * 100) - majorAlt) * 100;

// systemPrintf("fixedLong (should be -105.184774720): %0.09f\r\n", settings.fixedLong);
// systemPrintf("major (should be -1051847747): %lld\r\n", majorLat);
// systemPrintf("minor (should be -20): %lld\r\n", minorLat);
//
// systemPrintf("fixedLat (should be 40.090335429): %0.09f\r\n", settings.fixedLat);
// systemPrintf("major (should be 400903354): %lld\r\n", majorLong);
// systemPrintf("minor (should be 29): %lld\r\n", minorLong);
//
// systemPrintf("fixedAlt (should be 1560.2284): %0.04f\r\n", settings.fixedAltitude);
// systemPrintf("major (should be 156022): %ld\r\n", majorAlt);
// systemPrintf("minor (should be 84): %ld\r\n", minorAlt);

response &= theGNSS.newCfgValset();
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_MODE, 2); // Fixed
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_POS_TYPE, 1); // Position in LLH
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_LAT, majorLat);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_LAT_HP, minorLat);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_LON, majorLong);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_LON_HP, minorLong);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_HEIGHT, majorAlt);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_HEIGHT_HP, minorAlt);
response &= theGNSS.sendCfgValset(maxWait);
}

response &= theGNSS.newCfgValset();
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_MODE, 2); // Fixed
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_POS_TYPE, 1); // Position in LLH
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_LAT, majorLat);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_LAT_HP, minorLat);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_LON, majorLong);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_LON_HP, minorLong);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_HEIGHT, majorAlt);
response &= theGNSS.addCfgValset(UBLOX_CFG_TMODE_HEIGHT_HP, minorAlt);
response &= theGNSS.sendCfgValset();
}
if (!response) {
systemPrint("startFixedBase failed! ");
if (retries <= 2) {
systemPrintln("Retrying...");
delay(1000);
maxWait = 2200;
}
else {
systemPrintln("Giving up and going into Rover mode!");
}
}
} while ((!response) && (++retries <= 3));

return (response);
}
Expand Down Expand Up @@ -349,7 +365,8 @@ void DevUBLOXGNSS::processRTCM(uint8_t incoming)
rtcmLastReceived = millis();
rtcmBytesSent++;

ntripServerProcessRTCM(incoming);
for (int serverIndex = 0; serverIndex < NTRIP_SERVER_MAX; serverIndex++)
ntripServerProcessRTCM(serverIndex, incoming);

espnowProcessRTCM(incoming);
}
Expand Down Expand Up @@ -391,7 +408,8 @@ void processRTCMBuffer()
rtcmLastReceived = millis();
rtcmBytesSent++;

ntripServerProcessRTCM(incoming);
for (int serverIndex = 0; serverIndex < NTRIP_SERVER_MAX; serverIndex++)
ntripServerProcessRTCM(serverIndex, incoming);

espnowProcessRTCM(incoming);
}
Expand Down
12 changes: 10 additions & 2 deletions Firmware/RTK_Surveyor/Begin.ino
Original file line number Diff line number Diff line change
Expand Up @@ -283,6 +283,8 @@ void beginBoard()
settings.enablePrintBatteryMessages = false; // No pesky battery messages
}

displaySfeFlame();

char versionString[21];
getFirmwareVersion(versionString, sizeof(versionString), true);
systemPrintf("SparkFun RTK %s %s\r\n", platformPrefix, versionString);
Expand Down Expand Up @@ -361,6 +363,9 @@ void beginBoard()

void beginSD()
{
if(sdCardForcedOffline == true)
return;

bool gotSemaphore;

online.microSD = false;
Expand Down Expand Up @@ -445,6 +450,8 @@ void beginSD()
systemPrintln("SD init failed - using SPI and SdFat. Is card formatted?");
digitalWrite(pin_microSD_CS, HIGH); // Be sure SD is deselected

sdCardForcedOffline = true; //Prevent future scans for SD cards

// Check reset count and prevent rolling reboot
if (settings.resetCount < 5)
{
Expand Down Expand Up @@ -807,13 +814,14 @@ void beginGNSS()
// Construct the firmware version as uint8_t. Note: will fail above 2.55!
zedFirmwareVersionInt = (theGNSS.getFirmwareVersionHigh() * 100) + theGNSS.getFirmwareVersionLow();

// Check this is known firmware
// Check if this is known firmware
//"1.20" - Mostly for F9R HPS 1.20, but also F9P HPG v1.20
//"1.21" - F9R HPS v1.21
//"1.30" - ZED-F9P (HPG) released Dec, 2021. Also ZED-F9R (HPS) released Sept, 2022
//"1.32" - ZED-F9P released May, 2022
//"1.50" - ZED-F9P released July, 2024

const uint8_t knownFirmwareVersions[] = {100, 112, 113, 120, 121, 130, 132};
const uint8_t knownFirmwareVersions[] = {100, 112, 113, 120, 121, 130, 132, 150};
bool knownFirmware = false;
for (uint8_t i = 0; i < (sizeof(knownFirmwareVersions) / sizeof(uint8_t)); i++)
{
Expand Down
8 changes: 4 additions & 4 deletions Firmware/RTK_Surveyor/Developer.ino
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,10 @@ void ntripClientValidateTables() {}
// NTRIP server
//----------------------------------------

bool ntripServerIsCasting() {return false;}
void ntripServerPrintStatus() {systemPrint("NTRIP Server not compiled");}
void ntripServerProcessRTCM(uint8_t incoming) {}
void ntripServerStop(bool clientAllocated) {online.ntripServer = false;}
bool ntripServerIsCasting(int serverIndex) {return false;}
void ntripServerPrintStatus(int serverIndex) {systemPrintf("**NTRIP Server %d not compiled**\r\n", serverIndex);}
void ntripServerProcessRTCM(int serverIndex, uint8_t incoming) {}
void ntripServerStop(int serverIndex, bool clientAllocated) {online.ntripServer[serverIndex] = false;}
void ntripServerUpdate() {}
void ntripServerValidateTables() {}

Expand Down
Loading

0 comments on commit ef0bac1

Please sign in to comment.