Skip to content

Release v2.5 - Add TCP and extend AP config #333

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 81 commits into from
Sep 21, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
81 commits
Select commit Hold shift + click to select a range
fb57513
Update the NMEA client support program
LeeLeahy2 Aug 28, 2022
1434768
Move certificateContents and keyContents into menuPP.ino
LeeLeahy2 Aug 28, 2022
ae91741
Rework updatePointPerfectKeys to have a single exit
LeeLeahy2 Aug 28, 2022
2140cc9
Allocate and free the context buffers
LeeLeahy2 Aug 28, 2022
399480d
Merge pull request #310 from LeeLeahy2/nmea-pc
nseidle Aug 29, 2022
3a2171d
Rename loggingSemaphoreWait_ms
nseidle Aug 29, 2022
5d35bda
Update L-Band error message
nseidle Aug 29, 2022
6ced4b8
Merge pull request #313 from LeeLeahy2/malloc-key
nseidle Aug 29, 2022
6b8a996
Increase version
nseidle Aug 29, 2022
dd77bf3
Display and print error is SSID is not detected for NTRIP Client/Server
nseidle Aug 29, 2022
40377e6
Rename pointperfect functions
nseidle Aug 29, 2022
23ea030
Migrate to printTextCenter()
nseidle Aug 29, 2022
700a525
Prevent WiFi->write if disconnected.
nseidle Aug 30, 2022
93b5134
Empty UART data into ring buffer then send data
LeeLeahy2 Aug 30, 2022
9563e55
Add NMEA over TCP setting to systemMenu and NVM
LeeLeahy2 Aug 19, 2022
92c1044
Start NMEA TCP server and send data to NMEA TCP clients
LeeLeahy2 Aug 19, 2022
6c02333
Add NMEA TCP server to the ring buffer
LeeLeahy2 Aug 19, 2022
1e9a240
Enable NMEA TCP client - Connect to phone
LeeLeahy2 Aug 28, 2022
872427b
Reset the maximum logging time when logging is disabled
LeeLeahy2 Aug 18, 2022
00734fe
Print logTest messages in not-just Release Candidates
nseidle Aug 31, 2022
4c3531c
Merge pull request #298 from LeeLeahy2/uart-first
nseidle Aug 31, 2022
f3c62ea
Merge pull request #287 from LeeLeahy2/log-time
nseidle Aug 31, 2022
df71723
Add ESP-Now broadcast override
nseidle Sep 1, 2022
d3d3201
Fix for #316 - prevent panic during SD update on 4MB devices
nseidle Sep 1, 2022
a49d557
Fix #318 - Add individual profile reset to defaults
nseidle Sep 1, 2022
af08bba
Issue #317 - Print NTRIP Client response if IP banned
nseidle Sep 1, 2022
1a84b8c
Fix for #319 - Duplicate firmware list
nseidle Sep 1, 2022
731a66a
Set default peer count
nseidle Sep 1, 2022
f7bfe3b
Fix issue #290 - Revert resetCount store to NVM
nseidle Sep 1, 2022
73093b3
Comment update
nseidle Sep 1, 2022
cdce40d
Dynamically allocate/free jsonZtp and tempHolder buffers
LeeLeahy2 Aug 31, 2022
8a678a3
#269 - Add antenna height and reference point to Geodetic base
nseidle Sep 2, 2022
6efdcd5
Remove http:// from caster address. Print caster info.
nseidle Sep 2, 2022
2fecded
Fix wrap problem with task loop
nseidle Sep 6, 2022
41342d4
Merge branch 'release_candidate' into nmea-tcp
nseidle Sep 6, 2022
c2e41d0
Merge pull request #299 from LeeLeahy2/nmea-tcp
nseidle Sep 6, 2022
e00f2f4
Merge pull request #309 from LeeLeahy2/nmea-client
nseidle Sep 6, 2022
04fb3d5
Fix PR merge typo
nseidle Sep 6, 2022
0700aaa
Skip tasks if not bytes to send
nseidle Sep 7, 2022
9093fcd
Fix init of WiFi AP mode
nseidle Sep 7, 2022
7639a74
Add AP config support for new features
nseidle Sep 7, 2022
1798809
Add reset profile over AP config
nseidle Sep 8, 2022
472e00c
Line wrap state if no RTC
nseidle Sep 8, 2022
19dea7b
Include tokens file if available
nseidle Sep 8, 2022
0885b85
Fix #314 - Turn off Bluetooth during secure WiFi
nseidle Sep 8, 2022
207f1b3
Turn off Bluetooth during secure WiFi
nseidle Sep 8, 2022
6b17e2a
Merge pull request #320 from LeeLeahy2/key-buf
nseidle Sep 8, 2022
72834ef
Adjust AP header text
nseidle Sep 8, 2022
2d74e27
Fix timer for initial pvt wait
nseidle Sep 9, 2022
41da2e9
Stop NTRIP Client/Server if SSID is blank
nseidle Sep 9, 2022
9480089
Format ifdefs
nseidle Sep 9, 2022
68ffeeb
Add NTRIP Client/Server uptime to System menu
nseidle Sep 9, 2022
5564427
Increase all menu timeouts to 10minutes
nseidle Sep 9, 2022
5e16e4b
Set Measurement, Nav, and GSV during module config
nseidle Sep 9, 2022
1ddb2df
Correct debug printing of GGA
nseidle Sep 9, 2022
360cdbd
Fix stack overflow
nseidle Sep 11, 2022
7ec535f
Move NTRIP variables for System Status printing
nseidle Sep 11, 2022
5657cad
Fix info bubble text typo
nseidle Sep 12, 2022
236fe4e
Add throttling to NTRIP Client
nseidle Sep 12, 2022
26f1d9d
NTRIP Server: Throttle (do not give up) if SSID is not found
nseidle Sep 12, 2022
29f531a
Allow for negative values of antennaHeight and ARP
nseidle Sep 14, 2022
68e3f5c
Fix Bluetooth on AP config
nseidle Sep 14, 2022
2a10718
Bug fixes for ESP32 core v2.0.4
nseidle Sep 14, 2022
c798e71
Merge branch 'main' into release_candidate
nseidle Sep 15, 2022
8bdd917
Change gateway to match IP during AP config
nseidle Sep 15, 2022
197e1c2
Add back ESPNow variable
nseidle Sep 15, 2022
b032180
Correct WiFi TCP logic. Change NTRIP Client to 15s throttling.
nseidle Sep 16, 2022
649a28a
Pass high precision coordinates to AP config
nseidle Sep 16, 2022
59eaf59
Update ESPNOW.ino
nseidle Sep 16, 2022
d604722
Fix bug during profile select from AP config
nseidle Sep 16, 2022
2ba5589
Move HAE number of decimals to global const
nseidle Sep 16, 2022
38a8ab7
Move profile changes to heap.
nseidle Sep 16, 2022
956076f
L-Band: Display days remaining at each boot. Show RTC wait.
nseidle Sep 19, 2022
68ec63a
NTRIP Server retries if authorized, but returns error.
nseidle Sep 19, 2022
5e1b486
Update NtripServer.ino
nseidle Sep 19, 2022
d06fabd
Update System_Check.ino.esp32.bin
nseidle Sep 21, 2022
b9d63c3
Reduce RTCM count to avoid activity bar
nseidle Sep 21, 2022
1b0f93d
Change line endings to \r\n
nseidle Sep 21, 2022
8e7b737
Report NTRIP connection attempts total
nseidle Sep 21, 2022
50bf22c
Fix tool tip typo
nseidle Sep 21, 2022
7f1f97a
Stop ESP-Now before firmware update.
nseidle Sep 21, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
213 changes: 191 additions & 22 deletions Firmware/RTK_Surveyor/AP-Config/index.html

Large diffs are not rendered by default.

92 changes: 90 additions & 2 deletions Firmware/RTK_Surveyor/AP-Config/src/main.js
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,12 @@ function ge(e) {
}

var platformPrefix = "Surveyor";
var geodeticLat = 40.01;
var geodeticLon = -105.19;
var geodeticAlt = 1500.1;
var ecefX = 100;
var ecefY = -100;
var ecefZ = -200;

function parseIncoming(msg) {
//console.log("incoming message: " + msg);
Expand Down Expand Up @@ -92,6 +98,7 @@ function parseIncoming(msg) {
|| id.includes("profile5Name")
|| id.includes("profile6Name")
|| id.includes("profile7Name")
|| id.includes("radioMAC")
) {
ge(id).innerHTML = val;
}
Expand All @@ -105,6 +112,41 @@ function parseIncoming(msg) {
else if (id.includes("firmwareUploadStatus")) {
firmwareUploadStatus(val);
}
else if (id.includes("geodeticLat")) {
geodeticLat = val;
ge(id).innerHTML = val;
}
else if (id.includes("geodeticLon")) {
geodeticLon = val;
ge(id).innerHTML = val;
}
else if (id.includes("geodeticAlt")) {
geodeticAlt = val;
ge(id).innerHTML = val;
}
else if (id.includes("ecefX")) {
ecefX = val;
ge(id).innerHTML = val;
}
else if (id.includes("ecefY")) {
ecefY = val;
ge(id).innerHTML = val;
}
else if (id.includes("ecefZ")) {
ecefZ = val;
ge(id).innerHTML = val;
}
else if (id.includes("bluetoothRadioType")) {
currentBtNumber = val;
$("input[name=bluetoothRadioType][value=" + currentBtNumber + "]").prop('checked', true);
}
else if (id.includes("espnowPeerCount")) {
if(val > 0)
ge("peerMACs").innerHTML = "";
}
else if (id.includes("peerMAC")) {
ge("peerMACs").innerHTML += val + "<br>";
}

//Check boxes / radio buttons
else if (val == "true") {
Expand Down Expand Up @@ -134,6 +176,7 @@ function parseIncoming(msg) {
//console.log("Settings loaded");

ge("profileChangeMessage").innerHTML = '';
ge("resetProfileMsg").innerHTML = '';

//Force element updates
ge("measurementRateHz").dispatchEvent(new CustomEvent('change'));
Expand All @@ -147,6 +190,7 @@ function parseIncoming(msg) {
ge("dataPortChannel").dispatchEvent(new CustomEvent('change'));
ge("enableExternalPulse").dispatchEvent(new CustomEvent('change'));
ge("enablePointPerfectCorrections").dispatchEvent(new CustomEvent('change'));
ge("radioType").dispatchEvent(new CustomEvent('change'));
}

function hide(id) {
Expand Down Expand Up @@ -215,6 +259,7 @@ function validateFields() {
collapseSection("collapseSensorConfig", "sensorCaret");
collapseSection("collapsePPConfig", "pointPerfectCaret");
collapseSection("collapsePortsConfig", "portsCaret");
collapseSection("collapseRadioConfig", "radioCaret");
collapseSection("collapseSystemConfig", "systemCaret");

errorCount = 0;
Expand Down Expand Up @@ -350,6 +395,8 @@ function validateFields() {
clearElement("fixedLat", 40.09029479);
clearElement("fixedLong", -105.18505761);
clearElement("fixedAltitude", 1560.089);
clearElement("antennaHeight", 0);
clearElement("antennaReferencePoint", 0);
}
else {
clearElement("observationSeconds", 60);
Expand All @@ -372,6 +419,9 @@ function validateFields() {
checkElementValue("fixedLat", -180, 180, "Must be -180 to 180", "collapseBaseConfig");
checkElementValue("fixedLong", -180, 180, "Must be -180 to 180", "collapseBaseConfig");
checkElementValue("fixedAltitude", -11034, 8849, "Must be -11034 to 8849", "collapseBaseConfig");

checkElementValue("antennaHeight", -15000, 15000, "Must be -15000 to 15000", "collapseBaseConfig");
checkElementValue("antennaReferencePoint", -200.0, 200.0, "Must be -200.0 to 200.0", "collapseBaseConfig");
}
}

Expand Down Expand Up @@ -553,7 +603,7 @@ function clearElement(id, value) {
}

function resetToFactoryDefaults() {
ge("factoryDefaultsMsg").innerHTML = "Defaults Applied. Please wait for device reset..."
ge("factoryDefaultsMsg").innerHTML = "Defaults Applied. Please wait for device reset...";
ws.send("factoryDefaultReset,1,");
}

Expand Down Expand Up @@ -669,6 +719,16 @@ function resetToLoggingDefaults() {
ge("UBX_RXM_RAWX").value = 1;
ge("UBX_RXM_SFRBX").value = 1;
}
function useECEFCoordinates() {
ge("fixedEcefX").value = ecefX;
ge("fixedEcefY").value = ecefY;
ge("fixedEcefZ").value = ecefZ;
}
function useGeodeticCoordinates() {
ge("fixedLat").value = geodeticLat;
ge("fixedLong").value = geodeticLon;
ge("fixedAltitude").value = geodeticAlt;
}

function exitConfig() {
show("exitPage");
Expand All @@ -689,6 +749,17 @@ function firmwareUploadComplete() {
hide("mainPage");
}

function forgetPairedRadios() {
ge("btnForgetRadiosMsg").innerHTML = "All radios forgotten.";
ge("peerMACs").innerHTML = "None";
ws.send("forgetEspNowPeers,1,");
}

function btnResetProfile() {
ge("resetProfileMsg").innerHTML = "Resetting profile.";
ws.send("resetProfile,1,");
}

document.addEventListener("DOMContentLoaded", (event) => {

var radios = document.querySelectorAll('input[name=profileRadio]');
Expand Down Expand Up @@ -812,6 +883,24 @@ document.addEventListener("DOMContentLoaded", (event) => {
}
});

ge("radioType").addEventListener("change", function () {
if (ge("radioType").value == 0) {
hide("radioDetails");
}
else if (ge("radioType").value == 1){
show("radioDetails");
}
});

ge("enableForgetRadios").addEventListener("change", function () {
if (ge("enableForgetRadios").checked) {
ge("btnForgetRadios").disabled = false;
}
else {
ge("btnForgetRadios").disabled = true;
}
});

ge("enableLogging").addEventListener("change", function () {
if (ge("enableLogging").checked) {
show("enableLoggingDetails");
Expand All @@ -820,5 +909,4 @@ document.addEventListener("DOMContentLoaded", (event) => {
hide("enableLoggingDetails");
}
});

})
41 changes: 21 additions & 20 deletions Firmware/RTK_Surveyor/Base.ino
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ bool beginSurveyIn()
return (false);
}

Serial.printf("Survey started. This will run until %d seconds have passed and less than %0.03f meter accuracy is achieved.\n\r",
Serial.printf("Survey started. This will run until %d seconds have passed and less than %0.03f meter accuracy is achieved.\r\n",
settings.observationSeconds,
settings.observationPositionAccuracy
);
Expand Down Expand Up @@ -173,9 +173,9 @@ bool startFixedBase()
long majorEcefZ = floor((settings.fixedEcefZ * 100) + 0.5);
long minorEcefZ = floor((((settings.fixedEcefZ * 100.0) - majorEcefZ) * 100.0) + 0.5);

// Serial.printf("fixedEcefY (should be -4716808.5807): %0.04f\n\r", settings.fixedEcefY);
// Serial.printf("major (should be -471680858): %ld\n\r", majorEcefY);
// Serial.printf("minor (should be -7): %ld\n\r", minorEcefY);
// Serial.printf("fixedEcefY (should be -4716808.5807): %0.04f\r\n", settings.fixedEcefY);
// Serial.printf("major (should be -471680858): %ld\r\n", majorEcefY);
// Serial.printf("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...
Expand All @@ -188,26 +188,31 @@ bool startFixedBase()
}
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 = settings.fixedAltitude * 100;
int32_t minorAlt = ((settings.fixedAltitude * 100) - majorAlt) * 100;
int32_t majorAlt = totalFixedAltitude * 100;
int32_t minorAlt = ((totalFixedAltitude * 100) - majorAlt) * 100;

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

response = i2cGNSS.setStaticPosition(
majorLat, minorLat,
Expand All @@ -230,13 +235,9 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming)
{
if (rtcmPacketsSent > 99) rtcmPacketsSent = 1; //Trim to two digits to avoid overlap
}
else if (logIncreasing == true)
{
if (rtcmPacketsSent > 999) rtcmPacketsSent = 1; //Trim to three digits to avoid log icon
}
else
{
if (rtcmPacketsSent > 9999) rtcmPacketsSent = 1;
if (rtcmPacketsSent > 999) rtcmPacketsSent = 1; //Trim to three digits to avoid log icon and increasing bar
}

//Determine if we should check this byte with the RTCM checker or simply pass it along
Expand Down
22 changes: 16 additions & 6 deletions Firmware/RTK_Surveyor/Begin.ino
Original file line number Diff line number Diff line change
Expand Up @@ -148,17 +148,29 @@ void beginBoard()
btMACAddress[5] += 2; //Convert MAC address to Bluetooth MAC (add 2): https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/system/system.html#mac-address

//For all boards, check reset reason. If reset was due to wdt or panic, append last log
loadSettingsPartial(); //Get resetCount
loadSettingsPartial(); //Loads settings from LFS
if (esp_reset_reason() == ESP_RST_POWERON)
{
reuseLastLog = false; //Start new log

if (settings.enableResetDisplay == true)
{
settings.resetCount = 0;
recordSystemSettingsToFileLFS(settingsFileName); //Avoid overwriting LittleFS settings onto SD
}
settings.resetCount = 0;
}
else
{
reuseLastLog = true; //Attempt to reuse previous log
settings.resetCount++;

if (settings.enableResetDisplay == true)
{
settings.resetCount++;
Serial.printf("resetCount: %d\r\n", settings.resetCount);
recordSystemSettingsToFileLFS(settingsFileName); //Avoid overwriting LittleFS settings onto SD
}

Serial.print("Reset reason: ");
switch (esp_reset_reason())
{
Expand All @@ -175,8 +187,6 @@ void beginBoard()
default : Serial.println("Unknown");
}
}

recordSystemSettings(); //Record resetCount to NVM
}

void beginSD()
Expand Down Expand Up @@ -445,7 +455,7 @@ void beginGNSS()
zedFirmwareVersionInt = 132;
else
{
Serial.printf("Unknown firmware version: %s\n\r", zedFirmwareVersion);
Serial.printf("Unknown firmware version: %s\r\n", zedFirmwareVersion);
zedFirmwareVersionInt = 99; //0.99 invalid firmware version
}

Expand All @@ -456,7 +466,7 @@ void beginGNSS()
zedModuleType = PLATFORM_F9R;
else
{
Serial.printf("Unknown ZED module: %s\n\r", i2cGNSS.minfo.extension[3]);
Serial.printf("Unknown ZED module: %s\r\n", i2cGNSS.minfo.extension[3]);
zedModuleType = PLATFORM_F9P;
}

Expand Down
2 changes: 1 addition & 1 deletion Firmware/RTK_Surveyor/Bluetooth.ino
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ Bluetooth States:
// Locals - compiled out
//----------------------------------------

#ifdef COMPILE_BT
#ifdef COMPILE_BT
BTSerialInterface *bluetoothSerial;
static volatile byte bluetoothState = BT_OFF;

Expand Down
Loading