3
3
void identifyBoard ()
4
4
{
5
5
// Use ADC to check resistor divider
6
- int pin_adc_rtk_facet = 35 ;
7
- uint16_t idValue = analogReadMilliVolts (pin_adc_rtk_facet);
8
- log_d (" Board ADC ID: %d" , idValue);
9
-
10
- if (idValue > (3300 / 2 * 0.9 ) && idValue < (3300 / 2 * 1.1 ))
6
+ // Express: 10/3.3
7
+ // Express+: 3.3/10
8
+ // Facet: 10/10
9
+ // Facet L-Band: 10/20
10
+ // Reference Station: 20/10
11
+ // Facet L-Band Direct: 10/100
12
+ // Surveyor: ID resistors do not exist
13
+
14
+ const float rtkExpressID = 3.3 / (10 + 3.3 ) * 3300 ; // 819mV
15
+ const float rtkExressPlusID = 10.0 / (10 + 3.3 ) * 3300 ; // 2418mV
16
+ const float rtkFacetID = 10.0 / (10 + 10 ) * 3300 ; // 1650mV
17
+ const float rtkFacetLbandID = 20.0 / (20 + 10 ) * 3300 ; // 2200mV
18
+ const float rtkReferenceStationID = 10.0 / (10 + 20 ) * 3300 ; // 1100mV
19
+ const float rtkFacetLbandDirectID = 1.0 / (4.7 + 1 ) * 3300 ; // 579mV
20
+
21
+ const float tolerance = 0.0475 ; // 4.75% Testing shows the combined ADC+resistors is under a 1% window
22
+ const float upperThreshold = 1 + tolerance; // 104.75%
23
+ const float lowerThreshold = 1 - tolerance; // 95.25%
24
+
25
+ int pin_deviceID = 35 ;
26
+ uint16_t idValue = analogReadMilliVolts (pin_deviceID);
27
+ log_d (" Board ADC ID (mV): %d" , idValue);
28
+
29
+ if (idValue > (rtkFacetID * lowerThreshold) && idValue < (rtkFacetID * upperThreshold))
11
30
{
12
31
productVariant = RTK_FACET;
13
32
}
14
- else if (idValue > (3300 * 2 / 3 * 0.9 ) && idValue < (3300 * 2 / 3 * 1.1 ))
33
+ else if (idValue > (rtkFacetLbandID * lowerThreshold ) && idValue < (rtkFacetLbandID * upperThreshold ))
15
34
{
16
35
productVariant = RTK_FACET_LBAND;
17
36
}
18
- else if (idValue > (3300 * 3.3 / 13.3 * 0.9 ) && idValue < (3300 * 3.3 / 13.3 * 1.1 ))
37
+ else if (idValue > (rtkExpressID * lowerThreshold ) && idValue < (rtkExpressID * upperThreshold ))
19
38
{
20
39
productVariant = RTK_EXPRESS;
21
40
}
22
- else if (idValue > (3300 * 10 / 13.3 * 0.9 ) && idValue < (3300 * 10 / 13.3 * 1.1 ))
41
+ else if (idValue > (rtkExressPlusID * lowerThreshold ) && idValue < (rtkExressPlusID * upperThreshold ))
23
42
{
24
43
productVariant = RTK_EXPRESS_PLUS;
25
44
}
26
- else if (idValue > (3300 * 1 / 3 * 0.9 ) && idValue < (3300 * 1 / 3 * 1.1 ))
45
+ else if (idValue > (rtkReferenceStationID * lowerThreshold ) && idValue < (rtkReferenceStationID * upperThreshold ))
27
46
{
28
47
productVariant = REFERENCE_STATION;
29
48
// We can't auto-detect the ZED version if the firmware is in configViaEthernet mode,
30
49
// so fake it here - otherwise messageSupported always returns false
31
50
zedFirmwareVersionInt = 112 ;
32
51
}
52
+ else if (idValue > (rtkFacetLbandDirectID * lowerThreshold) && idValue < (rtkFacetLbandDirectID * upperThreshold))
53
+ {
54
+ productVariant = RTK_FACET_LBAND_DIRECT;
55
+ }
33
56
else
34
57
{
35
58
productVariant = RTK_UNKNOWN; // Need to wait until the GNSS and Accel have been initialized
@@ -112,10 +135,28 @@ void beginBoard()
112
135
}
113
136
else
114
137
{
115
- productVariant = RTK_SURVEYOR;
138
+ // Detect RTK Expresses (v1.3 and below) that do not have an accel or device ID resistors
139
+
140
+ // On a Surveyor, pin 34 is not connected. On Express, 34 is connected to ZED_TX_READY
141
+ const int pin_ZedTxReady = 34 ;
142
+ uint16_t pinValue = analogReadMilliVolts (pin_ZedTxReady);
143
+ log_d (" Alternate ID pinValue (mV): %d\r\n " , pinValue); // Surveyor = 142 to 152, //Express = 3129
144
+ if (pinValue > 3000 )
145
+ {
146
+ if (zedModuleType == PLATFORM_F9P)
147
+ productVariant = RTK_EXPRESS;
148
+ else if (zedModuleType == PLATFORM_F9R)
149
+ productVariant = RTK_EXPRESS_PLUS;
150
+ }
151
+ else
152
+ productVariant = RTK_SURVEYOR;
116
153
}
117
154
}
118
155
156
+ // We need some settings before we are completely powered on
157
+ // ie, disablePowerFiltering, enableResetDisplay, resetCount, etc
158
+ loadSettingsPartial (); // Loads settings from LFS
159
+
119
160
// Setup hardware pins
120
161
if (productVariant == RTK_SURVEYOR)
121
162
{
@@ -173,7 +214,8 @@ void beginBoard()
173
214
strncpy (platformPrefix, " Express Plus" , sizeof (platformPrefix) - 1 );
174
215
}
175
216
}
176
- else if (productVariant == RTK_FACET || productVariant == RTK_FACET_LBAND)
217
+ else if (productVariant == RTK_FACET || productVariant == RTK_FACET_LBAND ||
218
+ productVariant == RTK_FACET_LBAND_DIRECT)
177
219
{
178
220
// v11
179
221
pin_muxA = 2 ;
@@ -219,6 +261,15 @@ void beginBoard()
219
261
strncpy (platformFilePrefix, " SFE_Facet_LBand" , sizeof (platformFilePrefix) - 1 );
220
262
strncpy (platformPrefix, " Facet L-Band" , sizeof (platformPrefix) - 1 );
221
263
}
264
+ else if (productVariant == RTK_FACET_LBAND_DIRECT)
265
+ {
266
+ strncpy (platformFilePrefix, " SFE_Facet_LBand_Direct" , sizeof (platformFilePrefix) - 1 );
267
+ strncpy (platformPrefix, " Facet L-Band Direct" , sizeof (platformPrefix) - 1 );
268
+
269
+ // Override the default setting if a user has not explicitly configured the setting
270
+ if (settings.useI2cForLbandCorrectionsConfigured == false )
271
+ settings.useI2cForLbandCorrections = false ;
272
+ }
222
273
}
223
274
else if (productVariant == REFERENCE_STATION)
224
275
{
@@ -244,7 +295,6 @@ void beginBoard()
244
295
ethernetMACAddress[5 ] += 3 ; // Convert MAC address to Ethernet MAC (add 3)
245
296
246
297
// For all boards, check reset reason. If reset was due to wdt or panic, append last log
247
- loadSettingsPartial (); // Loads settings from LFS
248
298
if ((esp_reset_reason () == ESP_RST_POWERON) || (esp_reset_reason () == ESP_RST_SW))
249
299
{
250
300
reuseLastLog = false ; // Start new log
@@ -446,13 +496,13 @@ void beginSD()
446
496
}
447
497
}
448
498
}
449
- #else // COMPILE_SD_MMC
499
+ #else // COMPILE_SD_MMC
450
500
else
451
501
{
452
502
log_d (" SD_MMC not compiled" );
453
503
break ; // No SD available.
454
504
}
455
- #endif // COMPILE_SD_MMC
505
+ #endif // COMPILE_SD_MMC
456
506
457
507
if (createTestFile () == false )
458
508
{
@@ -491,7 +541,7 @@ void endSD(bool alreadyHaveSemaphore, bool releaseSemaphore)
491
541
#ifdef COMPILE_SD_MMC
492
542
else
493
543
SD_MMC.end ();
494
- #endif // COMPILE_SD_MMC
544
+ #endif // COMPILE_SD_MMC
495
545
496
546
online.microSD = false ;
497
547
systemPrintln (" microSD: Offline" );
@@ -549,20 +599,38 @@ void resetSPI()
549
599
// See issue: https://github.com/espressif/arduino-esp32/issues/3386
550
600
void beginUART2 ()
551
601
{
552
- ringBuffer = (uint8_t *)malloc (settings.gnssHandlerBufferSize );
553
-
554
- if (pinUART2TaskHandle == nullptr )
555
- xTaskCreatePinnedToCore (
556
- pinUART2Task,
557
- " UARTStart" , // Just for humans
558
- 2000 , // Stack Size
559
- nullptr , // Task input parameter
560
- 0 , // Priority, with 3 (configMAX_PRIORITIES - 1) being the highest, and 0 being the lowest
561
- &pinUART2TaskHandle, // Task handle
562
- settings.gnssUartInterruptsCore ); // Core where task should run, 0=core, 1=Arduino
563
-
564
- while (uart2pinned == false ) // Wait for task to run once
565
- delay (1 );
602
+ size_t length;
603
+
604
+ // Determine the length of data to be retained in the ring buffer
605
+ // after discarding the oldest data
606
+ length = settings.gnssHandlerBufferSize ;
607
+ rbOffsetEntries = (length >> 1 ) / AVERAGE_SENTENCE_LENGTH_IN_BYTES;
608
+ length = settings.gnssHandlerBufferSize
609
+ + (rbOffsetEntries * sizeof (RING_BUFFER_OFFSET));
610
+ ringBuffer = nullptr ;
611
+ rbOffsetArray = (RING_BUFFER_OFFSET *)malloc (length);
612
+ if (!rbOffsetArray)
613
+ {
614
+ rbOffsetEntries = 0 ;
615
+ systemPrintln (" ERROR: Failed to allocate the ring buffer!" );
616
+ }
617
+ else
618
+ {
619
+ ringBuffer = (uint8_t *)&rbOffsetArray[rbOffsetEntries];
620
+ rbOffsetArray[0 ] = 0 ;
621
+ if (pinUART2TaskHandle == nullptr )
622
+ xTaskCreatePinnedToCore (
623
+ pinUART2Task,
624
+ " UARTStart" , // Just for humans
625
+ 2000 , // Stack Size
626
+ nullptr , // Task input parameter
627
+ 0 , // Priority, with 3 (configMAX_PRIORITIES - 1) being the highest, and 0 being the lowest
628
+ &pinUART2TaskHandle, // Task handle
629
+ settings.gnssUartInterruptsCore ); // Core where task should run, 0=core, 1=Arduino
630
+
631
+ while (uart2pinned == false ) // Wait for task to run once
632
+ delay (1 );
633
+ }
566
634
}
567
635
568
636
// Assign UART2 interrupts to the core that started the task. See:
@@ -877,7 +945,7 @@ void beginInterrupts()
877
945
pinMode (pin_Ethernet_Interrupt, INPUT_PULLUP); // Prepare the interrupt pin
878
946
attachInterrupt (pin_Ethernet_Interrupt, ethernetISR, FALLING); // Attach the interrupt
879
947
}
880
- #endif // COMPILE_ETHERNET
948
+ #endif // COMPILE_ETHERNET
881
949
}
882
950
883
951
// Set LEDs for output and configure PWM
@@ -981,7 +1049,7 @@ void beginSystemState()
981
1049
if (systemState > STATE_NOT_SET)
982
1050
{
983
1051
systemPrintln (" Unknown state - factory reset" );
984
- factoryReset (false ); // We do not have the SD semaphore
1052
+ factoryReset (false ); // We do not have the SD semaphore
985
1053
}
986
1054
987
1055
if (productVariant == RTK_SURVEYOR)
@@ -1002,6 +1070,7 @@ void beginSystemState()
1002
1070
systemState = STATE_ROVER_NOT_STARTED; // Assume Rover. ButtonCheckTask() will correct as needed.
1003
1071
1004
1072
setupBtn = new Button (pin_setupButton); // Create the button in memory
1073
+ // Allocation failure handled in ButtonCheckTask
1005
1074
}
1006
1075
else if (productVariant == RTK_EXPRESS || productVariant == RTK_EXPRESS_PLUS)
1007
1076
{
@@ -1020,8 +1089,10 @@ void beginSystemState()
1020
1089
1021
1090
setupBtn = new Button (pin_setupButton); // Create the button in memory
1022
1091
powerBtn = new Button (pin_powerSenseAndControl); // Create the button in memory
1092
+ // Allocation failures handled in ButtonCheckTask
1023
1093
}
1024
- else if (productVariant == RTK_FACET || productVariant == RTK_FACET_LBAND)
1094
+ else if (productVariant == RTK_FACET || productVariant == RTK_FACET_LBAND ||
1095
+ productVariant == RTK_FACET_LBAND_DIRECT)
1025
1096
{
1026
1097
if (settings.lastState == STATE_NOT_SET) // Default
1027
1098
{
@@ -1041,6 +1112,7 @@ void beginSystemState()
1041
1112
firstRoverStart = false ;
1042
1113
1043
1114
powerBtn = new Button (pin_powerSenseAndControl); // Create the button in memory
1115
+ // Allocation failure handled in ButtonCheckTask
1044
1116
}
1045
1117
else if (productVariant == REFERENCE_STATION)
1046
1118
{
@@ -1055,6 +1127,7 @@ void beginSystemState()
1055
1127
.lastState ; // Return to either NTP, Base or Rover Not Started. The last state previous to power down.
1056
1128
1057
1129
setupBtn = new Button (pin_setupButton); // Create the button in memory
1130
+ // Allocation failure handled in ButtonCheckTask
1058
1131
}
1059
1132
1060
1133
// Starts task for monitoring button presses
0 commit comments