Skip to content

Commit

Permalink
Merge pull request #119 from sparkfun/release_candidate
Browse files Browse the repository at this point in the history
Firmware release v2.2
  • Loading branch information
PaulZC authored Apr 8, 2022
2 parents c5c2947 + 4b10c8c commit c1305cc
Show file tree
Hide file tree
Showing 15 changed files with 169 additions and 76 deletions.
Binary file added Binaries/OpenLog_Artemis-V10-v22.bin
Binary file not shown.
Binary file added Binaries/OpenLog_Artemis-X04-v22.bin
Binary file not shown.
45 changes: 30 additions & 15 deletions Firmware/OpenLog_Artemis/OpenLog_Artemis.ino
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,6 @@
The Board should be set to SparkFun Apollo3 \ RedBoard Artemis ATP.
Please note: this version of the firmware compiles on v2.1.0 of the Apollo3 boards.
(At the time of writing, data logging with the the u-blox ZED-F9P is problematic when using v2.1.1 of the core.)
v1.0 Power Consumption:
Sleep between reads, RTC fully charged, no Qwiic, SD, no USB, no Power LED: 260uA
10Hz logging IMU, no Qwiic, SD, no USB, no Power LED: 9-27mA
Expand Down Expand Up @@ -112,10 +108,27 @@
(done) Add a fix for issue #109 - check if a BME280 is connected before calling multiplexerBegin: https://github.com/sparkfun/OpenLog_Artemis/issues/109
(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
the SPI lines low, preventing communication with the IMU: https://github.com/sparkfun/OpenLog_Artemis/issues/104
v2.2:
Use Apollo3 v2.2.1 with changes by paulvha to fix Issue 117 (Thank you Paul!)
https://github.com/sparkfun/OpenLog_Artemis/issues/117#issuecomment-1085881142
Also includes Paul's SPI.end fix
https://github.com/sparkfun/Arduino_Apollo3/issues/442
In libraries/SPI/src/SPI.cpp change end() to:
void arduino::MbedSPI::end() {
if (dev) {
delete dev;
dev = NULL;
}
}
Use SdFat v2.1.2
Compensate for missing / not-populated IMU
Add support for yyyy/mm/dd and ISO 8601 date style (Issue 118)
Add support for fractional time zone offsets
*/

const int FIRMWARE_VERSION_MAJOR = 2;
const int FIRMWARE_VERSION_MINOR = 1;
const int FIRMWARE_VERSION_MINOR = 2;

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

#include "settings.h"

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

#include <SdFat.h> //SdFat v2.0.7 by Bill Greiman: http://librarymanager/All#SdFat_exFAT
#include <SdFat.h> //SdFat by Bill Greiman: http://librarymanager/All#SdFat_exFAT

#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.
#define SD_CONFIG SdSpiConfig(PIN_MICROSD_CHIP_SELECT, SHARED_SPI, SD_SCK_MHZ(24)) // 24MHz
Expand Down Expand Up @@ -448,7 +461,7 @@ void setup() {
else SerialPrintln(F("Serial logging offline"));

if (online.IMU == true) SerialPrintln(F("IMU online"));
else SerialPrintln(F("IMU offline"));
else SerialPrintln(F("IMU offline - or not present"));

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

Expand Down Expand Up @@ -480,7 +493,7 @@ void setup() {

//If we are sleeping between readings then we cannot rely on millis() as it is powered down
//Use RTC instead
measurementStartTime = bestMillis();
measurementStartTime = rtcMillis();

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

Expand Down Expand Up @@ -547,12 +560,12 @@ void loop() {

//If we are sleeping between readings then we cannot rely on millis() as it is powered down
//Use RTC instead
lastSeriaLogSyncTime = bestMillis(); //Reset the last sync time to now
lastSeriaLogSyncTime = rtcMillis(); //Reset the last sync time to now
newSerialData = true;
}
else if (newSerialData == true)
{
if ((bestMillis() - lastSeriaLogSyncTime) > MAX_IDLE_TIME_MSEC) //If we haven't received any characters recently then sync log file
if ((rtcMillis() - lastSeriaLogSyncTime) > MAX_IDLE_TIME_MSEC) //If we haven't received any characters recently then sync log file
{
if (incomingBufferSpot > 0)
{
Expand All @@ -568,7 +581,7 @@ void loop() {
}

newSerialData = false;
lastSeriaLogSyncTime = bestMillis(); //Reset the last sync time to now
lastSeriaLogSyncTime = rtcMillis(); //Reset the last sync time to now
printDebug("Total chars received: " + (String)charsReceived + "\r\n");
}
}
Expand Down Expand Up @@ -660,9 +673,9 @@ void loop() {
}

//Force sync every 500ms
if (bestMillis() - lastDataLogSyncTime > 500)
if (rtcMillis() - lastDataLogSyncTime > 500)
{
lastDataLogSyncTime = bestMillis();
lastDataLogSyncTime = rtcMillis();
sensorDataFile.sync();
if (settings.frequentFileAccessTimestamps == true)
updateDataFileAccess(&sensorDataFile); // Update the file access time & date
Expand Down Expand Up @@ -719,7 +732,7 @@ void loop() {
{
// Check if we have been awake long enough (millis is reset to zero when waking from sleep)
// goToSleep will automatically compensate for how long we have been awake
if ((bestMillis() - lastAwakeTimeMillis) < settings.minimumAwakeTimeMillis)
if ((rtcMillis() - lastAwakeTimeMillis) < settings.minimumAwakeTimeMillis)
return; // Too early to sleep - leave sleepAfterRead set true
}

Expand Down Expand Up @@ -1233,6 +1246,7 @@ void beginDataLogging()
}

updateDataFileCreate(&sensorDataFile); // Update the file create time & date
sensorDataFile.sync();

online.dataLogging = true;
}
Expand All @@ -1257,6 +1271,7 @@ void beginSerialLogging()
}

updateDataFileCreate(&serialDataFile); // Update the file create time & date
serialDataFile.sync();

//We need to manually restore the Serial1 TX and RX pins
configureSerial1TxRx();
Expand Down
18 changes: 12 additions & 6 deletions Firmware/OpenLog_Artemis/Sensors.ino
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,7 @@ void getData()

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

SFE_UBLOX_GNSS *nodeDevice = (SFE_UBLOX_GNSS *)temp->classPtr;
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;

if (nodeSetting->log == true)
{
Expand All @@ -299,12 +299,18 @@ void gatherDeviceValues()
else
sprintf(gnssMonthStr, "%d", gnssMonth);
sprintf(gnssYearStr, "%d", gnssYear);
if (settings.americanDateStyle == true)
if (settings.dateStyle == 0)
{
sprintf(tempData, "%s/%s/%s,", gnssMonthStr, gnssDayStr, gnssYearStr);
}
else
else if (settings.dateStyle == 1)
{
sprintf(tempData, "%s/%s/%s,", gnssDayStr, gnssMonthStr, gnssYearStr);
}
else // if (settings.dateStyle == 2)
{
sprintf(tempData, "%s/%s/%s,", gnssYearStr, gnssMonthStr, gnssDayStr);
}
strcat(outputData, tempData);
}
if (nodeSetting->logTime)
Expand Down Expand Up @@ -1182,7 +1188,7 @@ void printHelperText(bool terminalOnly)
break;
case DEVICE_GPS_UBLOX:
{
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;
if (nodeSetting->log)
{
if (nodeSetting->logDate)
Expand Down Expand Up @@ -1566,7 +1572,7 @@ void setMaxI2CSpeed()
if (temp->deviceType == DEVICE_GPS_UBLOX)
{
//Check if i2cSpeed is lowered
struct_uBlox *sensor = (struct_uBlox*)temp->configPtr;
struct_ublox *sensor = (struct_ublox*)temp->configPtr;
if (sensor->i2cSpeed == 100000)
{
//printDebug("setMaxI2CSpeed: sensor->i2cSpeed is 100000. Reducing maxSpeed to 100kHz\r\n");
Expand Down
8 changes: 4 additions & 4 deletions Firmware/OpenLog_Artemis/autoDetect.ino
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ bool addDevice(deviceType_e deviceType, uint8_t address, uint8_t muxAddress, uin
case DEVICE_GPS_UBLOX:
{
temp->classPtr = new SFE_UBLOX_GNSS;
temp->configPtr = new struct_uBlox;
temp->configPtr = new struct_ublox;
}
break;
case DEVICE_PROXIMITY_VCNL4040:
Expand Down Expand Up @@ -351,7 +351,7 @@ bool beginQwiicDevices()
{
setQwiicPullups(0); //Disable pullups for u-blox comms.
SFE_UBLOX_GNSS *tempDevice = (SFE_UBLOX_GNSS *)temp->classPtr;
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr; //Create a local pointer that points to same spot as node does
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr; //Create a local pointer that points to same spot as node does
if (nodeSetting->powerOnDelayMillis > qwiicPowerOnDelayMillis) qwiicPowerOnDelayMillis = nodeSetting->powerOnDelayMillis; // Increase qwiicPowerOnDelayMillis if required
if(settings.printGNSSDebugMessages == true) tempDevice->enableDebugging(); // Enable debug messages if required
temp->online = tempDevice->begin(qwiic, temp->address); //Wire port, Address
Expand Down Expand Up @@ -661,7 +661,7 @@ void configureDevice(node * temp)
setQwiicPullups(0); //Disable pullups for u-blox comms.

SFE_UBLOX_GNSS *sensor = (SFE_UBLOX_GNSS *)temp->classPtr;
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;

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

Expand Down Expand Up @@ -882,7 +882,7 @@ FunctionPointer getConfigFunctionPtr(uint8_t nodeNumber)
ptr = (FunctionPointer)menuConfigure_VL53L1X;
break;
case DEVICE_GPS_UBLOX:
ptr = (FunctionPointer)menuConfigure_uBlox;
ptr = (FunctionPointer)menuConfigure_ublox;
break;
case DEVICE_PROXIMITY_VCNL4040:
ptr = (FunctionPointer)menuConfigure_VCNL4040;
Expand Down
26 changes: 16 additions & 10 deletions Firmware/OpenLog_Artemis/lowerPower.ino
Original file line number Diff line number Diff line change
Expand Up @@ -322,6 +322,11 @@ void goToSleep(uint32_t sysTicksToSleep)
{
am_hal_gpio_pinconfig(48 , g_AM_HAL_GPIO_DISABLE); //TX0
am_hal_gpio_pinconfig(49 , g_AM_HAL_GPIO_DISABLE); //RX0
if (settings.useTxRxPinsForTerminal == true)
{
am_hal_gpio_pinconfig(12 , g_AM_HAL_GPIO_DISABLE); //TX1
am_hal_gpio_pinconfig(13 , g_AM_HAL_GPIO_DISABLE); //RX1
}
}

//Make sure PIN_POWER_LOSS is configured as an input for the WDT
Expand Down Expand Up @@ -438,13 +443,11 @@ void wakeFromSleep()
am_hal_gpio_pincfg_t intPinConfig = g_AM_HAL_GPIO_INPUT_PULLUP;
if (settings.fallingEdgeTrigger == true)
{
SerialPrintln(F("Falling-edge triggering is enabled. Sensor data will be logged on a falling edge on GPIO pin 11."));
attachInterrupt(PIN_TRIGGER, triggerPinISR, FALLING); // Enable the interrupt
intPinConfig.eIntDir = AM_HAL_GPIO_PIN_INTDIR_HI2LO;
}
else
{
SerialPrintln(F("Rising-edge triggering is enabled. Sensor data will be logged on a rising edge on GPIO pin 11."));
attachInterrupt(PIN_TRIGGER, triggerPinISR, RISING); // Enable the interrupt
intPinConfig.eIntDir = AM_HAL_GPIO_PIN_INTDIR_LO2HI;
}
Expand All @@ -469,6 +472,10 @@ void wakeFromSleep()
{
pin_config(PinName(48), g_AM_BSP_GPIO_COM_UART_TX);
pin_config(PinName(49), g_AM_BSP_GPIO_COM_UART_RX);
if (settings.useTxRxPinsForTerminal == true)
{
configureSerial1TxRx();
}
}

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

if (settings.useTxRxPinsForTerminal == true)
{
//We may need to manually restore the Serial1 TX and RX pins?
configureSerial1TxRx();

Serial1.begin(settings.serialTerminalBaudRate); // Start the serial port
}

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

qwiicPowerOnTime = bestMillis(); //Record this time so we wait enough time before detecting certain sensors
qwiicPowerOnTime = rtcMillis(); //Record this time so we wait enough time before detecting certain sensors
}
void qwiicPowerOff()
{
Expand Down
10 changes: 5 additions & 5 deletions Firmware/OpenLog_Artemis/menuAttachedDevices.ino
Original file line number Diff line number Diff line change
Expand Up @@ -961,14 +961,14 @@ void menuConfigure_NAU7802(void *configPtr)
}
}

void menuConfigure_uBlox(void *configPtr)
void menuConfigure_ublox(void *configPtr)
{
struct_uBlox *sensorSetting = (struct_uBlox*)configPtr;
struct_ublox *sensorSetting = (struct_ublox*)configPtr;

while (1)
{
SerialPrintln(F(""));
SerialPrintln(F("Menu: Configure uBlox GPS Receiver"));
SerialPrintln(F("Menu: Configure u-blox GPS Receiver"));

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

SFE_UBLOX_GNSS *nodeDevice = (SFE_UBLOX_GNSS *)temp->classPtr;
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;

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

SFE_UBLOX_GNSS *nodeDevice = (SFE_UBLOX_GNSS *)temp->classPtr;
struct_uBlox *nodeSetting = (struct_uBlox *)temp->configPtr;
struct_ublox *nodeSetting = (struct_ublox *)temp->configPtr;

//Reset the module to the factory defaults
nodeDevice->factoryDefault();
Expand Down
7 changes: 4 additions & 3 deletions Firmware/OpenLog_Artemis/menuMain.ino
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,8 @@ void menuMain()

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

SerialPrintln(F("3) Configure IMU Logging"));
if (online.IMU)
SerialPrintln(F("3) Configure IMU Logging"));

if (settings.useTxRxPinsForTerminal == false)
SerialPrintln(F("4) Configure Serial Logging"));
Expand Down Expand Up @@ -42,7 +43,7 @@ void menuMain()
menuLogRate();
else if (incoming == '2')
menuTimeStamp();
else if (incoming == '3')
else if ((incoming == '3') && (online.IMU))
restartIMU = menuIMU();
else if ((incoming == '4') && (settings.useTxRxPinsForTerminal == false))
menuSerialLogging();
Expand Down Expand Up @@ -175,7 +176,7 @@ void menuMain()
totalCharactersPrinted = 0;
//If we are sleeping between readings then we cannot rely on millis() as it is powered down
//Use RTC instead
measurementStartTime = bestMillis();
measurementStartTime = rtcMillis();

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

0 comments on commit c1305cc

Please sign in to comment.