Skip to content

Commit 92d3f8e

Browse files
authored
Merge pull request #392 from sparkfun/AddTipAltitudeSetting
Add tip altitude setting
2 parents 56c100f + 5fc762c commit 92d3f8e

File tree

11 files changed

+318
-194
lines changed

11 files changed

+318
-194
lines changed

Firmware/RTK_Everywhere/AP-Config/index.html

Lines changed: 29 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -700,7 +700,7 @@
700700

701701

702702
<div class="form-group row">
703-
<label for="antennaHeight" class="box-margin40 col-sm-3 col-5 col-form-label">Antenna
703+
<label for="antennaHeight_mm" class="box-margin40 col-sm-3 col-5 col-form-label">Antenna
704704
Height(mm):
705705
<span class="tt" data-bs-placement="right"
706706
title="Distance from the base of the antenna to the mark on the ground. This is usually the total length of the prism pole and any extensions. Amount is added to HAE before starting fixed base.">
@@ -709,22 +709,22 @@
709709
</label>
710710

711711
<div class="col-sm-4 col-5">
712-
<input type="number" class="form-control" id="antennaHeight">
713-
<p id="antennaHeightError" class="inlineError"></p>
712+
<input type="number" class="form-control" id="antennaHeight_mm">
713+
<p id="antennaHeight_mmError" class="inlineError"></p>
714714
</div>
715715
</div>
716716

717717
<div class="form-group row">
718-
<label for="antennaReferencePoint" class="box-margin40 col-5 col-form-label">Antenna
719-
Reference Point(mm):
718+
<label for="antennaPhaseCenter_mm" class="box-margin40 col-5 col-form-label">Antenna
719+
Phase Center(mm):
720720
<span class="tt" data-bs-placement="right"
721-
title="ARP is the distance from the base of the antenna to the antenna phase center. This is usually printed on the side of the antenna and is calculated during antenna calibration. Amount is added to HAE before starting fixed base. Common ARPs: Facet L-Band (69mm) Torch(117mm)">
721+
title="APC is the distance from the base of the antenna to the antenna phase center. This is usually printed on the side of the antenna and is calculated during antenna calibration. Amount is added to HAE before starting fixed base. Common APCs: Torch(117mm)">
722722
<span class="icon-info-circle text-primary ms-2"></span>
723723
</span>
724724
</label>
725725
<div class="col-sm-4 col-5">
726-
<input type="number" class="form-control" id="antennaReferencePoint">
727-
<p id="antennaReferencePointError" class="inlineError"></p>
726+
<input type="number" class="form-control" id="antennaPhaseCenter_mm">
727+
<p id="antennaPhaseCenter_mm" class="inlineError"></p>
728728
</div>
729729
</div>
730730

@@ -1687,11 +1687,11 @@
16871687
</div>
16881688
</div>
16891689

1690-
<!-- --------- Tilt Config --------- -->
1690+
<!-- --------- Instrument Config --------- -->
16911691
<div class="d-grid gap-2">
16921692
<button class="btn btn-primary mt-3 toggle-btn" id="tiltConfig" type="button" data-toggle="collapse"
16931693
data-target="#collapseTiltConfig" aria-expanded="false" aria-controls="collapseTiltConfig">
1694-
Tilt Configuration <i id="tiltCaret" class="caret-icon bi icon-caret-down"></i>
1694+
Instrument Configuration <i id="tiltCaret" class="caret-icon bi icon-caret-down"></i>
16951695
</button>
16961696
</div>
16971697
<div class="collapse" id="collapseTiltConfig">
@@ -1708,17 +1708,32 @@
17081708
</span>
17091709
</div>
17101710

1711-
<div id="poleLengthConfig">
1711+
<div id="antennaHeight_mConfig">
17121712
<div class="form-group row">
1713-
<label for="tiltPoleLength" class="col-sm-4 col-6 col-form-label">Pole Length (m):
1713+
<label for="antennaHeight_m" class="col-sm-4 col-6 col-form-label">Antenna Height (a.k.a. Pole Length) (m):
17141714
<span class="tt" data-bs-placement="right"
17151715
title="This is the length of the pole only, no additional ARP should be included. Default: 1.8m">
17161716
<span class="icon-info-circle text-primary ms-2"></span>
17171717
</span>
17181718
</label>
17191719
<div class="col-sm-4 col-6">
1720-
<input type="number" class="form-control" id="tiltPoleLength">
1721-
<p id="tiltPoleLengthError" class="inlineError"></p>
1720+
<input type="number" class="form-control" id="antennaHeight_m">
1721+
<p id="antennaHeight_mError" class="inlineError"></p>
1722+
</div>
1723+
</div>
1724+
</div>
1725+
1726+
<div id="antennaPhaseCenter_mmConfig">
1727+
<div class="form-group row">
1728+
<label for="antennaPhaseCenter_mm" class="col-sm-4 col-6 col-form-label">Antenna Phase Center (mm):
1729+
<span class="tt" data-bs-placement="right"
1730+
title="This is the distance between the ARP and the antenna phase center. Default: 116mm">
1731+
<span class="icon-info-circle text-primary ms-2"></span>
1732+
</span>
1733+
</label>
1734+
<div class="col-sm-4 col-6">
1735+
<input type="number" class="form-control" id="antennaPhaseCenter_mm">
1736+
<p id="antennaPhaseCenter_mmError" class="inlineError"></p>
17221737
</div>
17231738
</div>
17241739
</div>

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

Lines changed: 22 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -425,7 +425,7 @@ function parseIncoming(msg) {
425425
ge("enablePointPerfectCorrections").dispatchEvent(new CustomEvent('change'));
426426
ge("enableExternalPulse").dispatchEvent(new CustomEvent('change'));
427427
ge("enableEspNow").dispatchEvent(new CustomEvent('change'));
428-
ge("antennaReferencePoint").dispatchEvent(new CustomEvent('change'));
428+
ge("antennaPhaseCenter_mm").dispatchEvent(new CustomEvent('change'));
429429
ge("enableLogging").dispatchEvent(new CustomEvent('change'));
430430
ge("enableARPLogging").dispatchEvent(new CustomEvent('change'));
431431
ge("enableAutoFirmwareUpdate").dispatchEvent(new CustomEvent('change'));
@@ -439,7 +439,6 @@ function parseIncoming(msg) {
439439
dhcpEthernet();
440440
updateLatLong();
441441
updateCorrectionsPriorities();
442-
tiltCompensationBoxes();
443442
}
444443
}
445444

@@ -642,8 +641,8 @@ function validateFields() {
642641
clearElement("fixedLatText", 40.09029479);
643642
clearElement("fixedLongText", -105.18505761);
644643
clearElement("fixedAltitude", 1560.089);
645-
clearElement("antennaHeight", 0);
646-
clearElement("antennaReferencePoint", 0);
644+
clearElement("antennaHeight_mm", 0);
645+
clearElement("antennaPhaseCenter_mm", 0);
647646
}
648647
else {
649648
clearElement("observationSeconds", 60);
@@ -653,8 +652,8 @@ function validateFields() {
653652
clearElement("fixedLatText", 40.09029479);
654653
clearElement("fixedLongText", -105.18505761);
655654
clearElement("fixedAltitude", 1560.089);
656-
clearElement("antennaHeight", 0);
657-
clearElement("antennaReferencePoint", 0);
655+
clearElement("antennaHeight_mm", 0);
656+
clearElement("antennaPhaseCenter_mm", 0);
658657

659658
checkElementValue("fixedEcefX", -7000000, 7000000, "Must be -7000000 to 7000000", "collapseBaseConfig");
660659
checkElementValue("fixedEcefY", -7000000, 7000000, "Must be -7000000 to 7000000", "collapseBaseConfig");
@@ -668,8 +667,8 @@ function validateFields() {
668667
checkLatLong(); //Verify Lat/Long input type
669668
checkElementValue("fixedAltitude", -11034, 8849, "Must be -11034 to 8849", "collapseBaseConfig");
670669

671-
checkElementValue("antennaHeight", -15000, 15000, "Must be -15000 to 15000", "collapseBaseConfig");
672-
checkElementValue("antennaReferencePoint", -200.0, 200.0, "Must be -200.0 to 200.0", "collapseBaseConfig");
670+
checkElementValue("antennaHeight_mm", -15000, 15000, "Must be -15000 to 15000", "collapseBaseConfig");
671+
checkElementValue("antennaPhaseCenter_mm", -200.0, 200.0, "Must be -200.0 to 200.0", "collapseBaseConfig");
673672
}
674673
}
675674

@@ -1321,13 +1320,13 @@ document.addEventListener("DOMContentLoaded", (event) => {
13211320
show("geodeticConfig");
13221321

13231322
if ((platformPrefix == "Facet mosaic") || (platformPrefix == "Facet v2")) {
1324-
ge("antennaReferencePoint").value = 61.4;
1323+
ge("antennaPhaseCenter_mm").value = 61.4;
13251324
}
13261325
else if (platformPrefix == "Torch") {
1327-
ge("antennaReferencePoint").value = 116.2;
1326+
ge("antennaPhaseCenter_mm").value = 116.2;
13281327
}
13291328
else {
1330-
ge("antennaReferencePoint").value = 0.0;
1329+
ge("antennaPhaseCenter_mm").value = 0.0;
13311330
}
13321331
}
13331332
});
@@ -1450,11 +1449,11 @@ document.addEventListener("DOMContentLoaded", (event) => {
14501449
adjustHAE();
14511450
});
14521451

1453-
ge("antennaHeight").addEventListener("change", function () {
1452+
ge("antennaHeight_mm").addEventListener("change", function () {
14541453
adjustHAE();
14551454
});
14561455

1457-
ge("antennaReferencePoint").addEventListener("change", function () {
1456+
ge("antennaPhaseCenter_mm").addEventListener("change", function () {
14581457
adjustHAE();
14591458
});
14601459

@@ -1621,21 +1620,21 @@ function addGeodetic() {
16211620
checkElementString("nicknameGeodetic", 1, 49, "Must be 1 to 49 characters", "collapseBaseConfig");
16221621
checkLatLong();
16231622
checkElementValue("fixedAltitude", -11034, 8849, "Must be -11034 to 8849", "collapseBaseConfig");
1624-
checkElementValue("antennaHeight", -15000, 15000, "Must be -15000 to 15000", "collapseBaseConfig");
1625-
checkElementValue("antennaReferencePoint", -200.0, 200.0, "Must be -200.0 to 200.0", "collapseBaseConfig");
1623+
checkElementValue("antennaHeight_mm", -15000, 15000, "Must be -15000 to 15000", "collapseBaseConfig");
1624+
checkElementValue("antennaPhaseCenter_mm", -200.0, 200.0, "Must be -200.0 to 200.0", "collapseBaseConfig");
16261625

16271626
if (errorCount == 0) {
16281627
//Check name against the list
16291628
var index = 0;
16301629
for (; index < recordsGeodetic.length; ++index) {
16311630
var parts = recordsGeodetic[index].split(' ');
16321631
if (ge("nicknameGeodetic").value == parts[0]) {
1633-
recordsGeodetic[index] = nicknameGeodetic.value + ' ' + fixedLatText.value + ' ' + fixedLongText.value + ' ' + fixedAltitude.value + ' ' + antennaHeight.value + ' ' + antennaReferencePoint.value;
1632+
recordsGeodetic[index] = nicknameGeodetic.value + ' ' + fixedLatText.value + ' ' + fixedLongText.value + ' ' + fixedAltitude.value + ' ' + antennaHeight_mm.value + ' ' + antennaPhaseCenter_mm.value;
16341633
break;
16351634
}
16361635
}
16371636
if (index == recordsGeodetic.length)
1638-
recordsGeodetic.push(nicknameGeodetic.value + ' ' + fixedLatText.value + ' ' + fixedLongText.value + ' ' + fixedAltitude.value + ' ' + antennaHeight.value + ' ' + antennaReferencePoint.value);
1637+
recordsGeodetic.push(nicknameGeodetic.value + ' ' + fixedLatText.value + ' ' + fixedLongText.value + ' ' + fixedAltitude.value + ' ' + antennaHeight_mm.value + ' ' + antennaPhaseCenter_mm.value);
16391638
}
16401639

16411640
updateGeodeticList();
@@ -1661,13 +1660,13 @@ function adjustHAE() {
16611660
if (haeMethod == 1) {
16621661
ge("fixedHAEAPC").disabled = false;
16631662
ge("fixedAltitude").disabled = true;
1664-
hae = Number(ge("fixedHAEAPC").value) - (Number(ge("antennaHeight").value) / 1000 + Number(ge("antennaReferencePoint").value) / 1000);
1663+
hae = Number(ge("fixedHAEAPC").value) - (Number(ge("antennaHeight_mm").value) / 1000 + Number(ge("antennaPhaseCenter_mm").value) / 1000);
16651664
ge("fixedAltitude").value = hae.toFixed(3);
16661665
}
16671666
else {
16681667
ge("fixedHAEAPC").disabled = true;
16691668
ge("fixedAltitude").disabled = false;
1670-
hae = Number(ge("fixedAltitude").value) + (Number(ge("antennaHeight").value) / 1000 + Number(ge("antennaReferencePoint").value) / 1000);
1669+
hae = Number(ge("fixedAltitude").value) + (Number(ge("antennaHeight_mm").value) / 1000 + Number(ge("antennaPhaseCenter_mm").value) / 1000);
16711670
ge("fixedHAEAPC").value = hae.toFixed(3);
16721671
}
16731672
}
@@ -1693,8 +1692,8 @@ function loadGeodetic() {
16931692
}
16941693
}
16951694
ge("fixedAltitude").value = parts[numParts - 3];
1696-
ge("antennaHeight").value = parts[numParts - 2];
1697-
ge("antennaReferencePoint").value = parts[numParts - 1];
1695+
ge("antennaHeight_mm").value = parts[numParts - 2];
1696+
ge("antennaPhaseCenter_mm").value = parts[numParts - 1];
16981697

16991698
$("input[name=markRadio][value=1]").prop('checked', false);
17001699
$("input[name=markRadio][value=2]").prop('checked', true);
@@ -1705,8 +1704,8 @@ function loadGeodetic() {
17051704
clearError("fixedLatText");
17061705
clearError("fixedLongText");
17071706
clearError("fixedAltitude");
1708-
clearError("antennaHeight");
1709-
clearError("antennaReferencePoint");
1707+
clearError("antennaHeight_mm");
1708+
clearError("antennaPhaseCenter_mm");
17101709
}
17111710
else {
17121711
console.log("stationGeodetic split error");
@@ -1924,15 +1923,6 @@ function udpBoxes() {
19241923
}
19251924
}
19261925

1927-
function tiltCompensationBoxes() {
1928-
if (ge("enableTiltCompensation").checked == true) {
1929-
show("poleLengthConfig");
1930-
}
1931-
else {
1932-
hide("poleLengthConfig");
1933-
}
1934-
}
1935-
19361926
function dhcpEthernet() {
19371927
if (ge("ethernetDHCP").checked == true) {
19381928
hide("fixedIPSettingsConfigEthernet");

Firmware/RTK_Everywhere/Begin.ino

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@ Begin.ino
55
radio, etc.
66
------------------------------------------------------------------------------*/
77

8-
#include <esp_mac.h> // required - exposes esp_mac_type_t values
8+
#include <esp_mac.h> // required - exposes esp_mac_type_t values
99

1010
//----------------------------------------
1111
// Constants
@@ -141,7 +141,7 @@ void beginBoard()
141141
present.button_powerHigh = true; // Button is pressed when high
142142
present.beeper = true;
143143
present.gnss_to_uart = true;
144-
present.antennaReferencePoint_mm = 115.7;
144+
present.antennaPhaseCenter_mm = 115.7;
145145
present.needsExternalPpl = true; // Uses the PointPerfect Library
146146
present.galileoHasCapable = true;
147147

@@ -835,9 +835,9 @@ void beginInterrupts()
835835
if (present.ethernet_ws5500 == true)
836836
{
837837
DMW_if systemPrintf("pin_Ethernet_Interrupt: %d\r\n", pin_Ethernet_Interrupt);
838-
pinMode(pin_Ethernet_Interrupt, INPUT); // Prepare the interrupt pin
838+
pinMode(pin_Ethernet_Interrupt, INPUT); // Prepare the interrupt pin
839839
// TODO: figure out how to handle NTP mode and timestamp the arrival of UDP NTP requests
840-
//attachInterrupt(pin_Ethernet_Interrupt, ethernetISR, FALLING); // Attach the interrupt
840+
// attachInterrupt(pin_Ethernet_Interrupt, ethernetISR, FALLING); // Attach the interrupt
841841
}
842842
#endif // COMPILE_ETHERNET
843843
}
@@ -848,22 +848,22 @@ void tickerBegin()
848848
if (pin_bluetoothStatusLED != PIN_UNDEFINED)
849849
{
850850
ledcAttach(pin_bluetoothStatusLED, pwmFreq, pwmResolution);
851-
ledcWrite(pin_bluetoothStatusLED, 255); // Turn on BT LED at startup
852-
//Attach happens in bluetoothStart()
851+
ledcWrite(pin_bluetoothStatusLED, 255); // Turn on BT LED at startup
852+
// Attach happens in bluetoothStart()
853853
}
854854

855855
if (pin_gnssStatusLED != PIN_UNDEFINED)
856856
{
857857
ledcAttach(pin_gnssStatusLED, pwmFreq, pwmResolution);
858-
ledcWrite(pin_gnssStatusLED, 0); // Turn off GNSS LED at startup
858+
ledcWrite(pin_gnssStatusLED, 0); // Turn off GNSS LED at startup
859859
gnssLedTask.detach(); // Turn off any previous task
860860
gnssLedTask.attach(1.0 / gnssTaskUpdatesHz, tickerGnssLedUpdate); // Rate in seconds, callback
861861
}
862862

863863
if (pin_batteryStatusLED != PIN_UNDEFINED)
864864
{
865865
ledcAttach(pin_batteryStatusLED, pwmFreq, pwmResolution);
866-
ledcWrite(pin_batteryStatusLED, 0); // Turn off battery LED at startup
866+
ledcWrite(pin_batteryStatusLED, 0); // Turn off battery LED at startup
867867
batteryLedTask.detach(); // Turn off any previous task
868868
batteryLedTask.attach(1.0 / batteryTaskUpdatesHz, tickerBatteryLedUpdate); // Rate in seconds, callback
869869
}
@@ -1114,6 +1114,10 @@ void beginSystemState()
11141114

11151115
if (settings.enablePointPerfectCorrections)
11161116
systemState = STATE_KEYS_STARTED; // Begin process for getting new keys
1117+
1118+
//If the setting is not set, override with default
1119+
if (settings.antennaPhaseCenter_mm == 0.0)
1120+
settings.antennaPhaseCenter_mm = present.antennaPhaseCenter_mm;
11171121
}
11181122
else
11191123
{

Firmware/RTK_Everywhere/Tasks.ino

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -477,13 +477,11 @@ void processUart1Message(SEMP_PARSE_STATE *parse, uint16_t type)
477477
}
478478
}
479479

480-
if (tiltIsCorrecting() == true)
480+
// Handle LLA compensation due to tilt or outputTipAltitude setting
481+
if (type == RTK_NMEA_PARSER_INDEX)
481482
{
482-
if (type == RTK_NMEA_PARSER_INDEX)
483-
{
484-
parse->buffer[parse->length++] = '\0'; // Null terminate string
485-
tiltApplyCompensation((char *)parse->buffer, parse->length);
486-
}
483+
parse->buffer[parse->length++] = '\0'; // Null terminate string
484+
nmeaApplyCompensation((char *)parse->buffer, parse->length);
487485
}
488486

489487
// Determine where to send RTCM data

0 commit comments

Comments
 (0)