Skip to content

Commit 15455bd

Browse files
authored
Merge pull request #143 from sparkfun/release_candidate
v2.0 Release
2 parents 428f063 + d9bd587 commit 15455bd

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

49 files changed

+7532
-992
lines changed
1.86 MB
Binary file not shown.

Binaries/readme.md

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,17 @@
1-
This folder contains the various firmware versions for RTK Products (Surveyor, Express, Express+, and Facet). Each binary is created by exporting a sketch binary from Arduino. The sketch binary is then uploaded to the ESP32 along with boot_app0.bin, RTK_Surveyor.ino.bootloader.bin, and RTK_Surveyor.ino.partitions.bin. You can update the firmware on a device by loading a binary onto the SD card and inserting it into the RTK Surveyor (see more information [here](https://learn.sparkfun.com/tutorials/sparkfun-rtk-surveyor-hookup-guide/firmware-updates-and-customization)) or by using the following CLI:
1+
This folder contains the various firmware versions for RTK Products (Surveyor, Express, Express+, and Facet).
2+
3+
Updating the firmware can be achieved by using one of the following methods:
4+
5+
* Load the firmware on an SD card, then use a serial terminal with *Firmware Upgrade* menu
6+
* Load the firmware over WiFi when the device is in WiFi AP Config Mode
7+
* Use the [Windows GUI](https://github.com/sparkfun/SparkFun_RTK_Firmware/Uploader_GUI) and a USB cable. (This method is python based which can also be used on Linux, Mac OS, and Raspberry Pi)
8+
* Use the command line *batch_program.bat* (see below)
9+
10+
The SD method is generally recommended. For more information see [here](https://learn.sparkfun.com/tutorials/sparkfun-rtk-surveyor-hookup-guide/firmware-updates-and-customization).
11+
12+
Each binary is created by exporting a sketch binary from Arduino. The sketch binary is then uploaded to the ESP32 along with boot_app0.bin, RTK_Surveyor.ino.bootloader.bin, and RTK_Surveyor.ino.partitions.bin. You can update the firmware on a device by loading a binary onto the SD card and inserting it into the RTK Surveyor ) or by using the included 'batch_program.bat' along with the binary file name and COM port. For example *batch_program.bat RTK_Surveyor_Firmware_v2_0.bin COM3*.
13+
14+
The batch file runs the following commands:
215

316
esptool.exe --chip esp32 --port COM4 --baud 921600 --before default_reset --after hard_reset write_flash -z --flash_mode dio --flash_freq 80m --flash_size detect 0x1000 ./bin/RTK_Surveyor.ino.bootloader.bin 0x8000 ./bin/RTK_Surveyor.ino.partitions.bin 0xe000 ./bin/boot_app0.bin 0x10000 ./RTK_Surveyor_Firmware_vxx.bin
417

Firmware/RTK_Surveyor/Base.ino

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ bool configureUbloxModuleBase()
77
int maxWait = 2000;
88

99
//If our settings haven't changed, and this is first config since power on, trust ZED's settings
10-
if (updateZEDSettings == false && firstPowerOn == true)
10+
if (settings.updateZEDSettings == false && firstPowerOn == true)
1111
{
1212
firstPowerOn = false; //Next time user switches modes, new settings will be applied
1313
log_d("Skipping ZED Base configuration");

Firmware/RTK_Surveyor/Begin.ino

Lines changed: 129 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,17 @@ void beginBoard()
66
{
77
//Use ADC to check 50% resistor divider
88
int pin_adc_rtk_facet = 35;
9-
if (analogReadMilliVolts(pin_adc_rtk_facet) > (3300 / 2 * 0.9) && analogReadMilliVolts(pin_adc_rtk_facet) < (3300 / 2 * 1.1))
9+
uint16_t idValue = analogReadMilliVolts(pin_adc_rtk_facet);
10+
log_d("Board ADC ID: %d", idValue);
11+
12+
if (idValue > (3300 / 2 * 0.9) && idValue < (3300 / 2 * 1.1))
1013
{
1114
productVariant = RTK_FACET;
1215
}
16+
else if (idValue > (3300 * 2 / 3 * 0.9) && idValue < (3300 * 2 / 3 * 1.1))
17+
{
18+
productVariant = RTK_FACET_LBAND;
19+
}
1320
else if (isConnected(0x19) == true) //Check for accelerometer
1421
{
1522
if (zedModuleType == PLATFORM_F9P) productVariant = RTK_EXPRESS;
@@ -77,7 +84,7 @@ void beginBoard()
7784
strcpy(platformPrefix, "Express Plus");
7885
}
7986
}
80-
else if (productVariant == RTK_FACET)
87+
else if (productVariant == RTK_FACET || productVariant == RTK_FACET_LBAND)
8188
{
8289
//v11
8390
pin_muxA = 2;
@@ -113,12 +120,24 @@ void beginBoard()
113120
pinMode(pin_radio_cts, OUTPUT);
114121
digitalWrite(pin_radio_cts, LOW);
115122

116-
strcpy(platformFilePrefix, "SFE_Facet");
117-
strcpy(platformPrefix, "Facet");
123+
if (productVariant == RTK_FACET)
124+
{
125+
strcpy(platformFilePrefix, "SFE_Facet");
126+
strcpy(platformPrefix, "Facet");
127+
}
128+
else if (productVariant == RTK_FACET_LBAND)
129+
{
130+
strcpy(platformFilePrefix, "SFE_Facet_LBand");
131+
strcpy(platformPrefix, "Facet L-Band");
132+
}
118133
}
119134

120135
Serial.printf("SparkFun RTK %s v%d.%d-%s\r\n", platformPrefix, FIRMWARE_VERSION_MAJOR, FIRMWARE_VERSION_MINOR, __DATE__);
121136

137+
//Get unit MAC address
138+
esp_read_mac(unitMACAddress, ESP_MAC_WIFI_STA);
139+
unitMACAddress[5] += 2; //Convert MAC address to Bluetooth MAC (add 2): https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/system/system.html#mac-address
140+
122141
//For all boards, check reset reason. If reset was due to wdt or panic, append last log
123142
if (esp_reset_reason() == ESP_RST_POWERON)
124143
{
@@ -139,8 +158,8 @@ void beginBoard()
139158
if (settings.enableResetDisplay == true)
140159
{
141160
settings.resetCount++;
142-
recordSystemSettings(); //Record to NVM
143161
Serial.printf("resetCount: %d\n\r", settings.resetCount);
162+
recordSystemSettings(); //Record to NVM
144163
}
145164

146165
Serial.print("Reset reason: ");
@@ -222,11 +241,11 @@ void beginSD()
222241
}
223242

224243
//Setup FAT file access semaphore
225-
if (xFATSemaphore == NULL)
244+
if (sdCardSemaphore == NULL)
226245
{
227-
xFATSemaphore = xSemaphoreCreateMutex();
228-
if (xFATSemaphore != NULL)
229-
xSemaphoreGive(xFATSemaphore); //Make the file system available for use
246+
sdCardSemaphore = xSemaphoreCreateMutex();
247+
if (sdCardSemaphore != NULL)
248+
xSemaphoreGive(sdCardSemaphore); //Make the file system available for use
230249
}
231250

232251
if (createTestFile() == false)
@@ -320,16 +339,14 @@ void stopUART2Tasks()
320339

321340
void beginFS()
322341
{
323-
#define FORMAT_LITTLEFS_IF_FAILED true
324-
325342
if (online.fs == false)
326343
{
327-
Serial.println("Starting FS");
328-
329-
if (!LittleFS.begin(FORMAT_LITTLEFS_IF_FAILED)) {
344+
if (!LittleFS.begin(true)) //Format LittleFS if begin fails
345+
{
330346
log_d("Error: LittleFS not online");
331347
return;
332348
}
349+
Serial.println("LittleFS Started");
333350
online.fs = true;
334351
}
335352
}
@@ -350,7 +367,7 @@ void beginDisplay()
350367
{
351368
Serial.println(F("Display not detected"));
352369
}
353-
else if (productVariant == RTK_EXPRESS || productVariant == RTK_EXPRESS_PLUS || productVariant == RTK_FACET)
370+
else if (productVariant == RTK_EXPRESS || productVariant == RTK_EXPRESS_PLUS || productVariant == RTK_FACET || productVariant == RTK_FACET_LBAND)
354371
{
355372
Serial.println(F("Display Error: Not detected."));
356373
}
@@ -401,19 +418,25 @@ void beginGNSS()
401418
zedFirmwareVersionInt = 121;
402419
else if (strstr(zedFirmwareVersion, "1.30") != NULL) //ZED-F9P released Dec, 2021
403420
zedFirmwareVersionInt = 130;
421+
else if (strstr(zedFirmwareVersion, "1.32") != NULL) //ZED-F9P released May, 2022
422+
zedFirmwareVersionInt = 132;
404423
else
424+
{
405425
Serial.printf("Unknown firmware version: %s\n\r", zedFirmwareVersion);
426+
zedFirmwareVersionInt = 99; //0.99 invalid firmware version
427+
}
406428

407429
//Determine if we have a ZED-F9P (Express/Facet) or an ZED-F9R (Express Plus/Facet Plus)
408430
if (strstr(i2cGNSS.minfo.extension[3], "ZED-F9P") != NULL)
409-
{
410431
zedModuleType = PLATFORM_F9P;
411-
}
412432
else if (strstr(i2cGNSS.minfo.extension[3], "ZED-F9R") != NULL)
413-
{
414433
zedModuleType = PLATFORM_F9R;
434+
else
435+
{
436+
Serial.printf("Unknown ZED module: %s\n\r", i2cGNSS.minfo.extension[3]);
437+
zedModuleType = PLATFORM_F9P;
415438
}
416-
439+
417440
printModuleInfo(); //Print module type and firmware version
418441
}
419442

@@ -429,7 +452,7 @@ void configureGNSS()
429452
//Configuring the ZED can take more than 2000ms. We save configuration to
430453
//ZED so there is no need to update settings unless user has modified
431454
//the settings file or internal settings.
432-
if (updateZEDSettings == false)
455+
if (settings.updateZEDSettings == false)
433456
{
434457
log_d("Skipping ZED configuration");
435458
return;
@@ -549,16 +572,22 @@ void beginSystemState()
549572
{
550573
//If the rocker switch was moved while off, force module settings
551574
//When switch is set to '1' = BASE, pin will be shorted to ground
552-
if (settings.lastState == STATE_ROVER_NOT_STARTED && digitalRead(pin_setupButton) == LOW) updateZEDSettings = true;
553-
else if (settings.lastState == STATE_BASE_NOT_STARTED && digitalRead(pin_setupButton) == HIGH) updateZEDSettings = true;
575+
if (settings.lastState == STATE_ROVER_NOT_STARTED && digitalRead(pin_setupButton) == LOW) settings.updateZEDSettings = true;
576+
else if (settings.lastState == STATE_BASE_NOT_STARTED && digitalRead(pin_setupButton) == HIGH) settings.updateZEDSettings = true;
554577

555-
systemState = STATE_ROVER_NOT_STARTED; //Assume Rover. ButtonCheckTask() will correct as needed.
578+
if (online.lband == false)
579+
systemState = STATE_ROVER_NOT_STARTED; //Assume Rover. ButtonCheckTask() will correct as needed.
580+
else
581+
systemState = STATE_KEYS_STARTED; //Begin process for getting new keys
556582

557583
setupBtn = new Button(pin_setupButton); //Create the button in memory
558584
}
559585
else if (productVariant == RTK_EXPRESS || productVariant == RTK_EXPRESS_PLUS)
560586
{
561-
systemState = settings.lastState; //Return to system state previous to power down.
587+
if (online.lband == false)
588+
systemState = settings.lastState; //Return to either Rover or Base Not Started. The last state previous to power down.
589+
else
590+
systemState = STATE_KEYS_STARTED; //Begin process for getting new keys
562591

563592
if (systemState > STATE_SHUTDOWN)
564593
{
@@ -569,18 +598,20 @@ void beginSystemState()
569598
setupBtn = new Button(pin_setupButton); //Create the button in memory
570599
powerBtn = new Button(pin_powerSenseAndControl); //Create the button in memory
571600
}
572-
else if (productVariant == RTK_FACET)
601+
else if (productVariant == RTK_FACET || productVariant == RTK_FACET_LBAND)
573602
{
574-
systemState = settings.lastState; //Return to system state previous to power down.
603+
if (online.lband == false)
604+
systemState = settings.lastState; //Return to either Rover or Base Not Started. The last state previous to power down.
605+
else
606+
systemState = STATE_KEYS_STARTED; //Begin process for getting new keys
575607

576608
if (systemState > STATE_SHUTDOWN)
577609
{
578610
Serial.println("Unknown state - factory reset");
579611
factoryReset();
580612
}
581613

582-
if (systemState == STATE_ROVER_NOT_STARTED)
583-
firstRoverStart = true; //Allow user to enter test screen during first rover start
614+
firstRoverStart = true; //Allow user to enter test screen during first rover start
584615

585616
powerBtn = new Button(pin_powerSenseAndControl); //Create the button in memory
586617
}
@@ -603,7 +634,7 @@ bool beginExternalTriggers()
603634
if (online.gnss == false) return (false);
604635

605636
//If our settings haven't changed, trust ZED's settings
606-
if (updateZEDSettings == false)
637+
if (settings.updateZEDSettings == false)
607638
{
608639
log_d("Skipping ZED Trigger configuration");
609640
return (true);
@@ -644,3 +675,72 @@ bool beginExternalTriggers()
644675

645676
return (response);
646677
}
678+
679+
//Check if NEO-D9S is connected. Configure if available.
680+
void beginLBand()
681+
{
682+
if (i2cLBand.begin(Wire, 0x43) == false) //Connect to the u-blox NEO-D9S using Wire port. The D9S default I2C address is 0x43 (not 0x42)
683+
{
684+
log_d("L-Band not detected");
685+
return;
686+
}
687+
688+
if (online.gnss == true)
689+
{
690+
i2cGNSS.checkUblox(); //Regularly poll to get latest data and any RTCM
691+
i2cGNSS.checkCallbacks(); //Process any callbacks: ie, eventTriggerReceived
692+
}
693+
694+
//If we have a fix, check which frequency to use
695+
if (fixType == 2 || fixType == 3 || fixType == 4 || fixType == 5) //2D, 3D, 3D+DR, or Time
696+
{
697+
if ( (longitude > -125 && longitude < -67) && (latitude > -90 && latitude < 90))
698+
{
699+
log_d("Setting L-Band to US");
700+
settings.LBandFreq = 1556290000; //We are in US band
701+
}
702+
else if ( (longitude > -25 && longitude < 70) && (latitude > -90 && latitude < 90))
703+
{
704+
log_d("Setting L-Band to EU");
705+
settings.LBandFreq = 1545260000; //We are in EU band
706+
}
707+
else
708+
{
709+
Serial.println("Unknown band area");
710+
settings.LBandFreq = 1556290000; //Default to US
711+
}
712+
recordSystemSettings();
713+
}
714+
else
715+
log_d("No fix available for L-Band frequency determination");
716+
717+
bool response = true;
718+
response &= i2cLBand.setVal32(UBLOX_CFG_PMP_CENTER_FREQUENCY, settings.LBandFreq); // Default 1539812500 Hz
719+
response &= i2cLBand.setVal16(UBLOX_CFG_PMP_SEARCH_WINDOW, 2200); // Default 2200 Hz
720+
response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_SERVICE_ID, 0); // Default 1
721+
response &= i2cLBand.setVal16(UBLOX_CFG_PMP_SERVICE_ID, 21845); // Default 50821
722+
response &= i2cLBand.setVal16(UBLOX_CFG_PMP_DATA_RATE, 2400); // Default 2400 bps
723+
response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_DESCRAMBLER, 1); // Default 1
724+
response &= i2cLBand.setVal16(UBLOX_CFG_PMP_DESCRAMBLER_INIT, 26969); // Default 23560
725+
response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_PRESCRAMBLING, 0); // Default 0
726+
response &= i2cLBand.setVal64(UBLOX_CFG_PMP_UNIQUE_WORD, 16238547128276412563ull);
727+
response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_I2C, 1); // Ensure UBX-RXM-PMP is enabled on the I2C port
728+
response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_UART1, 1); // Output UBX-RXM-PMP on UART1
729+
response &= i2cLBand.setVal(UBLOX_CFG_UART2OUTPROT_UBX, 1); // Enable UBX output on UART2
730+
response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_UART2, 1); // Output UBX-RXM-PMP on UART2
731+
response &= i2cLBand.setVal32(UBLOX_CFG_UART1_BAUDRATE, 38400); // match baudrate with ZED default
732+
response &= i2cLBand.setVal32(UBLOX_CFG_UART2_BAUDRATE, 38400); // match baudrate with ZED default
733+
734+
if (response == false)
735+
Serial.println("L-Band failed to configure");
736+
737+
i2cLBand.softwareResetGNSSOnly(); // Do a restart
738+
739+
i2cLBand.setRXMPMPmessageCallbackPtr(&pushRXMPMP); // Call pushRXMPMP when new PMP data arrives. Push it to the GNSS
740+
741+
i2cGNSS.setRXMCORcallbackPtr(&checkRXMCOR); // Check if the PMP data is being decrypted successfully
742+
743+
log_d("L-Band online");
744+
745+
online.lband = true;
746+
}

Firmware/RTK_Surveyor/Buttons.ino

Lines changed: 12 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -3,22 +3,14 @@
33
//Let's make sure they continue to press for 500ms
44
void powerOnCheck()
55
{
6-
#ifdef ENABLE_DEVELOPER
7-
return;
8-
#endif
9-
106
powerPressedStartTime = millis();
7+
if (digitalRead(pin_powerSenseAndControl) == LOW)
8+
delay(500);
119

12-
while (digitalRead(pin_powerSenseAndControl) == LOW)
13-
{
14-
delay(10);
15-
16-
if (millis() - powerPressedStartTime > 500)
17-
break;
18-
}
19-
20-
if (millis() - powerPressedStartTime < 500)
10+
#ifndef ENABLE_DEVELOPER
11+
if (digitalRead(pin_powerSenseAndControl) != LOW)
2112
powerDown(false); //Power button tap. Returning to off state.
13+
#endif
2214

2315
powerPressedStartTime = 0; //Reset var to return to normal 'on' state
2416
}
@@ -31,13 +23,17 @@ void powerDown(bool displayInfo)
3123
{
3224
//Attempt to write to file system. This avoids collisions with file writing from other functions like recordSystemSettingsToFile()
3325
//Wait up to 1000ms
34-
if (xSemaphoreTake(xFATSemaphore, 1000 / portTICK_PERIOD_MS) == pdPASS)
26+
if (xSemaphoreTake(sdCardSemaphore, 1000 / portTICK_PERIOD_MS) == pdPASS)
3527
{
3628
//Close down file system
3729
ubxFile.sync();
3830
ubxFile.close();
39-
//xSemaphoreGive(xFATSemaphore); //Do not release semaphore
40-
} //End xFATSemaphore
31+
//xSemaphoreGive(sdCardSemaphore); //Do not release semaphore
32+
} //End sdCardSemaphore
33+
else
34+
{
35+
Serial.printf("sdCardSemaphore failed to yield, %s line %d\r\n", __FILE__, __LINE__);
36+
}
4137

4238
online.logging = false;
4339
}

0 commit comments

Comments
 (0)