Skip to content

Commit c2e64ed

Browse files
committed
Merge branch 'release_candidate' into Fix_#363
2 parents fa5688e + 7590ed0 commit c2e64ed

File tree

11 files changed

+2808
-2772
lines changed

11 files changed

+2808
-2772
lines changed

Firmware/RTK_Everywhere/AP-Config/index.html

Lines changed: 818 additions & 843 deletions
Large diffs are not rendered by default.

Firmware/RTK_Everywhere/AP-Config/src/main.js

Lines changed: 17 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -138,10 +138,10 @@ function parseIncoming(msg) {
138138
hide("ethernetConfig");
139139
hide("ntpConfig");
140140
show("portsConfig");
141-
141+
142142
hide("externalPortOptions");
143143
show("noExternalPortOptions");
144-
144+
145145
hide("logToSDCard");
146146

147147
hide("constellationSbas"); //Not supported on UM980
@@ -378,6 +378,11 @@ function parseIncoming(msg) {
378378
}
379379
}
380380

381+
//Convert incoming mm to local meters
382+
else if (id.includes("antennaHeight_mm")) {
383+
ge("antennaHeight_m").value = val / 1000.0;
384+
}
385+
381386
//Check boxes / radio buttons
382387
else if (val == "true") {
383388
try {
@@ -641,8 +646,6 @@ function validateFields() {
641646
clearElement("fixedLatText", 40.09029479);
642647
clearElement("fixedLongText", -105.18505761);
643648
clearElement("fixedAltitude", 1560.089);
644-
clearElement("antennaHeight_mm", 0);
645-
clearElement("antennaPhaseCenter_mm", 0);
646649
}
647650
else {
648651
clearElement("observationSeconds", 60);
@@ -652,8 +655,6 @@ function validateFields() {
652655
clearElement("fixedLatText", 40.09029479);
653656
clearElement("fixedLongText", -105.18505761);
654657
clearElement("fixedAltitude", 1560.089);
655-
clearElement("antennaHeight_mm", 0);
656-
clearElement("antennaPhaseCenter_mm", 0);
657658

658659
checkElementValue("fixedEcefX", -7000000, 7000000, "Must be -7000000 to 7000000", "collapseBaseConfig");
659660
checkElementValue("fixedEcefY", -7000000, 7000000, "Must be -7000000 to 7000000", "collapseBaseConfig");
@@ -667,7 +668,7 @@ function validateFields() {
667668
checkLatLong(); //Verify Lat/Long input type
668669
checkElementValue("fixedAltitude", -11034, 8849, "Must be -11034 to 8849", "collapseBaseConfig");
669670

670-
checkElementValue("antennaHeight_mm", -15000, 15000, "Must be -15000 to 15000", "collapseBaseConfig");
671+
checkElementValue("antennaHeight_m", -15, 15, "Must be -15 to 15", "collapseBaseConfig");
671672
checkElementValue("antennaPhaseCenter_mm", -200.0, 200.0, "Must be -200.0 to 200.0", "collapseBaseConfig");
672673
}
673674
}
@@ -862,6 +863,7 @@ function changeProfile() {
862863
collapseSection("collapseEthernetConfig", "ethernetCaret");
863864
collapseSection("collapseNTPConfig", "ntpCaret");
864865
collapseSection("collapseFileManager", "fileManagerCaret");
866+
collapseSection("collapseInstrumentConfig", "instrumentCaret");
865867
}
866868
}
867869

@@ -1449,7 +1451,7 @@ document.addEventListener("DOMContentLoaded", (event) => {
14491451
adjustHAE();
14501452
});
14511453

1452-
ge("antennaHeight_mm").addEventListener("change", function () {
1454+
ge("antennaHeight_m").addEventListener("change", function () {
14531455
adjustHAE();
14541456
});
14551457

@@ -1620,7 +1622,7 @@ function addGeodetic() {
16201622
checkElementString("nicknameGeodetic", 1, 49, "Must be 1 to 49 characters", "collapseBaseConfig");
16211623
checkLatLong();
16221624
checkElementValue("fixedAltitude", -11034, 8849, "Must be -11034 to 8849", "collapseBaseConfig");
1623-
checkElementValue("antennaHeight_mm", -15000, 15000, "Must be -15000 to 15000", "collapseBaseConfig");
1625+
checkElementValue("antennaHeight_m", -15, 15, "Must be -15 to 15", "collapseBaseConfig");
16241626
checkElementValue("antennaPhaseCenter_mm", -200.0, 200.0, "Must be -200.0 to 200.0", "collapseBaseConfig");
16251627

16261628
if (errorCount == 0) {
@@ -1629,12 +1631,12 @@ function addGeodetic() {
16291631
for (; index < recordsGeodetic.length; ++index) {
16301632
var parts = recordsGeodetic[index].split(' ');
16311633
if (ge("nicknameGeodetic").value == parts[0]) {
1632-
recordsGeodetic[index] = nicknameGeodetic.value + ' ' + fixedLatText.value + ' ' + fixedLongText.value + ' ' + fixedAltitude.value + ' ' + antennaHeight_mm.value + ' ' + antennaPhaseCenter_mm.value;
1634+
recordsGeodetic[index] = nicknameGeodetic.value + ' ' + fixedLatText.value + ' ' + fixedLongText.value + ' ' + fixedAltitude.value + ' ' + antennaHeight_m.value + ' ' + antennaPhaseCenter_mm.value;
16331635
break;
16341636
}
16351637
}
16361638
if (index == recordsGeodetic.length)
1637-
recordsGeodetic.push(nicknameGeodetic.value + ' ' + fixedLatText.value + ' ' + fixedLongText.value + ' ' + fixedAltitude.value + ' ' + antennaHeight_mm.value + ' ' + antennaPhaseCenter_mm.value);
1639+
recordsGeodetic.push(nicknameGeodetic.value + ' ' + fixedLatText.value + ' ' + fixedLongText.value + ' ' + fixedAltitude.value + ' ' + antennaHeight_m.value + ' ' + antennaPhaseCenter_mm.value);
16381640
}
16391641

16401642
updateGeodeticList();
@@ -1660,13 +1662,13 @@ function adjustHAE() {
16601662
if (haeMethod == 1) {
16611663
ge("fixedHAEAPC").disabled = false;
16621664
ge("fixedAltitude").disabled = true;
1663-
hae = Number(ge("fixedHAEAPC").value) - (Number(ge("antennaHeight_mm").value) / 1000 + Number(ge("antennaPhaseCenter_mm").value) / 1000);
1665+
hae = Number(ge("fixedHAEAPC").value) - (Number(ge("antennaHeight_m").value) + Number(ge("antennaPhaseCenter_mm").value) / 1000);
16641666
ge("fixedAltitude").value = hae.toFixed(3);
16651667
}
16661668
else {
16671669
ge("fixedHAEAPC").disabled = true;
16681670
ge("fixedAltitude").disabled = false;
1669-
hae = Number(ge("fixedAltitude").value) + (Number(ge("antennaHeight_mm").value) / 1000 + Number(ge("antennaPhaseCenter_mm").value) / 1000);
1671+
hae = Number(ge("fixedAltitude").value) + (Number(ge("antennaHeight_m").value) + Number(ge("antennaPhaseCenter_mm").value) / 1000);
16701672
ge("fixedHAEAPC").value = hae.toFixed(3);
16711673
}
16721674
}
@@ -1692,7 +1694,7 @@ function loadGeodetic() {
16921694
}
16931695
}
16941696
ge("fixedAltitude").value = parts[numParts - 3];
1695-
ge("antennaHeight_mm").value = parts[numParts - 2];
1697+
ge("antennaHeight_m").value = parts[numParts - 2];
16961698
ge("antennaPhaseCenter_mm").value = parts[numParts - 1];
16971699

16981700
$("input[name=markRadio][value=1]").prop('checked', false);
@@ -1704,7 +1706,7 @@ function loadGeodetic() {
17041706
clearError("fixedLatText");
17051707
clearError("fixedLongText");
17061708
clearError("fixedAltitude");
1707-
clearError("antennaHeight_mm");
1709+
clearError("antennaHeight_m");
17081710
clearError("antennaPhaseCenter_mm");
17091711
}
17101712
else {

Firmware/RTK_Everywhere/MQTT_Client.ino

Lines changed: 12 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,6 @@ enum MQTTClientState
9292
{
9393
MQTT_CLIENT_OFF = 0, // Using Bluetooth or NTRIP server
9494
MQTT_CLIENT_ON, // WIFI_STATE_START state
95-
MQTT_CLIENT_CHECK_CERTS, // Check certs are available - with timeout
9695
MQTT_CLIENT_NETWORK_STARTED, // Connecting to WiFi access point or Ethernet
9796
MQTT_CLIENT_CONNECTING_2_SERVER, // Connecting to the MQTT server
9897
MQTT_CLIENT_SUBSCRIBE_KEY, // Subscribe to the MQTT_TOPIC_KEY
@@ -106,7 +105,6 @@ enum MQTTClientState
106105
const char *const mqttClientStateName[] = {
107106
"MQTT_CLIENT_OFF",
108107
"MQTT_CLIENT_ON",
109-
"MQTT_CLIENT_CHECK_CERTS",
110108
"MQTT_CLIENT_NETWORK_STARTED",
111109
"MQTT_CLIENT_CONNECTING_2_SERVER",
112110
"MQTT_CLIENT_SUBSCRIBE_KEY",
@@ -222,7 +220,6 @@ void mqttClientPrintStateSummary()
222220
break;
223221

224222
case MQTT_CLIENT_ON:
225-
case MQTT_CLIENT_CHECK_CERTS:
226223
case MQTT_CLIENT_NETWORK_STARTED:
227224
systemPrint("Disconnected");
228225
break;
@@ -484,11 +481,14 @@ void mqttClientShutdown()
484481
// Start the MQTT client
485482
void mqttClientStart()
486483
{
487-
// Display the heap state
488-
reportHeapNow(settings.debugMqttClientState);
484+
if (settings.debugMqttClientState)
485+
{
486+
// Display the heap state
487+
reportHeapNow(settings.debugMqttClientState);
489488

490-
// Start the MQTT client
491-
systemPrintln("MQTT Client start");
489+
// Start the MQTT client
490+
systemPrintln("MQTT Client start");
491+
}
492492
mqttClientStop(false);
493493
}
494494

@@ -601,22 +601,11 @@ void mqttClientUpdate()
601601

602602
// Start the network
603603
case MQTT_CLIENT_ON: {
604-
if (networkUserOpen(NETWORK_USER_MQTT_CLIENT, NETWORK_TYPE_ACTIVE))
605-
mqttClientSetState(MQTT_CLIENT_CHECK_CERTS);
606-
break;
607-
}
608-
609-
// Check for certs, wait for them to be available
610-
case MQTT_CLIENT_CHECK_CERTS: {
611-
// Determine if the network has failed
612-
if (networkIsShuttingDown(NETWORK_USER_MQTT_CLIENT))
613-
// Failed to connect to the network, attempt to restart the network
614-
mqttClientStop(true); // Was mqttClientRestart(); - #StopVsRestart
615-
616-
// Determine if certs are available
617-
else if (checkCertificates())
618-
// The network is available for the MQTT client
619-
mqttClientSetState(MQTT_CLIENT_NETWORK_STARTED);
604+
if ((millis() - mqttClientTimer) > mqttClientConnectionAttemptTimeout)
605+
{
606+
if (networkUserOpen(NETWORK_USER_MQTT_CLIENT, NETWORK_TYPE_ACTIVE))
607+
mqttClientSetState(MQTT_CLIENT_NETWORK_STARTED);
608+
}
620609
break;
621610
}
622611

Firmware/RTK_Everywhere/Network.ino

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -494,6 +494,31 @@ uint8_t networkGetActiveType()
494494
//----------------------------------------
495495
// Get the network type
496496
//----------------------------------------
497+
uint8_t networkGetType()
498+
{
499+
NETWORK_DATA *network;
500+
501+
// Return the current type if known
502+
network = networkGet(NETWORK_TYPE_ACTIVE, false);
503+
if (network && (network->type < NETWORK_TYPE_MAX))
504+
return network->type;
505+
506+
// Network type not determined yet
507+
// Determine if this type will be Ethernet
508+
if (present.ethernet_ws5500)
509+
{
510+
if ((settings.defaultNetworkType == NETWORK_TYPE_USE_DEFAULT)
511+
|| (settings.defaultNetworkType == NETWORK_TYPE_ETHERNET))
512+
return NETWORK_TYPE_ETHERNET;
513+
}
514+
515+
// Type will be WiFi
516+
return NETWORK_TYPE_WIFI;
517+
}
518+
519+
//----------------------------------------
520+
// Get the network type for a network user
521+
//----------------------------------------
497522
uint8_t networkGetType(uint8_t user)
498523
{
499524
NETWORK_DATA *network;

Firmware/RTK_Everywhere/System.ino

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -606,13 +606,13 @@ void coordinateConvertInput(double coordinate, CoordinateInputType coordinateInp
606606
coordinate *= -1;
607607

608608
if (coordinateInputType == COORDINATE_INPUT_TYPE_DDMM)
609-
snprintf(coordinateString, sizeOfCoordinateString, "%02d%010.7f", longitudeDegrees, coordinate);
609+
snprintf(coordinateString, sizeOfCoordinateString, "%02d%011.8f", longitudeDegrees, coordinate);
610610
else if (coordinateInputType == COORDINATE_INPUT_TYPE_DD_MM_DASH)
611-
snprintf(coordinateString, sizeOfCoordinateString, "%02d-%010.7f", longitudeDegrees, coordinate);
611+
snprintf(coordinateString, sizeOfCoordinateString, "%02d-%011.8f", longitudeDegrees, coordinate);
612612
else if (coordinateInputType == COORDINATE_INPUT_TYPE_DD_MM_SYMBOL)
613-
snprintf(coordinateString, sizeOfCoordinateString, "%02d°%010.7f'", longitudeDegrees, coordinate);
613+
snprintf(coordinateString, sizeOfCoordinateString, "%02d°%011.8f'", longitudeDegrees, coordinate);
614614
else if (coordinateInputType == COORDINATE_INPUT_TYPE_DD_MM)
615-
snprintf(coordinateString, sizeOfCoordinateString, "%02d %010.7f", longitudeDegrees, coordinate);
615+
snprintf(coordinateString, sizeOfCoordinateString, "%02d %011.8f", longitudeDegrees, coordinate);
616616
}
617617
else if (coordinateInputType == COORDINATE_INPUT_TYPE_DD_MM_SS ||
618618
coordinateInputType == COORDINATE_INPUT_TYPE_DDMMSS ||

0 commit comments

Comments
 (0)