Skip to content

Commit e124b37

Browse files
authored
Merge pull request #147 from sparkfun/release_candidate
v2.5
2 parents 3ebf231 + 6e5d390 commit e124b37

16 files changed

+1551
-245
lines changed
380 KB
Binary file not shown.
380 KB
Binary file not shown.
378 KB
Binary file not shown.

CHANGELOG.md

Lines changed: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,49 @@
11
Change Log
22
======================
33

4+
v2.5:
5+
---------
6+
7+
* Add Tony Whipple's PR #146 - thank you @whipple63
8+
* Add support for the ISM330DHCX, MMC5983MA, KX134 and ADS1015
9+
* Resolve issue #87
10+
11+
v2.4:
12+
---------
13+
14+
* Add noPowerLossProtection to the main branch
15+
* Add changes by KDB: If we are streaming to Serial, start the stream with a Mime Type marker, followed by CR
16+
* Add debug option to only open the menu using a printable character: based on https://github.com/sparkfun/OpenLog_Artemis/pull/125
17+
18+
v2.3:
19+
---------
20+
21+
* Resolve https://forum.sparkfun.com/viewtopic.php?f=171&t=58109
22+
23+
v2.2:
24+
---------
25+
26+
* Use Apollo3 v2.2.1 with changes by paulvha to fix Issue 117 (Thank you Paul!)
27+
* https://github.com/sparkfun/OpenLog_Artemis/issues/117#issuecomment-1085881142
28+
* Also includes Paul's SPI.end fix
29+
* https://github.com/sparkfun/Arduino_Apollo3/issues/442
30+
31+
In libraries/SPI/src/SPI.cpp change ```end()``` to:
32+
33+
```
34+
void arduino::MbedSPI::end() {
35+
if (dev) {
36+
delete dev;
37+
dev = NULL;
38+
}
39+
}
40+
```
41+
42+
* Use SdFat v2.1.2
43+
* Compensate for missing / not-populated IMU
44+
* Add support for yyyy/mm/dd and ISO 8601 date style (Issue 118)
45+
* Add support for fractional time zone offsets
46+
447
v2.1
548
---------
649

Firmware/OpenLog_Artemis/OpenLog_Artemis.ino

Lines changed: 38 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,12 @@
11
/*
22
OpenLog Artemis
3-
By: Nathan Seidle
3+
By: Nathan Seidle and Paul Clark
44
SparkFun Electronics
55
Date: November 26th, 2019
6-
License: This code is public domain but you buy me a beer if you use this
7-
and we meet someday (Beerware license).
6+
License: MIT. Please see LICENSE.md for more details.
87
Feel like supporting our work? Buy a board from SparkFun!
9-
https://www.sparkfun.com/products/15793
8+
https://www.sparkfun.com/products/16832
9+
https://www.sparkfun.com/products/19426
1010
1111
This firmware runs the OpenLog Artemis. A large variety of system settings can be
1212
adjusted by connecting at 115200bps.
@@ -30,7 +30,7 @@
3030
(done) Change settings extension to txt
3131
(done) Fix max I2C speed to use linked list
3232
Currently device settings are not recorded to EEPROM, only deviceSettings.txt
33-
Is there a better way to dynamically create size of outputData array so we don't ever get larger than X sensors outputting?
33+
Is there a better way to dynamically create size of sdOutputData array so we don't ever get larger than X sensors outputting?
3434
Find way to store device configs into EEPROM
3535
Log four pressure sensors and graph them on plotter
3636
(checked) Test GPS - not sure about %d with int32s. Does lat, long, and alt look correct?
@@ -140,11 +140,15 @@
140140
Add noPowerLossProtection to the main branch
141141
Add changes by KDB: If we are streaming to Serial, start the stream with a Mime Type marker, followed by CR
142142
Add debug option to only open the menu using a printable character: based on https://github.com/sparkfun/OpenLog_Artemis/pull/125
143-
143+
144+
v2.5:
145+
Add Tony Whipple's PR #146 - thank you @whipple63
146+
Add support for the ISM330DHCX, MMC5983MA, KX134 and ADS1015
147+
Resolve issue #87
144148
*/
145149

146150
const int FIRMWARE_VERSION_MAJOR = 2;
147-
const int FIRMWARE_VERSION_MINOR = 4;
151+
const int FIRMWARE_VERSION_MINOR = 5;
148152

149153
//Define the OLA board identifier:
150154
// This is an int which is unique to this variant of the OLA and which allows us
@@ -154,7 +158,7 @@ const int FIRMWARE_VERSION_MINOR = 4;
154158
// the variant * 0x100 (OLA = 1; GNSS_LOGGER = 2; GEOPHONE_LOGGER = 3)
155159
// the major firmware version * 0x10
156160
// the minor firmware version
157-
#define OLA_IDENTIFIER 0x124 // Stored as 292 decimal in OLA_settings.txt
161+
#define OLA_IDENTIFIER 0x125 // Stored as 293 decimal in OLA_settings.txt
158162

159163
//#define noPowerLossProtection // Uncomment this line to disable the sleep-on-power-loss functionality
160164

@@ -310,6 +314,10 @@ icm_20948_DMP_data_t dmpData; // Global storage for the DMP data - extracted fro
310314
#include "MS5837.h" // Click here to download the library: https://github.com/sparkfunX/BlueRobotics_MS5837_Library
311315
#include "SparkFun_Qwiic_Button.h" // Click here to get the library: http://librarymanager/All#SparkFun_Qwiic_Button_Switch
312316
#include "SparkFun_Bio_Sensor_Hub_Library.h" // Click here to get the library: http://librarymanager/All#SparkFun_Bio_Sensor
317+
#include "SparkFun_ISM330DHCX.h" // Click here to get the library: http://librarymanager/All#SparkFun_6DoF_ISM330DHCX
318+
#include "SparkFun_MMC5983MA_Arduino_Library.h" //Click here to get the library: http://librarymanager/All#SparkFun_MMC5983MA
319+
#include "SparkFun_ADS1015_Arduino_Library.h" //Click here to get the library: http://librarymanager/All#SparkFun_ADS1015
320+
#include "SparkFun_KX13X.h" //Click here to get the library: http://librarymanager/All#SparkFun_KX13X
313321

314322
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
315323

@@ -319,14 +327,15 @@ uint64_t measurementStartTime; //Used to calc the actual update rate. Max is ~80
319327
uint64_t lastSDFileNameChangeTime; //Used to calculate the interval since the last SD filename change
320328
unsigned long measurementCount = 0; //Used to calc the actual update rate.
321329
unsigned long measurementTotal = 0; //The total number of recorded measurements. (Doesn't get reset when the menu is opened)
322-
char outputData[512 * 2]; //Factor of 512 for easier recording to SD in 512 chunks
330+
char sdOutputData[512 * 2]; //Factor of 512 for easier recording to SD in 512 chunks
323331
unsigned long lastReadTime = 0; //Used to delay until user wants to record a new reading
324332
unsigned long lastDataLogSyncTime = 0; //Used to record to SD every half second
325333
unsigned int totalCharactersPrinted = 0; //Limit output rate based on baud rate and number of characters to print
326334
bool takeReading = true; //Goes true when enough time has passed between readings or we've woken from sleep
327335
bool sleepAfterRead = false; //Used to keep the code awake for at least minimumAwakeTimeMillis
328336
const uint64_t maxUsBeforeSleep = 2000000ULL; //Number of us between readings before sleep is activated.
329337
const byte menuTimeout = 15; //Menus will exit/timeout after this number of seconds
338+
const int sdCardMenuTimeout = 60; // sdCard menu will exit/timeout after this number of seconds
330339
volatile static bool stopLoggingSeen = false; //Flag to indicate if we should stop logging
331340
uint64_t qwiicPowerOnTime = 0; //Used to delay after Qwiic power on to allow sensors to power on, then answer autodetect
332341
unsigned long qwiicPowerOnDelayMillis; //Wait for this many milliseconds after turning on the Qwiic power before attempting to communicate with Qwiic devices
@@ -711,26 +720,26 @@ void loop() {
711720
}
712721
#endif
713722

714-
getData(outputData, sizeof(outputData)); //Query all enabled sensors for data
723+
getData(sdOutputData, sizeof(sdOutputData)); //Query all enabled sensors for data
715724

716725
//Print to terminal
717726
if (settings.enableTerminalOutput == true)
718-
SerialPrint(outputData); //Print to terminal
727+
SerialPrint(sdOutputData); //Print to terminal
719728

720729
//Output to TX pin
721730
if ((settings.outputSerial == true) && (online.serialOutput == true))
722-
Serial1.print(outputData); //Print to TX pin
731+
Serial1.print(sdOutputData); //Print to TX pin
723732

724733
//Record to SD
725734
if ((settings.logData == true) && (online.microSD))
726735
{
727736
digitalWrite(PIN_STAT_LED, HIGH);
728-
uint32_t recordLength = sensorDataFile.write(outputData, strlen(outputData));
729-
if (recordLength != strlen(outputData)) //Record the buffer to the card
737+
uint32_t recordLength = sensorDataFile.write(sdOutputData, strlen(sdOutputData));
738+
if (recordLength != strlen(sdOutputData)) //Record the buffer to the card
730739
{
731740
if (settings.printDebugMessages == true)
732741
{
733-
SerialPrintf3("*** sensorDataFile.write data length mismatch! *** recordLength: %d, outputDataLength: %d\r\n", recordLength, strlen(outputData));
742+
SerialPrintf3("*** sensorDataFile.write data length mismatch! *** recordLength: %d, outputDataLength: %d\r\n", recordLength, strlen(sdOutputData));
734743
}
735744
}
736745

@@ -1164,6 +1173,13 @@ void beginIMU(bool silent)
11641173
SerialPrintln(F("Error: Could not startup the IMU in DMP mode!"));
11651174
success = false;
11661175
}
1176+
1177+
int ODR = 0; // Set ODR to 55Hz
1178+
if (settings.usBetweenReadings >= 500000ULL)
1179+
ODR = 3; // 17Hz ODR rate when DMP is running at 55Hz
1180+
if (settings.usBetweenReadings >= 1000000ULL)
1181+
ODR = 10; // 5Hz ODR rate when DMP is running at 55Hz
1182+
11671183
if (settings.imuLogDMPQuat6)
11681184
{
11691185
retval = myICM.enableDMPSensor(INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR);
@@ -1172,7 +1188,7 @@ void beginIMU(bool silent)
11721188
SerialPrintln(F("Error: Could not enable the Game Rotation Vector (Quat6)!"));
11731189
success = false;
11741190
}
1175-
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Quat6, 0); // Set ODR to 55Hz
1191+
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Quat6, ODR);
11761192
if (retval != ICM_20948_Stat_Ok)
11771193
{
11781194
SerialPrintln(F("Error: Could not set the Quat6 ODR!"));
@@ -1187,7 +1203,7 @@ void beginIMU(bool silent)
11871203
SerialPrintln(F("Error: Could not enable the Rotation Vector (Quat9)!"));
11881204
success = false;
11891205
}
1190-
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Quat9, 0); // Set ODR to 55Hz
1206+
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Quat9, ODR);
11911207
if (retval != ICM_20948_Stat_Ok)
11921208
{
11931209
SerialPrintln(F("Error: Could not set the Quat9 ODR!"));
@@ -1202,7 +1218,7 @@ void beginIMU(bool silent)
12021218
SerialPrintln(F("Error: Could not enable the DMP Accelerometer!"));
12031219
success = false;
12041220
}
1205-
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Accel, 0); // Set ODR to 55Hz
1221+
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Accel, ODR);
12061222
if (retval != ICM_20948_Stat_Ok)
12071223
{
12081224
SerialPrintln(F("Error: Could not set the Accel ODR!"));
@@ -1217,13 +1233,13 @@ void beginIMU(bool silent)
12171233
SerialPrintln(F("Error: Could not enable the DMP Gyroscope!"));
12181234
success = false;
12191235
}
1220-
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Gyro, 0); // Set ODR to 55Hz
1236+
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Gyro, ODR);
12211237
if (retval != ICM_20948_Stat_Ok)
12221238
{
12231239
SerialPrintln(F("Error: Could not set the Gyro ODR!"));
12241240
success = false;
12251241
}
1226-
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Gyro_Calibr, 0); // Set ODR to 55Hz
1242+
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Gyro_Calibr, ODR);
12271243
if (retval != ICM_20948_Stat_Ok)
12281244
{
12291245
SerialPrintln(F("Error: Could not set the Gyro Calibr ODR!"));
@@ -1238,13 +1254,13 @@ void beginIMU(bool silent)
12381254
SerialPrintln(F("Error: Could not enable the DMP Compass!"));
12391255
success = false;
12401256
}
1241-
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Cpass, 0); // Set ODR to 55Hz
1257+
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Cpass, ODR);
12421258
if (retval != ICM_20948_Stat_Ok)
12431259
{
12441260
SerialPrintln(F("Error: Could not set the Compass ODR!"));
12451261
success = false;
12461262
}
1247-
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Cpass_Calibr, 0); // Set ODR to 55Hz
1263+
retval = myICM.setDMPODRrate(DMP_ODR_Reg_Cpass_Calibr, ODR);
12481264
if (retval != ICM_20948_Stat_Ok)
12491265
{
12501266
SerialPrintln(F("Error: Could not set the Compass Calibr ODR!"));

0 commit comments

Comments
 (0)