Skip to content

Commit 4130719

Browse files
committed
Merge branch 'release_candidate' into pr/277
2 parents c6bb559 + 05db063 commit 4130719

File tree

11 files changed

+156
-78
lines changed

11 files changed

+156
-78
lines changed

.github/workflows/compile-rtk-everywhere.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,7 @@ jobs:
8888
"ArduinoMqttClient"@0.1.8
8989
"SparkFun u-blox PointPerfect Library"@1.11.4
9090
"SparkFun IM19 IMU Arduino Library"@1.0.1
91-
"SparkFun UM980 Triband RTK GNSS Arduino Library"@1.0.3
91+
"SparkFun UM980 Triband RTK GNSS Arduino Library"@1.0.4
9292

9393
- name: Enable external libs
9494
run: arduino-cli config set library.enable_unsafe_install true

Firmware/RTK_Everywhere/Begin.ino

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -139,8 +139,9 @@ void beginBoard()
139139
present.button_powerHigh = true; // Button is pressed when high
140140
present.beeper = true;
141141
present.gnss_to_uart = true;
142-
present.antennaReferencePoint_mm = 102.0;
142+
present.antennaReferencePoint_mm = 115.7;
143143
present.needsExternalPpl = true; // Uses the PointPerfect Library
144+
present.galileoHasCapable = true;
144145

145146
#ifdef COMPILE_IM19_IMU
146147
present.imu_im19 = true; // Allow tiltUpdate() to run
@@ -159,6 +160,7 @@ void beginBoard()
159160

160161
pin_GNSS_TimePulse = 39; // PPS on UM980
161162

163+
pin_muxA = 18; //Controls U12 switch between ESP UART1 to UM980 or LoRa
162164
pin_usbSelect = 21;
163165
pin_powerAdapterDetect = 36; // Goes low when USB cable is plugged in
164166

@@ -208,6 +210,9 @@ void beginBoard()
208210
pinMode(pin_usbSelect, OUTPUT);
209211
digitalWrite(pin_usbSelect, HIGH); // Keep CH340 connected to USB bus
210212

213+
pinMode(pin_muxA, OUTPUT);
214+
digitalWrite(pin_muxA, LOW); // Keep ESP UART1 connected to UM980
215+
211216
settings.dataPortBaud = 115200; // Override settings. Use UM980 at 115200bps.
212217

213218
pinMode(pin_loraRadio_power, OUTPUT);
@@ -783,7 +788,7 @@ void pinGnssUartTask(void *pvParameters)
783788
serialGNSS = new HardwareSerial(2); // Use UART2 on the ESP32 for communication with the GNSS module
784789

785790
serialGNSS->setRxBufferSize(
786-
settings.uartReceiveBufferSize); // TODO: work out if we can reduce or skip this when using SPI GNSS
791+
settings.uartReceiveBufferSize);
787792
serialGNSS->setTimeout(settings.serialTimeoutGNSS); // Requires serial traffic on the UART pins for detection
788793

789794
if (pin_GnssUart_RX == -1 || pin_GnssUart_TX == -1)

Firmware/RTK_Everywhere/Developer.ino

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,7 @@ void tiltUpdate() {}
177177
void tiltStop() {}
178178
void tiltSensorFactoryReset() {}
179179
bool tiltIsCorrecting() {return(false);}
180+
void tiltRequestStop() {}
180181

181182
#endif // COMPILE_IM19_IMU
182183

Firmware/RTK_Everywhere/Tasks.ino

Lines changed: 1 addition & 50 deletions
Original file line numberDiff line numberDiff line change
@@ -1204,9 +1204,6 @@ void tickerBluetoothLedUpdate()
12041204
void tickerGnssLedUpdate()
12051205
{
12061206
static uint8_t ledCallCounter = 0; // Used to calculate a 50% or 10% on rate for blinking
1207-
// static int gnssFadeLevel = 0; // Used to fade LED when needed
1208-
// static int gnssPwmFadeAmount = 255 / gnssTaskUpdatesHz; // Fade in/out with 20 steps, as limited by the ticker
1209-
// rate of 20Hz
12101207

12111208
ledCallCounter++;
12121209
ledCallCounter %= gnssTaskUpdatesHz; // Wrap to X calls per 1 second
@@ -1224,52 +1221,6 @@ void tickerGnssLedUpdate()
12241221
{
12251222
ledcWrite(ledGnssChannel, 0);
12261223
}
1227-
1228-
// // Solid during tilt corrected RTK fix
1229-
// if (tiltIsCorrecting() == true)
1230-
// {
1231-
// ledcWrite(ledGnssChannel, 255);
1232-
// }
1233-
// else
1234-
// {
1235-
// ledcWrite(ledGnssChannel, 0);
1236-
// }
1237-
1238-
// Fade on/off during RTK Fix
1239-
// else if (gnssIsRTKFix() == true)
1240-
// {
1241-
// // Fade in/out the GNSS LED during RTK Fix
1242-
// gnssFadeLevel += gnssPwmFadeAmount;
1243-
// if (gnssFadeLevel <= 0 || gnssFadeLevel >= 255)
1244-
// gnssPwmFadeAmount *= -1;
1245-
1246-
// if (gnssFadeLevel > 255)
1247-
// gnssFadeLevel = 255;
1248-
// if (gnssFadeLevel < 0)
1249-
// gnssFadeLevel = 0;
1250-
1251-
// ledcWrite(ledGnssChannel, gnssFadeLevel);
1252-
// }
1253-
1254-
// // Blink 2Hz 50% during RTK float
1255-
// else if (gnssIsRTKFloat() == true)
1256-
// {
1257-
// if (ledCallCounter <= (gnssTaskUpdatesHz / 2))
1258-
// ledcWrite(ledGnssChannel, 255);
1259-
// else
1260-
// ledcWrite(ledGnssChannel, 0);
1261-
// }
1262-
1263-
// // Blink a short PPS when GNSS 3D fixed
1264-
// else if (gnssIsFixed() == true)
1265-
// {
1266-
// if (ledCallCounter == (gnssTaskUpdatesHz / 10))
1267-
// {
1268-
// ledcWrite(ledGnssChannel, 255);
1269-
// }
1270-
// else
1271-
// ledcWrite(ledGnssChannel, 0);
1272-
// }
12731224
}
12741225
}
12751226

@@ -1438,7 +1389,7 @@ void buttonCheckTask(void *e)
14381389
// The user button only exits tilt mode
14391390
if ((singleTap || doubleTap) && (tiltIsCorrecting() == true))
14401391
{
1441-
tiltStop();
1392+
tiltRequestStop(); //Don't force the hardware off here as it may be in use in another task
14421393
}
14431394

14441395
else if (doubleTap)

Firmware/RTK_Everywhere/Tilt.ino

Lines changed: 32 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ typedef enum
7272
TILT_STARTED,
7373
TILT_INITIALIZED,
7474
TILT_CORRECTING,
75-
75+
TILT_REQUEST_STOP,
7676
} TiltState;
7777
TiltState tiltState = TILT_DISABLED;
7878

@@ -141,7 +141,7 @@ void tiltUpdate()
141141
// Check to see if tilt compensation is active
142142
if (tiltSensor->isCorrecting())
143143
{
144-
beepMultiple(2, 500, 500); //Number of beeps, length of beep ms, length of quiet ms
144+
beepMultiple(2, 500, 500); // Number of beeps, length of beep ms, length of quiet ms
145145

146146
lastTiltBeepMs = millis();
147147

@@ -207,6 +207,10 @@ void tiltUpdate()
207207
}
208208

209209
break;
210+
211+
case TILT_REQUEST_STOP:
212+
tiltStop(); // Changes state to TILT_OFFILINE
213+
break;
210214
}
211215
}
212216

@@ -343,7 +347,8 @@ void beginTilt()
343347
// Set the overall length of the GNSS setup in meters: rod length 1800mm + internal length 96.45mm + antenna
344348
// POC 19.25mm = 1915.7mm
345349
char clubVector[strlen("CLUB_VECTOR=0,0,1.916") + 1];
346-
float arp_m = present.antennaReferencePoint_mm / 1000.0;
350+
float arp_m =
351+
present.antennaReferencePoint_mm / 1000.0; // Convert mm to m. antennaReferencePoint_mm assigned in begin()
347352

348353
snprintf(clubVector, sizeof(clubVector), "CLUB_VECTOR=0,0,%0.3f", settings.tiltPoleLength + arp_m);
349354
result &= tiltSensor->sendCommand(clubVector);
@@ -369,9 +374,9 @@ void beginTilt()
369374

370375
// Enable magnetic field mode
371376
// 'it is recommended to use the magnetic field initialization mode to speed up the initialization process'
372-
result &= tiltSensor->sendCommand("AHRS=ENABLE");
377+
result &= tiltSensor->sendCommand("AHRS=ENABLE");
373378

374-
result &= tiltSensor->sendCommand("MAG_AUTO_SAVE=ENABLE");
379+
result &= tiltSensor->sendCommand("MAG_AUTO_SAVE=ENABLE");
375380

376381
if (result == true)
377382
{
@@ -388,19 +393,37 @@ void beginTilt()
388393

389394
void tiltStop()
390395
{
396+
// Gracefully stop the UART before freeing resources
397+
while (SerialForTilt->available())
398+
SerialForTilt->read();
399+
400+
SerialForTilt->end();
401+
391402
// Free the resources
392-
delete tiltSensor;
393-
tiltSensor = nullptr;
403+
if (tiltSensor != nullptr)
404+
{
405+
delete tiltSensor;
406+
tiltSensor = nullptr;
407+
}
394408

395-
delete SerialForTilt;
396-
SerialForTilt = nullptr;
409+
if (SerialForTilt != nullptr)
410+
{
411+
delete SerialForTilt;
412+
SerialForTilt = nullptr;
413+
}
397414

398415
if (tiltState == TILT_CORRECTING)
399416
beepDurationMs(1000); // Indicate we are going offline
400417

401418
tiltState = TILT_OFFLINE;
402419
}
403420

421+
// Called by other tasks. Prevents stopping serial port while within a library transaction.
422+
void tiltRequestStop()
423+
{
424+
tiltState = TILT_REQUEST_STOP;
425+
}
426+
404427
bool tiltIsCorrecting()
405428
{
406429
if (tiltState == TILT_CORRECTING)

Firmware/RTK_Everywhere/UM980.ino

Lines changed: 72 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -141,8 +141,67 @@ bool um980ConfigureOnce()
141141

142142
response &= um980SetConstellations();
143143

144-
// response &= um980->sendCommand("CONFIG SIGNALGROUP 2"); //Enable L1C
145-
// SIGNALGROUP causes the UM980 to automatically save and reset
144+
if (um980->isConfigurationPresent("CONFIG SIGNALGROUP 2") == false)
145+
{
146+
if (um980->sendCommand("CONFIG SIGNALGROUP 2") == false)
147+
systemPrintln("Signal group 2 command failed");
148+
else
149+
{
150+
systemPrintln("Enabling additional reception on UM980. This can take a few seconds.");
151+
152+
while (1)
153+
{
154+
delay(1000); // Wait for device to reboot
155+
if (um980->isConnected() == true)
156+
break;
157+
else
158+
systemPrintln("UM980 rebooting");
159+
}
160+
161+
systemPrintln("UM980 has completed reboot.");
162+
}
163+
}
164+
165+
// Enable E6 and PPP if enabled and possible
166+
if (settings.enableGalileoHas == true)
167+
{
168+
// E6 reception requires version 11833 or greater
169+
int um980Version = String(um980->getVersion()).toInt(); // Convert the string response to a value
170+
if (um980Version >= 11833)
171+
{
172+
if (um980->isConfigurationPresent("CONFIG PPP ENABLE E6-HAS") == false)
173+
{
174+
if (um980->sendCommand("CONFIG PPP ENABLE E6-HAS") == true)
175+
systemPrintln("Galileo E6 service enabled");
176+
else
177+
systemPrintln("Galileo E6 service config error");
178+
179+
if (um980->sendCommand("CONFIG PPP DATUM WGS84") == true)
180+
systemPrintln("WGS84 Datum applied");
181+
else
182+
systemPrintln("WGS84 Datum error");
183+
}
184+
}
185+
else
186+
{
187+
systemPrintf("Current UM980 firmware: v%d. Galileo E6 reception requires 11833 or newer. Please update the "
188+
"firmware on your UM980 to allow for HAS operation.\r\n",
189+
um980Version);
190+
}
191+
}
192+
else
193+
{
194+
// Turn off HAS/E6
195+
if (um980->isConfigurationPresent("CONFIG PPP ENABLE E6-HAS") == true)
196+
{
197+
if (um980->sendCommand("CONFIG PPP DISABLE") == true)
198+
{
199+
//systemPrintln("Galileo E6 service disabled");
200+
}
201+
else
202+
systemPrintln("Galileo E6 service config error");
203+
}
204+
}
146205

147206
if (response == true)
148207
{
@@ -1059,16 +1118,26 @@ void um980MenuConstellations()
10591118
systemPrintln();
10601119
}
10611120

1121+
if (present.galileoHasCapable)
1122+
{
1123+
systemPrintf("%d) Galileo E6 Corrections: %s\r\n", MAX_UM980_CONSTELLATIONS + 1,
1124+
settings.enableGalileoHas ? "Enabled" : "Disabled");
1125+
}
1126+
10621127
systemPrintln("x) Exit");
10631128

10641129
int incoming = getUserInputNumber(); // Returns EXIT, TIMEOUT, or long
10651130

1066-
if (incoming >= 1 && incoming <= MAX_CONSTELLATIONS)
1131+
if (incoming >= 1 && incoming <= MAX_UM980_CONSTELLATIONS)
10671132
{
10681133
incoming--; // Align choice to constellation array of 0 to 5
10691134

10701135
settings.um980Constellations[incoming] ^= 1;
10711136
}
1137+
else if ((incoming == MAX_UM980_CONSTELLATIONS + 1) && present.galileoHasCapable)
1138+
{
1139+
settings.enableGalileoHas ^= 1;
1140+
}
10721141
else if (incoming == INPUT_RESPONSE_GETNUMBER_EXIT)
10731142
break;
10741143
else if (incoming == INPUT_RESPONSE_GETNUMBER_TIMEOUT)

Firmware/RTK_Everywhere/form.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
// python main_js_zipper.py
2727

2828
static const uint8_t main_js[] PROGMEM = {
29-
0x1F, 0x8B, 0x08, 0x08, 0x3F, 0x5E, 0x32, 0x66, 0x02, 0xFF, 0x6D, 0x61, 0x69, 0x6E, 0x2E, 0x6A,
29+
0x1F, 0x8B, 0x08, 0x08, 0x82, 0xEC, 0x3E, 0x66, 0x02, 0xFF, 0x6D, 0x61, 0x69, 0x6E, 0x2E, 0x6A,
3030
0x73, 0x2E, 0x67, 0x7A, 0x69, 0x70, 0x00, 0xED, 0x7D, 0xEB, 0x7A, 0xDB, 0x38, 0x92, 0xE8, 0xFF,
3131
0x3C, 0x05, 0x46, 0x3B, 0x67, 0x24, 0x8D, 0x65, 0x99, 0x92, 0x2F, 0xB1, 0xE3, 0x38, 0x7B, 0x7C,
3232
0x4D, 0x7C, 0xDA, 0x17, 0x1D, 0xCB, 0x4E, 0x3A, 0xC9, 0x64, 0xBD, 0xB4, 0x08, 0xCB, 0x9C, 0x48,
@@ -886,7 +886,7 @@ static const uint8_t main_js[] PROGMEM = {
886886
// python index_html_zipper.py
887887

888888
static const uint8_t index_html[] PROGMEM = {
889-
0x1F, 0x8B, 0x08, 0x08, 0x3F, 0x5E, 0x32, 0x66, 0x02, 0xFF, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x2E,
889+
0x1F, 0x8B, 0x08, 0x08, 0x82, 0xEC, 0x3E, 0x66, 0x02, 0xFF, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x2E,
890890
0x68, 0x74, 0x6D, 0x6C, 0x2E, 0x67, 0x7A, 0x69, 0x70, 0x00, 0xED, 0x7D, 0xEB, 0x52, 0xE3, 0x4A,
891891
0x93, 0xE0, 0xFF, 0xF3, 0x14, 0x35, 0x9E, 0x9D, 0x81, 0x9E, 0xC1, 0xC6, 0x17, 0xA0, 0x69, 0xBE,
892892
0x6E, 0x22, 0xB8, 0x76, 0xB3, 0x1F, 0x74, 0x3B, 0x30, 0xFD, 0x9D, 0xCB, 0xC6, 0xEE, 0x09, 0x21,

Firmware/RTK_Everywhere/menuSystem.ino

Lines changed: 33 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -512,23 +512,48 @@ void menuDebugHardware()
512512
}
513513
else if (incoming == 13 && present.gnss_um980)
514514
{
515-
systemPrintln("Press ! to exit");
515+
// Stop all UART tasks
516+
tasksStopGnssUart();
517+
518+
systemPrintln("Entering UM980 direct connect at 115200bps for firmware update and configuration. Use "
519+
"UPrecise to update "
520+
"the firmware. Power cycle RTK Torch to "
521+
"return to normal operation.");
522+
523+
// Make sure ESP-UART1 is connected to UM980
524+
digitalWrite(pin_muxA, LOW);
525+
526+
// UPrecise needs to query the device before entering bootload mode
527+
// Wait for UPrecise to send bootloader trigger (character T followed by character @) before resetting UM980
528+
bool inBootMode = false;
516529

517530
// Echo everything to/from UM980
518531
while (1)
519532
{
520-
while (serialGNSS->available())
533+
// Data coming from UM980 to external USB
534+
if (serialGNSS->available())
521535
systemWrite(serialGNSS->read());
522536

537+
// Data coming from external USB to UM980
523538
if (systemAvailable())
524539
{
525540
byte incoming = systemRead();
526-
if (incoming == '!')
527-
break;
528-
else if (incoming == '1')
529-
serialGNSS->println("mask");
530-
else if (incoming == '2')
531-
serialGNSS->println("config");
541+
serialGNSS->write(incoming);
542+
543+
// Detect bootload sequence
544+
if (inBootMode == false && incoming == 'T')
545+
{
546+
byte nextIncoming = Serial.peek();
547+
if (nextIncoming == '@')
548+
{
549+
// Reset UM980
550+
um980Reset();
551+
delay(25);
552+
um980Boot();
553+
554+
inBootMode = true;
555+
}
556+
}
532557
}
533558
}
534559
}

0 commit comments

Comments
 (0)