Skip to content

Commit f910f5f

Browse files
committed
Tidying up @mkrawcz1 's WOMThreshold example
1 parent 1d08680 commit f910f5f

File tree

6 files changed

+50
-76
lines changed

6 files changed

+50
-76
lines changed

examples/Arduino/Example3_Interrupts/Example3_Interrupts.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,8 @@
1919
#define SERIAL_PORT Serial
2020

2121
#define INT_PIN 2 // Make sure to connect this pin on your uC to the "INT" pin on the ICM-20948 breakout
22-
#define LED_PIN 13
23-
//#define LED_PIN LED_BUILTIN
22+
//#define LED_PIN 13
23+
#define LED_PIN LED_BUILTIN
2424
#define BUFFER_SAMPLE_NUM 32
2525

2626
#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined

examples/Arduino/Example4_WakeOnMotion/Example4_WakeOnMotion.ino

Lines changed: 38 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,15 @@
11
/****************************************************************
22
* Example4_WakeOnMotion.ino
3-
* ICM 20948 Arduino Library Demo
3+
* ICM 20948 Arduino Library Demo
44
* Based on Example3_Interrupts.ino by Owen Lyke @ SparkFun Electronics
55
* Original Creation Date: Dec 5 2020
66
* Created by mkrawcz1 (***** ***)
7-
*
8-
* For this example you must connect the interrupt pin "INT" on the breakout
7+
*
8+
* For this example you must connect the interrupt pin "INT" on the breakout
99
* board to the pin specified by "INT_PIN" on your microcontroller.
10-
*
11-
* This code is freeware;
12-
*
10+
*
11+
* Please see License.md for the license information.
12+
*
1313
* Distributed as-is; no warranty is given.
1414
***************************************************************/
1515
#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU
@@ -28,8 +28,8 @@
2828
#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined
2929

3030
#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined
31-
#define AD0_VAL 1 // The value of the last bit of the I2C address.
32-
// On the SparkFun 9DoF IMU breakout the default is 1, and when
31+
#define AD0_VAL 1 // The value of the last bit of the I2C address.
32+
// On the SparkFun 9DoF IMU breakout the default is 1, and when
3333
// the ADR jumper is closed the value becomes 0
3434

3535
#ifdef USE_SPI
@@ -42,8 +42,10 @@
4242
volatile bool isrFired = false;
4343
volatile bool sensorSleep = false;
4444
volatile bool canToggle = false;
45-
unsigned int WOM_threshold=255;
46-
double lastTrigerred;
45+
unsigned long lastTriggered;
46+
47+
// Threshold LSB is 4mg. Range is 0mg to 1020mg.
48+
unsigned int WOM_threshold = 255;
4749

4850
void setup() {
4951

@@ -62,12 +64,14 @@ void setup() {
6264
WIRE_PORT.begin();
6365
WIRE_PORT.setClock(400000);
6466
#endif
65-
67+
68+
//myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial
69+
6670
bool initialized = false;
6771
while( !initialized ){
6872

6973
#ifdef USE_SPI
70-
myICM.begin( CS_PIN, SPI_PORT, SPI_FREQ ); // Here we are using the user-defined SPI_FREQ as the clock speed of the SPI bus
74+
myICM.begin( CS_PIN, SPI_PORT, SPI_FREQ ); // Here we are using the user-defined SPI_FREQ as the clock speed of the SPI bus
7175
#else
7276
myICM.begin( WIRE_PORT, AD0_VAL );
7377
#endif
@@ -92,7 +96,7 @@ void setup() {
9296
SERIAL_PORT.println(myICM.statusString());
9397
}
9498
delay(250);
95-
99+
96100
// Now wake the sensor up
97101
myICM.sleep( sensorSleep );
98102
myICM.lowPower( false );
@@ -102,7 +106,7 @@ void setup() {
102106
// Set Gyro and Accelerometer to a particular sample mode
103107
// options: ICM_20948_Sample_Mode_Continuous
104108
// ICM_20948_Sample_Mode_Cycled
105-
myICM.setSampleMode( (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Cycled );
109+
myICM.setSampleMode( (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Cycled );
106110
SERIAL_PORT.print(F("setSampleMode returned: "));
107111
SERIAL_PORT.println(myICM.statusString());
108112

@@ -112,23 +116,23 @@ void setup() {
112116
myICM.setSampleRate( ICM_20948_Internal_Gyr, mySmplrt );
113117
SERIAL_PORT.print(F("setSampleRate returned: "));
114118
SERIAL_PORT.println(myICM.statusString());
115-
119+
116120
// Set full scale ranges for both acc and gyr
117121
ICM_20948_fss_t myFSS; // This uses a "Full Scale Settings" structure that can contain values for all configurable sensors
118-
122+
119123
myFSS.a = gpm2; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e)
120124
// gpm2
121125
// gpm4
122126
// gpm8
123127
// gpm16
124-
128+
125129
myFSS.g = dps250; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e)
126130
// dps250
127131
// dps500
128132
// dps1000
129133
// dps2000
130-
131-
myICM.setFullScale( (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS );
134+
135+
myICM.setFullScale( (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS );
132136
if( myICM.status != ICM_20948_Stat_Ok){
133137
SERIAL_PORT.print(F("setFullScale returned: "));
134138
SERIAL_PORT.println(myICM.statusString());
@@ -155,7 +159,7 @@ void setup() {
155159
// gyr_d11bw6_n17bw8
156160
// gyr_d5bw7_n8bw9
157161
// gyr_d361bw4_n376bw5
158-
162+
159163
myICM.setDLPFcfg( (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myDLPcfg );
160164
if( myICM.status != ICM_20948_Stat_Ok){
161165
SERIAL_PORT.print(F("setDLPcfg returned: "));
@@ -194,48 +198,49 @@ void setup() {
194198
myICM.cfgIntLatch(true); // Latch the interrupt until cleared
195199
SERIAL_PORT.print(F("cfgIntLatch returned: "));
196200
SERIAL_PORT.println(myICM.statusString());
197-
201+
198202
myICM.WOMThreshold(WOM_threshold); // set WoM threshold
199-
SERIAL_PORT.print(F("Set threshold returned: "));
203+
SERIAL_PORT.print(F("Set threshold returned: "));
200204
SERIAL_PORT.println(myICM.statusString());
201-
205+
202206
myICM.intEnableWOM(true); // enable interrupts on WakeOnMotion
203207
SERIAL_PORT.print(F("intEnableWOM returned: "));
204208
SERIAL_PORT.println(myICM.statusString());
205209

206210
myICM.WOMThreshold(WOM_threshold); // set WoM threshold - just in case...
207-
SERIAL_PORT.print(F("Set threshold returned: "));
211+
SERIAL_PORT.print(F("Set threshold returned: "));
208212
SERIAL_PORT.println(myICM.statusString());
209213

210214
SERIAL_PORT.println();
211-
SERIAL_PORT.println(F("Configuration complete!"));
215+
SERIAL_PORT.println(F("Configuration complete!"));
212216
}
213217

214218
void loop() {
215219
if( isrFired ){ // If our isr flag is set then clear the interrupts on the ICM
216220
isrFired = false;
217221
myICM.getAGMT(); // get the A, G, M, and T readings
218-
// printScaledAGMT( myICM.agmt); // This function takes into account the sclae settings from when the measurement was made to calculate the values with units
222+
// printScaledAGMT( myICM.agmt); // This function takes into account the scale settings from when the measurement was made to calculate the values with units
219223
SERIAL_PORT.println(F("Shock detected"));
220224
digitalWrite(LED_PIN, HIGH);
221-
lastTrigerred=millis();
225+
lastTriggered = millis();
222226
delay(30);
223227
myICM.clearInterrupts(); // This would be efficient... but not compatible with Uno
224228
}
225229

226-
myICM.clearInterrupts(); // clear interrupts for next time -
227-
// usually you'd do this only if an interrupt has occurred, however
230+
myICM.clearInterrupts(); // clear interrupts for next time -
231+
// usually you'd do this only if an interrupt has occurred, however
228232
// on the 328p I2C usage can block interrupts. This means that sometimes
229233
// an interrupt is missed. When missed, if using an edge-based interrupt
230-
// and only clearing interrupts when one was detected there will be no more
231-
// edges to respond to, so no more interrupts will be detected. Here are
234+
// and only clearing interrupts when one was detected there will be no more
235+
// edges to respond to, so no more interrupts will be detected. Here are
232236
// some possible solutions:
233237
// 1. use a level based interrupt
234238
// 2. use the pulse-based interrupt in ICM settings (set cfgIntLatch to false)
235239
// 3. use a microcontroller with nestable interrupts
236240
// 4. clear the interrupts often
237-
if(millis()-lastTrigerred>1000)
238-
digitalWrite(LED_PIN, LOW);;
241+
242+
if(millis() - lastTriggered > 1000) // Turn the LED off after one second
243+
digitalWrite(LED_PIN, LOW);
239244
}
240245

241246
void icmISR( void ){

keywords.txt

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -17,12 +17,12 @@ ICM_20948_InternalSensorID_bm KEYWORD1
1717
#######################################
1818

1919
ICM_20948 KEYWORD2
20-
enableDebugging
21-
disableDebugging
22-
debugPrintStatus
23-
debugPrint
24-
debugPrintln
25-
doDebugPrint
20+
enableDebugging KEYWORD2
21+
disableDebugging KEYWORD2
22+
debugPrintStatus KEYWORD2
23+
debugPrint KEYWORD2
24+
debugPrintln KEYWORD2
25+
doDebugPrint KEYWORD2
2626
getAGMT KEYWORD2
2727
magX KEYWORD2
2828
magY KEYWORD2
@@ -70,6 +70,7 @@ magIsConnected KEYWORD2
7070
getMagnetometerData KEYWORD2
7171
ICM_20948_SPI KEYWORD2
7272
begin KEYWORD2
73+
WOMThreshold KEYWORD2
7374

7475
#######################################
7576
# Constants (LITERAL1)

src/ICM_20948.cpp

Lines changed: 0 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -678,7 +678,6 @@ ICM_20948_Status_e ICM_20948::intEnableWatermarkFIFO(uint8_t bm_enable)
678678
return status;
679679
}
680680

681-
682681
ICM_20948_Status_e ICM_20948::WOMThreshold(uint8_t threshold)
683682
{
684683
ICM_20948_ACCEL_WOM_THR_t thr; // storage
@@ -701,8 +700,6 @@ ICM_20948_Status_e ICM_20948::WOMThreshold(uint8_t threshold)
701700
return status;
702701
}
703702

704-
705-
706703
// Interface Options
707704
ICM_20948_Status_e ICM_20948::i2cMasterPassthrough(bool passthrough)
708705
{
@@ -1274,26 +1271,3 @@ ICM_20948_Status_e ICM_20948_read_SPI(uint8_t reg, uint8_t *buff, uint32_t len,
12741271

12751272
return ICM_20948_Stat_Ok;
12761273
}
1277-
/*
1278-
ICM_20948_Status_e ICM_20948::WOMThreshold(uint8_t threshold)
1279-
{
1280-
ICM_20948_ACCEL_WOM_THR_t thr; // storage
1281-
status = ICM_20948_wom_threshold(&_device, NULL, &thr); // read phase
1282-
if (status != ICM_20948_Stat_Ok)
1283-
{
1284-
return status;
1285-
}
1286-
thr.WOM_THRESHOLD = threshold; // change the setting
1287-
status = ICM_20948_wom_threshold(&_device, &thr, &thr); // write phase w/ readback
1288-
if (status != ICM_20948_Stat_Ok)
1289-
{
1290-
return status;
1291-
}
1292-
if (thr.WOM_THRESHOLD != threshold)
1293-
{
1294-
status = ICM_20948_Stat_Err;
1295-
return status;
1296-
}
1297-
return status;
1298-
}
1299-
*/

src/ICM_20948.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -130,8 +130,8 @@ class ICM_20948
130130
ICM_20948_Status_e intEnableOverflowFIFO(uint8_t bm_enable);
131131
ICM_20948_Status_e intEnableWatermarkFIFO(uint8_t bm_enable);
132132

133-
ICM_20948_Status_e ICM_20948::WOMThreshold(uint8_t threshold);
134-
133+
ICM_20948_Status_e WOMThreshold(uint8_t threshold);
134+
135135
// Interface Options
136136
ICM_20948_Status_e i2cMasterPassthrough(bool passthrough = true);
137137
ICM_20948_Status_e i2cMasterEnable(bool enable = true);

src/util/ICM_20948_C.c

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -425,12 +425,6 @@ ICM_20948_Status_e ICM_20948_int_enable(ICM_20948_Device_t *pdev, ICM_20948_INT_
425425
return retval;
426426
}
427427

428-
429-
430-
431-
432-
433-
434428
ICM_20948_Status_e ICM_20948_wom_threshold(ICM_20948_Device_t *pdev, ICM_20948_ACCEL_WOM_THR_t *write, ICM_20948_ACCEL_WOM_THR_t *read)
435429
{
436430
ICM_20948_Status_e retval = ICM_20948_Stat_Ok;
@@ -442,7 +436,7 @@ ICM_20948_Status_e ICM_20948_wom_threshold(ICM_20948_Device_t *pdev, ICM_20948_A
442436
if (write != NULL)
443437
{ // If the write pointer is not NULL then write to the registers BEFORE reading
444438
thr.WOM_THRESHOLD = write->WOM_THRESHOLD;
445-
439+
446440
retval = ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_WOM_THR, (uint8_t *)&thr, sizeof(ICM_20948_ACCEL_WOM_THR_t));
447441
if (retval != ICM_20948_Stat_Ok)
448442
{

0 commit comments

Comments
 (0)