Skip to content

Commit 7f05163

Browse files
authored
Merge pull request #282 from sparkfun/release_candidate
Add HAS/E6 support. Add NMEA output over USB.
2 parents d5a3153 + 0024a71 commit 7f05163

18 files changed

+394
-97
lines changed

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ on:
66
env:
77
FILENAME_PREFIX: RTK_Everywhere_Firmware
88
FIRMWARE_VERSION_MAJOR: 1
9-
FIRMWARE_VERSION_MINOR: 0
9+
FIRMWARE_VERSION_MINOR: 1
1010
POINTPERFECT_LBAND_TOKEN: ${{ secrets.POINTPERFECT_LBAND_TOKEN }}
1111
POINTPERFECT_IP_TOKEN: ${{ secrets.POINTPERFECT_IP_TOKEN }}
1212
POINTPERFECT_LBAND_IP_TOKEN: ${{ secrets.POINTPERFECT_LBAND_IP_TOKEN }}

Firmware/RTK_Everywhere/AP-Config/index.html

+1-1
Original file line numberDiff line numberDiff line change
@@ -112,7 +112,7 @@
112112
<div align="center" class="row" style="display:block;">
113113

114114
<div align="center" class="small left">
115-
RTK Firmware: <span id="rtkFirmwareVersion" style="display:inline;">v0.0</span><br>
115+
RTK Everywhere Firmware: <span id="rtkFirmwareVersion" style="display:inline;">v0.0</span><br>
116116
<span id="gnssFirmwareVersion" style="display:inline;">GNSS Firmware: v0.0</span> <br>
117117
<span id="deviceBTID" style="display:inline;">Device Bluetooth ID: 0000</span> <br>
118118
<span id="coordinatesLLH" style="display:inline;">LLh:

Firmware/RTK_Everywhere/Begin.ino

+7-2
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

+1
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/GNSS.ino

+34
Original file line numberDiff line numberDiff line change
@@ -741,6 +741,40 @@ bool gnssIsRTKFloat()
741741
return (false);
742742
}
743743

744+
bool gnssIsPppConverging()
745+
{
746+
if (online.gnss == true)
747+
{
748+
if (present.gnss_zedf9p)
749+
{
750+
return (false);
751+
}
752+
else if (present.gnss_um980)
753+
{
754+
if (um980GetPositionType() == 68) // 68 = PPP solution converging
755+
return (true);
756+
}
757+
}
758+
return (false);
759+
}
760+
761+
bool gnssIsPppConverged()
762+
{
763+
if (online.gnss == true)
764+
{
765+
if (present.gnss_zedf9p)
766+
{
767+
return (false);
768+
}
769+
else if (present.gnss_um980)
770+
{
771+
if (um980GetPositionType() == 69) // 69 = Precision Point Positioning
772+
return (true);
773+
}
774+
}
775+
return (false);
776+
}
777+
744778
float gnssGetHorizontalAccuracy()
745779
{
746780
if (online.gnss == true)

Firmware/RTK_Everywhere/RTK_Everywhere.ino

+27
Original file line numberDiff line numberDiff line change
@@ -445,6 +445,29 @@ float batteryChargingPercentPerHour;
445445
#include "bluetoothSelect.h"
446446
#endif // COMPILE_BT
447447

448+
// This value controls the data that is output from the USB serial port
449+
// to the host PC. By default (false) status and debug messages are output
450+
// to the USB serial port. When this value is set to true then the status
451+
// and debug messages are discarded and only GNSS data is output to USB
452+
// serial.
453+
//
454+
// Switching from status and debug messages to GNSS output is done in two
455+
// places, at the end of setup and at the end of maenuMain. In both of
456+
// these places the new value comes from settings.enableGnssToUsbSerial.
457+
// Upon boot status and debug messages are output at least until the end
458+
// of setup. Upon entry into menuMain, this value is set false to again
459+
// output menu output, status and debug messages to be output. At the end
460+
// of setup the value is updated and if enabled GNSS data is sent to the
461+
// USB serial port and PC.
462+
volatile bool forwardGnssDataToUsbSerial;
463+
464+
// Timeout between + characters to enter the +++ sequence while
465+
// forwardGnssDataToUsbSerial is true. When sequence is properly entered
466+
// forwardGnssDataToUsbSerial is set to false and menuMain is displayed.
467+
// If the timeout between characters occurs or an invalid character is
468+
// entered then no changes are made and the +++ sequence must be re-entered.
469+
#define PLUS_PLUS_PLUS_TIMEOUT (2 * 1000) // Milliseconds
470+
448471
#define platformPrefix platformPrefixTable[productVariant] // Sets the prefix for broadcast names
449472

450473
#include <driver/uart.h> //Required for uart_set_rx_full_threshold() on cores <v2.0.5
@@ -1113,6 +1136,10 @@ void setup()
11131136
systemPrintf("%8d mSec: Total boot time\r\n", bootTime[bootTimeIndex]);
11141137
systemPrintln();
11151138
}
1139+
1140+
// If necessary, switch to sending GNSS data out the USB serial port
1141+
// to the PC
1142+
forwardGnssDataToUsbSerial = settings.enableGnssToUsbSerial;
11161143
}
11171144

11181145
void loop()

Firmware/RTK_Everywhere/System.ino

+4
Original file line numberDiff line numberDiff line change
@@ -377,6 +377,10 @@ void printReports()
377377
systemPrint("RTK Fix");
378378
else if (gnssIsRTKFloat() == true)
379379
systemPrint("RTK Float");
380+
else if (gnssIsPppConverged() == true)
381+
systemPrint("PPP Converged");
382+
else if (gnssIsPppConverging() == true)
383+
systemPrint("PPP Converging");
380384
else if (gnssIsDgpsFixed() == true)
381385
systemPrint("DGPS Fix");
382386
else if (gnssIsFixed() == true)

Firmware/RTK_Everywhere/Tasks.ino

+58-53
Original file line numberDiff line numberDiff line change
@@ -56,12 +56,13 @@ enum RingBufferConsumers
5656
RBC_TCP_SERVER,
5757
RBC_SD_CARD,
5858
RBC_UDP_SERVER,
59+
RBC_USB_SERIAL,
5960
// Insert new consumers here
6061
RBC_MAX
6162
};
6263

6364
const char *const ringBufferConsumer[] = {
64-
"Bluetooth", "TCP Client", "TCP Server", "SD Card", "UDP Server",
65+
"Bluetooth", "TCP Client", "TCP Server", "SD Card", "UDP Server", "USB Serial",
6566
};
6667

6768
const int ringBufferConsumerEntries = sizeof(ringBufferConsumer) / sizeof(ringBufferConsumer[0]);
@@ -101,6 +102,7 @@ unsigned long lastGnssSend; // Timestamp of the last time we sent RTCM to GNSS
101102
// Ring buffer tails
102103
static RING_BUFFER_OFFSET btRingBufferTail; // BT Tail advances as it is sent over BT
103104
static RING_BUFFER_OFFSET sdRingBufferTail; // SD Tail advances as it is recorded to SD
105+
static RING_BUFFER_OFFSET usbRingBufferTail; // USB Tail advances as it is sent over USB serial
104106

105107
// Ring buffer offsets
106108
static uint16_t rbOffsetHead;
@@ -898,6 +900,58 @@ void handleGnssDataTask(void *e)
898900
}
899901
}
900902

903+
//----------------------------------------------------------------------
904+
// Send data over USB serial
905+
//----------------------------------------------------------------------
906+
907+
startMillis = millis();
908+
909+
// Determine USB serial connection state
910+
if (!forwardGnssDataToUsbSerial)
911+
// Discard the data
912+
usbRingBufferTail = dataHead;
913+
else
914+
{
915+
// Determine the amount of USB serial data in the buffer
916+
bytesToSend = dataHead - usbRingBufferTail;
917+
if (bytesToSend < 0)
918+
bytesToSend += settings.gnssHandlerBufferSize;
919+
if (bytesToSend > 0)
920+
{
921+
// Reduce bytes to send if we have more to send then the end of
922+
// the buffer, we'll wrap next loop
923+
if ((usbRingBufferTail + bytesToSend) > settings.gnssHandlerBufferSize)
924+
bytesToSend = settings.gnssHandlerBufferSize - usbRingBufferTail;
925+
926+
// Send data over USB serial to the PC
927+
bytesToSend = systemWriteGnssDataToUsbSerial(&ringBuffer[usbRingBufferTail], bytesToSend);
928+
929+
// Account for the data that was sent
930+
if (bytesToSend > 0)
931+
{
932+
// Account for the sent or dropped data
933+
usbRingBufferTail += bytesToSend;
934+
if (usbRingBufferTail >= settings.gnssHandlerBufferSize)
935+
usbRingBufferTail -= settings.gnssHandlerBufferSize;
936+
937+
// Remember the maximum transfer time
938+
deltaMillis = millis() - startMillis;
939+
if (maxMillis[RBC_USB_SERIAL] < deltaMillis)
940+
maxMillis[RBC_USB_SERIAL] = deltaMillis;
941+
}
942+
943+
// Determine the amount of data that remains in the buffer
944+
bytesToSend = dataHead - usbRingBufferTail;
945+
if (bytesToSend < 0)
946+
bytesToSend += settings.gnssHandlerBufferSize;
947+
if (usedSpace < bytesToSend)
948+
{
949+
usedSpace = bytesToSend;
950+
slowConsumer = "USB Serial";
951+
}
952+
}
953+
}
954+
901955
//----------------------------------------------------------------------
902956
// Send data to the network clients
903957
//----------------------------------------------------------------------
@@ -1150,9 +1204,6 @@ void tickerBluetoothLedUpdate()
11501204
void tickerGnssLedUpdate()
11511205
{
11521206
static uint8_t ledCallCounter = 0; // Used to calculate a 50% or 10% on rate for blinking
1153-
// static int gnssFadeLevel = 0; // Used to fade LED when needed
1154-
// static int gnssPwmFadeAmount = 255 / gnssTaskUpdatesHz; // Fade in/out with 20 steps, as limited by the ticker
1155-
// rate of 20Hz
11561207

11571208
ledCallCounter++;
11581209
ledCallCounter %= gnssTaskUpdatesHz; // Wrap to X calls per 1 second
@@ -1161,61 +1212,15 @@ void tickerGnssLedUpdate()
11611212
{
11621213
// Update the GNSS LED according to our state
11631214

1164-
// Solid once RTK Fix is achieved
1165-
if (gnssIsRTKFix() == true)
1215+
// Solid once RTK Fix is achieved, or PPP converges
1216+
if (gnssIsRTKFix() == true || gnssIsPppConverged())
11661217
{
11671218
ledcWrite(ledGnssChannel, 255);
11681219
}
11691220
else
11701221
{
11711222
ledcWrite(ledGnssChannel, 0);
11721223
}
1173-
1174-
// // Solid during tilt corrected RTK fix
1175-
// if (tiltIsCorrecting() == true)
1176-
// {
1177-
// ledcWrite(ledGnssChannel, 255);
1178-
// }
1179-
// else
1180-
// {
1181-
// ledcWrite(ledGnssChannel, 0);
1182-
// }
1183-
1184-
// Fade on/off during RTK Fix
1185-
// else if (gnssIsRTKFix() == true)
1186-
// {
1187-
// // Fade in/out the GNSS LED during RTK Fix
1188-
// gnssFadeLevel += gnssPwmFadeAmount;
1189-
// if (gnssFadeLevel <= 0 || gnssFadeLevel >= 255)
1190-
// gnssPwmFadeAmount *= -1;
1191-
1192-
// if (gnssFadeLevel > 255)
1193-
// gnssFadeLevel = 255;
1194-
// if (gnssFadeLevel < 0)
1195-
// gnssFadeLevel = 0;
1196-
1197-
// ledcWrite(ledGnssChannel, gnssFadeLevel);
1198-
// }
1199-
1200-
// // Blink 2Hz 50% during RTK float
1201-
// else if (gnssIsRTKFloat() == true)
1202-
// {
1203-
// if (ledCallCounter <= (gnssTaskUpdatesHz / 2))
1204-
// ledcWrite(ledGnssChannel, 255);
1205-
// else
1206-
// ledcWrite(ledGnssChannel, 0);
1207-
// }
1208-
1209-
// // Blink a short PPS when GNSS 3D fixed
1210-
// else if (gnssIsFixed() == true)
1211-
// {
1212-
// if (ledCallCounter == (gnssTaskUpdatesHz / 10))
1213-
// {
1214-
// ledcWrite(ledGnssChannel, 255);
1215-
// }
1216-
// else
1217-
// ledcWrite(ledGnssChannel, 0);
1218-
// }
12191224
}
12201225
}
12211226

@@ -1384,7 +1389,7 @@ void buttonCheckTask(void *e)
13841389
// The user button only exits tilt mode
13851390
if ((singleTap || doubleTap) && (tiltIsCorrecting() == true))
13861391
{
1387-
tiltStop();
1392+
tiltRequestStop(); //Don't force the hardware off here as it may be in use in another task
13881393
}
13891394

13901395
else if (doubleTap)

0 commit comments

Comments
 (0)