diff --git a/Binaries/OpenLog_Artemis-V10-v25-NoPowerLossProtection.bin b/Binaries/OpenLog_Artemis-V10-v25-NoPowerLossProtection.bin new file mode 100644 index 0000000..7438abf Binary files /dev/null and b/Binaries/OpenLog_Artemis-V10-v25-NoPowerLossProtection.bin differ diff --git a/Binaries/OpenLog_Artemis-V10-v25.bin b/Binaries/OpenLog_Artemis-V10-v25.bin new file mode 100644 index 0000000..06c09d0 Binary files /dev/null and b/Binaries/OpenLog_Artemis-V10-v25.bin differ diff --git a/Binaries/OpenLog_Artemis-X04-v25.bin b/Binaries/OpenLog_Artemis-X04-v25.bin new file mode 100644 index 0000000..f9ac81d Binary files /dev/null and b/Binaries/OpenLog_Artemis-X04-v25.bin differ diff --git a/CHANGELOG.md b/CHANGELOG.md index 2cc65e2..9ae9d55 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,6 +1,49 @@ Change Log ====================== +v2.5: +--------- + +* Add Tony Whipple's PR #146 - thank you @whipple63 +* Add support for the ISM330DHCX, MMC5983MA, KX134 and ADS1015 +* Resolve issue #87 + +v2.4: +--------- + +* Add noPowerLossProtection to the main branch +* Add changes by KDB: If we are streaming to Serial, start the stream with a Mime Type marker, followed by CR +* Add debug option to only open the menu using a printable character: based on https://github.com/sparkfun/OpenLog_Artemis/pull/125 + +v2.3: +--------- + +* Resolve https://forum.sparkfun.com/viewtopic.php?f=171&t=58109 + +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 + v2.1 --------- diff --git a/Firmware/OpenLog_Artemis/OpenLog_Artemis.ino b/Firmware/OpenLog_Artemis/OpenLog_Artemis.ino index 32ac96e..dc94a6d 100644 --- a/Firmware/OpenLog_Artemis/OpenLog_Artemis.ino +++ b/Firmware/OpenLog_Artemis/OpenLog_Artemis.ino @@ -1,12 +1,12 @@ /* OpenLog Artemis - By: Nathan Seidle + By: Nathan Seidle and Paul Clark SparkFun Electronics Date: November 26th, 2019 - License: This code is public domain but you buy me a beer if you use this - and we meet someday (Beerware license). + License: MIT. Please see LICENSE.md for more details. Feel like supporting our work? Buy a board from SparkFun! - https://www.sparkfun.com/products/15793 + https://www.sparkfun.com/products/16832 + https://www.sparkfun.com/products/19426 This firmware runs the OpenLog Artemis. A large variety of system settings can be adjusted by connecting at 115200bps. @@ -30,7 +30,7 @@ (done) Change settings extension to txt (done) Fix max I2C speed to use linked list Currently device settings are not recorded to EEPROM, only deviceSettings.txt - Is there a better way to dynamically create size of outputData array so we don't ever get larger than X sensors outputting? + Is there a better way to dynamically create size of sdOutputData array so we don't ever get larger than X sensors outputting? Find way to store device configs into EEPROM Log four pressure sensors and graph them on plotter (checked) Test GPS - not sure about %d with int32s. Does lat, long, and alt look correct? @@ -140,11 +140,15 @@ Add noPowerLossProtection to the main branch Add changes by KDB: If we are streaming to Serial, start the stream with a Mime Type marker, followed by CR Add debug option to only open the menu using a printable character: based on https://github.com/sparkfun/OpenLog_Artemis/pull/125 - + + v2.5: + Add Tony Whipple's PR #146 - thank you @whipple63 + Add support for the ISM330DHCX, MMC5983MA, KX134 and ADS1015 + Resolve issue #87 */ const int FIRMWARE_VERSION_MAJOR = 2; -const int FIRMWARE_VERSION_MINOR = 4; +const int FIRMWARE_VERSION_MINOR = 5; //Define the OLA board identifier: // 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; // the variant * 0x100 (OLA = 1; GNSS_LOGGER = 2; GEOPHONE_LOGGER = 3) // the major firmware version * 0x10 // the minor firmware version -#define OLA_IDENTIFIER 0x124 // Stored as 292 decimal in OLA_settings.txt +#define OLA_IDENTIFIER 0x125 // Stored as 293 decimal in OLA_settings.txt //#define noPowerLossProtection // Uncomment this line to disable the sleep-on-power-loss functionality @@ -310,6 +314,10 @@ icm_20948_DMP_data_t dmpData; // Global storage for the DMP data - extracted fro #include "MS5837.h" // Click here to download the library: https://github.com/sparkfunX/BlueRobotics_MS5837_Library #include "SparkFun_Qwiic_Button.h" // Click here to get the library: http://librarymanager/All#SparkFun_Qwiic_Button_Switch #include "SparkFun_Bio_Sensor_Hub_Library.h" // Click here to get the library: http://librarymanager/All#SparkFun_Bio_Sensor +#include "SparkFun_ISM330DHCX.h" // Click here to get the library: http://librarymanager/All#SparkFun_6DoF_ISM330DHCX +#include "SparkFun_MMC5983MA_Arduino_Library.h" //Click here to get the library: http://librarymanager/All#SparkFun_MMC5983MA +#include "SparkFun_ADS1015_Arduino_Library.h" //Click here to get the library: http://librarymanager/All#SparkFun_ADS1015 +#include "SparkFun_KX13X.h" //Click here to get the library: http://librarymanager/All#SparkFun_KX13X //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- @@ -319,7 +327,7 @@ uint64_t measurementStartTime; //Used to calc the actual update rate. Max is ~80 uint64_t lastSDFileNameChangeTime; //Used to calculate the interval since the last SD filename change unsigned long measurementCount = 0; //Used to calc the actual update rate. unsigned long measurementTotal = 0; //The total number of recorded measurements. (Doesn't get reset when the menu is opened) -char outputData[512 * 2]; //Factor of 512 for easier recording to SD in 512 chunks +char sdOutputData[512 * 2]; //Factor of 512 for easier recording to SD in 512 chunks unsigned long lastReadTime = 0; //Used to delay until user wants to record a new reading unsigned long lastDataLogSyncTime = 0; //Used to record to SD every half second unsigned int totalCharactersPrinted = 0; //Limit output rate based on baud rate and number of characters to print @@ -327,6 +335,7 @@ bool takeReading = true; //Goes true when enough time has passed between reading bool sleepAfterRead = false; //Used to keep the code awake for at least minimumAwakeTimeMillis const uint64_t maxUsBeforeSleep = 2000000ULL; //Number of us between readings before sleep is activated. const byte menuTimeout = 15; //Menus will exit/timeout after this number of seconds +const int sdCardMenuTimeout = 60; // sdCard menu will exit/timeout after this number of seconds volatile static bool stopLoggingSeen = false; //Flag to indicate if we should stop logging uint64_t qwiicPowerOnTime = 0; //Used to delay after Qwiic power on to allow sensors to power on, then answer autodetect 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() { } #endif - getData(outputData, sizeof(outputData)); //Query all enabled sensors for data + getData(sdOutputData, sizeof(sdOutputData)); //Query all enabled sensors for data //Print to terminal if (settings.enableTerminalOutput == true) - SerialPrint(outputData); //Print to terminal + SerialPrint(sdOutputData); //Print to terminal //Output to TX pin if ((settings.outputSerial == true) && (online.serialOutput == true)) - Serial1.print(outputData); //Print to TX pin + Serial1.print(sdOutputData); //Print to TX pin //Record to SD if ((settings.logData == true) && (online.microSD)) { digitalWrite(PIN_STAT_LED, HIGH); - uint32_t recordLength = sensorDataFile.write(outputData, strlen(outputData)); - if (recordLength != strlen(outputData)) //Record the buffer to the card + uint32_t recordLength = sensorDataFile.write(sdOutputData, strlen(sdOutputData)); + if (recordLength != strlen(sdOutputData)) //Record the buffer to the card { if (settings.printDebugMessages == true) { - SerialPrintf3("*** sensorDataFile.write data length mismatch! *** recordLength: %d, outputDataLength: %d\r\n", recordLength, strlen(outputData)); + SerialPrintf3("*** sensorDataFile.write data length mismatch! *** recordLength: %d, outputDataLength: %d\r\n", recordLength, strlen(sdOutputData)); } } @@ -1164,6 +1173,13 @@ void beginIMU(bool silent) SerialPrintln(F("Error: Could not startup the IMU in DMP mode!")); success = false; } + + int ODR = 0; // Set ODR to 55Hz + if (settings.usBetweenReadings >= 500000ULL) + ODR = 3; // 17Hz ODR rate when DMP is running at 55Hz + if (settings.usBetweenReadings >= 1000000ULL) + ODR = 10; // 5Hz ODR rate when DMP is running at 55Hz + if (settings.imuLogDMPQuat6) { retval = myICM.enableDMPSensor(INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR); @@ -1172,7 +1188,7 @@ void beginIMU(bool silent) SerialPrintln(F("Error: Could not enable the Game Rotation Vector (Quat6)!")); success = false; } - retval = myICM.setDMPODRrate(DMP_ODR_Reg_Quat6, 0); // Set ODR to 55Hz + retval = myICM.setDMPODRrate(DMP_ODR_Reg_Quat6, ODR); if (retval != ICM_20948_Stat_Ok) { SerialPrintln(F("Error: Could not set the Quat6 ODR!")); @@ -1187,7 +1203,7 @@ void beginIMU(bool silent) SerialPrintln(F("Error: Could not enable the Rotation Vector (Quat9)!")); success = false; } - retval = myICM.setDMPODRrate(DMP_ODR_Reg_Quat9, 0); // Set ODR to 55Hz + retval = myICM.setDMPODRrate(DMP_ODR_Reg_Quat9, ODR); if (retval != ICM_20948_Stat_Ok) { SerialPrintln(F("Error: Could not set the Quat9 ODR!")); @@ -1202,7 +1218,7 @@ void beginIMU(bool silent) SerialPrintln(F("Error: Could not enable the DMP Accelerometer!")); success = false; } - retval = myICM.setDMPODRrate(DMP_ODR_Reg_Accel, 0); // Set ODR to 55Hz + retval = myICM.setDMPODRrate(DMP_ODR_Reg_Accel, ODR); if (retval != ICM_20948_Stat_Ok) { SerialPrintln(F("Error: Could not set the Accel ODR!")); @@ -1217,13 +1233,13 @@ void beginIMU(bool silent) SerialPrintln(F("Error: Could not enable the DMP Gyroscope!")); success = false; } - retval = myICM.setDMPODRrate(DMP_ODR_Reg_Gyro, 0); // Set ODR to 55Hz + retval = myICM.setDMPODRrate(DMP_ODR_Reg_Gyro, ODR); if (retval != ICM_20948_Stat_Ok) { SerialPrintln(F("Error: Could not set the Gyro ODR!")); success = false; } - retval = myICM.setDMPODRrate(DMP_ODR_Reg_Gyro_Calibr, 0); // Set ODR to 55Hz + retval = myICM.setDMPODRrate(DMP_ODR_Reg_Gyro_Calibr, ODR); if (retval != ICM_20948_Stat_Ok) { SerialPrintln(F("Error: Could not set the Gyro Calibr ODR!")); @@ -1238,13 +1254,13 @@ void beginIMU(bool silent) SerialPrintln(F("Error: Could not enable the DMP Compass!")); success = false; } - retval = myICM.setDMPODRrate(DMP_ODR_Reg_Cpass, 0); // Set ODR to 55Hz + retval = myICM.setDMPODRrate(DMP_ODR_Reg_Cpass, ODR); if (retval != ICM_20948_Stat_Ok) { SerialPrintln(F("Error: Could not set the Compass ODR!")); success = false; } - retval = myICM.setDMPODRrate(DMP_ODR_Reg_Cpass_Calibr, 0); // Set ODR to 55Hz + retval = myICM.setDMPODRrate(DMP_ODR_Reg_Cpass_Calibr, ODR); if (retval != ICM_20948_Stat_Ok) { SerialPrintln(F("Error: Could not set the Compass Calibr ODR!")); diff --git a/Firmware/OpenLog_Artemis/Sensors.ino b/Firmware/OpenLog_Artemis/Sensors.ino index 0f56955..2415f25 100644 --- a/Firmware/OpenLog_Artemis/Sensors.ino +++ b/Firmware/OpenLog_Artemis/Sensors.ino @@ -6,7 +6,7 @@ #define HELPER_BUFFER_SIZE 1024 //Query each enabled sensor for its most recent data -void getData(char* outputData, size_t lenData) +void getData(char* sdOutputData, size_t lenData) { measurementCount++; measurementTotal++; @@ -15,14 +15,14 @@ void getData(char* outputData, size_t lenData) char tempData1[16]; char tempData2[16]; char tempData3[16]; - outputData[0] = '\0'; //Clear string contents + sdOutputData[0] = '\0'; //Clear string contents if (settings.logRTC) { //Code written by @DennisMelamed in PR #70 char timeString[37]; getTimeString(timeString); // getTimeString is in timeStamp.ino - strlcat(outputData, timeString, lenData); + strlcat(sdOutputData, timeString, lenData); } if (settings.logA11) @@ -38,7 +38,7 @@ void getData(char* outputData, size_t lenData) else sprintf(tempData, "%d,", analog11); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.logA12) @@ -54,7 +54,7 @@ void getData(char* outputData, size_t lenData) else sprintf(tempData, "%d,", analog12); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.logA13) @@ -70,7 +70,7 @@ void getData(char* outputData, size_t lenData) else sprintf(tempData, "%d,", analog13); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.logA32) @@ -86,7 +86,7 @@ void getData(char* outputData, size_t lenData) else sprintf(tempData, "%d,", analog32); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.logVIN) @@ -94,7 +94,7 @@ void getData(char* outputData, size_t lenData) float voltage = readVIN(); olaftoa(voltage, tempData1, 2, sizeof(tempData1) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (online.IMU) @@ -115,7 +115,7 @@ void getData(char* outputData, size_t lenData) olaftoa(myICM.accY(), tempData2, 2, sizeof(tempData2) / sizeof(char)); olaftoa(myICM.accZ(), tempData3, 2, sizeof(tempData3) / sizeof(char)); sprintf(tempData, "%s,%s,%s,", tempData1, tempData2, tempData3); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.logIMUGyro) { @@ -123,7 +123,7 @@ void getData(char* outputData, size_t lenData) olaftoa(myICM.gyrY(), tempData2, 2, sizeof(tempData2) / sizeof(char)); olaftoa(myICM.gyrZ(), tempData3, 2, sizeof(tempData3) / sizeof(char)); sprintf(tempData, "%s,%s,%s,", tempData1, tempData2, tempData3); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.logIMUMag) { @@ -131,13 +131,13 @@ void getData(char* outputData, size_t lenData) olaftoa(myICM.magY(), tempData2, 2, sizeof(tempData2) / sizeof(char)); olaftoa(myICM.magZ(), tempData3, 2, sizeof(tempData3) / sizeof(char)); sprintf(tempData, "%s,%s,%s,", tempData1, tempData2, tempData3); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.logIMUTemp) { olaftoa(myICM.temp(), tempData1, 2, sizeof(tempData1) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } //else @@ -158,7 +158,7 @@ void getData(char* outputData, size_t lenData) olaftoa(((double)dmpData.Quat6.Data.Q2) / 1073741824.0, tempData2, 5, sizeof(tempData2) / sizeof(char)); olaftoa(((double)dmpData.Quat6.Data.Q3) / 1073741824.0, tempData3, 5, sizeof(tempData3) / sizeof(char)); sprintf(tempData, "%s,%s,%s,", tempData1, tempData2, tempData3); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.imuLogDMPQuat9) { @@ -166,28 +166,28 @@ void getData(char* outputData, size_t lenData) olaftoa(((double)dmpData.Quat9.Data.Q2) / 1073741824.0, tempData2, 5, sizeof(tempData2) / sizeof(char)); olaftoa(((double)dmpData.Quat9.Data.Q3) / 1073741824.0, tempData3, 5, sizeof(tempData3) / sizeof(char)); sprintf(tempData, "%s,%s,%s,%d,", tempData1, tempData2, tempData3, dmpData.Quat9.Data.Accuracy); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.imuLogDMPAccel) { sprintf(tempData, "%d,%d,%d,", dmpData.Raw_Accel.Data.X, dmpData.Raw_Accel.Data.Y, dmpData.Raw_Accel.Data.Z); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.imuLogDMPGyro) { sprintf(tempData, "%d,%d,%d,", dmpData.Raw_Gyro.Data.X, dmpData.Raw_Gyro.Data.Y, dmpData.Raw_Gyro.Data.Z); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.imuLogDMPCpass) { sprintf(tempData, "%d,%d,%d,", dmpData.Compass.Data.X, dmpData.Compass.Data.Y, dmpData.Compass.Data.Z); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } - //Append all external sensor data on linked list to outputData - gatherDeviceValues(outputData, lenData); + //Append all external sensor data on linked list to sdOutputData + gatherDeviceValues(sdOutputData, lenData); if (settings.logHertz) { @@ -203,26 +203,28 @@ void getData(char* outputData, size_t lenData) actualRate = measurementCount * 1000.0 / (currentMillis - measurementStartTime); olaftoa(actualRate, tempData1, 3, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (settings.printMeasurementCount) { sprintf(tempData, "%d,", measurementTotal); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } - strlcat(outputData, "\r\n", lenData); + strlcat(sdOutputData, "\r\n", lenData); - totalCharactersPrinted += strlen(outputData); + totalCharactersPrinted += strlen(sdOutputData); } //Read values from the devices on the node list -//Append values to outputData -void gatherDeviceValues(char * outputData, size_t lenData) +//Append values to sdOutputData +void gatherDeviceValues(char * sdOutputData, size_t lenData) { char tempData[100]; char tempData1[20]; + char tempData2[20]; + char tempData3[20]; //Step through list, printing values as we go node *temp = head; @@ -251,7 +253,7 @@ void gatherDeviceValues(char * outputData, size_t lenData) float currentWeight = nodeDevice->getWeight(false, nodeSetting->averageAmount); //Do not allow negative weights, take average of X readings olaftoa(currentWeight, tempData1, nodeSetting->decimalPlaces, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } break; @@ -265,17 +267,17 @@ void gatherDeviceValues(char * outputData, size_t lenData) if (nodeSetting->logDistance) { sprintf(tempData, "%d,", nodeDevice->getDistance()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logRangeStatus) { sprintf(tempData, "%d,", nodeDevice->getRangeStatus()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logSignalRate) { sprintf(tempData, "%d,", nodeDevice->getSignalRate()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -318,7 +320,7 @@ void gatherDeviceValues(char * outputData, size_t lenData) { sprintf(tempData, "%s/%s/%s,", gnssYearStr, gnssMonthStr, gnssDayStr); } - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTime) { @@ -354,57 +356,57 @@ void gatherDeviceValues(char * outputData, size_t lenData) sprintf(gnssMillisStr, "%d", gnssMillis); sprintf(tempData, "%s:%s:%s.%s,", gnssHourStr, gnssMinStr, gnssSecStr, gnssMillisStr); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPosition) { sprintf(tempData, "%d,%d,", nodeDevice->getLatitude(), nodeDevice->getLongitude()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logAltitude) { sprintf(tempData, "%d,", nodeDevice->getAltitude()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logAltitudeMSL) { sprintf(tempData, "%d,", nodeDevice->getAltitudeMSL()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logSIV) { sprintf(tempData, "%d,", nodeDevice->getSIV()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logFixType) { sprintf(tempData, "%d,", nodeDevice->getFixType()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logCarrierSolution) { sprintf(tempData, "%d,", nodeDevice->getCarrierSolutionType()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logGroundSpeed) { sprintf(tempData, "%d,", nodeDevice->getGroundSpeed()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logHeadingOfMotion) { sprintf(tempData, "%d,", nodeDevice->getHeading()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logpDOP) { sprintf(tempData, "%d,", nodeDevice->getPDOP()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logiTOW) { sprintf(tempData, "%d,", nodeDevice->getTimeOfWeek()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } @@ -422,12 +424,12 @@ void gatherDeviceValues(char * outputData, size_t lenData) if (nodeSetting->logProximity) { sprintf(tempData, "%d,", nodeDevice->getProximity()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logAmbientLight) { sprintf(tempData, "%d,", nodeDevice->getAmbient()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -443,7 +445,7 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->readTempC(), tempData1, 4, sizeof(tempData) / sizeof(char)); //Resolution to 0.0078°C, accuracy of 0.1°C sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -459,13 +461,13 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->getPressure(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(nodeDevice->getTemperature(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -480,13 +482,13 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->getPressure_hPa(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(nodeDevice->getTemperature_degC(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -501,25 +503,25 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->readFloatPressure(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logHumidity) { olaftoa(nodeDevice->readFloatHumidity(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logAltitude) { olaftoa(nodeDevice->readFloatAltitudeMeters(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(nodeDevice->readTempC(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -534,19 +536,19 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->uva(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logUVB) { olaftoa(nodeDevice->uvb(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logUVIndex) { olaftoa(nodeDevice->index(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -562,12 +564,12 @@ void gatherDeviceValues(char * outputData, size_t lenData) if (nodeSetting->logTVOC) { sprintf(tempData, "%d,", nodeDevice->getTVOC()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logCO2) { sprintf(tempData, "%d,", nodeDevice->getCO2()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -584,22 +586,22 @@ void gatherDeviceValues(char * outputData, size_t lenData) if (nodeSetting->logTVOC) { sprintf(tempData, "%d,", nodeDevice->TVOC); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logCO2) { sprintf(tempData, "%d,", nodeDevice->CO2); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logH2) { sprintf(tempData, "%d,", nodeDevice->H2); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logEthanol) { sprintf(tempData, "%d,", nodeDevice->ethanol); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -613,19 +615,19 @@ void gatherDeviceValues(char * outputData, size_t lenData) if (nodeSetting->logCO2) { sprintf(tempData, "%d,", nodeDevice->getCO2()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logHumidity) { olaftoa(nodeDevice->getHumidity(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(nodeDevice->getTemperature(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -640,19 +642,19 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->getHumidity(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPressure) { olaftoa(nodeDevice->getPressure(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(nodeDevice->getTemperature(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -667,13 +669,13 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->getThermocoupleTemp(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logAmbientTemperature) { olaftoa(nodeDevice->getAmbientTemp(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -688,13 +690,13 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->getHumidity(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(nodeDevice->getTemperature(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -710,13 +712,13 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->toPercent(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(nodeDevice->toDegC(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -770,24 +772,24 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->readPT100Centigrade(), tempData1, 3, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logFahrenheit) { olaftoa(nodeDevice->readPT100Fahrenheit(), tempData1, 3, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logInternalTemperature) { olaftoa(nodeDevice->readInternalTemperature(), tempData1, 3, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logRawVoltage) { sprintf(tempData, "%d,", nodeDevice->readRawVoltage()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -802,43 +804,43 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->readPressure(), tempData1, 4, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->usePA) { olaftoa(nodeDevice->readPressure(PA), tempData1, 1, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->useKPA) { olaftoa(nodeDevice->readPressure(KPA), tempData1, 4, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->useTORR) { olaftoa(nodeDevice->readPressure(TORR), tempData1, 3, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->useINHG) { olaftoa(nodeDevice->readPressure(INHG), tempData1, 4, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->useATM) { olaftoa(nodeDevice->readPressure(ATM), tempData1, 6, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->useBAR) { olaftoa(nodeDevice->readPressure(BAR), tempData1, 6, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -853,69 +855,69 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->getPM1_0(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPM25) { olaftoa(nodeDevice->getPM2_5(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPM10) { olaftoa(nodeDevice->getPM10(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPC05) { sprintf(tempData, "%d,", nodeDevice->getPC0_5()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPC1) { sprintf(tempData, "%d,", nodeDevice->getPC1_0()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPC25) { sprintf(tempData, "%d,", nodeDevice->getPC2_5()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPC50) { sprintf(tempData, "%d,", nodeDevice->getPC5_0()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPC75) { sprintf(tempData, "%d,", nodeDevice->getPC7_5()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPC10) { sprintf(tempData, "%d,", nodeDevice->getPC10()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logSensorStatus) { sprintf(tempData, "%d,", nodeDevice->getStatusSensors()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logPDStatus) { sprintf(tempData, "%d,", nodeDevice->getStatusPD()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logLDStatus) { sprintf(tempData, "%d,", nodeDevice->getStatusLD()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logFanStatus) { sprintf(tempData, "%d,", nodeDevice->getStatusFan()); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -929,7 +931,7 @@ void gatherDeviceValues(char * outputData, size_t lenData) if (nodeSetting->logVOC) { sprintf(tempData, "%d,", nodeDevice->getVOCindex(nodeSetting->RH, nodeSetting->T)); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -951,13 +953,13 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(pressure, tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(temperature, tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -976,25 +978,25 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(nodeDevice->pressure(nodeSetting->conversion), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logTemperature) { olaftoa(nodeDevice->temperature(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logDepth) { olaftoa(nodeDevice->depth(), tempData1, 3, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logAltitude) { olaftoa(nodeDevice->altitude(), tempData1, 2, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -1014,7 +1016,7 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(((float)pressedPopped) / 1000.0, tempData1, 3, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } long clickedPopped = 0; @@ -1027,7 +1029,7 @@ void gatherDeviceValues(char * outputData, size_t lenData) { olaftoa(((float)clickedPopped) / 1000.0, tempData1, 3, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->toggleLEDOnClick) @@ -1037,7 +1039,7 @@ void gatherDeviceValues(char * outputData, size_t lenData) else nodeDevice->LEDoff(); sprintf(tempData, "%d,", nodeSetting->ledState); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } } } @@ -1056,33 +1058,222 @@ void gatherDeviceValues(char * outputData, size_t lenData) if (nodeSetting->logHeartrate) { sprintf(tempData, "%d,", body.heartRate); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logConfidence) { sprintf(tempData, "%d,", body.confidence); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logOxygen) { sprintf(tempData, "%d,", body.oxygen); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logStatus) { sprintf(tempData, "%d,", body.status); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logExtendedStatus) { sprintf(tempData, "%d,", body.extStatus); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); } if (nodeSetting->logRValue) { olaftoa(body.rValue, tempData1, 1, sizeof(tempData) / sizeof(char)); sprintf(tempData, "%s,", tempData1); - strlcat(outputData, tempData, lenData); + strlcat(sdOutputData, tempData, lenData); + } + } + } + break; + case DEVICE_ISM330DHCX: + { + SparkFun_ISM330DHCX *nodeDevice = (SparkFun_ISM330DHCX *)temp->classPtr; + struct_ISM330DHCX *nodeSetting = (struct_ISM330DHCX *)temp->configPtr; + if (nodeSetting->log == true) + { + // Structs for X,Y,Z data + static sfe_ism_data_t accelData; + static sfe_ism_data_t gyroData; + static bool dataReady; + if ((nodeSetting->logAccel) || (nodeSetting->logGyro)) + { + // Check if both gyroscope and accelerometer data is available. + dataReady = nodeDevice->checkStatus(); + if( dataReady ) + { + nodeDevice->getAccel(&accelData); + nodeDevice->getGyro(&gyroData); + } + } + if (nodeSetting->logAccel) + { + olaftoa(accelData.xData, tempData1, 2, sizeof(tempData1) / sizeof(char)); + olaftoa(accelData.yData, tempData2, 2, sizeof(tempData2) / sizeof(char)); + olaftoa(accelData.zData, tempData3, 2, sizeof(tempData3) / sizeof(char)); + sprintf(tempData, "%s,%s,%s,", tempData1, tempData2, tempData3); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logGyro) + { + olaftoa(gyroData.xData, tempData1, 2, sizeof(tempData1) / sizeof(char)); + olaftoa(gyroData.yData, tempData2, 2, sizeof(tempData2) / sizeof(char)); + olaftoa(gyroData.zData, tempData3, 2, sizeof(tempData3) / sizeof(char)); + sprintf(tempData, "%s,%s,%s,", tempData1, tempData2, tempData3); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logDataReady) + { + sprintf(tempData, "%d,", dataReady); + strlcat(sdOutputData, tempData, lenData); + } + } + } + break; + case DEVICE_MMC5983MA: + { + SFE_MMC5983MA *nodeDevice = (SFE_MMC5983MA *)temp->classPtr; + struct_MMC5983MA *nodeSetting = (struct_MMC5983MA *)temp->configPtr; + if (nodeSetting->log == true) + { + // X,Y,Z data + uint32_t rawValueX; + uint32_t rawValueY; + uint32_t rawValueZ; + double normalizedX; + double normalizedY; + double normalizedZ; + if (nodeSetting->logMag) + { + + nodeDevice->getMeasurementXYZ(&rawValueX, &rawValueY, &rawValueZ); + + // The magnetic field values are 18-bit unsigned. The zero (mid) point is 2^17 (131072). + // Normalize each field to +/- 1.0 + normalizedX = (double)rawValueX - 131072.0; + normalizedX /= 131072.0; + normalizedY = (double)rawValueY - 131072.0; + normalizedY /= 131072.0; + normalizedZ = (double)rawValueZ - 131072.0; + normalizedZ /= 131072.0; + // Convert to Gauss + normalizedX *= 8.0; + normalizedY *= 8.0; + normalizedZ *= 8.0; + + olaftoa(normalizedX, tempData1, 6, sizeof(tempData1) / sizeof(char)); + olaftoa(normalizedY, tempData2, 6, sizeof(tempData2) / sizeof(char)); + olaftoa(normalizedZ, tempData3, 6, sizeof(tempData3) / sizeof(char)); + sprintf(tempData, "%s,%s,%s,", tempData1, tempData2, tempData3); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logTemperature) + { + int temperature = nodeDevice->getTemperature(); + sprintf(tempData, "%d,", temperature); + strlcat(sdOutputData, tempData, lenData); + } + } + } + break; + case DEVICE_ADS1015: + { + ADS1015 *nodeDevice = (ADS1015 *)temp->classPtr; + struct_ADS1015 *nodeSetting = (struct_ADS1015 *)temp->configPtr; + if (nodeSetting->log == true) + { + if (nodeSetting->logA0) + { + float channel_mV = nodeDevice->getSingleEndedMillivolts(0); + olaftoa(channel_mV, tempData1, 3, sizeof(tempData1) / sizeof(char)); + sprintf(tempData, "%s,", tempData1); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logA1) + { + float channel_mV = nodeDevice->getSingleEndedMillivolts(1); + olaftoa(channel_mV, tempData1, 3, sizeof(tempData1) / sizeof(char)); + sprintf(tempData, "%s,", tempData1); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logA2) + { + float channel_mV = nodeDevice->getSingleEndedMillivolts(2); + olaftoa(channel_mV, tempData1, 3, sizeof(tempData1) / sizeof(char)); + sprintf(tempData, "%s,", tempData1); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logA3) + { + float channel_mV = nodeDevice->getSingleEndedMillivolts(3); + olaftoa(channel_mV, tempData1, 3, sizeof(tempData1) / sizeof(char)); + sprintf(tempData, "%s,", tempData1); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logA0A1) + { + float channel_mV = nodeDevice->getDifferentialMillivolts(ADS1015_CONFIG_MUX_DIFF_P0_N1); + olaftoa(channel_mV, tempData1, 3, sizeof(tempData1) / sizeof(char)); + sprintf(tempData, "%s,", tempData1); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logA0A3) + { + float channel_mV = nodeDevice->getDifferentialMillivolts(ADS1015_CONFIG_MUX_DIFF_P0_N3); + olaftoa(channel_mV, tempData1, 3, sizeof(tempData1) / sizeof(char)); + sprintf(tempData, "%s,", tempData1); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logA1A3) + { + float channel_mV = nodeDevice->getDifferentialMillivolts(ADS1015_CONFIG_MUX_DIFF_P1_N3); + olaftoa(channel_mV, tempData1, 3, sizeof(tempData1) / sizeof(char)); + sprintf(tempData, "%s,", tempData1); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logA2A3) + { + float channel_mV = nodeDevice->getDifferentialMillivolts(ADS1015_CONFIG_MUX_DIFF_P2_N3); + olaftoa(channel_mV, tempData1, 3, sizeof(tempData1) / sizeof(char)); + sprintf(tempData, "%s,", tempData1); + strlcat(sdOutputData, tempData, lenData); + } + } + } + break; + case DEVICE_KX134: + { + SparkFun_KX134 *nodeDevice = (SparkFun_KX134 *)temp->classPtr; + struct_KX134 *nodeSetting = (struct_KX134 *)temp->configPtr; + if (nodeSetting->log == true) + { + // X,Y,Z data + static outputData xyzData; + static bool dataReady = false; + + if ((nodeSetting->logAccel) || (nodeSetting->logDataReady)) + { + // Check if accel data is available. + dataReady = nodeDevice->dataReady(); + if (dataReady) + nodeDevice->getAccelData(&xyzData); + } + + if (nodeSetting->logAccel) + { + olaftoa(xyzData.xData, tempData1, 4, sizeof(tempData1) / sizeof(char)); + olaftoa(xyzData.yData, tempData2, 4, sizeof(tempData2) / sizeof(char)); + olaftoa(xyzData.zData, tempData3, 4, sizeof(tempData3) / sizeof(char)); + sprintf(tempData, "%s,%s,%s,", tempData1, tempData2, tempData3); + strlcat(sdOutputData, tempData, lenData); + } + if (nodeSetting->logDataReady) + { + sprintf(tempData, "%d,", dataReady); + strlcat(sdOutputData, tempData, lenData); } } } @@ -1539,6 +1730,68 @@ static void getHelperText(char* helperText, size_t lenText) } } break; + case DEVICE_ISM330DHCX: + { + struct_ISM330DHCX *nodeSetting = (struct_ISM330DHCX *)temp->configPtr; + if (nodeSetting->log) + { + if (nodeSetting->logAccel) + strlcat(helperText, "aX,aY,aZ,", lenText); + if (nodeSetting->logGyro) + strlcat(helperText, "gX,gY,gZ,", lenText); + if (nodeSetting->logDataReady) + strlcat(helperText, "dataRdy,", lenText); + } + } + break; + case DEVICE_MMC5983MA: + { + struct_MMC5983MA *nodeSetting = (struct_MMC5983MA *)temp->configPtr; + if (nodeSetting->log) + { + if (nodeSetting->logMag) + strlcat(helperText, "mX,mY,mZ,", lenText); + if (nodeSetting->logTemperature) + strlcat(helperText, "degC,", lenText); + } + } + break; + case DEVICE_KX134: + { + struct_KX134 *nodeSetting = (struct_KX134 *)temp->configPtr; + if (nodeSetting->log) + { + if (nodeSetting->logAccel) + strlcat(helperText, "aX,aY,aZ,", lenText); + if (nodeSetting->logDataReady) + strlcat(helperText, "dataRdy,", lenText); + } + } + break; + case DEVICE_ADS1015: + { + struct_ADS1015 *nodeSetting = (struct_ADS1015 *)temp->configPtr; + if (nodeSetting->log) + { + if (nodeSetting->logA0) + strlcat(helperText, "A0mV,", lenText); + if (nodeSetting->logA1) + strlcat(helperText, "A1mV,", lenText); + if (nodeSetting->logA2) + strlcat(helperText, "A2mV,", lenText); + if (nodeSetting->logA3) + strlcat(helperText, "A3mV,", lenText); + if (nodeSetting->logA0A1) + strlcat(helperText, "A0A1mV,", lenText); + if (nodeSetting->logA0A3) + strlcat(helperText, "A0A3mV,", lenText); + if (nodeSetting->logA1A3) + strlcat(helperText, "A1A3mV,", lenText); + if (nodeSetting->logA2A3) + strlcat(helperText, "A2A3mV,", lenText); + } + } + break; default: SerialPrintf2("\nprinterHelperText device not found: %d\r\n", temp->deviceType); break; diff --git a/Firmware/OpenLog_Artemis/autoDetect.ino b/Firmware/OpenLog_Artemis/autoDetect.ino index ee42b32..4c3ffb1 100644 --- a/Firmware/OpenLog_Artemis/autoDetect.ino +++ b/Firmware/OpenLog_Artemis/autoDetect.ino @@ -267,6 +267,30 @@ bool addDevice(deviceType_e deviceType, uint8_t address, uint8_t muxAddress, uin temp->configPtr = new struct_BIO_SENSOR_HUB; } break; + case DEVICE_ISM330DHCX: + { + temp->classPtr = new SparkFun_ISM330DHCX; + temp->configPtr = new struct_ISM330DHCX; + } + break; + case DEVICE_MMC5983MA: + { + temp->classPtr = new SFE_MMC5983MA; + temp->configPtr = new struct_MMC5983MA; + } + break; + case DEVICE_KX134: + { + temp->classPtr = new SparkFun_KX134; + temp->configPtr = new struct_KX134; + } + break; + case DEVICE_ADS1015: + { + temp->classPtr = new ADS1015; + temp->configPtr = new struct_ADS1015; + } + break; default: SerialPrintf2("addDevice Device type not found: %d\r\n", deviceType); break; @@ -546,6 +570,42 @@ bool beginQwiicDevices() temp->online = true; } break; + case DEVICE_ISM330DHCX: + { + SparkFun_ISM330DHCX *tempDevice = (SparkFun_ISM330DHCX *)temp->classPtr; + struct_ISM330DHCX *nodeSetting = (struct_ISM330DHCX *)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 (tempDevice->begin(qwiic, temp->address)) //Wire port, address + temp->online = true; + } + break; + case DEVICE_MMC5983MA: + { + SFE_MMC5983MA *tempDevice = (SFE_MMC5983MA *)temp->classPtr; + struct_MMC5983MA *nodeSetting = (struct_MMC5983MA *)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 (tempDevice->begin(qwiic)) //Wire port + temp->online = true; + } + break; + case DEVICE_KX134: + { + SparkFun_KX134 *tempDevice = (SparkFun_KX134 *)temp->classPtr; + struct_KX134 *nodeSetting = (struct_KX134 *)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 (tempDevice->begin(qwiic, temp->address)) //Wire port, address + temp->online = true; + } + break; + case DEVICE_ADS1015: + { + ADS1015 *tempDevice = (ADS1015 *)temp->classPtr; + struct_ADS1015 *nodeSetting = (struct_ADS1015 *)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 (tempDevice->begin(temp->address, qwiic)) //address, Wire port + temp->online = true; + } + break; default: SerialPrintf2("beginQwiicDevices: device type not found: %d\r\n", temp->deviceType); break; @@ -838,6 +898,88 @@ void configureDevice(node * temp) sensor->configBpm(MODE_TWO); // MODE_TWO provides the oxygen R value } break; + case DEVICE_ISM330DHCX: + { + SparkFun_ISM330DHCX *sensor = (SparkFun_ISM330DHCX *)temp->classPtr; + struct_ISM330DHCX *sensorSetting = (struct_ISM330DHCX *)temp->configPtr; + + sensor->deviceReset(); + + // Wait for it to finish reseting + while( !sensor->getDeviceReset() ){ + delay(1); + } + + sensor->setDeviceConfig(); + sensor->setBlockDataUpdate(); + + // Set the output data rate and precision of the accelerometer + sensor->setAccelDataRate(sensorSetting->accelRate); + sensor->setAccelFullScale(sensorSetting->accelScale); + + // Turn on the accelerometer's filter and apply settings. + sensor->setAccelFilterLP2(sensorSetting->accelFilterLP2); + sensor->setAccelSlopeFilter(sensorSetting->accelSlopeFilter); + + // Set the output data rate and precision of the gyroscope + sensor->setGyroDataRate(sensorSetting->gyroRate); + sensor->setGyroFullScale(sensorSetting->gyroScale); + + // Turn on the gyroscope's filter and apply settings. + sensor->setGyroFilterLP1(sensorSetting->gyroFilterLP1); + sensor->setGyroLP1Bandwidth(sensorSetting->gyroLP1BW); + } + break; + case DEVICE_MMC5983MA: + { + SFE_MMC5983MA *sensor = (SFE_MMC5983MA *)temp->classPtr; + struct_MMC5983MA *sensorSetting = (struct_MMC5983MA *)temp->configPtr; + + sensor->softReset(); + + sensor->enableAutomaticSetReset(); + } + break; + case DEVICE_KX134: + { + SparkFun_KX134 *sensor = (SparkFun_KX134 *)temp->classPtr; + struct_KX134 *sensorSetting = (struct_KX134 *)temp->configPtr; + + sensor->softwareReset(); + delay(5); + + sensor->enableAccel(false); + + if (sensorSetting->range8G) sensor->setRange(SFE_KX134_RANGE8G); + else if (sensorSetting->range16G) sensor->setRange(SFE_KX134_RANGE16G); + else if (sensorSetting->range32G) sensor->setRange(SFE_KX134_RANGE32G); + else sensor->setRange(SFE_KX134_RANGE64G); + + sensor->enableDataEngine(); // Enables the bit that indicates data is ready. + + if (sensorSetting->highSpeed) sensor->setOutputDataRate(9); // 400Hz + else sensor->setOutputDataRate(6); // Default is 50Hz + + sensor->enableAccel(); + } + break; + case DEVICE_ADS1015: + { + ADS1015 *sensor = (ADS1015 *)temp->classPtr; + struct_ADS1015 *sensorSetting = (struct_ADS1015 *)temp->configPtr; + + if (sensorSetting->gain23) sensor->setGain(ADS1015_CONFIG_PGA_TWOTHIRDS); + else if (sensorSetting->gain1) sensor->setGain(ADS1015_CONFIG_PGA_1); + else if (sensorSetting->gain2) sensor->setGain(ADS1015_CONFIG_PGA_2); + else if (sensorSetting->gain4) sensor->setGain(ADS1015_CONFIG_PGA_4); + else if (sensorSetting->gain8) sensor->setGain(ADS1015_CONFIG_PGA_8); + else sensor->setGain(ADS1015_CONFIG_PGA_16); + + //sensor->setSampleRate(ADS1015_CONFIG_RATE_490HZ); // Default is 1600Hz + + sensor->useConversionReady(true); + } + break; default: SerialPrintf3("configureDevice: Unknown device type %d: %s\r\n", deviceType, getDeviceName((deviceType_e)deviceType)); break; @@ -947,6 +1089,18 @@ FunctionPointer getConfigFunctionPtr(uint8_t nodeNumber) case DEVICE_BIO_SENSOR_HUB: ptr = (FunctionPointer)menuConfigure_BIO_SENSOR_HUB; break; + case DEVICE_ISM330DHCX: + ptr = (FunctionPointer)menuConfigure_ISM330DHCX; + break; + case DEVICE_MMC5983MA: + ptr = (FunctionPointer)menuConfigure_MMC5983MA; + break; + case DEVICE_KX134: + ptr = (FunctionPointer)menuConfigure_KX134; + break; + case DEVICE_ADS1015: + ptr = (FunctionPointer)menuConfigure_ADS1015; + break; default: SerialPrintln(F("getConfigFunctionPtr: Unknown device type")); SerialFlush(); @@ -1076,15 +1230,18 @@ void swap(struct node * a, struct node * b) //We no longer use defines in the search table. These are just here for reference. #define ADR_VEML6075 0x10 #define ADR_MPR0025PA1 0x18 +#define ADR_KX134 0x1E //Alternate: 0x1F #define ADR_SDP3X 0x21 //Alternates: 0x22, 0x23 #define ADR_NAU7802 0x2A #define ADR_VL53L1X 0x29 +#define ADR_MMC5983MA 0x30 #define ADR_SNGCJA5 0x33 #define ADR_AHT20 0x38 #define ADR_MS8607 0x40 //Humidity portion of the MS8607 sensor #define ADR_UBLOX 0x42 //But can be set to any address #define ADR_ADS122C04 0x45 //Alternates: 0x44, 0x41 and 0x40 #define ADR_TMP117 0x48 //Alternates: 0x49, 0x4A, and 0x4B +#define ADR_ADS1015 0x48 //Alternates: 0x49, 0x4A, and 0x4B #define ADR_BIO_SENSOR_HUB 0x55 #define ADR_SGP30 0x58 #define ADR_SGP40 0x59 @@ -1093,6 +1250,7 @@ void swap(struct node * a, struct node * b) #define ADR_VCNL4040 0x60 #define ADR_SCD30 0x61 #define ADR_MCP9600 0x60 //0x60 to 0x67 +#define ADR_ISM330DHCX 0x6A //Alternate: 0x6B #define ADR_QWIIC_BUTTON 0x6F //But can be any address... Limit the range to 0x68-0x6F #define ADR_MULTIPLEXER 0x70 //0x70 to 0x77 #define ADR_SHTC3 0x70 @@ -1124,24 +1282,17 @@ deviceType_e testDevice(uint8_t i2cAddress, uint8_t muxAddress, uint8_t portNumb return (DEVICE_PRESSURE_MPR0025PA1); } break; - case 0x21: + case 0x1E: + case 0x1F: { - //Confidence: High - .begin reads the product ID - SDP3X sensor; - sensor.stopContinuousMeasurement(i2cAddress, qwiic); //Make sure continuous measurements are stopped or .begin will fail - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_PRESSURE_SDP3X); + //Confidence: High - reads ID register + SparkFun_KX134 sensor; + if (sensor.begin(qwiic, i2cAddress) == true) //Wire port, Address + return (DEVICE_KX134); } break; + case 0x21: case 0x22: - { - //Confidence: High - .begin reads the product ID - SDP3X sensor; - sensor.stopContinuousMeasurement(i2cAddress, qwiic); //Make sure continuous measurements are stopped or .begin will fail - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_PRESSURE_SDP3X); - } - break; case 0x23: { //Confidence: High - .begin reads the product ID @@ -1168,6 +1319,14 @@ deviceType_e testDevice(uint8_t i2cAddress, uint8_t muxAddress, uint8_t portNumb return (DEVICE_DISTANCE_VL53L1X); } break; + case 0x30: + { + //Confidence: high - reads PROD_ID_REG + SFE_MMC5983MA sensor; + if (sensor.begin(qwiic) == true) //Wire port + return (DEVICE_MMC5983MA); + } + break; case 0x33: { //Confidence: low - basic isConnected test only... @@ -1230,35 +1389,19 @@ deviceType_e testDevice(uint8_t i2cAddress, uint8_t muxAddress, uint8_t portNumb } break; case 0x48: - { - //Confidence: High - Checks 16 bit ID - TMP117 sensor; - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_TEMPERATURE_TMP117); - } - break; case 0x49: - { - //Confidence: High - Checks 16 bit ID - TMP117 sensor; - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_TEMPERATURE_TMP117); - } - break; case 0x4A: - { - //Confidence: High - Checks 16 bit ID - TMP117 sensor; - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_TEMPERATURE_TMP117); - } - break; case 0x4B: { //Confidence: High - Checks 16 bit ID TMP117 sensor; if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port return (DEVICE_TEMPERATURE_TMP117); + + //Confidence: Low - only does a simple isConnected + ADS1015 sensor1; + if (sensor1.begin(i2cAddress, qwiic) == true) //Address, Wire port + return (DEVICE_ADS1015); } break; case 0x55: @@ -1332,42 +1475,11 @@ deviceType_e testDevice(uint8_t i2cAddress, uint8_t muxAddress, uint8_t portNumb } break; case 0x62: - { - //Always do the MCP9600 first. It's fussy... - //Confidence: High - Checks 8bit ID - MCP9600 sensor; - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_TEMPERATURE_MCP9600); - } - break; case 0x63: - { - //Always do the MCP9600 first. It's fussy... - //Confidence: High - Checks 8bit ID - MCP9600 sensor; - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_TEMPERATURE_MCP9600); - } - break; case 0x64: - { - //Always do the MCP9600 first. It's fussy... - //Confidence: High - Checks 8bit ID - MCP9600 sensor; - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_TEMPERATURE_MCP9600); - } - break; case 0x65: - { - //Always do the MCP9600 first. It's fussy... - //Confidence: High - Checks 8bit ID - MCP9600 sensor; - if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_TEMPERATURE_MCP9600); - } - break; case 0x66: + case 0x67: { //Always do the MCP9600 first. It's fussy... //Confidence: High - Checks 8bit ID @@ -1376,19 +1488,26 @@ deviceType_e testDevice(uint8_t i2cAddress, uint8_t muxAddress, uint8_t portNumb return (DEVICE_TEMPERATURE_MCP9600); } break; - case 0x67: + case 0x68: + case 0x69: { - //Always do the MCP9600 first. It's fussy... - //Confidence: High - Checks 8bit ID - MCP9600 sensor; + QwiicButton sensor; if (sensor.begin(i2cAddress, qwiic) == true) //Address, Wire port - return (DEVICE_TEMPERATURE_MCP9600); + return (DEVICE_QWIIC_BUTTON); } break; - case 0x68: - case 0x69: case 0x6A: case 0x6B: + { + SparkFun_ISM330DHCX sensor; + if (sensor.begin(qwiic, i2cAddress)) + return(DEVICE_ISM330DHCX); + + QwiicButton sensor1; + if (sensor1.begin(i2cAddress, qwiic) == true) //Address, Wire port + return (DEVICE_QWIIC_BUTTON); + } + break; case 0x6C: case 0x6D: case 0x6E: @@ -1411,29 +1530,9 @@ deviceType_e testDevice(uint8_t i2cAddress, uint8_t muxAddress, uint8_t portNumb } break; case 0x71: - { - //Ignore devices we've already recorded. This was causing the mux to get tested, a begin() would happen, and the mux would be reset. - if (deviceExists(DEVICE_MULTIPLEXER, i2cAddress, muxAddress, portNumber) == true) return (DEVICE_MULTIPLEXER); - } - break; case 0x72: - { - //Ignore devices we've already recorded. This was causing the mux to get tested, a begin() would happen, and the mux would be reset. - if (deviceExists(DEVICE_MULTIPLEXER, i2cAddress, muxAddress, portNumber) == true) return (DEVICE_MULTIPLEXER); - } - break; case 0x73: - { - //Ignore devices we've already recorded. This was causing the mux to get tested, a begin() would happen, and the mux would be reset. - if (deviceExists(DEVICE_MULTIPLEXER, i2cAddress, muxAddress, portNumber) == true) return (DEVICE_MULTIPLEXER); - } - break; case 0x74: - { - //Ignore devices we've already recorded. This was causing the mux to get tested, a begin() would happen, and the mux would be reset. - if (deviceExists(DEVICE_MULTIPLEXER, i2cAddress, muxAddress, portNumber) == true) return (DEVICE_MULTIPLEXER); - } - break; case 0x75: { //Ignore devices we've already recorded. This was causing the mux to get tested, a begin() would happen, and the mux would be reset. @@ -1754,6 +1853,18 @@ const char* getDeviceName(deviceType_e deviceNumber) case DEVICE_BIO_SENSOR_HUB: return "Bio-Sensor-Oximeter"; break; + case DEVICE_ISM330DHCX: + return "IMU-ISM330DHCX"; + break; + case DEVICE_MMC5983MA: + return "Mag-MMC5983MA"; + break; + case DEVICE_KX134: + return "Accel-KX134"; + break; + case DEVICE_ADS1015: + return "ADC-ADS1015"; + break; case DEVICE_UNKNOWN_DEVICE: return "Unknown device"; diff --git a/Firmware/OpenLog_Artemis/menuAttachedDevices.ino b/Firmware/OpenLog_Artemis/menuAttachedDevices.ino index 5281574..68a7838 100644 --- a/Firmware/OpenLog_Artemis/menuAttachedDevices.ino +++ b/Firmware/OpenLog_Artemis/menuAttachedDevices.ino @@ -357,6 +357,18 @@ void menuAttachedDevices() case DEVICE_BIO_SENSOR_HUB: SerialPrintf3("%s Bio Sensor Pulse Oximeter %s\r\n", strDeviceMenu, strAddress); break; + case DEVICE_ISM330DHCX: + SerialPrintf3("%s ISM330DHCX IMU %s\r\n", strDeviceMenu, strAddress); + break; + case DEVICE_MMC5983MA: + SerialPrintf3("%s MMC5983MA Magnetometer %s\r\n", strDeviceMenu, strAddress); + break; + case DEVICE_KX134: + SerialPrintf3("%s KX134 Accelerometer %s\r\n", strDeviceMenu, strAddress); + break; + case DEVICE_ADS1015: + SerialPrintf3("%s ADS1015 ADC %s\r\n", strDeviceMenu, strAddress); + break; default: SerialPrintf2("Unknown device type %d in menuAttachedDevices\r\n", temp->deviceType); break; @@ -2463,25 +2475,29 @@ void menuConfigure_MS5837(void *configPtr) if (sensorSetting->log == true) { + char tempStr[16]; + SerialPrint(F("2) Log Pressure: ")); if (sensorSetting->logPressure == true) SerialPrintln(F("Enabled")); else SerialPrintln(F("Disabled")); - + SerialPrint(F("3) Log Temperature: ")); if (sensorSetting->logTemperature == true) SerialPrintln(F("Enabled")); else SerialPrintln(F("Disabled")); - + SerialPrint(F("4) Log Depth: ")); if (sensorSetting->logDepth == true) SerialPrintln(F("Enabled")); else SerialPrintln(F("Disabled")); - + SerialPrint(F("5) Log Altitude: ")); if (sensorSetting->logAltitude == true) SerialPrintln(F("Enabled")); else SerialPrintln(F("Disabled")); - SerialPrintf2("6) Fluid Density (kg/m^3): %f\r\n", sensorSetting->fluidDensity); - - SerialPrintf2("7) Pressure Conversion Factor: %.02f\r\n", sensorSetting->conversion); + olaftoa(sensorSetting->fluidDensity, tempStr, 1, sizeof(tempStr) / sizeof(char)); + SerialPrintf2("6) Fluid Density (kg/m^3): %s\r\n", tempStr); + + olaftoa(sensorSetting->conversion, tempStr, 3, sizeof(tempStr) / sizeof(char)); + SerialPrintf2("7) Pressure Conversion Factor: %s\r\n", tempStr); } SerialPrintln(F("x) Exit")); @@ -2669,3 +2685,502 @@ void menuConfigure_BIO_SENSOR_HUB(void *configPtr) printUnknown(incoming); } } + +void menuConfigure_ISM330DHCX(void *configPtr) +{ + struct_ISM330DHCX *sensorSetting = (struct_ISM330DHCX *)configPtr; + + while (1) + { + SerialPrintln(F("")); + SerialPrintln(F("Menu: Configure ISM330DHCX IMU")); + + SerialPrint(F("1) Sensor Logging: ")); + if (sensorSetting->log == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + if (sensorSetting->log == true) + { + SerialPrint(F("2) Log Accelerometer: ")); + if (sensorSetting->logAccel == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("3) Log Gyro: ")); + if (sensorSetting->logGyro == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("4) Log Data Ready: ")); + if (sensorSetting->logDataReady == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrintf2("5) Accel Scale: %d\r\n", sensorSetting->accelScale); + SerialPrintf2("6) Accel Rate: %d\r\n", sensorSetting->accelRate); + SerialPrint(F("7) Accel Filter LP2: ")); + if (sensorSetting->accelFilterLP2 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + SerialPrintf2("8) Accel Slope Filter: %d\r\n", sensorSetting->accelSlopeFilter); + SerialPrintf2("9) Gyro Scale: %d\r\n", sensorSetting->gyroScale); + SerialPrintf2("10) Gyro Rate: %d\r\n", sensorSetting->gyroRate); + SerialPrint(F("11) Gyro Filter LP1: ")); + if (sensorSetting->gyroFilterLP1 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + SerialPrintf2("12) Gyro LP1 Bandwidth: %d\r\n", sensorSetting->gyroLP1BW); + } + SerialPrintln(F("x) Exit")); + + int incoming = getNumber(menuTimeout); //Timeout after x seconds + + if (incoming == 1) + sensorSetting->log ^= 1; + else if (sensorSetting->log == true) + { + if (incoming == 2) + sensorSetting->logAccel ^= 1; + else if (incoming == 3) + sensorSetting->logGyro ^= 1; + else if (incoming == 4) + sensorSetting->logDataReady ^= 1; + else if (incoming == 5) + { + SerialPrintln(F("2g : 0")); + SerialPrintln(F("16g: 1")); + SerialPrintln(F("4g : 2")); + SerialPrintln(F("8g : 3")); + SerialPrint(F("Enter the Accel Full Scale (0 to 3): ")); + int newNum = getNumber(menuTimeout); //x second timeout + if (newNum < 0 || newNum > 3) + SerialPrintln(F("Error: Out of range")); + else + sensorSetting->accelScale = newNum; + } + else if (incoming == 6) + { + SerialPrintln(F("OFF : 0")); + SerialPrintln(F("12.5Hz: 1")); + SerialPrintln(F("26Hz : 2")); + SerialPrintln(F("52Hz : 3")); + SerialPrintln(F("104Hz : 4")); + SerialPrintln(F("208Hz : 5")); + SerialPrintln(F("416Hz : 6")); + SerialPrintln(F("833Hz : 7")); + SerialPrintln(F("1666Hz: 8")); + SerialPrintln(F("3332Hz: 9")); + SerialPrintln(F("6667Hz: 10")); + SerialPrintln(F("1Hz6 : 11")); + SerialPrint(F("Enter the Accel Rate (0 to 11): ")); + int newNum = getNumber(menuTimeout); //x second timeout + if (newNum < 0 || newNum > 11) + SerialPrintln(F("Error: Out of range")); + else + sensorSetting->accelRate = newNum; + } + else if (incoming == 7) + sensorSetting->accelFilterLP2 ^= 1; + else if (incoming == 8) + { + SerialPrintln(F("HP_PATH_DISABLE_ON_OUT: 0")); + SerialPrintln(F("LP_ODR_DIV_10 : 1")); + SerialPrintln(F("LP_ODR_DIV_20 : 2")); + SerialPrintln(F("LP_ODR_DIV_45 : 3")); + SerialPrintln(F("LP_ODR_DIV_100 : 4")); + SerialPrintln(F("LP_ODR_DIV_200 : 5")); + SerialPrintln(F("LP_ODR_DIV_400 : 6")); + SerialPrintln(F("LP_ODR_DIV_800 : 7")); + SerialPrintln(F("SLOPE_ODR_DIV_4 : 16")); + SerialPrintln(F("HP_ODR_DIV_10 : 17")); + SerialPrintln(F("HP_ODR_DIV_20 : 18")); + SerialPrintln(F("HP_ODR_DIV_45 : 19")); + SerialPrintln(F("HP_ODR_DIV_100 : 20")); + SerialPrintln(F("HP_ODR_DIV_200 : 21")); + SerialPrintln(F("HP_ODR_DIV_400 : 22")); + SerialPrintln(F("HP_ODR_DIV_800 : 23")); + SerialPrintln(F("HP_REF_MD_ODR_DIV_10 : 49")); + SerialPrintln(F("HP_REF_MD_ODR_DIV_20 : 50")); + SerialPrintln(F("HP_REF_MD_ODR_DIV_45 : 51")); + SerialPrintln(F("HP_REF_MD_ODR_DIV_100 : 52")); + SerialPrintln(F("HP_REF_MD_ODR_DIV_200 : 53")); + SerialPrintln(F("HP_REF_MD_ODR_DIV_400 : 54")); + SerialPrintln(F("HP_REF_MD_ODR_DIV_800 : 55")); + SerialPrint(F("Enter the Accel Slope Filter setting (0 to 55): ")); + int newNum = getNumber(menuTimeout); //x second timeout + if (newNum < 0 || newNum > 55) + SerialPrintln(F("Error: Out of range")); + else + sensorSetting->accelSlopeFilter = newNum; + } + else if (incoming == 9) + { + SerialPrintln(F("125dps : 2")); + SerialPrintln(F("250dps : 0")); + SerialPrintln(F("500dps : 4")); + SerialPrintln(F("1000dps: 8")); + SerialPrintln(F("2000dps: 12")); + SerialPrintln(F("4000dps: 1")); + SerialPrint(F("Enter the Gyro Full Scale (0 to 12): ")); + int newNum = getNumber(menuTimeout); //x second timeout + if (newNum < 0 || newNum > 12) + SerialPrintln(F("Error: Out of range")); + else + sensorSetting->gyroScale = newNum; + } + else if (incoming == 10) + { + SerialPrintln(F("OFF : 0")); + SerialPrintln(F("12Hz : 1")); + SerialPrintln(F("26Hz : 2")); + SerialPrintln(F("52Hz : 3")); + SerialPrintln(F("104Hz : 4")); + SerialPrintln(F("208Hz : 5")); + SerialPrintln(F("416Hz : 6")); + SerialPrintln(F("833Hz : 7")); + SerialPrintln(F("1666Hz: 8")); + SerialPrintln(F("3332Hz: 9")); + SerialPrintln(F("6667Hz: 10")); + SerialPrint(F("Enter the Gyro Rate (0 to 10): ")); + int newNum = getNumber(menuTimeout); //x second timeout + if (newNum < 0 || newNum > 10) + SerialPrintln(F("Error: Out of range")); + else + sensorSetting->gyroRate = newNum; + } + else if (incoming == 11) + sensorSetting->gyroFilterLP1 ^= 1; + else if (incoming == 12) + { + SerialPrintln(F("ULTRA_LIGHT: 0")); + SerialPrintln(F("VERY_LIGHT : 1")); + SerialPrintln(F("LIGHT : 2")); + SerialPrintln(F("MEDIUM : 3")); + SerialPrintln(F("STRONG : 4")); + SerialPrintln(F("VERY_STRONG: 5")); + SerialPrintln(F("AGGRESSIVE : 6")); + SerialPrintln(F("XTREME : 7")); + SerialPrintln(F("Enter the Gyro LP1 Bandwidth (0 to 7): ")); + int newNum = getNumber(menuTimeout); //x second timeout + if (newNum < 0 || newNum > 7) + SerialPrintln(F("Error: Out of range")); + else + sensorSetting->gyroLP1BW = newNum; + } + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } +} + +void menuConfigure_MMC5983MA(void *configPtr) +{ + struct_MMC5983MA *sensorSetting = (struct_MMC5983MA *)configPtr; + + while (1) + { + SerialPrintln(F("")); + SerialPrintln(F("Menu: Configure MMC5983MA Magnetometer")); + + SerialPrint(F("1) Sensor Logging: ")); + if (sensorSetting->log == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + if (sensorSetting->log == true) + { + SerialPrint(F("2) Log Magnetometer: ")); + if (sensorSetting->logMag == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("3) Log Temperature: ")); + if (sensorSetting->logTemperature == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + } + SerialPrintln(F("x) Exit")); + + int incoming = getNumber(menuTimeout); //Timeout after x seconds + + if (incoming == 1) + sensorSetting->log ^= 1; + else if (sensorSetting->log == true) + { + if (incoming == 2) + sensorSetting->logMag ^= 1; + else if (incoming == 3) + sensorSetting->logTemperature ^= 1; + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } +} + +void menuConfigure_KX134(void *configPtr) +{ + struct_KX134 *sensorSetting = (struct_KX134 *)configPtr; + + while (1) + { + SerialPrintln(F("")); + SerialPrintln(F("Menu: Configure KX134 Accelerometer")); + + SerialPrint(F("1) Sensor Logging: ")); + if (sensorSetting->log == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + if (sensorSetting->log == true) + { + SerialPrint(F("2) Range 8G: ")); + if (sensorSetting->range8G == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("3) Range 16G: ")); + if (sensorSetting->range16G == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("4) Range 32G: ")); + if (sensorSetting->range32G == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("5) Range 64G: ")); + if (sensorSetting->range64G == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("6) High Speed (400Hz): ")); + if (sensorSetting->highSpeed == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + } + SerialPrintln(F("x) Exit")); + + int incoming = getNumber(menuTimeout); //Timeout after x seconds + + if (incoming == 1) + sensorSetting->log ^= 1; + else if (sensorSetting->log == true) + { + if (incoming == 2) + { + sensorSetting->range8G = true; + sensorSetting->range16G = false; + sensorSetting->range32G = false; + sensorSetting->range64G = false; + } + else if (incoming == 3) + { + sensorSetting->range8G = false; + sensorSetting->range16G = true; + sensorSetting->range32G = false; + sensorSetting->range64G = false; + } + else if (incoming == 3) + { + sensorSetting->range8G = false; + sensorSetting->range16G = false; + sensorSetting->range32G = true; + sensorSetting->range64G = false; + } + else if (incoming == 5) + { + sensorSetting->range8G = false; + sensorSetting->range16G = false; + sensorSetting->range32G = false; + sensorSetting->range64G = true; + } + else if (incoming == 6) + sensorSetting->highSpeed ^= 1; + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } +} + +void menuConfigure_ADS1015(void *configPtr) +{ + struct_ADS1015 *sensorSetting = (struct_ADS1015 *)configPtr; + + while (1) + { + SerialPrintln(F("")); + SerialPrintln(F("Menu: Configure ADS1015 ADC")); + + SerialPrint(F("1) Sensor Logging: ")); + if (sensorSetting->log == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + if (sensorSetting->log == true) + { + SerialPrint(F("2) Log A0: ")); + if (sensorSetting->logA0 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("3) Log A1: ")); + if (sensorSetting->logA1 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("4) Log A2: ")); + if (sensorSetting->logA2 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("5) Log A3: ")); + if (sensorSetting->logA3 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("6) Log A0-A1: ")); + if (sensorSetting->logA0A1 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("7) Log A0-A3: ")); + if (sensorSetting->logA0A3 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("8) Log A1-A3: ")); + if (sensorSetting->logA1A3 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("9) Log A2-A3: ")); + if (sensorSetting->logA2A3 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("10) Gain x2/3: ")); + if (sensorSetting->gain23 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("11) Gain x1: ")); + if (sensorSetting->gain1 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("12) Gain x2: ")); + if (sensorSetting->gain2 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("13) Gain x4: ")); + if (sensorSetting->gain4 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("14) Gain x8: ")); + if (sensorSetting->gain8 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + SerialPrint(F("15) Gain x16: ")); + if (sensorSetting->gain16 == true) SerialPrintln(F("Enabled")); + else SerialPrintln(F("Disabled")); + + } + SerialPrintln(F("x) Exit")); + + int incoming = getNumber(menuTimeout); //Timeout after x seconds + + if (incoming == 1) + sensorSetting->log ^= 1; + else if (sensorSetting->log == true) + { + if (incoming == 2) + sensorSetting->logA0 ^= 1; + else if (incoming == 3) + sensorSetting->logA1 ^= 1; + else if (incoming == 4) + sensorSetting->logA2 ^= 1; + else if (incoming == 5) + sensorSetting->logA3 ^= 1; + else if (incoming == 6) + sensorSetting->logA0A1 ^= 1; + else if (incoming == 7) + sensorSetting->logA0A3 ^= 1; + else if (incoming == 8) + sensorSetting->logA1A3 ^= 1; + else if (incoming == 9) + sensorSetting->logA2A3 ^= 1; + else if (incoming == 10) + { + sensorSetting->gain23 = true; + sensorSetting->gain1 = false; + sensorSetting->gain2 = false; + sensorSetting->gain4 = false; + sensorSetting->gain8 = false; + sensorSetting->gain16 = false; + } + else if (incoming == 11) + { + sensorSetting->gain23 = false; + sensorSetting->gain1 = true; + sensorSetting->gain2 = false; + sensorSetting->gain4 = false; + sensorSetting->gain8 = false; + sensorSetting->gain16 = false; + } + else if (incoming == 12) + { + sensorSetting->gain23 = false; + sensorSetting->gain1 = false; + sensorSetting->gain2 = true; + sensorSetting->gain4 = false; + sensorSetting->gain8 = false; + sensorSetting->gain16 = false; + } + else if (incoming == 13) + { + sensorSetting->gain23 = false; + sensorSetting->gain1 = false; + sensorSetting->gain2 = false; + sensorSetting->gain4 = true; + sensorSetting->gain8 = false; + sensorSetting->gain16 = false; + } + else if (incoming == 14) + { + sensorSetting->gain23 = false; + sensorSetting->gain1 = false; + sensorSetting->gain2 = false; + sensorSetting->gain4 = false; + sensorSetting->gain8 = true; + sensorSetting->gain16 = false; + } + else if (incoming == 15) + { + sensorSetting->gain23 = false; + sensorSetting->gain1 = false; + sensorSetting->gain2 = false; + sensorSetting->gain4 = false; + sensorSetting->gain8 = false; + sensorSetting->gain16 = true; + } + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } +} diff --git a/Firmware/OpenLog_Artemis/menuDebug.ino b/Firmware/OpenLog_Artemis/menuDebug.ino index 4d2b5f6..c672858 100644 --- a/Firmware/OpenLog_Artemis/menuDebug.ino +++ b/Firmware/OpenLog_Artemis/menuDebug.ino @@ -21,6 +21,8 @@ void menuDebug() if (settings.openMenuWithPrintable == true) SerialPrintln(F("Yes")); else SerialPrintln(F("No")); + SerialPrintln(F("5) Reboot the logger")); + SerialPrintln(F("x) Exit")); byte incoming = getByteChoice(menuTimeout); //Timeout after x seconds @@ -58,6 +60,16 @@ void menuDebug() { settings.openMenuWithPrintable ^= 1; } + else if (incoming == '5') + { + SerialPrint(F("Are you sure? Press 'y' to confirm: ")); + byte bContinue = getByteChoice(menuTimeout); + if (bContinue == 'y') + { + SerialPrintln(F("y")); + resetArtemis(); + } + } else if (incoming == 'x') break; else if (incoming == STATUS_GETBYTE_TIMEOUT) diff --git a/Firmware/OpenLog_Artemis/menuMain.ino b/Firmware/OpenLog_Artemis/menuMain.ino index 55dd333..fc38843 100644 --- a/Firmware/OpenLog_Artemis/menuMain.ino +++ b/Firmware/OpenLog_Artemis/menuMain.ino @@ -82,7 +82,9 @@ void menuMain(bool alwaysOpen) break; //return to logging } else if (incoming == 'd') + { menuDebug(); + } else if (incoming == 's') { if (online.microSD) @@ -103,20 +105,24 @@ void menuMain(bool alwaysOpen) SerialPrintln(F("")); SerialPrintln(F("")); - sdCardMenu(); // Located in zmodem.ino + sdCardMenu(sdCardMenuTimeout); // Located in zmodem.ino SerialPrintln(F("")); SerialPrintln(F("")); if (online.dataLogging == true) { - strcpy(sensorDataFileName, findNextAvailableLog(settings.nextDataLogNumber, "dataLog")); + // Check if the current datafile was deleted + if (sd.exists(sensorDataFileName) == false) + strcpy(sensorDataFileName, findNextAvailableLog(settings.nextDataLogNumber, "dataLog")); beginDataLogging(); //180ms if (settings.showHelperText == true) printHelperText(OL_OUTPUT_SERIAL | OL_OUTPUT_SDCARD); //printHelperText to terminal and sensor file } if (online.serialLogging == true) { - strcpy(serialDataFileName, findNextAvailableLog(settings.nextSerialLogNumber, "serialLog")); + // Check if the current serial file was deleted + if (sd.exists(serialDataFileName) == false) + strcpy(serialDataFileName, findNextAvailableLog(settings.nextSerialLogNumber, "serialLog")); beginSerialLogging(); } } diff --git a/Firmware/OpenLog_Artemis/nvm.ino b/Firmware/OpenLog_Artemis/nvm.ino index 10e31bf..2add83f 100644 --- a/Firmware/OpenLog_Artemis/nvm.ino +++ b/Firmware/OpenLog_Artemis/nvm.ino @@ -784,6 +784,64 @@ void recordDeviceSettingsToFile() settingsFile.println((String)base + "logRValue=" + nodeSetting->logRValue); } break; + case DEVICE_ISM330DHCX: + { + struct_ISM330DHCX *nodeSetting = (struct_ISM330DHCX *)temp->configPtr; + settingsFile.println((String)base + "log=" + nodeSetting->log); + settingsFile.println((String)base + "logAccel=" + nodeSetting->logAccel); + settingsFile.println((String)base + "logGyro=" + nodeSetting->logGyro); + settingsFile.println((String)base + "logDataReady=" + nodeSetting->logDataReady); + settingsFile.println((String)base + "accelScale=" + nodeSetting->accelScale); + settingsFile.println((String)base + "gyroScale=" + nodeSetting->gyroScale); + settingsFile.println((String)base + "accelRate=" + nodeSetting->accelRate); + settingsFile.println((String)base + "gyroRate=" + nodeSetting->gyroRate); + settingsFile.println((String)base + "accelFilterLP2=" + nodeSetting->accelFilterLP2); + settingsFile.println((String)base + "gyroFilterLP1=" + nodeSetting->gyroFilterLP1); + settingsFile.println((String)base + "gyroLP1BW=" + nodeSetting->gyroLP1BW); + settingsFile.println((String)base + "accelSlopeFilter=" + nodeSetting->accelSlopeFilter); + } + break; + case DEVICE_MMC5983MA: + { + struct_MMC5983MA *nodeSetting = (struct_MMC5983MA *)temp->configPtr; + settingsFile.println((String)base + "log=" + nodeSetting->log); + settingsFile.println((String)base + "logMag=" + nodeSetting->logMag); + settingsFile.println((String)base + "logTemperature=" + nodeSetting->logTemperature); + } + break; + case DEVICE_KX134: + { + struct_KX134 *nodeSetting = (struct_KX134 *)temp->configPtr; + settingsFile.println((String)base + "log=" + nodeSetting->log); + settingsFile.println((String)base + "logAccel=" + nodeSetting->logAccel); + settingsFile.println((String)base + "logDataReady=" + nodeSetting->logDataReady); + settingsFile.println((String)base + "range8G=" + nodeSetting->range8G); + settingsFile.println((String)base + "range16G=" + nodeSetting->range16G); + settingsFile.println((String)base + "range32G=" + nodeSetting->range32G); + settingsFile.println((String)base + "range64G=" + nodeSetting->range64G); + settingsFile.println((String)base + "highSpeed=" + nodeSetting->highSpeed); + } + break; + case DEVICE_ADS1015: + { + struct_ADS1015 *nodeSetting = (struct_ADS1015 *)temp->configPtr; + settingsFile.println((String)base + "log=" + nodeSetting->log); + settingsFile.println((String)base + "logA0=" + nodeSetting->logA0); + settingsFile.println((String)base + "logA1=" + nodeSetting->logA1); + settingsFile.println((String)base + "logA2=" + nodeSetting->logA2); + settingsFile.println((String)base + "logA3=" + nodeSetting->logA3); + settingsFile.println((String)base + "logA0A1=" + nodeSetting->logA0A1); + settingsFile.println((String)base + "logA0A3=" + nodeSetting->logA0A3); + settingsFile.println((String)base + "logA1A3=" + nodeSetting->logA1A3); + settingsFile.println((String)base + "logA2A3=" + nodeSetting->logA2A3); + settingsFile.println((String)base + "gain23=" + nodeSetting->gain23); + settingsFile.println((String)base + "gain1=" + nodeSetting->gain1); + settingsFile.println((String)base + "gain2=" + nodeSetting->gain2); + settingsFile.println((String)base + "gain4=" + nodeSetting->gain4); + settingsFile.println((String)base + "gain8=" + nodeSetting->gain8); + settingsFile.println((String)base + "gain16=" + nodeSetting->gain16); + } + break; default: SerialPrintf2("recordSettingsToFile Unknown device: %s\r\n", base); //settingsFile.println((String)base + "=UnknownDeviceSettings"); @@ -1409,6 +1467,110 @@ bool parseDeviceLine(char* str) { SerialPrintf2("Unknown device setting: %s\r\n", deviceSettingName); } break; + case DEVICE_ISM330DHCX: + { + struct_ISM330DHCX *nodeSetting = (struct_ISM330DHCX *)deviceConfigPtr; //Create a local pointer that points to same spot as node does + if (strcmp(deviceSettingName, "log") == 0) + nodeSetting->log = d; + else if (strcmp(deviceSettingName, "logAccel") == 0) + nodeSetting->logAccel = d; + else if (strcmp(deviceSettingName, "logGyro") == 0) + nodeSetting->logGyro = d; + else if (strcmp(deviceSettingName, "logDataReady") == 0) + nodeSetting->logDataReady = d; + else if (strcmp(deviceSettingName, "accelScale") == 0) + nodeSetting->accelScale = d; + else if (strcmp(deviceSettingName, "gyroScale") == 0) + nodeSetting->gyroScale = d; + else if (strcmp(deviceSettingName, "accelRate") == 0) + nodeSetting->accelRate = d; + else if (strcmp(deviceSettingName, "gyroRate") == 0) + nodeSetting->gyroRate = d; + else if (strcmp(deviceSettingName, "accelFilterLP2") == 0) + nodeSetting->accelFilterLP2 = d; + else if (strcmp(deviceSettingName, "gyroFilterLP1") == 0) + nodeSetting->gyroFilterLP1 = d; + else if (strcmp(deviceSettingName, "gyroLP1BW") == 0) + nodeSetting->gyroLP1BW = d; + else if (strcmp(deviceSettingName, "accelSlopeFilter") == 0) + nodeSetting->accelSlopeFilter = d; + else + SerialPrintf2("Unknown device setting: %s\r\n", deviceSettingName); + } + break; + case DEVICE_MMC5983MA: + { + struct_MMC5983MA *nodeSetting = (struct_MMC5983MA *)deviceConfigPtr; //Create a local pointer that points to same spot as node does + if (strcmp(deviceSettingName, "log") == 0) + nodeSetting->log = d; + else if (strcmp(deviceSettingName, "logMag") == 0) + nodeSetting->logMag = d; + else if (strcmp(deviceSettingName, "logTemperature") == 0) + nodeSetting->logTemperature = d; + else + SerialPrintf2("Unknown device setting: %s\r\n", deviceSettingName); + } + break; + case DEVICE_KX134: + { + struct_KX134 *nodeSetting = (struct_KX134 *)deviceConfigPtr; //Create a local pointer that points to same spot as node does + if (strcmp(deviceSettingName, "log") == 0) + nodeSetting->log = d; + else if (strcmp(deviceSettingName, "logAccel") == 0) + nodeSetting->logAccel = d; + else if (strcmp(deviceSettingName, "logDataReady") == 0) + nodeSetting->logDataReady = d; + else if (strcmp(deviceSettingName, "range8G") == 0) + nodeSetting->range8G = d; + else if (strcmp(deviceSettingName, "range16G") == 0) + nodeSetting->range16G = d; + else if (strcmp(deviceSettingName, "range32G") == 0) + nodeSetting->range32G = d; + else if (strcmp(deviceSettingName, "range64G") == 0) + nodeSetting->range64G = d; + else if (strcmp(deviceSettingName, "highSpeed") == 0) + nodeSetting->highSpeed = d; + else + SerialPrintf2("Unknown device setting: %s\r\n", deviceSettingName); + } + break; + case DEVICE_ADS1015: + { + struct_ADS1015 *nodeSetting = (struct_ADS1015 *)deviceConfigPtr; //Create a local pointer that points to same spot as node does + if (strcmp(deviceSettingName, "log") == 0) + nodeSetting->log = d; + else if (strcmp(deviceSettingName, "logA0") == 0) + nodeSetting->logA0 = d; + else if (strcmp(deviceSettingName, "logA1") == 0) + nodeSetting->logA1 = d; + else if (strcmp(deviceSettingName, "logA2") == 0) + nodeSetting->logA2 = d; + else if (strcmp(deviceSettingName, "logA3") == 0) + nodeSetting->logA3 = d; + else if (strcmp(deviceSettingName, "logA0A1") == 0) + nodeSetting->logA0A1 = d; + else if (strcmp(deviceSettingName, "logA0A3") == 0) + nodeSetting->logA0A3 = d; + else if (strcmp(deviceSettingName, "logA1A3") == 0) + nodeSetting->logA1A3 = d; + else if (strcmp(deviceSettingName, "logA2A3") == 0) + nodeSetting->logA2A3 = d; + else if (strcmp(deviceSettingName, "gain23") == 0) + nodeSetting->gain23 = d; + else if (strcmp(deviceSettingName, "gain1") == 0) + nodeSetting->gain1 = d; + else if (strcmp(deviceSettingName, "gain2") == 0) + nodeSetting->gain2 = d; + else if (strcmp(deviceSettingName, "gain4") == 0) + nodeSetting->gain4 = d; + else if (strcmp(deviceSettingName, "gain8") == 0) + nodeSetting->gain8 = d; + else if (strcmp(deviceSettingName, "gain16") == 0) + nodeSetting->gain16 = d; + else + SerialPrintf2("Unknown device setting: %s\r\n", deviceSettingName); + } + break; default: SerialPrintf2("Unknown device type: %d\r\n", deviceType); SerialFlush(); diff --git a/Firmware/OpenLog_Artemis/settings.h b/Firmware/OpenLog_Artemis/settings.h index 4a5cdc7..c5708b2 100644 --- a/Firmware/OpenLog_Artemis/settings.h +++ b/Firmware/OpenLog_Artemis/settings.h @@ -1,5 +1,5 @@ -//Needed for the MS8607 struct below #include "SparkFun_PHT_MS8607_Arduino_Library.h" //Click here to get the library: http://librarymanager/All#SparkFun_PHT_MS8607 +#include "SparkFun_ISM330DHCX.h" // Click here to get the library: http://librarymanager/All#SparkFun_6DoF_ISM330DHCX typedef enum { @@ -28,6 +28,10 @@ typedef enum DEVICE_PRESSURE_MS5837, DEVICE_QWIIC_BUTTON, DEVICE_BIO_SENSOR_HUB, + DEVICE_ISM330DHCX, + DEVICE_MMC5983MA, + DEVICE_KX134, + DEVICE_ADS1015, DEVICE_TOTAL_DEVICES, //Marks the end, used to iterate loops DEVICE_UNKNOWN_DEVICE, @@ -336,6 +340,130 @@ struct struct_BIO_SENSOR_HUB { unsigned long powerOnDelayMillis = minimumQwiicPowerOnDelay; // Wait for at least this many millis before communicating with this device. Increase if required! }; +struct struct_ISM330DHCX { + bool log = true; + bool logAccel = true; + bool logGyro = true; + bool logDataReady = true; + //Accelerometer Full Scale + //#define ISM_2g 0 + //#define ISM_16g 1 + //#define ISM_4g 2 + //#define ISM_8g 3 + int accelScale = ISM_4g; + //Acceleromter Output Data Rate + //#define ISM_XL_ODR_OFF 0 + //#define ISM_XL_ODR_12Hz5 1 + //#define ISM_XL_ODR_26Hz 2 + //#define ISM_XL_ODR_52Hz 3 + //#define ISM_XL_ODR_104Hz 4 + //#define ISM_XL_ODR_208Hz 5 + //#define ISM_XL_ODR_416Hz 6 + //#define ISM_XL_ODR_833Hz 7 + //#define ISM_XL_ODR_1666Hz 8 + //#define ISM_XL_ODR_3332Hz 9 + //#define ISM_XL_ODR_6667Hz 10 + //#define ISM_XL_ODR_1Hz6 11 + int accelRate = ISM_XL_ODR_208Hz; + bool accelFilterLP2 = true; + //Accel Regular Performance Filter Settings + //#define ISM_HP_PATH_DISABLE_ON_OUT 0x00 + //#define ISM_SLOPE_ODR_DIV_4 0x10 + //#define ISM_HP_ODR_DIV_10 0x11 + //#define ISM_HP_ODR_DIV_20 0x12 + //#define ISM_HP_ODR_DIV_45 0x13 + //#define ISM_HP_ODR_DIV_100 0x14 + //#define ISM_HP_ODR_DIV_200 0x15 + //#define ISM_HP_ODR_DIV_400 0x16 + //#define ISM_HP_ODR_DIV_800 0x17 + //#define ISM_HP_REF_MD_ODR_DIV_10 0x31 + //#define ISM_HP_REF_MD_ODR_DIV_20 0x32 + //#define ISM_HP_REF_MD_ODR_DIV_45 0x33 + //#define ISM_HP_REF_MD_ODR_DIV_100 0x34 + //#define ISM_HP_REF_MD_ODR_DIV_200 0x35 + //#define ISM_HP_REF_MD_ODR_DIV_400 0x36 + //#define ISM_HP_REF_MD_ODR_DIV_800 0x37 + //#define ISM_LP_ODR_DIV_10 0x01 + //#define ISM_LP_ODR_DIV_20 0x02 + //#define ISM_LP_ODR_DIV_45 0x03 + //#define ISM_LP_ODR_DIV_100 0x04 + //#define ISM_LP_ODR_DIV_200 0x05 + //#define ISM_LP_ODR_DIV_400 0x06 + //#define ISM_LP_ODR_DIV_800 0x07 + int accelSlopeFilter = ISM_LP_ODR_DIV_100; + //Gyroscope Full Scale + //#define ISM_125dps 2 + //#define ISM_250dps 0 + //#define ISM_500dps 4 + //#define ISM_1000dps 8 + //#define ISM_2000dps 12 + //#define ISM_4000dps 1 + int gyroScale = ISM_250dps; + //Gyroscope Output Data Rate + //#define ISM_GY_ODR_OFF 0 + //#define ISM_GY_ODR_12Hz 1 + //#define ISM_GY_ODR_26Hz 2 + //#define ISM_GY_ODR_52Hz 3 + //#define ISM_GY_ODR_104Hz 4 + //#define ISM_GY_ODR_208Hz 5 + //#define ISM_GY_ODR_416Hz 6 + //#define ISM_GY_ODR_833Hz 7 + //#define ISM_GY_ODR_1666Hz 8 + //#define ISM_GY_ODR_3332Hz 9 + //#define ISM_GY_ODR_6667Hz 10 + int gyroRate = ISM_GY_ODR_208Hz; + bool gyroFilterLP1 = true; + //Gyro Bandwidth set + //#define ISM_ULTRA_LIGHT 0 + //#define ISM_VERY_LIGHT 1 + //#define ISM_LIGHT 2 + //#define ISM_MEDIUM 3 + //#define ISM_STRONG 4 + //#define ISM_VERY_STRONG 5 + //#define ISM_AGGRESSIVE 6 + //#define ISM_XTREME 7 + int gyroLP1BW = ISM_MEDIUM; + unsigned long powerOnDelayMillis = minimumQwiicPowerOnDelay; // Wait for at least this many millis before communicating with this device. Increase if required! +}; + +struct struct_MMC5983MA { + bool log = true; + bool logMag = true; + bool logTemperature = true; + unsigned long powerOnDelayMillis = minimumQwiicPowerOnDelay; // Wait for at least this many millis before communicating with this device. Increase if required! +}; + +struct struct_KX134 { + bool log = true; + bool logAccel = true; + bool logDataReady = true; + bool range8G = false; + bool range16G = false; + bool range32G = false; + bool range64G = true; + bool highSpeed = false; + unsigned long powerOnDelayMillis = minimumQwiicPowerOnDelay; // Wait for at least this many millis before communicating with this device. Increase if required! +}; + +struct struct_ADS1015 { + bool log = true; + bool logA0 = true; + bool logA1 = true; + bool logA2 = true; + bool logA3 = true; + bool logA0A1 = false; + bool logA0A3 = false; + bool logA1A3 = false; + bool logA2A3 = false; + bool gain23 = false; + bool gain1 = true; + bool gain2 = false; + bool gain4 = false; + bool gain8 = false; + bool gain16 = false; + unsigned long powerOnDelayMillis = minimumQwiicPowerOnDelay; // Wait for at least this many millis before communicating with this device. Increase if required! +}; + //This is all the settings that can be set on OpenLog. It's recorded to NVM and the config file. struct struct_settings { diff --git a/Firmware/OpenLog_Artemis/zmodem.ino b/Firmware/OpenLog_Artemis/zmodem.ino index db44eeb..aefb0c2 100644 --- a/Firmware/OpenLog_Artemis/zmodem.ino +++ b/Firmware/OpenLog_Artemis/zmodem.ino @@ -201,10 +201,12 @@ int count_files(int *file_count, long *byte_count) return 0; } -void sdCardMenu(void) +void sdCardMenu(int numberOfSeconds) { sdCardHelp(); // Display the help + unsigned long startTime = millis(); + bool keepGoing = true; while (keepGoing) @@ -221,6 +223,7 @@ void sdCardMenu(void) { if (DSERIAL->available() > 0) { + startTime = millis(); // reset the start time if we receive a char c = DSERIAL->read(); if ((c == 8 or c == 127) && strlen(cmd) > 0) cmd[strlen(cmd)-1] = 0; if (c == '\n' || c == '\r') break; @@ -236,6 +239,11 @@ void sdCardMenu(void) // from Serial checkBattery(); delay(1); + if ( (millis() - startTime) / 1000 >= numberOfSeconds) + { + SerialPrintln(F("No user input received.")); + return; + } } } @@ -459,5 +467,7 @@ void sdCardMenu(void) { keepGoing = false; } + + startTime = millis(); // reset the start time after commanded action completes } } diff --git a/README.md b/README.md index ab8b46c..239c0fa 100644 --- a/README.md +++ b/README.md @@ -49,7 +49,10 @@ The OpenLog Artemis automatically scans, detects, configures, and logs various Q * [ADS122C04 ADC PT100 Sensor](https://www.sparkfun.com/products/16770) * [Qwiic Mux](https://www.sparkfun.com/products/16784) allowing for the chaining of up to 64 unique buses! * [Pulse Oximeter and Heart Rate Sensor](https://www.sparkfun.com/products/15219) (requires exclusive use of pins 32 and 11) -* More boards are being added all the time! +* [ISM330DHCX IMU](https://www.sparkfun.com/products/19764) +* [MMC5983MA Magnetometer](https://www.sparkfun.com/products/19921) +* [KX134 Accelerometer](https://www.sparkfun.com/products/17589) +* [ADS1015 ADC](https://www.sparkfun.com/products/15334) Very low power logging is supported. OpenLog Artemis can be configured to take readings at 500 times a second, or as slow as 1 reading every 24 hours. You choose! When there is more than 2 seconds between readings OLA will automatically power down itself and the sensors on the bus resulting in a sleep current of approximately 18uA. This means a normal [2Ah battery](https://www.sparkfun.com/products/13855) will enable logging for more than 4,000 days! OpenLog Artemis has built-in LiPo charging set at 450mA/hr. diff --git a/SENSOR_UNITS.md b/SENSOR_UNITS.md index 4a4ed7c..8a89b8d 100644 --- a/SENSOR_UNITS.md +++ b/SENSOR_UNITS.md @@ -60,6 +60,22 @@ This document summarizes the units used for each sensor measurement. - [Pulse Oximeter and Heart Rate Sensor](#Pulse-Oximeter) +### Inertial Measurement Unit: + +- [ISM330DHCX IMU](#ISM330DHCX-IMU) + +### Magnetometer: + +- [MMC5983MA magnetometer](#MMC5983MA-Magnetometer) + +### Accelerometer: + +- [KX134 accelerometer](#KX134-accelerometer) + +### ADC: + +- [ADS1015 ADC](#ADS1015-ADC) + --- ## Sensor Units @@ -359,4 +375,35 @@ Extended status: -3: No object detected -4: Pressing too hard -5: Object other than finger detected --6: Excessive finger motion \ No newline at end of file +-6: Excessive finger motion + +--- +## ISM330DHCX IMU + +| []() | | | +|---|---|---| +| Accelerometer | aX,aY,aZ | milli g | +| Gyro | gX,gY,gZ | milli Degrees per Second | + +--- +## MMC5983MA Magnetometer + +| []() | | | +|---|---|---| +| Magnetometer | mX,mY,mZ | Gauss | +| Temperature | degC | Degrees Centigrade | + +--- +## KX134 Accelerometer + +| []() | | | +|---|---|---| +| Accelerometer | aX,aY,aZ | g | + +--- +## ADS1015 ADC + +| []() | | | +|---|---|---| +| Voltage | A0mV,A1mV,A2mV,A3mV,A0A1mV,A0A3mV,A1A3mV,A2A3mV | milliVolts | + diff --git a/UPGRADE.md b/UPGRADE.md index 53928f5..299d384 100644 --- a/UPGRADE.md +++ b/UPGRADE.md @@ -7,8 +7,8 @@ Which is handy if you want to quickly update the firmware in the field, or are n The firmware is customized for the different versions of the OLA hardware. You will find versions for the **X04 SparkX (Black) OLA** and **V10 SparkFun (Red) OLA** plus any subsequent revisions. The filename tells you which hardware the firmware is for and what version it is: -* **OpenLog_Artemis-V10-v24.bin** - is the _stable_ version (2.4) for the **V10 SparkFun (Red) OLA** -* **OpenLog_Artemis-X04-v24.bin** - is the _stable_ version (2.4) for the **X04 SparkX (Black) OLA** +* **OpenLog_Artemis-V10-v25.bin** - is the _stable_ version (2.5) for the **V10 SparkFun (Red) OLA** +* **OpenLog_Artemis-X04-v25.bin** - is the _stable_ version (2.5) for the **X04 SparkX (Black) OLA**