Skip to content

Commit c1305cc

Browse files
authored
Merge pull request #119 from sparkfun/release_candidate
Firmware release v2.2
2 parents c5c2947 + 4b10c8c commit c1305cc

15 files changed

+169
-76
lines changed

Binaries/OpenLog_Artemis-V10-v22.bin

359 KB
Binary file not shown.

Binaries/OpenLog_Artemis-X04-v22.bin

358 KB
Binary file not shown.

Firmware/OpenLog_Artemis/OpenLog_Artemis.ino

+30-15
Original file line numberDiff line numberDiff line change
@@ -13,10 +13,6 @@
1313
1414
The Board should be set to SparkFun Apollo3 \ RedBoard Artemis ATP.
1515
16-
Please note: this version of the firmware compiles on v2.1.0 of the Apollo3 boards.
17-
18-
(At the time of writing, data logging with the the u-blox ZED-F9P is problematic when using v2.1.1 of the core.)
19-
2016
v1.0 Power Consumption:
2117
Sleep between reads, RTC fully charged, no Qwiic, SD, no USB, no Power LED: 260uA
2218
10Hz logging IMU, no Qwiic, SD, no USB, no Power LED: 9-27mA
@@ -112,10 +108,27 @@
112108
(done) Add a fix for issue #109 - check if a BME280 is connected before calling multiplexerBegin: https://github.com/sparkfun/OpenLog_Artemis/issues/109
113109
(done) Correct issue #104. enableSD was redundant. The microSD power always needs to be on if there is a card inserted, otherwise the card pulls
114110
the SPI lines low, preventing communication with the IMU: https://github.com/sparkfun/OpenLog_Artemis/issues/104
111+
112+
v2.2:
113+
Use Apollo3 v2.2.1 with changes by paulvha to fix Issue 117 (Thank you Paul!)
114+
https://github.com/sparkfun/OpenLog_Artemis/issues/117#issuecomment-1085881142
115+
Also includes Paul's SPI.end fix
116+
https://github.com/sparkfun/Arduino_Apollo3/issues/442
117+
In libraries/SPI/src/SPI.cpp change end() to:
118+
void arduino::MbedSPI::end() {
119+
if (dev) {
120+
delete dev;
121+
dev = NULL;
122+
}
123+
}
124+
Use SdFat v2.1.2
125+
Compensate for missing / not-populated IMU
126+
Add support for yyyy/mm/dd and ISO 8601 date style (Issue 118)
127+
Add support for fractional time zone offsets
115128
*/
116129

117130
const int FIRMWARE_VERSION_MAJOR = 2;
118-
const int FIRMWARE_VERSION_MINOR = 1;
131+
const int FIRMWARE_VERSION_MINOR = 2;
119132

120133
//Define the OLA board identifier:
121134
// This is an int which is unique to this variant of the OLA and which allows us
@@ -125,7 +138,7 @@ const int FIRMWARE_VERSION_MINOR = 1;
125138
// the variant * 0x100 (OLA = 1; GNSS_LOGGER = 2; GEOPHONE_LOGGER = 3)
126139
// the major firmware version * 0x10
127140
// the minor firmware version
128-
#define OLA_IDENTIFIER 0x121 // Stored as 289 decimal in OLA_settings.txt
141+
#define OLA_IDENTIFIER 0x122 // Stored as 290 decimal in OLA_settings.txt
129142

130143
#include "settings.h"
131144

@@ -192,7 +205,7 @@ TwoWire qwiic(PIN_QWIIC_SDA,PIN_QWIIC_SCL); //Will use pads 8/9
192205
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
193206
#include <SPI.h>
194207

195-
#include <SdFat.h> //SdFat v2.0.7 by Bill Greiman: http://librarymanager/All#SdFat_exFAT
208+
#include <SdFat.h> //SdFat by Bill Greiman: http://librarymanager/All#SdFat_exFAT
196209

197210
#define SD_FAT_TYPE 3 // SD_FAT_TYPE = 0 for SdFat/File, 1 for FAT16/FAT32, 2 for exFAT, 3 for FAT16/FAT32 and exFAT.
198211
#define SD_CONFIG SdSpiConfig(PIN_MICROSD_CHIP_SELECT, SHARED_SPI, SD_SCK_MHZ(24)) // 24MHz
@@ -448,7 +461,7 @@ void setup() {
448461
else SerialPrintln(F("Serial logging offline"));
449462

450463
if (online.IMU == true) SerialPrintln(F("IMU online"));
451-
else SerialPrintln(F("IMU offline"));
464+
else SerialPrintln(F("IMU offline - or not present"));
452465

453466
if (settings.logMaxRate == true) SerialPrintln(F("Logging analog pins at max data rate"));
454467

@@ -480,7 +493,7 @@ void setup() {
480493

481494
//If we are sleeping between readings then we cannot rely on millis() as it is powered down
482495
//Use RTC instead
483-
measurementStartTime = bestMillis();
496+
measurementStartTime = rtcMillis();
484497

485498
digitalWrite(PIN_STAT_LED, LOW); // Turn the STAT LED off now that everything is configured
486499

@@ -547,12 +560,12 @@ void loop() {
547560

548561
//If we are sleeping between readings then we cannot rely on millis() as it is powered down
549562
//Use RTC instead
550-
lastSeriaLogSyncTime = bestMillis(); //Reset the last sync time to now
563+
lastSeriaLogSyncTime = rtcMillis(); //Reset the last sync time to now
551564
newSerialData = true;
552565
}
553566
else if (newSerialData == true)
554567
{
555-
if ((bestMillis() - lastSeriaLogSyncTime) > MAX_IDLE_TIME_MSEC) //If we haven't received any characters recently then sync log file
568+
if ((rtcMillis() - lastSeriaLogSyncTime) > MAX_IDLE_TIME_MSEC) //If we haven't received any characters recently then sync log file
556569
{
557570
if (incomingBufferSpot > 0)
558571
{
@@ -568,7 +581,7 @@ void loop() {
568581
}
569582

570583
newSerialData = false;
571-
lastSeriaLogSyncTime = bestMillis(); //Reset the last sync time to now
584+
lastSeriaLogSyncTime = rtcMillis(); //Reset the last sync time to now
572585
printDebug("Total chars received: " + (String)charsReceived + "\r\n");
573586
}
574587
}
@@ -660,9 +673,9 @@ void loop() {
660673
}
661674

662675
//Force sync every 500ms
663-
if (bestMillis() - lastDataLogSyncTime > 500)
676+
if (rtcMillis() - lastDataLogSyncTime > 500)
664677
{
665-
lastDataLogSyncTime = bestMillis();
678+
lastDataLogSyncTime = rtcMillis();
666679
sensorDataFile.sync();
667680
if (settings.frequentFileAccessTimestamps == true)
668681
updateDataFileAccess(&sensorDataFile); // Update the file access time & date
@@ -719,7 +732,7 @@ void loop() {
719732
{
720733
// Check if we have been awake long enough (millis is reset to zero when waking from sleep)
721734
// goToSleep will automatically compensate for how long we have been awake
722-
if ((bestMillis() - lastAwakeTimeMillis) < settings.minimumAwakeTimeMillis)
735+
if ((rtcMillis() - lastAwakeTimeMillis) < settings.minimumAwakeTimeMillis)
723736
return; // Too early to sleep - leave sleepAfterRead set true
724737
}
725738

@@ -1233,6 +1246,7 @@ void beginDataLogging()
12331246
}
12341247

12351248
updateDataFileCreate(&sensorDataFile); // Update the file create time & date
1249+
sensorDataFile.sync();
12361250

12371251
online.dataLogging = true;
12381252
}
@@ -1257,6 +1271,7 @@ void beginSerialLogging()
12571271
}
12581272

12591273
updateDataFileCreate(&serialDataFile); // Update the file create time & date
1274+
serialDataFile.sync();
12601275

12611276
//We need to manually restore the Serial1 TX and RX pins
12621277
configureSerial1TxRx();

Firmware/OpenLog_Artemis/Sensors.ino

+12-6
Original file line numberDiff line numberDiff line change
@@ -188,7 +188,7 @@ void getData()
188188

189189
//If we are sleeping between readings then we cannot rely on millis() as it is powered down
190190
//Use RTC instead
191-
currentMillis = bestMillis();
191+
currentMillis = rtcMillis();
192192
float actualRate;
193193
if ((currentMillis - measurementStartTime) < 1) // Avoid divide by zero
194194
actualRate = 0.0;
@@ -278,7 +278,7 @@ void gatherDeviceValues()
278278
setQwiicPullups(0); //Disable pullups to minimize CRC issues
279279

280280
SFE_UBLOX_GNSS *nodeDevice = (SFE_UBLOX_GNSS *)temp->classPtr;
281-
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
281+
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;
282282

283283
if (nodeSetting->log == true)
284284
{
@@ -299,12 +299,18 @@ void gatherDeviceValues()
299299
else
300300
sprintf(gnssMonthStr, "%d", gnssMonth);
301301
sprintf(gnssYearStr, "%d", gnssYear);
302-
if (settings.americanDateStyle == true)
302+
if (settings.dateStyle == 0)
303303
{
304304
sprintf(tempData, "%s/%s/%s,", gnssMonthStr, gnssDayStr, gnssYearStr);
305305
}
306-
else
306+
else if (settings.dateStyle == 1)
307+
{
307308
sprintf(tempData, "%s/%s/%s,", gnssDayStr, gnssMonthStr, gnssYearStr);
309+
}
310+
else // if (settings.dateStyle == 2)
311+
{
312+
sprintf(tempData, "%s/%s/%s,", gnssYearStr, gnssMonthStr, gnssDayStr);
313+
}
308314
strcat(outputData, tempData);
309315
}
310316
if (nodeSetting->logTime)
@@ -1182,7 +1188,7 @@ void printHelperText(bool terminalOnly)
11821188
break;
11831189
case DEVICE_GPS_UBLOX:
11841190
{
1185-
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
1191+
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;
11861192
if (nodeSetting->log)
11871193
{
11881194
if (nodeSetting->logDate)
@@ -1566,7 +1572,7 @@ void setMaxI2CSpeed()
15661572
if (temp->deviceType == DEVICE_GPS_UBLOX)
15671573
{
15681574
//Check if i2cSpeed is lowered
1569-
struct_uBlox *sensor = (struct_uBlox*)temp->configPtr;
1575+
struct_ublox *sensor = (struct_ublox*)temp->configPtr;
15701576
if (sensor->i2cSpeed == 100000)
15711577
{
15721578
//printDebug("setMaxI2CSpeed: sensor->i2cSpeed is 100000. Reducing maxSpeed to 100kHz\r\n");

Firmware/OpenLog_Artemis/autoDetect.ino

+4-4
Original file line numberDiff line numberDiff line change
@@ -138,7 +138,7 @@ bool addDevice(deviceType_e deviceType, uint8_t address, uint8_t muxAddress, uin
138138
case DEVICE_GPS_UBLOX:
139139
{
140140
temp->classPtr = new SFE_UBLOX_GNSS;
141-
temp->configPtr = new struct_uBlox;
141+
temp->configPtr = new struct_ublox;
142142
}
143143
break;
144144
case DEVICE_PROXIMITY_VCNL4040:
@@ -351,7 +351,7 @@ bool beginQwiicDevices()
351351
{
352352
setQwiicPullups(0); //Disable pullups for u-blox comms.
353353
SFE_UBLOX_GNSS *tempDevice = (SFE_UBLOX_GNSS *)temp->classPtr;
354-
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr; //Create a local pointer that points to same spot as node does
354+
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr; //Create a local pointer that points to same spot as node does
355355
if (nodeSetting->powerOnDelayMillis > qwiicPowerOnDelayMillis) qwiicPowerOnDelayMillis = nodeSetting->powerOnDelayMillis; // Increase qwiicPowerOnDelayMillis if required
356356
if(settings.printGNSSDebugMessages == true) tempDevice->enableDebugging(); // Enable debug messages if required
357357
temp->online = tempDevice->begin(qwiic, temp->address); //Wire port, Address
@@ -661,7 +661,7 @@ void configureDevice(node * temp)
661661
setQwiicPullups(0); //Disable pullups for u-blox comms.
662662

663663
SFE_UBLOX_GNSS *sensor = (SFE_UBLOX_GNSS *)temp->classPtr;
664-
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
664+
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;
665665

666666
sensor->setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
667667

@@ -882,7 +882,7 @@ FunctionPointer getConfigFunctionPtr(uint8_t nodeNumber)
882882
ptr = (FunctionPointer)menuConfigure_VL53L1X;
883883
break;
884884
case DEVICE_GPS_UBLOX:
885-
ptr = (FunctionPointer)menuConfigure_uBlox;
885+
ptr = (FunctionPointer)menuConfigure_ublox;
886886
break;
887887
case DEVICE_PROXIMITY_VCNL4040:
888888
ptr = (FunctionPointer)menuConfigure_VCNL4040;

Firmware/OpenLog_Artemis/lowerPower.ino

+16-10
Original file line numberDiff line numberDiff line change
@@ -322,6 +322,11 @@ void goToSleep(uint32_t sysTicksToSleep)
322322
{
323323
am_hal_gpio_pinconfig(48 , g_AM_HAL_GPIO_DISABLE); //TX0
324324
am_hal_gpio_pinconfig(49 , g_AM_HAL_GPIO_DISABLE); //RX0
325+
if (settings.useTxRxPinsForTerminal == true)
326+
{
327+
am_hal_gpio_pinconfig(12 , g_AM_HAL_GPIO_DISABLE); //TX1
328+
am_hal_gpio_pinconfig(13 , g_AM_HAL_GPIO_DISABLE); //RX1
329+
}
325330
}
326331

327332
//Make sure PIN_POWER_LOSS is configured as an input for the WDT
@@ -438,13 +443,11 @@ void wakeFromSleep()
438443
am_hal_gpio_pincfg_t intPinConfig = g_AM_HAL_GPIO_INPUT_PULLUP;
439444
if (settings.fallingEdgeTrigger == true)
440445
{
441-
SerialPrintln(F("Falling-edge triggering is enabled. Sensor data will be logged on a falling edge on GPIO pin 11."));
442446
attachInterrupt(PIN_TRIGGER, triggerPinISR, FALLING); // Enable the interrupt
443447
intPinConfig.eIntDir = AM_HAL_GPIO_PIN_INTDIR_HI2LO;
444448
}
445449
else
446450
{
447-
SerialPrintln(F("Rising-edge triggering is enabled. Sensor data will be logged on a rising edge on GPIO pin 11."));
448451
attachInterrupt(PIN_TRIGGER, triggerPinISR, RISING); // Enable the interrupt
449452
intPinConfig.eIntDir = AM_HAL_GPIO_PIN_INTDIR_LO2HI;
450453
}
@@ -469,6 +472,10 @@ void wakeFromSleep()
469472
{
470473
pin_config(PinName(48), g_AM_BSP_GPIO_COM_UART_TX);
471474
pin_config(PinName(49), g_AM_BSP_GPIO_COM_UART_RX);
475+
if (settings.useTxRxPinsForTerminal == true)
476+
{
477+
configureSerial1TxRx();
478+
}
472479
}
473480

474481
//Re-enable CIPO, COPI, SCK and the chip selects but may as well leave ICM_INT disabled
@@ -486,9 +493,6 @@ void wakeFromSleep()
486493

487494
if (settings.useTxRxPinsForTerminal == true)
488495
{
489-
//We may need to manually restore the Serial1 TX and RX pins?
490-
configureSerial1TxRx();
491-
492496
Serial1.begin(settings.serialTerminalBaudRate); // Start the serial port
493497
}
494498

@@ -557,11 +561,13 @@ void waitForQwiicBusPowerDelay() // Wait while the qwiic devices power up
557561
//Depending on what hardware is configured, the Qwiic bus may have only been turned on a few ms ago
558562
//Give sensors, specifically those with a low I2C address, time to turn on
559563
// If we're not using the SD card, everything will have happened much quicker than usual.
560-
uint64_t qwiicPowerHasBeenOnFor = bestMillis() - qwiicPowerOnTime;
561-
if (qwiicPowerHasBeenOnFor < qwiicPowerOnDelayMillis)
564+
uint64_t qwiicPowerHasBeenOnFor = rtcMillis() - qwiicPowerOnTime;
565+
printDebug("waitForQwiicBusPowerDelay: qwiicPowerHasBeenOnFor " + (String)((unsigned long)qwiicPowerHasBeenOnFor) + "ms\r\n");
566+
if (qwiicPowerHasBeenOnFor < (uint64_t)qwiicPowerOnDelayMillis)
562567
{
563-
unsigned long delayFor = qwiicPowerOnDelayMillis - qwiicPowerHasBeenOnFor;
564-
for (unsigned long i = 0; i < delayFor; i++)
568+
uint64_t delayFor = (uint64_t)qwiicPowerOnDelayMillis - qwiicPowerHasBeenOnFor;
569+
printDebug("waitForQwiicBusPowerDelay: delaying for " + (String)((unsigned long)delayFor) + "\r\n");
570+
for (uint64_t i = 0; i < delayFor; i++)
565571
{
566572
checkBattery();
567573
delay(1);
@@ -579,7 +585,7 @@ void qwiicPowerOn()
579585
digitalWrite(PIN_QWIIC_POWER, HIGH);
580586
#endif
581587

582-
qwiicPowerOnTime = bestMillis(); //Record this time so we wait enough time before detecting certain sensors
588+
qwiicPowerOnTime = rtcMillis(); //Record this time so we wait enough time before detecting certain sensors
583589
}
584590
void qwiicPowerOff()
585591
{

Firmware/OpenLog_Artemis/menuAttachedDevices.ino

+5-5
Original file line numberDiff line numberDiff line change
@@ -961,14 +961,14 @@ void menuConfigure_NAU7802(void *configPtr)
961961
}
962962
}
963963

964-
void menuConfigure_uBlox(void *configPtr)
964+
void menuConfigure_ublox(void *configPtr)
965965
{
966-
struct_uBlox *sensorSetting = (struct_uBlox*)configPtr;
966+
struct_ublox *sensorSetting = (struct_ublox*)configPtr;
967967

968968
while (1)
969969
{
970970
SerialPrintln(F(""));
971-
SerialPrintln(F("Menu: Configure uBlox GPS Receiver"));
971+
SerialPrintln(F("Menu: Configure u-blox GPS Receiver"));
972972

973973
SerialPrint(F("1) Sensor Logging: "));
974974
if (sensorSetting->log == true) SerialPrintln(F("Enabled"));
@@ -1137,7 +1137,7 @@ void getUbloxDateTime(int &year, int &month, int &day, int &hour, int &minute, i
11371137
setQwiicPullups(0); //Disable pullups to minimize CRC issues
11381138

11391139
SFE_UBLOX_GNSS *nodeDevice = (SFE_UBLOX_GNSS *)temp->classPtr;
1140-
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
1140+
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;
11411141

11421142
//If autoPVT is enabled, flush the data to make sure we get fresh date and time
11431143
if (nodeSetting->useAutoPVT) nodeDevice->flushPVT();
@@ -1175,7 +1175,7 @@ void gnssFactoryDefault(void)
11751175
setQwiicPullups(0); //Disable pullups to minimize CRC issues
11761176

11771177
SFE_UBLOX_GNSS *nodeDevice = (SFE_UBLOX_GNSS *)temp->classPtr;
1178-
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
1178+
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;
11791179

11801180
//Reset the module to the factory defaults
11811181
nodeDevice->factoryDefault();

Firmware/OpenLog_Artemis/menuMain.ino

+4-3
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,8 @@ void menuMain()
1212

1313
SerialPrintln(F("2) Configure Time Stamp"));
1414

15-
SerialPrintln(F("3) Configure IMU Logging"));
15+
if (online.IMU)
16+
SerialPrintln(F("3) Configure IMU Logging"));
1617

1718
if (settings.useTxRxPinsForTerminal == false)
1819
SerialPrintln(F("4) Configure Serial Logging"));
@@ -42,7 +43,7 @@ void menuMain()
4243
menuLogRate();
4344
else if (incoming == '2')
4445
menuTimeStamp();
45-
else if (incoming == '3')
46+
else if ((incoming == '3') && (online.IMU))
4647
restartIMU = menuIMU();
4748
else if ((incoming == '4') && (settings.useTxRxPinsForTerminal == false))
4849
menuSerialLogging();
@@ -175,7 +176,7 @@ void menuMain()
175176
totalCharactersPrinted = 0;
176177
//If we are sleeping between readings then we cannot rely on millis() as it is powered down
177178
//Use RTC instead
178-
measurementStartTime = bestMillis();
179+
measurementStartTime = rtcMillis();
179180

180181
//Edge case: after 10Hz reading, user sets the log rate above 2s mark. We never go to sleep because
181182
//takeReading is not true. And since we don't wake up, takeReading never gets set to true.

0 commit comments

Comments
 (0)