Skip to content

Commit 1ac4107

Browse files
authored
Merge pull request #772 from sparkfun/pcUpdates
pcUpdates
2 parents c9789f8 + 1aa3465 commit 1ac4107

File tree

14 files changed

+250
-79
lines changed

14 files changed

+250
-79
lines changed

Firmware/Dockerfile

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,9 @@ ARG DEBUG_LEVEL=error
1717
# Set to false for releases
1818
ARG ENABLE_DEVELOPER=true
1919

20+
# arduino-cli warnings: none default more all
21+
ARG WARNINGS=default
22+
2023
# If you have your own u-blox PointPerfect token(s), define them here
2124
# or pass in as args when building the Dockerfile
2225
# POINTPERFECT_LBAND_TOKEN is the token for the deprecated u-blox L-band SPARTN service
@@ -116,6 +119,7 @@ RUN cp RTKEverywhere.csv "/root/.arduino15/packages/esp32/hardware/esp32/${CORE_
116119
# Compile Sketch
117120
RUN cd ./RTK_Everywhere \
118121
&& arduino-cli compile --fqbn "esp32:esp32:esp32":DebugLevel=${DEBUG_LEVEL},PSRAM=enabled \
122+
--warnings ${WARNINGS} \
119123
./RTK_Everywhere.ino \
120124
--build-property build.partitions=RTKEverywhere \
121125
--build-property upload.maximum_size=4055040 \

Firmware/RTK_Everywhere/Developer.ino

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,9 @@
99
// Ethernet
1010
//----------------------------------------
1111

12-
bool ethernetLinkUp() {return false;}
13-
void menuEthernet() {systemPrintln("**Ethernet not compiled**");}
12+
bool ethernetLinkUp() {return false;}
13+
void menuEthernet() {systemPrintln("**Ethernet not compiled**");}
14+
void ethernetUpdate() {}
1415

1516
bool ntpLogIncreasing = false;
1617

Firmware/RTK_Everywhere/Display.ino

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1992,7 +1992,7 @@ void paintIPAddress()
19921992
char ipAddress[16];
19931993
snprintf(ipAddress, sizeof(ipAddress), "%s",
19941994
#ifdef COMPILE_ETHERNET
1995-
ETH.localIP().toString());
1995+
ETH.localIP().toString().c_str());
19961996
#else // COMPILE_ETHERNET
19971997
"0.0.0.0");
19981998
#endif // COMPILE_ETHERNET
@@ -2032,7 +2032,7 @@ void displayFullIPAddress(std::vector<iconPropertyBlinking> *iconList) // Bottom
20322032
{
20332033
static IPAddress ipAddress;
20342034
NetPriority_t priority;
2035-
static NetPriority_t previousPriority;
2035+
static NetPriority_t previousPriority = NETWORK_NONE;
20362036

20372037
// Max width: 15*6 = 90 pixels (6 pixels per character, nnn.nnn.nnn.nnn)
20382038
if (present.display_type == DISPLAY_128x64)
@@ -2052,7 +2052,7 @@ void displayFullIPAddress(std::vector<iconPropertyBlinking> *iconList) // Bottom
20522052
// Display the IP address when it is available
20532053
if (ipAddress != IPAddress((uint32_t)0))
20542054
{
2055-
snprintf(myAddress, sizeof(myAddress), "%s", ipAddress.toString());
2055+
snprintf(myAddress, sizeof(myAddress), "%s", ipAddress.toString().c_str());
20562056

20572057
oled->setFont(QW_FONT_5X7); // Set font to smallest
20582058
oled->setCursor(0, 55);

Firmware/RTK_Everywhere/Ethernet.ino

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -188,6 +188,9 @@ void ethernetEvent(arduino_event_id_t event, arduino_event_info_t info)
188188
case ARDUINO_EVENT_ETH_DISCONNECTED:
189189
if (settings.enablePrintEthernetDiag && (!inMainMenu))
190190
systemPrintln("ETH Disconnected");
191+
192+
ethernetRestartRequested = true; // Perform ETH.end() to disconnect TCP resources
193+
191194
break;
192195

193196
case ARDUINO_EVENT_ETH_STOP:
@@ -236,6 +239,20 @@ const char *ethernetGetEventName(arduino_event_id_t event)
236239
}
237240
}
238241

242+
//----------------------------------------
243+
// Update Ethernet. Restart if requested
244+
//----------------------------------------
245+
void ethernetUpdate()
246+
{
247+
if (ethernetRestartRequested)
248+
{
249+
if (settings.enablePrintEthernetDiag && (!inMainMenu))
250+
systemPrintln("Restarting Ethernet");
251+
ethernetRestart();
252+
ethernetRestartRequested = false;
253+
}
254+
}
255+
239256
//----------------------------------------
240257
// Restart the Ethernet controller
241258
//----------------------------------------

Firmware/RTK_Everywhere/NTP.ino

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -609,7 +609,7 @@ bool ntpProcessOneRequest(bool process, const timeval *recTv, const timeval *syn
609609
if (ntpDiag != nullptr)
610610
{
611611
char tmpbuf[128];
612-
snprintf(tmpbuf, sizeof(tmpbuf), "Originate Timestamp (Client Transmit): %u.%06u\r\n",
612+
snprintf(tmpbuf, sizeof(tmpbuf), "Originate Timestamp (Client Transmit): %lu.%06lu\r\n",
613613
packet.transmitTimestampSeconds,
614614
packet.convertFractionToMicros(packet.transmitTimestampFraction));
615615
strlcat(ntpDiag, tmpbuf, ntpDiagSize);
@@ -631,7 +631,7 @@ bool ntpProcessOneRequest(bool process, const timeval *recTv, const timeval *syn
631631
if (ntpDiag != nullptr)
632632
{
633633
char tmpbuf[128];
634-
snprintf(tmpbuf, sizeof(tmpbuf), "Received Timestamp: %u.%06u\r\n",
634+
snprintf(tmpbuf, sizeof(tmpbuf), "Received Timestamp: %lu.%06lu\r\n",
635635
packet.receiveTimestampSeconds,
636636
packet.convertFractionToMicros(packet.receiveTimestampFraction));
637637
strlcat(ntpDiag, tmpbuf, ntpDiagSize);
@@ -649,7 +649,7 @@ bool ntpProcessOneRequest(bool process, const timeval *recTv, const timeval *syn
649649
if (ntpDiag != nullptr)
650650
{
651651
char tmpbuf[128];
652-
snprintf(tmpbuf, sizeof(tmpbuf), "Reference Timestamp (Last Sync): %u.%06u\r\n",
652+
snprintf(tmpbuf, sizeof(tmpbuf), "Reference Timestamp (Last Sync): %lu.%06lu\r\n",
653653
packet.referenceTimestampSeconds,
654654
packet.convertFractionToMicros(packet.referenceTimestampFraction));
655655
strlcat(ntpDiag, tmpbuf, ntpDiagSize);
@@ -677,7 +677,7 @@ bool ntpProcessOneRequest(bool process, const timeval *recTv, const timeval *syn
677677
if (ntpDiag != nullptr)
678678
{
679679
char tmpbuf[128];
680-
snprintf(tmpbuf, sizeof(tmpbuf), "Transmit Timestamp: %u.%06u\r\n",
680+
snprintf(tmpbuf, sizeof(tmpbuf), "Transmit Timestamp: %lu.%06lu\r\n",
681681
packet.transmitTimestampSeconds,
682682
packet.convertFractionToMicros(packet.transmitTimestampFraction));
683683
strlcat(ntpDiag, tmpbuf, ntpDiagSize);

Firmware/RTK_Everywhere/NVM.ino

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -279,7 +279,7 @@ void recordSystemSettingsToFile(File *settingsFile)
279279
break;
280280
case _uint32_t: {
281281
uint32_t *ptr = (uint32_t *)rtkSettingsEntries[i].var;
282-
settingsFile->printf("%s=%d\r\n", rtkSettingsEntries[i].name, *ptr);
282+
settingsFile->printf("%s=%lu\r\n", rtkSettingsEntries[i].name, *ptr);
283283
}
284284
break;
285285
case _uint64_t: {

Firmware/RTK_Everywhere/Network.ino

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2453,10 +2453,12 @@ void networkUpdate()
24532453
// Update the WiFi state
24542454
wifiStationUpdate();
24552455

2456+
// Update Ethernet
2457+
ethernetUpdate();
2458+
24562459
// Update the network services
24572460
// Start or stop mDNS
2458-
if (networkMdnsRequests != networkMdnsRunning)
2459-
networkMulticastDNSUpdate();
2461+
networkMulticastDNSUpdate();
24602462

24612463
// Update the network services
24622464
DMW_c("mqttClientUpdate");

Firmware/RTK_Everywhere/NtripServer.ino

Lines changed: 41 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,7 @@ const RtkMode_t ntripServerMode = RTK_MODE_BASE_FIXED;
173173
//----------------------------------------
174174

175175
// NTRIP Servers
176-
volatile static NTRIP_SERVER_DATA ntripServerArray[NTRIP_SERVER_MAX];
176+
static NTRIP_SERVER_DATA ntripServerArray[NTRIP_SERVER_MAX];
177177

178178
//----------------------------------------
179179
// NTRIP Server Routines
@@ -184,7 +184,7 @@ volatile static NTRIP_SERVER_DATA ntripServerArray[NTRIP_SERVER_MAX];
184184
//----------------------------------------
185185
bool ntripServerConnectCaster(int serverIndex)
186186
{
187-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
187+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
188188
const int SERVER_BUFFER_SIZE = 512;
189189
char serverBuffer[SERVER_BUFFER_SIZE];
190190

@@ -240,7 +240,7 @@ bool ntripServerConnectLimitReached(int serverIndex)
240240
{
241241
bool limitReached;
242242
int minutes;
243-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
243+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
244244
int seconds;
245245

246246
// Retry the connection a few times
@@ -312,9 +312,9 @@ bool ntripServerEnabled(int serverIndex, const char ** line)
312312
{
313313
if (line)
314314
{
315-
if (settings.ntripServer_CasterHost[0] == 0)
315+
if (settings.ntripServer_CasterHost[serverIndex][0] == 0)
316316
*line = ", Caster host not specified!";
317-
else if (settings.ntripServer_CasterPort == 0)
317+
else if (settings.ntripServer_CasterPort[serverIndex] == 0)
318318
*line = ", Caster port not specified!";
319319
else
320320
*line = ", Mount point not specified!";
@@ -335,7 +335,7 @@ bool ntripServerEnabled(int serverIndex, const char ** line)
335335
//----------------------------------------
336336
void ntripServerPrintStateSummary(int serverIndex)
337337
{
338-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
338+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
339339

340340
switch (ntripServer->state)
341341
{
@@ -363,7 +363,7 @@ void ntripServerPrintStateSummary(int serverIndex)
363363
//----------------------------------------
364364
void ntripServerPrintStatus(int serverIndex)
365365
{
366-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
366+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
367367
uint64_t milliseconds;
368368
uint32_t days;
369369
byte hours;
@@ -380,7 +380,7 @@ void ntripServerPrintStatus(int serverIndex)
380380
if (ntripServer->state == NTRIP_SERVER_CASTING)
381381
// Use ntripServer->timer since it gets reset after each successful data
382382
// reception from the NTRIP caster
383-
milliseconds = ntripServer->timer - ntripServer->startTime;
383+
milliseconds = ntripServer->getUptime();
384384
else
385385
{
386386
milliseconds = ntripServer->startTime;
@@ -411,7 +411,7 @@ void ntripServerPrintStatus(int serverIndex)
411411
//----------------------------------------
412412
void ntripServerProcessRTCM(int serverIndex, uint8_t incoming)
413413
{
414-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
414+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
415415

416416
if (ntripServer->state == NTRIP_SERVER_CASTING)
417417
{
@@ -434,22 +434,27 @@ void ntripServerProcessRTCM(int serverIndex, uint8_t incoming)
434434
}
435435

436436
// If we have not gotten new RTCM bytes for a period of time, assume end of frame
437-
if (((millis() - ntripServer->timer) > 100) && (ntripServer->bytesSent > 0))
438-
{
439-
if ((!inMainMenu) && settings.debugNtripServerRtcm)
440-
systemPrintf("NTRIP Server %d transmitted %d RTCM bytes to Caster\r\n", serverIndex,
441-
ntripServer->bytesSent);
442-
443-
ntripServer->bytesSent = 0;
444-
}
437+
if (ntripServer->checkBytesSentAndReset(100) && (!inMainMenu) && settings.debugNtripServerRtcm)
438+
systemPrintf("NTRIP Server %d transmitted %d RTCM bytes to Caster\r\n", serverIndex,
439+
ntripServer->bytesSent);
445440

446441
if (ntripServer->networkClient && ntripServer->networkClient->connected())
447442
{
448-
ntripServer->networkClient->write(incoming); // Send this byte to socket
449-
ntripServer->bytesSent = ntripServer->bytesSent + 1;
450-
ntripServer->rtcmBytesSent = ntripServer->rtcmBytesSent + 1;
451-
ntripServer->timer = millis();
452-
netOutgoingRTCM = true;
443+
if (ntripServer->networkClient->write(incoming) == 1) // Send this byte to socket
444+
{
445+
ntripServer->updateTimerAndBytesSent();
446+
netOutgoingRTCM = true;
447+
while (ntripServer->networkClient->available())
448+
ntripServer->networkClient->read(); // Absorb any unwanted incoming traffic
449+
}
450+
// Failed to write the data
451+
else
452+
{
453+
// Done with this client connection
454+
if (settings.debugNtripServerRtcm && (!inMainMenu))
455+
systemPrintf("NTRIP Server %d broken connection to %s\r\n", serverIndex,
456+
settings.ntripServer_CasterHost[serverIndex]);
457+
}
453458
}
454459
}
455460

@@ -465,7 +470,7 @@ void ntripServerProcessRTCM(int serverIndex, uint8_t incoming)
465470
//----------------------------------------
466471
void ntripServerResponse(int serverIndex, char *response, size_t maxLength)
467472
{
468-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
473+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
469474
char *responseEnd;
470475

471476
// Make sure that we can zero terminate the response
@@ -484,11 +489,11 @@ void ntripServerResponse(int serverIndex, char *response, size_t maxLength)
484489
//----------------------------------------
485490
void ntripServerRestart(int serverIndex)
486491
{
487-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
492+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
488493

489494
// Save the previous uptime value
490495
if (ntripServer->state == NTRIP_SERVER_CASTING)
491-
ntripServer->startTime = ntripServer->timer - ntripServer->startTime;
496+
ntripServer->startTime = ntripServer->getUptime();
492497
ntripServerConnectLimitReached(serverIndex);
493498
}
494499

@@ -497,7 +502,7 @@ void ntripServerRestart(int serverIndex)
497502
//----------------------------------------
498503
void ntripServerSetState(int serverIndex, uint8_t newState)
499504
{
500-
volatile NTRIP_SERVER_DATA * ntripServer;
505+
NTRIP_SERVER_DATA * ntripServer;
501506

502507
ntripServer = &ntripServerArray[serverIndex];
503508
if (settings.debugNtripServerState)
@@ -549,7 +554,7 @@ void ntripServerStop(int serverIndex, bool shutdown)
549554
{
550555
bool enabled;
551556
int index;
552-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
557+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
553558

554559
if (ntripServer->networkClient)
555560
{
@@ -566,7 +571,7 @@ void ntripServerStop(int serverIndex, bool shutdown)
566571
// Increase timeouts if we started the network
567572
if (ntripServer->state > NTRIP_SERVER_OFF)
568573
// Mark the Server stop so that we don't immediately attempt re-connect to Caster
569-
ntripServer->timer = millis();
574+
ntripServer->setTimerToMillis();
570575

571576
// Determine the next NTRIP server state
572577
online.ntripServer[serverIndex] = false;
@@ -613,7 +618,7 @@ void ntripServerUpdate(int serverIndex)
613618
const char * line = "";
614619

615620
// Get the NTRIP data structure
616-
volatile NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
621+
NTRIP_SERVER_DATA *ntripServer = &ntripServerArray[serverIndex];
617622

618623
// Shutdown the NTRIP server when the mode or setting changes
619624
DMW_if
@@ -678,8 +683,7 @@ void ntripServerUpdate(int serverIndex)
678683
// Failed to connect to to the network, attempt to restart the network
679684
ntripServerRestart(serverIndex);
680685

681-
else if (settings.enableNtripServer &&
682-
((millis() - ntripServer->lastConnectionAttempt) > ntripServer->connectionAttemptTimeout))
686+
else if (settings.enableNtripServer)
683687
{
684688
// No RTCM correction data sent yet
685689
rtcmPacketsSent = 0;
@@ -697,7 +701,7 @@ void ntripServerUpdate(int serverIndex)
697701
// Initiate the connection to the NTRIP caster
698702
case NTRIP_SERVER_CONNECTING:
699703
// Delay before opening the NTRIP server connection
700-
if ((millis() - ntripServer->timer) >= ntripServer->connectionAttemptTimeout)
704+
if (ntripServer->checkConnectionAttemptTimeout())
701705
{
702706
// Attempt a connection to the NTRIP caster
703707
if (!ntripServerConnectCaster(serverIndex))
@@ -711,7 +715,7 @@ void ntripServerUpdate(int serverIndex)
711715
else
712716
{
713717
// Connection open to NTRIP caster, wait for the authorization response
714-
ntripServer->timer = millis();
718+
ntripServer->setTimerToMillis();
715719
ntripServerSetState(serverIndex, NTRIP_SERVER_AUTHORIZATION);
716720
}
717721
}
@@ -724,7 +728,7 @@ void ntripServerUpdate(int serverIndex)
724728
strlen("ICY 200 OK")) // Wait until at least a few bytes have arrived
725729
{
726730
// Check for response timeout
727-
if ((millis() - ntripServer->timer) > 10000)
731+
if (ntripServer->millisSinceTimer() > 10000)
728732
{
729733
if (ntripServerConnectLimitReached(serverIndex))
730734
systemPrintf(
@@ -771,7 +775,7 @@ void ntripServerUpdate(int serverIndex)
771775
settings.ntripServer_MountPoint[serverIndex]);
772776

773777
// Connection is now open, start the RTCM correction data timer
774-
ntripServer->timer = millis();
778+
ntripServer->setTimerToMillis();
775779

776780
// We don't use a task because we use I2C hardware (and don't have a semaphore).
777781
online.ntripServer[serverIndex] = true;
@@ -816,7 +820,7 @@ void ntripServerUpdate(int serverIndex)
816820
settings.ntripServer_CasterHost[serverIndex]);
817821
ntripServerRestart(serverIndex);
818822
}
819-
else if ((millis() - ntripServer->timer) > (10 * 1000))
823+
else if (ntripServer->millisSinceTimer() > (10 * 1000))
820824
{
821825
// GNSS stopped sending RTCM correction data
822826
systemPrintf("NTRIP Server %d breaking connection to %s due to lack of RTCM data!\r\n", serverIndex,
@@ -831,7 +835,7 @@ void ntripServerUpdate(int serverIndex)
831835
// connection. However increasing backoff delays should be
832836
// added when the NTRIP caster fails after a short connection
833837
// interval.
834-
if (((millis() - ntripServer->startTime) > NTRIP_SERVER_CONNECTION_TIME) &&
838+
if ((ntripServer->millisSinceStartTime() > NTRIP_SERVER_CONNECTION_TIME) &&
835839
(ntripServer->connectionAttempts || ntripServer->connectionAttemptTimeout))
836840
{
837841
// After a long connection period, reset the attempt counter

0 commit comments

Comments
 (0)