Skip to content

Commit

Permalink
Merge pull request sparkfun#333 from sparkfun/release_candidate
Browse files Browse the repository at this point in the history
Release v2.5 - Add TCP and extend AP config
  • Loading branch information
nseidle authored Sep 21, 2022
2 parents db59b33 + 7f1f97a commit cc4b12c
Show file tree
Hide file tree
Showing 30 changed files with 2,410 additions and 1,010 deletions.
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

0 comments on commit cc4b12c

Please sign in to comment.