├── DFRobot_ICM42688.cpp ├── DFRobot_ICM42688.h ├── LICENSE ├── README.md ├── README_CN.md ├── examples ├── getAccelGyroData │ └── getAccelGyroData.ino ├── getDataByFIFO │ └── getDataByFIFO.ino ├── significantMotionDet │ └── significantMotionDet.ino ├── tap │ └── tap.ino └── wakeOnMotion │ └── wakeOnMotion.ino ├── keywords.txt ├── library.properties ├── python └── raspberrypi │ ├── DFRobot_ICM42688.py │ ├── README.md │ ├── README_CN.md │ └── examples │ ├── get_data_by_FIFO.py │ ├── get_gyro_accel_temp_data.py │ ├── significan_motion_det.py │ ├── tap.py │ └── wake_on_motion_det.py └── resources └── images └── SEN0245svg1.png /DFRobot_ICM42688.cpp: -------------------------------------------------------------------------------- 1 | /*! 2 | * @file DFRobot_ICM42688.cpp 3 | * @brief Define basic structure of DFRobot_ICM42688 class, the implementation of basic method 4 | * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 5 | * @license The MIT License (MIT) 6 | * @author [yangfeng] 7 | * @version V1.0 8 | * @date 2021-05-13 9 | * @url https://github.com/DFRobot/DFRobot_ICM42688 10 | */ 11 | #include 12 | #include 13 | DFRobot_ICM42688::DFRobot_ICM42688() 14 | { 15 | accelConfig0.accelODR = 6; 16 | accelConfig0.accelFsSel = 0; 17 | gyroConfig0.gyroODR = 6; 18 | gyroConfig0.gyroFsSel = 0; 19 | _gyroRange = 4000/65535.0; 20 | _accelRange = 0.488f; 21 | FIFOMode = false; 22 | } 23 | 24 | int DFRobot_ICM42688::begin(void) 25 | { 26 | uint8_t bank = 0; 27 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 28 | uint8_t id=0; 29 | if(readReg(ICM42688_WHO_AM_I,&id,1) == 0){ 30 | //DBG("bus data access error"); 31 | return ERR_DATA_BUS; 32 | } 33 | DBG("real sensor id=");DBG(id); 34 | if(id != DFRobot_ICM42688_ID){ 35 | return ERR_IC_VERSION; 36 | } 37 | uint8_t reset = 0; 38 | writeReg(ICM42688_DEVICE_CONFIG,&reset,1); 39 | delay(2); 40 | return ERR_OK; 41 | } 42 | 43 | float DFRobot_ICM42688::getTemperature(void) 44 | { 45 | float value; 46 | if(FIFOMode){ 47 | value = (_temp/2.07) + 25; 48 | } else{ 49 | uint8_t data[2]; 50 | int16_t value2; 51 | readReg(ICM42688_TEMP_DATA1, data, 2); 52 | value2 = ((uint16_t )data[0]<<8) | (uint16_t )data[1]; 53 | value = value2/132.48 + 25; 54 | } 55 | return value; 56 | } 57 | 58 | float DFRobot_ICM42688::getAccelDataX(void) 59 | { 60 | float value; 61 | if(FIFOMode){ 62 | value = _accelX; 63 | } else{ 64 | uint8_t data[2]; 65 | readReg(ICM42688_ACCEL_DATA_X1, data, 2); 66 | int16_t value1 = ((uint16_t )data[0] << 8) | (uint16_t)data[1] ; 67 | value = value1; 68 | } 69 | return value*_accelRange; 70 | } 71 | 72 | float DFRobot_ICM42688::getAccelDataY(void) 73 | { 74 | float value; 75 | if(FIFOMode){ 76 | value = _accelY; 77 | } else{ 78 | uint8_t data[2]; 79 | readReg(ICM42688_ACCEL_DATA_Y1, data, 2); 80 | int16_t value1 = ((uint16_t )data[0] << 8) | (uint16_t)data[1] ; 81 | value = value1; 82 | } 83 | return value*_accelRange; 84 | } 85 | 86 | float DFRobot_ICM42688::getAccelDataZ(void) 87 | { 88 | float value; 89 | if(FIFOMode){ 90 | value = _accelZ; 91 | } else{ 92 | uint8_t data[2]; 93 | readReg(ICM42688_ACCEL_DATA_Z1, data, 2); 94 | int16_t value1 = ((uint16_t )data[0] << 8) | (uint16_t)data[1] ; 95 | value = value1; 96 | } 97 | return value*_accelRange; 98 | } 99 | 100 | float DFRobot_ICM42688::getGyroDataX(void) 101 | { 102 | float value; 103 | if(FIFOMode){ 104 | value = _gyroX; 105 | } else{ 106 | uint8_t data[2]; 107 | readReg(ICM42688_GYRO_DATA_X1, data, 2); 108 | int16_t value1 = ((uint16_t )data[0] << 8) | (uint16_t)data[1] ; 109 | value = value1; 110 | } 111 | return value*_gyroRange; 112 | } 113 | 114 | float DFRobot_ICM42688::getGyroDataY(void) 115 | { 116 | float value; 117 | if(FIFOMode){ 118 | value = _gyroY; 119 | } else{ 120 | uint8_t data[2]; 121 | readReg(ICM42688_GYRO_DATA_Y1, data, 2); 122 | int16_t value1 = ((uint16_t )data[0] << 8) | (uint16_t)data[1] ; 123 | value = value1; 124 | } 125 | return value*_gyroRange; 126 | } 127 | 128 | float DFRobot_ICM42688::getGyroDataZ(void) 129 | { 130 | float value; 131 | if(FIFOMode){ 132 | value = _gyroZ; 133 | } else{ 134 | uint8_t data[2]; 135 | readReg(ICM42688_GYRO_DATA_Z1, data, 2); 136 | int16_t value1 = ((uint16_t )data[0] << 8) | (uint16_t)data[1] ; 137 | value = value1; 138 | } 139 | return value*_gyroRange; 140 | } 141 | 142 | void DFRobot_ICM42688:: tapDetectionInit(uint8_t accelMode) 143 | { 144 | uint8_t bank = 0; 145 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 146 | if(accelMode == 0){ 147 | accelConfig0.accelODR = 15; 148 | writeReg(ICM42688_ACCEL_CONFIG0,&accelConfig0,1); 149 | PWRMgmt0.accelMode = 2; 150 | writeReg(ICM42688_PWR_MGMT0,&PWRMgmt0,1); 151 | delay(1); 152 | INTFConfig1.accelLpClkSel = 0; 153 | writeReg(ICM42688_INTF_CONFIG1,&INTFConfig1,1); 154 | accelConfig1.accelUIFiltORD = 2; 155 | writeReg(ICM42688_ACCEL_CONFIG1,&accelConfig1,1); 156 | gyroAccelConfig0.accelUIFiltBW = 0; 157 | writeReg(ICM42688_GYRO_ACCEL_CONFIG0,&gyroAccelConfig0,1); 158 | } else if(accelMode == 1){ 159 | accelConfig0.accelODR = 6; 160 | writeReg(ICM42688_ACCEL_CONFIG0,&accelConfig0,1); 161 | PWRMgmt0.accelMode = 3; 162 | writeReg(ICM42688_PWR_MGMT0,&PWRMgmt0,1); 163 | delay(1); 164 | accelConfig1.accelUIFiltORD = 2; 165 | writeReg(ICM42688_ACCEL_CONFIG1,&accelConfig1,1); 166 | gyroAccelConfig0.accelUIFiltBW = 0; 167 | writeReg(ICM42688_GYRO_ACCEL_CONFIG0,&gyroAccelConfig0,1); 168 | } else{ 169 | DBG("accelMode invalid !"); 170 | return; 171 | } 172 | delay(1); 173 | bank = 4; 174 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 175 | APEXConfig8.tapTmin = 3; 176 | APEXConfig8.tapTavg = 3; 177 | APEXConfig8.tapTmax = 2; 178 | writeReg(ICM42688_APEX_CONFIG8,&APEXConfig8,1); 179 | APEXConfig7.tapMinJerkThr = 17; 180 | APEXConfig7.tapMaxPeakTol = 1; 181 | writeReg(ICM42688_APEX_CONFIG7,&APEXConfig7,1); 182 | delay(1); 183 | INTSource.tapDetIntEn = 1; 184 | if(_INTPin==1){ 185 | writeReg(ICM42688_INT_SOURCE6,&INTSource,1); 186 | } else { 187 | writeReg(ICM42688_INT_SOURCE7,&INTSource,1); 188 | } 189 | delay(50); 190 | bank = 0; 191 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 192 | APEXConfig0.tapEnable = 1; 193 | writeReg(ICM42688_APEX_CONFIG0,&APEXConfig0,1); 194 | } 195 | void DFRobot_ICM42688::getTapInformation() 196 | { 197 | uint8_t data; 198 | readReg(ICM42688_APEX_DATA4, &data, 1); 199 | _tapNum = data & 0x18; 200 | _tapAxis = data & 0x06; 201 | _tapDir = data & 0x01; 202 | } 203 | uint8_t DFRobot_ICM42688:: numberOfTap() 204 | { 205 | return _tapNum; 206 | } 207 | uint8_t DFRobot_ICM42688:: axisOfTap() 208 | { 209 | return _tapAxis; 210 | } 211 | void DFRobot_ICM42688:: wakeOnMotionInit() 212 | { 213 | uint8_t bank = 0; 214 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 215 | accelConfig0.accelODR = 9; 216 | writeReg(ICM42688_ACCEL_CONFIG0,&accelConfig0,1); 217 | PWRMgmt0.accelMode = 2; 218 | writeReg(ICM42688_PWR_MGMT0,&PWRMgmt0,1); 219 | delay(1); 220 | INTFConfig1.accelLpClkSel = 0; 221 | writeReg(ICM42688_INTF_CONFIG1,&INTFConfig1,1); 222 | delay(1); 223 | } 224 | void DFRobot_ICM42688:: setWOMTh(uint8_t axis,uint8_t threshold) 225 | { 226 | uint8_t bank = 4; 227 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 228 | uint8_t womValue = threshold; 229 | if(axis == X_AXIS){ 230 | writeReg(ICM42688_ACCEL_WOM_X_THR,&womValue,1); 231 | } else if(axis == Y_AXIS){ 232 | writeReg(ICM42688_ACCEL_WOM_Y_THR,&womValue,1); 233 | } else if(axis == Z_AXIS){ 234 | writeReg(ICM42688_ACCEL_WOM_Z_THR,&womValue,1); 235 | } else if(axis == ALL){ 236 | writeReg(ICM42688_ACCEL_WOM_X_THR,&womValue,1); 237 | writeReg(ICM42688_ACCEL_WOM_Y_THR,&womValue,1); 238 | writeReg(ICM42688_ACCEL_WOM_Z_THR,&womValue,1); 239 | } 240 | delay(1); 241 | bank = 0; 242 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 243 | } 244 | void DFRobot_ICM42688:: setWOMInterrupt(uint8_t axis) 245 | { 246 | uint8_t bank = 0; 247 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 248 | if(_INTPin == 1){ 249 | writeReg(ICM42688_INT_SOURCE1,&axis,1); 250 | } else { 251 | writeReg(ICM42688_INT_SOURCE4,&axis,1); 252 | } 253 | delay(50); 254 | SMDConfig.SMDMode = 1; 255 | SMDConfig.WOMMode = 1; 256 | SMDConfig.WOMIntMode = 0; 257 | writeReg(ICM42688_SMD_CONFIG,&SMDConfig,1); 258 | } 259 | void DFRobot_ICM42688::enableSMDInterrupt(uint8_t mode) 260 | { 261 | uint8_t bank = 0; 262 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 263 | uint8_t INT = 1<<3 ; 264 | if(mode != 0){ 265 | if(_INTPin == 1){ 266 | writeReg(ICM42688_INT_SOURCE1,&INT,1); 267 | } else { 268 | writeReg(ICM42688_INT_SOURCE4,&INT,1); 269 | } 270 | } 271 | delay(50); 272 | SMDConfig.SMDMode = mode; 273 | SMDConfig.WOMMode = 1; 274 | SMDConfig.WOMIntMode = 0; 275 | writeReg(ICM42688_SMD_CONFIG,&SMDConfig,1); 276 | } 277 | 278 | uint8_t DFRobot_ICM42688::readInterruptStatus(uint8_t reg) 279 | { 280 | uint8_t bank = 0; 281 | uint8_t status = 0; 282 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 283 | readReg(reg,&status,1); 284 | return status; 285 | } 286 | 287 | bool DFRobot_ICM42688::setODRAndFSR(uint8_t who,uint8_t ODR,uint8_t FSR) 288 | { 289 | bool ret = true; 290 | uint8_t bank = 0; 291 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 292 | if(who == GYRO){ 293 | if(ODR > ODR_12_5KHZ || FSR > FSR_7){ 294 | ret = false; 295 | }else{ 296 | gyroConfig0.gyroODR = ODR; 297 | gyroConfig0.gyroFsSel = FSR; 298 | writeReg(ICM42688_GYRO_CONFIG0,&gyroConfig0,1); 299 | switch(FSR){ 300 | case FSR_0: 301 | _gyroRange = 4000/65535.0; 302 | break; 303 | case FSR_1: 304 | _gyroRange = 2000/65535.0; 305 | break; 306 | case FSR_2: 307 | _gyroRange = 1000/65535.0; 308 | break; 309 | case FSR_3: 310 | _gyroRange = 500/65535.0; 311 | break; 312 | case FSR_4: 313 | _gyroRange = 250/65535.0; 314 | break; 315 | case FSR_5: 316 | _gyroRange = 125/65535.0; 317 | break; 318 | case FSR_6: 319 | _gyroRange = 62.5/65535.0; 320 | break; 321 | case FSR_7: 322 | _gyroRange = 31.25/65535.0; 323 | break; 324 | } 325 | } 326 | } else if(who == ACCEL){ 327 | if(ODR > ODR_500HZ || FSR > FSR_3){ 328 | ret = false; 329 | } else{ 330 | accelConfig0.accelODR = ODR; 331 | accelConfig0.accelFsSel = FSR; 332 | writeReg(ICM42688_ACCEL_CONFIG0,&accelConfig0,1); 333 | switch(FSR){ 334 | case FSR_0: 335 | _accelRange = 0.488f; 336 | break; 337 | case FSR_1: 338 | _accelRange = 0.244f; 339 | break; 340 | case FSR_2: 341 | _accelRange = 0.122f; 342 | break; 343 | case FSR_3: 344 | _accelRange = 0.061f; 345 | break; 346 | } 347 | } 348 | } 349 | return ret; 350 | } 351 | 352 | void DFRobot_ICM42688::setFIFODataMode() 353 | { 354 | uint8_t bank = 0; 355 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 356 | FIFOConfig1.FIFOHiresEn = 0; 357 | FIFOConfig1.FIFOAccelEn = 1; 358 | FIFOConfig1.FIFOGyroEn = 1; 359 | FIFOConfig1.FIFOTempEn = 1; 360 | FIFOConfig1.FIFOTmstFsyncEn = 0; 361 | writeReg(ICM42688_FIFO_CONFIG1,&FIFOConfig1,1); 362 | 363 | } 364 | 365 | void DFRobot_ICM42688::startFIFOMode() 366 | { 367 | uint8_t bank = 0; 368 | FIFOMode = true; 369 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 370 | setFIFODataMode(); 371 | uint8_t start = 1<<6; 372 | writeReg(ICM42688_FIFO_CONFIG,&start,1); 373 | getFIFOData(); 374 | } 375 | void DFRobot_ICM42688::getFIFOData() 376 | { 377 | uint8_t data[16]; 378 | readReg(ICM42688_FIFO_DATA,data,16); 379 | _accelX = (uint16_t)data[1]<<8 | (uint16_t)data[2]; 380 | //DBG("_accelX");DBG(_accelX); 381 | _accelY = (uint16_t)data[3]<<8 | (uint16_t)data[4]; 382 | //DBG("_accelY");DBG(_accelY); 383 | _accelZ = (uint16_t)data[5]<<8 | (uint16_t)data[6]; 384 | //DBG("_accelZ");DBG(_accelZ); 385 | _gyroX = (uint16_t)data[7]<<8 | (uint16_t)data[8]; 386 | //DBG("_gyroX");DBG(_gyroX); 387 | _gyroY = (uint16_t)data[9]<<8 | (uint16_t)data[10]; 388 | //DBG("_gyroY");DBG(_gyroY); 389 | _gyroZ = (uint16_t)data[11]<<8 | (uint16_t)data[12]; 390 | //DBG("_gyroZ");DBG(_gyroZ); 391 | _temp = (uint8_t)data[13]; 392 | //DBG("_temp");DBG(data[13]); 393 | } 394 | void DFRobot_ICM42688::sotpFIFOMode() 395 | { 396 | uint8_t bank = 0; 397 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 398 | uint8_t start = 1<<7; 399 | writeReg(ICM42688_FIFO_CONFIG,&start,1); 400 | } 401 | 402 | void DFRobot_ICM42688::setINTMode(uint8_t INTPin,uint8_t INTmode,uint8_t INTPolarity,uint8_t INTDriveCircuit) 403 | { 404 | uint8_t bank = 0; 405 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 406 | if(INTPin == 1){ 407 | _INTPin = 1; 408 | INTConfig.INT1Mode = INTmode; 409 | INTConfig.INT1DriveCirCuit = INTDriveCircuit; 410 | INTConfig.INT1Polarity = INTPolarity; 411 | } else if(INTPin == 2){ 412 | _INTPin = 2; 413 | INTConfig.INT2Mode = INTmode; 414 | INTConfig.INT2DriveCirCuit = INTDriveCircuit; 415 | INTConfig.INT2Polarity = INTPolarity; 416 | } 417 | writeReg(ICM42688_INT_CONFIG,&INTConfig,1); 418 | } 419 | 420 | void DFRobot_ICM42688::startTempMeasure() 421 | { 422 | PWRMgmt0.tempDis = 0; 423 | uint8_t bank = 0; 424 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 425 | writeReg(ICM42688_PWR_MGMT0,&PWRMgmt0,1); 426 | delay(1); 427 | } 428 | void DFRobot_ICM42688::startGyroMeasure(uint8_t mode) 429 | { 430 | PWRMgmt0.gyroMode = mode; 431 | uint8_t bank = 0; 432 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 433 | writeReg(ICM42688_PWR_MGMT0,&PWRMgmt0,1); 434 | delay(1); 435 | } 436 | 437 | void DFRobot_ICM42688::startAccelMeasure(uint8_t mode) 438 | { 439 | PWRMgmt0.accelMode = mode; 440 | uint8_t bank = 0; 441 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 442 | writeReg(ICM42688_PWR_MGMT0,&PWRMgmt0,1); 443 | delay(10); 444 | } 445 | void DFRobot_ICM42688:: setGyroNotchFilterFHz(double freq,uint8_t axis) 446 | { 447 | uint8_t bank = 1; 448 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 449 | double fdesired = freq * 1000; 450 | double coswz = cos(2*3.14*fdesired/32); 451 | int16_t nfCoswz; 452 | uint8_t nfCoswzSel; 453 | if(abs(coswz)<=0.875){ 454 | nfCoswz = round(coswz*256); 455 | nfCoswzSel = 0; 456 | } else { 457 | nfCoswzSel = 1; 458 | if(coswz> 0.875){ 459 | nfCoswz = round(8*(1-coswz)*256); 460 | } else if(coswz < -0.875){ 461 | nfCoswz = round(-8*(1+coswz)*256); 462 | } 463 | } 464 | if(axis == X_AXIS){ 465 | gyroConfigStatic9.gyroNFCoswzSelX = nfCoswzSel; 466 | gyroConfigStatic9.gyroNFCoswzX8 = nfCoswz>>8; 467 | writeReg(ICM42688_GYRO_CONFIG_STATIC6,&nfCoswz,1); 468 | writeReg(ICM42688_GYRO_CONFIG_STATIC9,&gyroConfigStatic9,1); 469 | } else if(axis == Y_AXIS){ 470 | gyroConfigStatic9.gyroNFCoswzSelY = nfCoswzSel; 471 | gyroConfigStatic9.gyroNFCoswzY8 = nfCoswz>>8; 472 | writeReg(ICM42688_GYRO_CONFIG_STATIC7,&nfCoswz,1); 473 | writeReg(ICM42688_GYRO_CONFIG_STATIC9,&gyroConfigStatic9,1); 474 | } else if(axis == Z_AXIS){ 475 | gyroConfigStatic9.gyroNFCoswzSelZ = nfCoswzSel; 476 | gyroConfigStatic9.gyroNFCoswzZ8 = nfCoswz>>8; 477 | writeReg(ICM42688_GYRO_CONFIG_STATIC8,&nfCoswz,1); 478 | writeReg(ICM42688_GYRO_CONFIG_STATIC9,&gyroConfigStatic9,1); 479 | } else if(axis == ALL) 480 | { 481 | gyroConfigStatic9.gyroNFCoswzSelX = nfCoswzSel; 482 | gyroConfigStatic9.gyroNFCoswzX8 = nfCoswz>>8; 483 | gyroConfigStatic9.gyroNFCoswzSelY = nfCoswzSel; 484 | gyroConfigStatic9.gyroNFCoswzY8 = nfCoswz>>8; 485 | gyroConfigStatic9.gyroNFCoswzSelZ = nfCoswzSel; 486 | gyroConfigStatic9.gyroNFCoswzZ8 = nfCoswz>>8; 487 | writeReg(ICM42688_GYRO_CONFIG_STATIC6,&nfCoswz,1); 488 | writeReg(ICM42688_GYRO_CONFIG_STATIC7,&nfCoswz,1); 489 | writeReg(ICM42688_GYRO_CONFIG_STATIC8,&nfCoswz,1); 490 | writeReg(ICM42688_GYRO_CONFIG_STATIC9,&gyroConfigStatic9,1); 491 | } 492 | bank = 0; 493 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 494 | } 495 | 496 | void DFRobot_ICM42688::setGyroNFbandwidth(uint8_t bw) 497 | { 498 | uint8_t bank = 1; 499 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 500 | uint8_t bandWidth = (bw<<4) | 0x01; 501 | writeReg(ICM42688_GYRO_CONFIG_STATIC10,&bandWidth,1); 502 | bank = 0; 503 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 504 | } 505 | 506 | void DFRobot_ICM42688::setGyroNotchFilter(bool mode) 507 | { 508 | if(mode){ 509 | gyroConfigStatic2.gyroNFDis = 0; 510 | } else { 511 | gyroConfigStatic2.gyroNFDis = 1; 512 | } 513 | uint8_t bank = 1; 514 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 515 | writeReg(ICM42688_GYRO_CONFIG_STATIC2,&gyroConfigStatic2,1); 516 | bank = 0; 517 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 518 | } 519 | void DFRobot_ICM42688::setAAFBandwidth(uint8_t who,uint8_t BWIndex) 520 | { 521 | uint8_t bank = 0; 522 | uint16_t AAFDeltsqr = BWIndex*BWIndex; 523 | if(who == GYRO){ 524 | bank = 1; 525 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 526 | writeReg(ICM42688_GYRO_CONFIG_STATIC3,&BWIndex,1); 527 | writeReg(ICM42688_GYRO_CONFIG_STATIC4,&AAFDeltsqr,1); 528 | gyroConfigStatic5.gyroAAFDeltsqr = AAFDeltsqr>>8; 529 | if(BWIndex == 1){ 530 | gyroConfigStatic5.gyroAAFBitshift = 15; 531 | } else if(BWIndex == 2){ 532 | gyroConfigStatic5.gyroAAFBitshift = 13; 533 | } else if(BWIndex == 3){ 534 | gyroConfigStatic5.gyroAAFBitshift = 12; 535 | } else if(BWIndex == 4){ 536 | gyroConfigStatic5.gyroAAFBitshift = 11; 537 | } else if(BWIndex == 5||BWIndex == 6){ 538 | gyroConfigStatic5.gyroAAFBitshift = 10; 539 | } else if(BWIndex > 6 && BWIndex < 10){ 540 | gyroConfigStatic5.gyroAAFBitshift = 9; 541 | } else if(BWIndex > 9 && BWIndex < 14){ 542 | gyroConfigStatic5.gyroAAFBitshift = 8; 543 | } else if(BWIndex > 13 && BWIndex < 19){ 544 | gyroConfigStatic5.gyroAAFBitshift = 7; 545 | } else if(BWIndex > 18 && BWIndex < 27){ 546 | gyroConfigStatic5.gyroAAFBitshift = 6; 547 | } else if(BWIndex > 26 && BWIndex < 37){ 548 | gyroConfigStatic5.gyroAAFBitshift = 5; 549 | } else if(BWIndex > 36 && BWIndex < 53){ 550 | gyroConfigStatic5.gyroAAFBitshift = 4; 551 | } else if(BWIndex > 53 && BWIndex <= 63){ 552 | gyroConfigStatic5.gyroAAFBitshift = 3; 553 | } 554 | writeReg(ICM42688_GYRO_CONFIG_STATIC5,&gyroConfigStatic5,1); 555 | bank = 0; 556 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 557 | } else if(who == ACCEL){ 558 | bank = 2; 559 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 560 | accelConfigStatic2.accelAAFDelt = BWIndex; 561 | writeReg(ICM42688_ACCEL_CONFIG_STATIC2,&accelConfigStatic2,1); 562 | writeReg(ICM42688_ACCEL_CONFIG_STATIC3,&AAFDeltsqr,1); 563 | accelConfigStatic4.accelAAFDeltsqr = AAFDeltsqr>>8; 564 | if(BWIndex == 1){ 565 | accelConfigStatic4.accelAAFBitshift = 15; 566 | } else if(BWIndex == 2){ 567 | accelConfigStatic4.accelAAFBitshift = 13; 568 | } else if(BWIndex == 3){ 569 | accelConfigStatic4.accelAAFBitshift = 12; 570 | } else if(BWIndex == 4){ 571 | accelConfigStatic4.accelAAFBitshift = 11; 572 | } else if(BWIndex == 5||BWIndex == 6){ 573 | accelConfigStatic4.accelAAFBitshift = 10; 574 | } else if(BWIndex > 6 && BWIndex < 10){ 575 | accelConfigStatic4.accelAAFBitshift = 9; 576 | } else if(BWIndex > 9 && BWIndex < 14){ 577 | accelConfigStatic4.accelAAFBitshift = 8; 578 | } else if(BWIndex > 13 && BWIndex < 19){ 579 | accelConfigStatic4.accelAAFBitshift = 7; 580 | } else if(BWIndex > 18 && BWIndex < 27){ 581 | accelConfigStatic4.accelAAFBitshift = 6; 582 | } else if(BWIndex > 26 && BWIndex < 37){ 583 | accelConfigStatic4.accelAAFBitshift = 5; 584 | } else if(BWIndex > 36 && BWIndex < 53){ 585 | accelConfigStatic4.accelAAFBitshift = 4; 586 | } else if(BWIndex > 53 && BWIndex <= 63){ 587 | accelConfigStatic4.accelAAFBitshift = 3; 588 | } 589 | writeReg(ICM42688_ACCEL_CONFIG_STATIC4,&accelConfigStatic4,1); 590 | 591 | bank = 0; 592 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 593 | } else if(who == ALL){ 594 | bank = 1; 595 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 596 | writeReg(ICM42688_GYRO_CONFIG_STATIC3,&BWIndex,1); 597 | writeReg(ICM42688_GYRO_CONFIG_STATIC4,&AAFDeltsqr,1); 598 | gyroConfigStatic5.gyroAAFDeltsqr = AAFDeltsqr>>8; 599 | if(BWIndex == 1){ 600 | gyroConfigStatic5.gyroAAFBitshift = 15; 601 | } else if(BWIndex == 2){ 602 | gyroConfigStatic5.gyroAAFBitshift = 13; 603 | } else if(BWIndex == 3){ 604 | gyroConfigStatic5.gyroAAFBitshift = 12; 605 | } else if(BWIndex == 4){ 606 | gyroConfigStatic5.gyroAAFBitshift = 11; 607 | } else if(BWIndex == 5||BWIndex == 6){ 608 | gyroConfigStatic5.gyroAAFBitshift = 10; 609 | } else if(BWIndex > 6 && BWIndex < 10){ 610 | gyroConfigStatic5.gyroAAFBitshift = 9; 611 | } else if(BWIndex > 9 && BWIndex < 14){ 612 | gyroConfigStatic5.gyroAAFBitshift = 8; 613 | } else if(BWIndex > 13 && BWIndex < 19){ 614 | gyroConfigStatic5.gyroAAFBitshift = 7; 615 | } else if(BWIndex > 18 && BWIndex < 27){ 616 | gyroConfigStatic5.gyroAAFBitshift = 6; 617 | } else if(BWIndex > 26 && BWIndex < 37){ 618 | gyroConfigStatic5.gyroAAFBitshift = 5; 619 | } else if(BWIndex > 36 && BWIndex < 53){ 620 | gyroConfigStatic5.gyroAAFBitshift = 4; 621 | } else if(BWIndex > 53 && BWIndex <= 63){ 622 | gyroConfigStatic5.gyroAAFBitshift = 3; 623 | } 624 | writeReg(ICM42688_GYRO_CONFIG_STATIC5,&gyroConfigStatic5,1); 625 | bank = 2; 626 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 627 | accelConfigStatic2.accelAAFDelt = BWIndex; 628 | writeReg(ICM42688_ACCEL_CONFIG_STATIC2,&accelConfigStatic2,1); 629 | writeReg(ICM42688_ACCEL_CONFIG_STATIC3,&AAFDeltsqr,1); 630 | accelConfigStatic4.accelAAFDeltsqr = AAFDeltsqr>>8; 631 | if(BWIndex == 1){ 632 | accelConfigStatic4.accelAAFBitshift = 15; 633 | } else if(BWIndex == 2){ 634 | accelConfigStatic4.accelAAFBitshift = 13; 635 | } else if(BWIndex == 3){ 636 | accelConfigStatic4.accelAAFBitshift = 12; 637 | } else if(BWIndex == 4){ 638 | accelConfigStatic4.accelAAFBitshift = 11; 639 | } else if(BWIndex == 5||BWIndex == 6){ 640 | accelConfigStatic4.accelAAFBitshift = 10; 641 | } else if(BWIndex > 6 && BWIndex < 10){ 642 | accelConfigStatic4.accelAAFBitshift = 9; 643 | } else if(BWIndex > 9 && BWIndex < 14){ 644 | accelConfigStatic4.accelAAFBitshift = 8; 645 | } else if(BWIndex > 13 && BWIndex < 19){ 646 | accelConfigStatic4.accelAAFBitshift = 7; 647 | } else if(BWIndex > 18 && BWIndex < 27){ 648 | accelConfigStatic4.accelAAFBitshift = 6; 649 | } else if(BWIndex > 26 && BWIndex < 37){ 650 | accelConfigStatic4.accelAAFBitshift = 5; 651 | } else if(BWIndex > 36 && BWIndex < 53){ 652 | accelConfigStatic4.accelAAFBitshift = 4; 653 | } else if(BWIndex > 53 && BWIndex <= 63){ 654 | accelConfigStatic4.accelAAFBitshift = 3; 655 | } 656 | writeReg(ICM42688_ACCEL_CONFIG_STATIC4,&accelConfigStatic4,1); 657 | bank = 0; 658 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 659 | } 660 | } 661 | void DFRobot_ICM42688::setAAF(uint8_t who,bool mode) 662 | { 663 | uint8_t bank = 0; 664 | if(who == GYRO){ 665 | if(mode){ 666 | gyroConfigStatic2.gyroAAFDis = 0; 667 | } else { 668 | gyroConfigStatic2.gyroAAFDis = 1; 669 | } 670 | bank = 1; 671 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 672 | writeReg(ICM42688_GYRO_CONFIG_STATIC2,&gyroConfigStatic2,1); 673 | }else if(who == ACCEL){ 674 | if(mode){ 675 | accelConfigStatic2.accelAAFDis = 0; 676 | } else { 677 | accelConfigStatic2.accelAAFDis = 1; 678 | } 679 | bank = 2; 680 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 681 | writeReg(ICM42688_ACCEL_CONFIG_STATIC2,&accelConfigStatic2,1); 682 | } else if(who == ALL){ 683 | if(mode){ 684 | gyroConfigStatic2.gyroAAFDis = 0; 685 | accelConfigStatic2.accelAAFDis = 0; 686 | } else { 687 | gyroConfigStatic2.gyroAAFDis = 1; 688 | accelConfigStatic2.accelAAFDis = 1; 689 | } 690 | bank = 1; 691 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 692 | writeReg(ICM42688_GYRO_CONFIG_STATIC2,&gyroConfigStatic2,1); 693 | bank = 2; 694 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 695 | writeReg(ICM42688_ACCEL_CONFIG_STATIC2,&accelConfigStatic2,1); 696 | } 697 | bank = 0; 698 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 699 | } 700 | 701 | bool DFRobot_ICM42688::setUIFilter(uint8_t who,uint8_t filterOrder ,uint8_t UIFilterIndex) 702 | { 703 | bool ret = true; 704 | uint8_t bank = 0; 705 | writeReg(ICM42688_REG_BANK_SEL,&bank,1); 706 | if(filterOrder > 3 || UIFilterIndex > 15){ 707 | ret = false; 708 | } else{ 709 | if(who == GYRO){ 710 | gyroConfig1.gyroUIFiltODR = filterOrder; 711 | writeReg(ICM42688_GYRO_CONFIG1,&gyroConfig1,1); 712 | gyroAccelConfig0.gyroUIFiltBW = UIFilterIndex; 713 | writeReg(ICM42688_GYRO_ACCEL_CONFIG0,&gyroAccelConfig0,1); 714 | } else if(who == ACCEL){ 715 | accelConfig1.accelUIFiltORD = filterOrder; 716 | writeReg(ICM42688_ACCEL_CONFIG1,&accelConfig1,1); 717 | gyroAccelConfig0.accelUIFiltBW = UIFilterIndex; 718 | writeReg(ICM42688_GYRO_ACCEL_CONFIG0,&gyroAccelConfig0,1); 719 | } else if(who == ALL){ 720 | gyroConfig1.gyroUIFiltODR = filterOrder; 721 | writeReg(ICM42688_GYRO_CONFIG1,&gyroConfig1,1); 722 | accelConfig1.accelUIFiltORD = filterOrder; 723 | writeReg(ICM42688_ACCEL_CONFIG1,&accelConfig1,1); 724 | gyroAccelConfig0.gyroUIFiltBW = UIFilterIndex; 725 | gyroAccelConfig0.accelUIFiltBW = UIFilterIndex; 726 | writeReg(ICM42688_GYRO_ACCEL_CONFIG0,&gyroAccelConfig0,1); 727 | } 728 | } 729 | return ret; 730 | } 731 | 732 | DFRobot_ICM42688_I2C::DFRobot_ICM42688_I2C(uint8_t i2cAddr,TwoWire *pWire) 733 | { 734 | _deviceAddr = i2cAddr; 735 | _pWire = pWire; 736 | } 737 | 738 | int DFRobot_ICM42688_I2C::begin(void) 739 | { 740 | _pWire->begin(); 741 | return DFRobot_ICM42688::begin(); 742 | } 743 | 744 | void DFRobot_ICM42688_I2C::writeReg(uint8_t reg, void* pBuf, size_t size) 745 | { 746 | if(pBuf == NULL){ 747 | DBG("pBuf ERROR!! : null pointer"); 748 | } 749 | uint8_t * _pBuf = (uint8_t *)pBuf; 750 | _pWire->beginTransmission(_deviceAddr); 751 | _pWire->write(®, 1); 752 | for(uint16_t i = 0; i < size; i++){ 753 | _pWire->write(_pBuf[i]); 754 | } 755 | _pWire->endTransmission(); 756 | } 757 | 758 | uint8_t DFRobot_ICM42688_I2C::readReg(uint8_t reg, void* pBuf, size_t size) 759 | { 760 | if(pBuf == NULL){ 761 | DBG("pBuf ERROR!! : null pointer"); 762 | } 763 | uint8_t * _pBuf = (uint8_t *)pBuf; 764 | _pWire->beginTransmission(_deviceAddr); 765 | _pWire->write(®, 1); 766 | if( _pWire->endTransmission() != 0){ 767 | return 0; 768 | } 769 | _pWire->requestFrom(_deviceAddr, (uint8_t) size); 770 | for(uint16_t i = 0; i < size; i++){ 771 | _pBuf[i] = _pWire->read(); 772 | } 773 | return size; 774 | } 775 | 776 | DFRobot_ICM42688_SPI::DFRobot_ICM42688_SPI(uint8_t csPin,SPIClass *pSpi) 777 | { 778 | _pSpi = pSpi; 779 | _csPin = csPin; 780 | } 781 | 782 | int DFRobot_ICM42688_SPI::begin(void) 783 | { 784 | _pSpi->begin(); 785 | pinMode(_csPin, OUTPUT); 786 | digitalWrite(_csPin,1); 787 | return DFRobot_ICM42688::begin(); 788 | } 789 | 790 | void DFRobot_ICM42688_SPI::writeReg(uint8_t reg, void* pBuf, size_t size) 791 | { 792 | if(pBuf == NULL){ 793 | DBG("pBuf ERROR!! : null pointer"); 794 | } 795 | delay(1); 796 | uint8_t * _pBuf = (uint8_t *)pBuf; 797 | _pSpi->beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0)); 798 | digitalWrite(_csPin,0); 799 | _pSpi->transfer(reg); 800 | while(size--) { 801 | _pSpi->transfer(*_pBuf); 802 | _pBuf++; 803 | } 804 | SPI.endTransaction(); 805 | digitalWrite(_csPin,1); 806 | } 807 | 808 | uint8_t DFRobot_ICM42688_SPI::readReg(uint8_t reg, void* pBuf, size_t size) 809 | { 810 | if(pBuf == NULL){ 811 | DBG("pBuf ERROR!! : null pointer"); 812 | } 813 | uint8_t * _pBuf = (uint8_t *)pBuf; 814 | size_t count = 0; 815 | _pSpi->beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0)); 816 | digitalWrite(_csPin,0); 817 | _pSpi->transfer(reg | 0x80); 818 | while(size--) { 819 | *_pBuf = SPI.transfer(0x00); 820 | _pBuf++; 821 | count++; 822 | } 823 | _pSpi->endTransaction(); 824 | digitalWrite(_csPin,1); 825 | return count; 826 | } 827 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Copyright 2010 DFRobot Co.Ltd 2 | 3 | Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: 4 | 5 | The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. 6 | 7 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # DFRobot_ICM42688 2 | 3 | - [中文版](./README_CN.md) 4 | 5 | The ICM-42688-P is a 6-axis MEMS MotionTracking device that combines a 3-axis gyroscope and a 3-axis accelerometer. It has a configurable host interface that supports I3CSM, I2C and SPI serial communication, features a 2 kB FIFO and 2 programmable interrupts with ultra low-power wake-on-motion support to minimize system power consumption. 6 | 7 | 8 | 9 | ![产品实物图](./resources/images/SEN0452.jpg) 10 | 11 | 12 | ## Product Link(https://www.dfrobot.com/) 13 | SKU:SEN0452 14 | 15 | ## Table of Contents 16 | 17 | * [Summary](#summary) 18 | * [Installation](#installation) 19 | * [Methods](#methods) 20 | * [Compatibility](#compatibility) 21 | * [History](#history) 22 | * [Credits](#credits) 23 | 24 | ## Summary 25 | 26 | * Get temperature data, gyroscope data and accelerometer data. 27 | * Tap detection 28 | * Wake on Motion 29 | * Significant Motion Detection 30 | 31 | ## Installation 32 | 33 | There are two ways to use the library: 34 | 1. Open the Arduino IDE, search for "DFRobot_ICM42688" in Tools --> Manager Libraries on the status bar, and install the library. 35 | 2. First download the library file, paste it into the \Arduino\libraries directory, then open the examples folder and run the demo in that folder. 36 | 37 | ## Methods 38 | 39 | ```C++ 40 | /** 41 | * @fn begin 42 | * @brief Init function 43 | * @return Init result 44 | * @retval ERR_OK Init succeed 45 | * @retval ERR_DATA_BUS Bus data read error 46 | * @retval ERR_IC_VERSION The read Sensor ID is wrong 47 | */ 48 | int begin(void); 49 | 50 | /** 51 | * @fn getTemperature 52 | * @brief Get measured temperature 53 | * @return Temperature unit: ℃ 54 | */ 55 | float getTemperature(void); 56 | 57 | /** 58 | * @fn getAccelDataX 59 | * @brief Get X-axis accelerometer value 60 | * @return X-axis accelerometer value unit: mg 61 | */ 62 | float getAccelDataX(void); 63 | 64 | /** 65 | * @fn getAccelDataY 66 | * @brief Get Y-axis accelerometer value 67 | * @return Y-axis accelerometer value unit: mg 68 | */ 69 | float getAccelDataY(void); 70 | 71 | /** 72 | * @fn getAccelDataZ 73 | * @brief Get Z-axis accelerometer value 74 | * @return Z-axis accelerometer value unit: mg 75 | */ 76 | float getAccelDataZ(void); 77 | 78 | /** 79 | * @fn getGyroDataX 80 | * @brief Get X-axis gyroscope value 81 | * @return X-axis gyroscope value unit: dps 82 | */ 83 | float getGyroDataX(void); 84 | 85 | /** 86 | * @fn getGyroDataY 87 | * @brief Get Y-axis gyroscope value 88 | * @return Y-axis gyroscope value unit: dps 89 | */ 90 | float getGyroDataY(void); 91 | 92 | /** 93 | * @fn getGyroDataZ 94 | * @brief Get Z-axis gyroscope value 95 | * @return Z-axis gyroscope value unit: dps 96 | */ 97 | float getGyroDataZ(void); 98 | 99 | /** 100 | * @fn tapDetectionInit 101 | * @brief Tap detection init 102 | * @param accelMode Accelerometer operating mode 103 | * @n 0 for operating in low-power mode 104 | * @n 1 for operating in low-noise mode 105 | */ 106 | void tapDetectionInit(uint8_t accelMode); 107 | 108 | /** 109 | * @fn getTapInformation 110 | * @brief Get tap information 111 | */ 112 | void getTapInformation(); 113 | 114 | /** 115 | * @fn numberOfTap 116 | * @brief Get the number of tap: single-tap or double tap 117 | * @return The number of tap 118 | * @retval TAP_SINGLE single-tap 119 | * @n TAP_DOUBLE double tap 120 | */ 121 | uint8_t numberOfTap(); 122 | 123 | /** 124 | * @fn axisOfTap 125 | * @brief Get the axis on which the tap occurred: X-axis, Y-axis, or Z-axis 126 | * @return Tap axis 127 | * @retval X_AXIS X-axis 128 | * @retval Y_AXIS Y-axis 129 | * @retval Z_AXIS Z-axis 130 | */ 131 | uint8_t axisOfTap(); 132 | 133 | /** 134 | * @fn wakeOnMotionInit 135 | * @brief Wake on motion init 136 | */ 137 | void wakeOnMotionInit(); 138 | 139 | /** 140 | * @fn setWOMTh 141 | * @brief Set wake on motion interrupt threshold of an axis accelerometer 142 | * @param axis x/y/z axis 143 | * @n X_AXIS_WOM 144 | * @n Y_AXIS_WOM 145 | * @n Z_AXIS_WOM 146 | * @n ALL 147 | * @param threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 148 | */ 149 | void setWOMTh(uint8_t axis,uint8_t threshold); 150 | 151 | /** 152 | * @fn setWOMInterrupt 153 | * @brief Enable wake on motion interrupt 154 | * @param axis x/y/z axis 155 | * @n X_AXIS_WOM 156 | * @n Y_AXIS_WOM 157 | * @n Z_AXIS_WOM 158 | */ 159 | void setWOMInterrupt(uint8_t axis); 160 | 161 | /** 162 | * @fn enableSMDInterrupt 163 | * @brief Set essential motion detection mode and enable SMD interrupt 164 | * @param mode 165 | * @n 0: disable SMD 166 | * @n 2 : SMD short (1 sec wait) An SMD event is detected when two WOM are detected 1 sec apart 167 | * @n 3 : SMD long (3 sec wait) An SMD event is detected when two WOM are detected 3 sec apart 168 | */ 169 | void enableSMDInterrupt(uint8_t mode); 170 | 171 | /** 172 | * @fn readInterruptStatus 173 | * @brief Read interrupt information and clear interrupt 174 | * @param reg Interrupt information register 175 | * @n ICM42688_INT_STATUS2 Obtain interrupt information of SMD_INT, WOM_X_INT, WOM_Y_INT, WOM_Z_INT and clear them 176 | * @n ICM42688_INT_STATUS3 Obtain interrupt information of STEP_DET_INT, STEP_CNT_OVF_INT, TILT_DET_INT, WAKE_INT, TAP_DET_INT and clear them 177 | * @return Interrupt information, return 0 when no interrupt 178 | */ 179 | uint8_t readInterruptStatus(uint8_t reg); 180 | 181 | /** 182 | * @fn setODRAndFSR 183 | * @brief Set ODR and Full-scale range of gyroscope or accelerometer 184 | * @param who GYRO/ACCEL/ALL 185 | * @n GYRO: indicate only set gyroscope 186 | * @n ACCEL: indicate only set accelerometer 187 | * @param ODR Output data rate 188 | * @n ODR_32KHZ Support: Gyro/Accel(LN mode) 189 | * @n ODR_16KHZ Support: Gyro/Accel(LN mode) 190 | * @n ODR_8KHZ Support: Gyro/Accel(LN mode) 191 | * @n ODR_4KHZ Support: Gyro/Accel(LN mode) 192 | * @n ODR_2KHZ Support: Gyro/Accel(LN mode) 193 | * @n ODR_1KHZ Support: Gyro/Accel(LN mode) 194 | * @n ODR_200HZ Support: Gyro/Accel(LP or LN mode) 195 | * @n ODR_100HZ Support: Gyro/Accel(LP or LN mode) 196 | * @n ODR_50HZ Support: Gyro/Accel(LP or LN mode) 197 | * @n ODR_25KHZ Support: Gyro/Accel(LP or LN mode) 198 | * @n ODR_12_5KHZ Support: Gyro/Accel(LP or LN mode) 199 | * @n ODR_6_25KHZ Support: Accel(LP mode) 200 | * @n ODR_3_125HZ Support: Accel(LP mode) 201 | * @n ODR_1_5625HZ Support: Accel(LP mode) 202 | * @n ODR_500HZ Support: Accel(LP or LN mode) 203 | * @param FSR Full-scale range 204 | * @n FSR_0 Gyro:±2000dps / Accel: ±16g 205 | * @n FSR_1 Gyro:±1000dps / Accel: ±8g 206 | * @n FSR_2 Gyro:±500dps / Accel: ±4g 207 | * @n FSR_3 Gyro:±250dps / Accel: ±2g 208 | * @n FSR_4 Gyro:±125dps / Accel: not optional 209 | * @n FSR_5 Gyro:±62.5dps / Accel: not optional 210 | * @n FSR_6 Gyro:±31.25dps / Accel: not optional 211 | * @n FSR_7 Gyro:±15.625dps / Accel: not optional 212 | * @return Set result 213 | * @retval true The setting succeeds 214 | * @retval flase Selected parameter is wrong 215 | */ 216 | bool setODRAndFSR(uint8_t who,uint8_t ODR,uint8_t FSR); 217 | 218 | /** 219 | * @fn startFIFOMode 220 | * @brief Enable FIFO 221 | */ 222 | void startFIFOMode(); 223 | 224 | /** 225 | * @fn sotpFIFOMode 226 | * @brief Disable FIFO 227 | */ 228 | void sotpFIFOMode(); 229 | 230 | /** 231 | * @fn getFIFOData 232 | * @brief Read FIFO data, read temperature, gyroscope and accelerometer data and save them for parse. 233 | */ 234 | void getFIFOData(); 235 | 236 | /** 237 | * @fn setINTMode 238 | * @brief Set interrupt mode 239 | * @param INTPin Interrupt pin 240 | * @n 1 Use INT1 interrupt pin 241 | * @n 2 Use INT2 interrupt pin 242 | * @param INTmode Set interrupt mode 243 | * @n 1 Interrupt lock mode (remain polarity after interrupt trigger, and restore after clearing interrupt) 244 | * @n 0 Pulse mode 245 | * @param INTPolarity Level polarity output by interrupt 246 | * @n 0 Interrupt pin polarity is LOW when producing interrupt 247 | * @n 1 Interrupt pin polarity is HIGH when producing interrupt 248 | * @param INTDriveCircuit 249 | * @n 0 Open drain 250 | * @n 1 Push pull 251 | */ 252 | void setINTMode(uint8_t INTPin,uint8_t INTmode,uint8_t INTPolarity,uint8_t INTDriveCircuit); 253 | 254 | /** 255 | * @fn startGyroMeasure 256 | * @brief Start gyroscope 257 | * @param mode Set gyroscope working mode 258 | * @n STANDBY_MODE_ONLY_GYRO 1 Set stanby mode, only support gyroscope 259 | * @n LN_MODE 3 Set low-noise mode 260 | */ 261 | void startGyroMeasure(uint8_t mode); 262 | 263 | /** 264 | * @fn startAccelMeasure 265 | * @brief Start accelerometer 266 | * @param mode Set accelerometer working mode 267 | * @n LP_MODE_ONLY_ACCEL 2 Set low-power mode, only support accelerometer 268 | * @n LN_MODE 3 Set low-noise mode 269 | */ 270 | void startAccelMeasure(uint8_t mode); 271 | 272 | /** 273 | * @fn startTempMeasure 274 | * @brief Start thermometer 275 | */ 276 | void startTempMeasure(); 277 | ``` 278 | 279 | ## Compatibility 280 | 281 | MCU | Work Well | Work Wrong | Untested | Remarks | 282 | ------------------ | :----------: | :----------: | :---------: | :---------:| 283 | Arduino uno | | | | only support 3.3V | 284 | FireBeetle esp32 | √ | | | | 285 | FireBeetle esp8266 | √ | | | | 286 | FireBeetle m0 | √ | | | | 287 | Leonardo | | | | only support 3.3V | 288 | Microbit | √ | | | | 289 | Arduino MEGA2560 | | | | only support 3.3V | 290 | 291 | 292 | ## History 293 | 294 | - 2021/09/28 - Version 1.0.0 released. 295 | 296 | 297 | ## Credits 298 | 299 | Written by yangfeng(feng.yang@dfrobot.com), 2021. (Welcome to our [website](https://www.dfrobot.com/)) 300 | 301 | 302 | 303 | 304 | 305 | -------------------------------------------------------------------------------- /README_CN.md: -------------------------------------------------------------------------------- 1 | # DFRobot_ICM42688 2 | 3 | - [English Version](./README.md) 4 | 5 | ICM-42688-P是一款6轴MEMS运动跟踪设备,它结合了一个3轴陀螺仪和一个3轴加速度计。它有一个可配置的主机接口,支持I3CSM, I2C和SPI串行通信,具有2 kB的FIFO和2个可编程中断,超低功率动态尾流支持,以最大限度地减少系统功耗。 6 | 7 | ![产品实物图](./resources/images/SEN0352.jpg) 8 | 9 | 10 | ## 产品链接(https://www.dfrobot.com.cn/) 11 | SKU:SEN0352 12 | 13 | ## 目录 14 | 15 | * [概述](#概述) 16 | * [库安装](#库安装) 17 | * [方法](#方法) 18 | * [兼容性](#兼容性) 19 | * [历史](#历史) 20 | * [创作者](#创作者) 21 | 22 | 23 | ## 概述 24 | 25 | * 获取温度数据、陀螺仪数据、加速计数据 26 | * 敲击检测 27 | * 移动唤醒 28 | * 重要的运动检测 29 | 30 | 31 | ## 库安装 32 | 33 | 这里提供两种使用本库的方法: 34 | 1. 打开Arduino IDE,在状态栏中的Tools--->Manager Libraries 搜索"DFRobot_ICM42688"并安装本库. 35 | 2. 首先下载库文件,将其粘贴到\Arduino\libraries目录中,然后打开examples文件夹并在该文件夹中运行演示. 36 | 37 | 38 | ## 方法 39 | 40 | ```C++ 41 | /** 42 | * @fn begin 43 | * @brief 初始化函数 44 | * @return 初始化结果 45 | * @retval ERR_OK 初始化成功 46 | * @retval ERR_DATA_BUS 总线数据访问错误 47 | * @retval ERR_IC_VERSION 读取的传感器ID有误 48 | */ 49 | int begin(void); 50 | 51 | /** 52 | * @fn getTemperature 53 | * @brief 获取测量温度值 54 | * @return 温度值 单位:℃ 55 | */ 56 | float getTemperature(void); 57 | 58 | /** 59 | * @fn getAccelDataX 60 | * @brief 获取X轴加速计值 61 | * @return X轴加速计值 单位:mg 62 | */ 63 | float getAccelDataX(void); 64 | 65 | /** 66 | * @fn getAccelDataY 67 | * @brief 获取Y轴加速计值 68 | * @return Y轴加速计值 单位:mg 69 | */ 70 | float getAccelDataY(void); 71 | 72 | /** 73 | * @fn getAccelDataZ 74 | * @brief 获取Z轴加速计值 75 | * @return Z轴加速计值 单位:mg 76 | */ 77 | float getAccelDataZ(void); 78 | 79 | /** 80 | * @fn getGyroDataX 81 | * @brief 获取X轴陀螺仪值 82 | * @return X轴陀螺仪值 单位:dps 83 | */ 84 | float getGyroDataX(void); 85 | 86 | /** 87 | * @fn getGyroDataY 88 | * @brief 获取Y轴陀螺仪值 89 | * @return Y轴陀螺仪值 单位:dps 90 | */ 91 | float getGyroDataY(void); 92 | 93 | /** 94 | * @fn getGyroDataZ 95 | * @brief 获取Z轴陀螺仪值 96 | * @return Z轴陀螺仪值 单位:dps 97 | */ 98 | float getGyroDataZ(void); 99 | 100 | /** 101 | * @fn tapDetectionInit 102 | * @brief 敲击事件初始化 103 | * @param accelMode 加速计工作模式 104 | * @n 0 代表工作在低功耗模式 105 | * @n 1 代表工作在低噪声模式 106 | */ 107 | void tapDetectionInit(uint8_t accelMode); 108 | 109 | /** 110 | * @fn getTapInformation 111 | * @brief 获取敲击信息 112 | */ 113 | void getTapInformation(); 114 | 115 | /** 116 | * @fn numberOfTap 117 | * @brief 获取敲击次数,分别是:单击、双击 118 | * @return 敲击次数 119 | * @retval TAP_SINGLE 单击 120 | * @retval TAP_DOUBLE 双击 121 | */ 122 | uint8_t numberOfTap(); 123 | 124 | /** 125 | * @fn axisOfTap 126 | * @brief 获取敲击轴,分别是:X\Y\Z轴 127 | * @return 敲击轴 128 | * @retval X_AXIS X轴 129 | * @retval Y_AXIS Y轴 130 | * @retval Z_AXIS Z轴 131 | */ 132 | uint8_t axisOfTap(); 133 | 134 | /** 135 | * @fn wakeOnMotionInit 136 | * @brief 初始化移动唤醒 137 | */ 138 | void wakeOnMotionInit(); 139 | 140 | /** 141 | * @fn setWOMTh 142 | * @brief 设置某轴加速度计的运动中断唤醒的阈值 143 | * @param axis x/y/z轴 144 | * @n X_AXIS_WOM 145 | * @n Y_AXIS_WOM 146 | * @n Z_AXIS_WOM 147 | * @n ALL 148 | * @param threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 149 | */ 150 | void setWOMTh(uint8_t axis,uint8_t threshold); 151 | 152 | /** 153 | * @fn setWOMInterrupt 154 | * @brief 使能运动唤醒中断 155 | * @param axis x/y/z轴 156 | * @n X_AXIS_WOM 157 | * @n Y_AXIS_WOM 158 | * @n Z_AXIS_WOM 159 | */ 160 | void setWOMInterrupt(uint8_t axis); 161 | 162 | /** 163 | * @fn enableSMDInterrupt 164 | * @brief 设置重要运动检测模式并且开启SMD中断 165 | * @param mode 166 | * @n 0: disable SMD 167 | * @n 2 : SMD short (1 sec wait) An SMD event is detected when two WOM are detected 1 sec apart 168 | * @n 3 : SMD long (3 sec wait) An SMD event is detected when two WOM are detected 3 sec apart 169 | */ 170 | void enableSMDInterrupt(uint8_t mode); 171 | 172 | /** 173 | * @fn readInterruptStatus 174 | * @brief 读取中断信息,并清除中断 175 | * @param reg 中断信息寄存器 176 | * @n ICM42688_INT_STATUS2 可以获取SMD_INT、WOM_X_INT、WOM_Y_INT、WOM_Z_INT中断信息并且清除 177 | * @n ICM42688_INT_STATUS3 可以获取STEP_DET_INT、STEP_CNT_OVF_INT、TILT_DET_INT、WAKE_INT、TAP_DET_INT中断信息并且清除 178 | * @return 中断信息,无中断时返回0。 179 | */ 180 | uint8_t readInterruptStatus(uint8_t reg); 181 | 182 | /** 183 | * @fn setODRAndFSR 184 | * @brief 设置陀螺仪或者加速计的ODR和 Full-scale range 185 | * @param who GYRO/ACCEL/ALL 186 | * @n GYRO:代表只设置陀螺仪 187 | * @n ACCEL:代表只设置加速计 188 | * @param ODR 输出数据速率 189 | * @n ODR_32KHZ 支持:Gyro/Accel(LN mode) 190 | * @n ODR_16KHZ 支持:Gyro/Accel(LN mode) 191 | * @n ODR_8KHZ 支持:Gyro/Accel(LN mode) 192 | * @n ODR_4KHZ 支持:Gyro/Accel(LN mode) 193 | * @n ODR_2KHZ 支持:Gyro/Accel(LN mode) 194 | * @n ODR_1KHZ 支持:Gyro/Accel(LN mode) 195 | * @n ODR_200HZ 支持:Gyro/Accel(LP or LN mode) 196 | * @n ODR_100HZ 支持:Gyro/Accel(LP or LN mode) 197 | * @n ODR_50HZ 支持:Gyro/Accel(LP or LN mode) 198 | * @n ODR_25KHZ 支持:Gyro/Accel(LP or LN mode) 199 | * @n ODR_12_5KHZ 支持:Gyro/Accel(LP or LN mode) 200 | * @n ODR_6_25KHZ 支持:Accel(LP mode) 201 | * @n ODR_3_125HZ 支持:Accel(LP mode) 202 | * @n ODR_1_5625HZ 支持:Accel(LP mode) 203 | * @n ODR_500HZ 支持:Accel(LP or LN mode) 204 | * @param FSR Full-scale range 205 | * @n FSR_0 Gyro:±2000dps / Accel: ±16g 206 | * @n FSR_1 Gyro:±1000dps / Accel: ±8g 207 | * @n FSR_2 Gyro:±500dps / Accel: ±4g 208 | * @n FSR_3 Gyro:±250dps / Accel: ±2g 209 | * @n FSR_4 Gyro:±125dps / Accel: 不可选 210 | * @n FSR_5 Gyro:±62.5dps / Accel: 不可选 211 | * @n FSR_6 Gyro:±31.25dps / Accel: 不可选 212 | * @n FSR_7 Gyro:±15.625dps / Accel: 不可选 213 | * @return 设置结果 214 | * @retval true 设置设置成功 215 | * @retval flase 选择的参数有误 216 | */ 217 | bool setODRAndFSR(uint8_t who,uint8_t ODR,uint8_t FSR); 218 | 219 | /** 220 | * @fn startFIFOMode 221 | * @brief 启用FIFO 222 | */ 223 | void startFIFOMode(); 224 | 225 | /** 226 | * @fn sotpFIFOMode 227 | * @brief 关闭停用FIFO 228 | */ 229 | void sotpFIFOMode(); 230 | 231 | /** 232 | * @fn getFIFOData 233 | * @brief 读取FIFO数据,分别读出温度数据、陀螺仪数据、加速计数据并保存等待解析 234 | */ 235 | void getFIFOData(); 236 | 237 | /** 238 | * @fn setINTMode 239 | * @brief 设置中断模式 240 | * @param INTPin 中断引脚 241 | * @n 1 使用INT1中断引脚 242 | * @n 2 使用INT2中断引脚 243 | * @param INTmode 设置中断模式 244 | * @n 1 中断锁定模式(即中断触发后会保持极性,清除中断后恢复) 245 | * @n 0 脉冲模式 246 | * @param INTPolarity 中断输出的电平极性 247 | * @n 0 产生中断时中断引脚极性为LOW 248 | * @n 1 产生中断时中断引脚极性为HIGH 249 | * @param INTDriveCircuit 250 | * @n 0 Open drain 251 | * @n 1 Push pull 252 | */ 253 | void setINTMode(uint8_t INTPin,uint8_t INTmode,uint8_t INTPolarity,uint8_t INTDriveCircuit); 254 | 255 | /** 256 | * @fn startGyroMeasure 257 | * @brief 启动陀螺仪 258 | * @param mode 设置陀螺仪的工作模式 259 | * @n STANDBY_MODE_ONLY_GYRO 1 设置为备用模式,仅支持陀螺仪 260 | * @n LN_MODE 3 设置为低噪声模式 261 | */ 262 | void startGyroMeasure(uint8_t mode); 263 | 264 | /** 265 | * @fn startAccelMeasure 266 | * @brief 启动加速计 267 | * @param mode 设置加速计的工作模式 268 | * @n LP_MODE_ONLY_ACCEL 2 设置为低功耗模式,仅支持加速计 269 | * @n LN_MODE 3 设置为低噪声模式 270 | */ 271 | void startAccelMeasure(uint8_t mode); 272 | 273 | /** 274 | * @fn startTempMeasure 275 | * @brief 启动温度计 276 | */ 277 | void startTempMeasure(); 278 | ``` 279 | 280 | 281 | ## 兼容性 282 | 283 | 主控 | 正常运行 | 运行失败 | 未测试 | 备注 284 | ------------------ | :----------: | :----------: | :---------: | :---------:| 285 | Arduino uno | | | | 只支持3.3V | 286 | FireBeetle esp32 | √ | | | | 287 | FireBeetle esp8266 | √ | | | | 288 | FireBeetle m0 | √ | | | | 289 | Leonardo | | | | 只支持3.3V | 290 | Microbit | √ | | | | 291 | Arduino MEGA2560 | | | | 只支持3.3V | 292 | 293 | 294 | ## 历史 295 | 296 | - 2019/06/25 - 1.0.0 版本 297 | 298 | ## 创作者 299 | 300 | Written by yangfeng(feng.yang@dfrobot.com), 2021. (Welcome to our [website](https://www.dfrobot.com/)) 301 | 302 | -------------------------------------------------------------------------------- /examples/getAccelGyroData/getAccelGyroData.ino: -------------------------------------------------------------------------------- 1 | /*! 2 | * @file getAccelGyroData.ino 3 | * @brief Get temperature, gyroscope and accelerometer data 4 | * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 5 | * @license The MIT License (MIT) 6 | * @author [yangfeng] 7 | * @version V1.0 8 | * @date 2021-05-13 9 | * @url https://github.com/DFRobot/DFRobot_ICM42688 10 | */ 11 | #include 12 | //Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default to internal pull-up) 13 | //DFRobot_ICM42688_I2C_L_ADDR 0x68 14 | //DFRobot_ICM42688_I2C_H_ADDR 0x69 15 | //DFRobot_ICM42688_I2C ICM42688(/*i2cAddr = */ DFRobot_ICM42688_I2C_H_ADDR); 16 | DFRobot_ICM42688_SPI ICM42688(/* csPin= */5); 17 | 18 | void setup() { 19 | int ret; 20 | Serial.begin(9600); 21 | while((ret =ICM42688.begin()) !=0){ 22 | if(ret == -1){ 23 | Serial.println("bus data access error"); 24 | } else 25 | Serial.println("Chip versions do not match"); 26 | delay(1000); 27 | } 28 | Serial.println("ICM42688 begin success!!!"); 29 | /** 30 | * Set ODR and Full-scale range of gyroscope or accelerometer 31 | * who GYRO/ACCEL/ALL 32 | * GYRO: indicate only set gyroscope 33 | * ACCEL: indicate only set accelerometer 34 | * ODR Output data rate 35 | * ODR_32KHZ Support: Gyro/Accel(LN mode) 36 | * ODR_16KHZ Support: Gyro/Accel(LN mode) 37 | * ODR_8KHZ Support: Gyro/Accel(LN mode) 38 | * ODR_4KHZ Support: Gyro/Accel(LN mode) 39 | * ODR_2KHZ Support: Gyro/Accel(LN mode) 40 | * ODR_1KHZ Support: Gyro/Accel(LN mode) 41 | * ODR_200HZ Support: Gyro/Accel(LP or LN mode) 42 | * ODR_100HZ Support: Gyro/Accel(LP or LN mode) 43 | * ODR_50HZ Support: Gyro/Accel(LP or LN mode) 44 | * ODR_25KHZ Support: Gyro/Accel(LP or LN mode) 45 | * ODR_12_5KHZ Support: Gyro/Accel(LP or LN mode) 46 | * ODR_6_25KHZ Support: Accel(LP mode) 47 | * ODR_3_125HZ Support: Accel(LP mode) 48 | * ODR_1_5625HZ Support: Accel(LP mode) 49 | * ODR_500HZ Support: Accel(LP or LN mode) 50 | * FSR Full-scale range 51 | * FSR_0 Gyro:±2000dps / Accel: ±16g 52 | * FSR_1 Gyro:±1000dps / Accel: ±8g 53 | * FSR_2 Gyro:±500dps / Accel: ±4g 54 | * FSR_3 Gyro:±250dps / Accel: ±2g 55 | * FSR_4 Gyro:±125dps / Accel: not optional 56 | * FSR_5 Gyro:±62.5dps / Accel: not optional 57 | * FSR_6 Gyro:±31.25dps / Accel: not optional 58 | * FSR_7 Gyro:±15.625dps / Accel: not optional 59 | * true indicate the setting succeeds; flase indicate selected parameter is wrong 60 | */ 61 | ICM42688.setODRAndFSR(/* who= */GYRO,/* ODR= */ODR_1KHZ, /* FSR = */FSR_0); 62 | ICM42688.setODRAndFSR(/* who= */ACCEL,/* ODR= */ODR_500HZ, /* FSR = */FSR_0); 63 | /** 64 | * Set gyroscope and accelerometer working mode 65 | * mode 66 | * OFF_MODE 0 Disable 67 | * STANDBY_MODE_ONLY_GYRO 1 Set stanby mode, only support gyroscope 68 | * LP_MODE_ONLY_ACCEL 2 Set low-power mode, only support accelerometer 69 | * LN_MODE 3 Set low-noise mode 70 | */ 71 | ICM42688.startTempMeasure(); 72 | ICM42688.startGyroMeasure(/* mode= */LN_MODE); 73 | ICM42688.startAccelMeasure(/* mode= */LN_MODE); 74 | } 75 | 76 | void loop() { 77 | float accelDataX,accelDataY,accelDataZ,gyroDataX,gyroDataY,gyroDataZ,tempData; 78 | tempData= ICM42688.getTemperature(); 79 | accelDataX = ICM42688.getAccelDataX(); 80 | accelDataY= ICM42688.getAccelDataY(); 81 | accelDataZ= ICM42688.getAccelDataZ(); 82 | gyroDataX= ICM42688.getGyroDataX(); 83 | gyroDataY= ICM42688.getGyroDataY(); 84 | gyroDataZ= ICM42688.getGyroDataZ(); 85 | Serial.print("Temperature: "); 86 | Serial.print(tempData); 87 | Serial.println(" C"); 88 | 89 | Serial.print("Accel_X: "); 90 | Serial.print(accelDataX); 91 | Serial.print(" mg Accel_Y:"); 92 | Serial.print(accelDataY); 93 | Serial.print(" mg Accel_Z: "); 94 | Serial.print(accelDataZ); 95 | Serial.println(" mg"); 96 | 97 | Serial.print("Gyro_X: "); 98 | Serial.print(gyroDataX); 99 | Serial.print(" dps Gyro_Y: "); 100 | Serial.print(gyroDataY); 101 | Serial.print(" dps Gyro_Z: "); 102 | Serial.print(gyroDataZ); 103 | Serial.println(" dps"); 104 | delay(1000); 105 | } 106 | -------------------------------------------------------------------------------- /examples/getDataByFIFO/getDataByFIFO.ino: -------------------------------------------------------------------------------- 1 | /*! 2 | * @file getDataByFIFO.ino 3 | * @brief Get temperature, gyroscope and accelerometer data by FIFO 4 | * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 5 | * @license The MIT License (MIT) 6 | * @author [yangfeng] 7 | * @version V1.0 8 | * @date 2021-05-13 9 | * @url https://github.com/DFRobot/DFRobot_ICM42688 10 | */ 11 | #include 12 | //Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default to internal pull up) 13 | //DFRobot_ICM42688_I2C_L_ADDR 0x68 14 | //DFRobot_ICM42688_I2C_H_ADDR 0x69 15 | //DFRobot_ICM42688_I2C ICM42688(/*i2cAddr = */ DFRobot_ICM42688_I2C_H_ADDR); 16 | DFRobot_ICM42688_SPI ICM42688(/* csPin= */5); 17 | 18 | void setup() { 19 | int ret; 20 | Serial.begin(9600); 21 | while((ret =ICM42688.begin()) !=0){ 22 | if(ret == -1){ 23 | Serial.println("bus data access error"); 24 | } else 25 | Serial.println("Chip versions do not match"); 26 | delay(1000); 27 | } 28 | Serial.println("ICM42688 begin success!!!"); 29 | 30 | /** 31 | * Set ODR and Full-scale range of gyroscope or accelerometer 32 | * who GYRO/ACCEL/ALL 33 | * GYRO: indicate only set gyroscope 34 | * ACCEL: indicate only set accelerometer 35 | * ODR Output data rate 36 | * ODR_32KHZ Support: Gyro/Accel(LN mode) 37 | * ODR_16KHZ Support: Gyro/Accel(LN mode) 38 | * ODR_8KHZ Support: Gyro/Accel(LN mode) 39 | * ODR_4KHZ Support: Gyro/Accel(LN mode) 40 | * ODR_2KHZ Support: Gyro/Accel(LN mode) 41 | * ODR_1KHZ Support: Gyro/Accel(LN mode) 42 | * ODR_200HZ Support: Gyro/Accel(LP or LN mode) 43 | * ODR_100HZ Support: Gyro/Accel(LP or LN mode) 44 | * ODR_50HZ Support: Gyro/Accel(LP or LN mode) 45 | * ODR_25KHZ Support: Gyro/Accel(LP or LN mode) 46 | * ODR_12_5KHZ Support: Gyro/Accel(LP or LN mode) 47 | * ODR_6_25KHZ Support: Accel(LP mode) 48 | * ODR_3_125HZ Support: Accel(LP mode) 49 | * ODR_1_5625HZ Support: Accel(LP mode) 50 | * ODR_500HZ Support: Accel(LP or LN mode) 51 | * FSR Full-scale range 52 | * FSR_0 Gyro:±2000dps / Accel: ±16g 53 | * FSR_1 Gyro:±1000dps / Accel: ±8g 54 | * FSR_2 Gyro:±500dps / Accel: ±4g 55 | * FSR_3 Gyro:±250dps / Accel: ±2g 56 | * FSR_4 Gyro:±125dps / Accel: not optional 57 | * FSR_5 Gyro:±62.5dps / Accel: not optional 58 | * FSR_6 Gyro:±31.25dps / Accel: not optional 59 | * FSR_7 Gyro:±15.625dps / Accel: not optional 60 | * Note: 61 | * In FIFO mode, set gyroscope and accelerometer ODR to be the same and the selected ODR should be no more than 8KHz. Otherwise, the temperature data integration rate will not match reading rate. 62 | */ 63 | ICM42688.setODRAndFSR(/* who= */GYRO,/* ODR= */ODR_1KHZ, /* FSR = */FSR_0); 64 | ICM42688.setODRAndFSR(/* who= */ACCEL,/* ODR= */ODR_1KHZ, /* FSR = */FSR_0); 65 | /** 66 | * Set gyroscope and accelerometer working mode 67 | * mode 68 | * OFF_MODE 0 Disable 69 | * STANDBY_MODE_ONLY_GYRO 1 Set stanby mode, only support gyroscope 70 | * LP_MODE_ONLY_ACCEL 2 Set low-power mode, only support accelerometer 71 | * LN_MODE 3 Set low-noise mode 72 | */ 73 | ICM42688.startTempMeasure(); 74 | ICM42688.startGyroMeasure(/* mode= */LN_MODE); 75 | ICM42688.startAccelMeasure(/* mode= */LN_MODE); 76 | ICM42688.startFIFOMode(); //Enable FIFO 77 | } 78 | 79 | void loop() { 80 | float accelDataX,accelDataY,accelDataZ,gyroDataX,gyroDataY,gyroDataZ,tempData; 81 | 82 | ICM42688.getFIFOData(); //Read FIFO data, read temperature, gyroscope and accelerometer data and save them for parsing. 83 | tempData= ICM42688.getTemperature(); //Get measured temperature value, unit: ℃ 84 | //Get accelerometer value 85 | accelDataX = ICM42688.getAccelDataX(); 86 | accelDataY= ICM42688.getAccelDataY(); 87 | accelDataZ= ICM42688.getAccelDataZ(); 88 | //Get gyroscope value 89 | gyroDataX= ICM42688.getGyroDataX(); 90 | gyroDataY= ICM42688.getGyroDataY(); 91 | gyroDataZ= ICM42688.getGyroDataZ(); 92 | Serial.print("T: "); 93 | Serial.print(tempData); 94 | Serial.println(" C"); 95 | 96 | Serial.print("Accel_X: "); 97 | Serial.print(accelDataX); 98 | Serial.print(" mg Accel_Y:"); 99 | Serial.print(accelDataY); 100 | Serial.print(" mg Accel_Z: "); 101 | Serial.print(accelDataZ); 102 | Serial.println(" mg"); 103 | 104 | Serial.print("Gyro_X: "); 105 | Serial.print(gyroDataX); 106 | Serial.print(" dps Gyro_Y: "); 107 | Serial.print(gyroDataY); 108 | Serial.print(" dps Gyro_Z: "); 109 | Serial.print(gyroDataZ); 110 | Serial.println(" dps"); 111 | delay(1000); 112 | } 113 | -------------------------------------------------------------------------------- /examples/significantMotionDet/significantMotionDet.ino: -------------------------------------------------------------------------------- 1 | /*! 2 | * @file significantMotionDet.ino 3 | * @brief Significant Motion Detection 4 | * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 5 | * @license The MIT License (MIT) 6 | * @author [yangfeng] 7 | * @version V1.0 8 | * @date 2021-05-13 9 | * @url https://github.com/DFRobot/DFRobot_ICM42688 10 | */ 11 | #include 12 | 13 | //Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default internal pull up) 14 | //DFRobot_ICM42688_I2C_L_ADDR 0x68 15 | //DFRobot_ICM42688_I2C_H_ADDR 0x69 16 | //DFRobot_ICM42688_I2C ICM42688(/*i2cAddr = */ DFRobot_ICM42688_I2C_H_ADDR); 17 | DFRobot_ICM42688_SPI ICM42688(/* csPin= */5); 18 | uint8_t flag = 0; 19 | 20 | void interEvent(){ 21 | flag = 1; 22 | } 23 | 24 | void setup() { 25 | int ret; 26 | Serial.begin(9600); 27 | while((ret =ICM42688.begin()) !=0){ 28 | if(ret == -1){ 29 | Serial.println("bus data access error"); 30 | } else 31 | Serial.println("Chip versions do not match"); 32 | delay(1000); 33 | } 34 | Serial.println("ICM42688 begin success!!!"); 35 | #if defined(ESP32) || defined(ESP8266) 36 | //Use D6 pin as interrupt pin by default, or select other non-conflicting pins as external interrupt pin 37 | attachInterrupt(digitalPinToInterrupt(D9)/*Query the interrupt number of the D9 pin*/,interEvent,FALLING); 38 | #elif defined(ARDUINO_SAM_ZERO) 39 | //Use 5 pin as interrupt pin by default, or select other non-conflicting pins as external interrupt pin 40 | attachInterrupt(digitalPinToInterrupt(6)/*Query the interrupt number of the 5 pin*/,interEvent,FALLING); 41 | #else 42 | /* The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers 43 | * --------------------------------------------------------------------------------------- 44 | * | | DigitalPin | 2 | 3 | | 45 | * | Uno, Nano, Mini, other 328-based |--------------------------------------------| 46 | * | | Interrupt No | 0 | 1 | | 47 | * |-------------------------------------------------------------------------------------| 48 | * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | 49 | * | Mega2560 |--------------------------------------------| 50 | * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | 51 | * |-------------------------------------------------------------------------------------| 52 | * | | Pin | 3 | 2 | 0 | 1 | 7 | | 53 | * | Leonardo, other 32u4-based |--------------------------------------------| 54 | * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | 55 | * |-------------------------------------------------------------------------------------- 56 | */ 57 | /* The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers 58 | * --------------------------------------------------------------------------------------------------------------------------------------------- 59 | * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | 60 | * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| 61 | * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | 62 | * |-------------------------------------------------------------------------------------------------------------------------------------------| 63 | */ 64 | attachInterrupt(/*Interrupt No*/0,interEvent,FALLING);//Open the external interrupt 0, connect INT1/2 to the digital pin of the main control: 65 | //UNO(2), Mega2560(2), Leonardo(3), microbit(P0). 66 | #endif 67 | /** 68 | * Set interrupt mode 69 | * INTPin Interrupt pin : 1 represents using INT1 interrupt pin; 2 represents using INT2 interrupt pin 70 | * INTmode Set interrupt mode, 1 represents interrupt lock mode (polarity remain unchanged when interrupt triggerred, and restore after clearing interrupt); 0 represents pulse mode 71 | * INTPolarity Interrupt output level polarity, 0 represents interrupt pin polarity is LOW when producing interrupt, 1 represents interrupt pin polarity is HIGH when producing interrupt 72 | * INTDriveCircuit 0 represents Open drain 1 represents Push pull 73 | */ 74 | ICM42688.setINTMode(/*INTPin=*/1, /*INTmode=*/0, /*INTPolarity=*/0, /*INTDriveCircuit=*/1); 75 | /** 76 | * @brief Wake on motion init 77 | */ 78 | ICM42688.wakeOnMotionInit(); 79 | 80 | /** 81 | * Set wake on motion interrupt threshold of axis accelerometer 82 | * axis 83 | * X_AXIS_WOM 84 | * Y_AXIS_WOM 85 | * Z_AXIS_WOM 86 | * ALL 87 | * threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 88 | */ 89 | ICM42688.setWOMTh(/*axis=*/ALL,/*threshold=*/98); 90 | 91 | /** 92 | * Set essential motion detection mode and enable SMD interrupt 93 | * mode 0: disable SMD 94 | * 2 : SMD short (1 sec wait) An SMD event is detected when two WOM are detected 1 sec apart 95 | * 3 : SMD long (3 sec wait) An SMD event is detected when two WOM are detected 3 sec apart 96 | */ 97 | ICM42688.enableSMDInterrupt(/*mode=*/3); 98 | } 99 | void loop() { 100 | uint8_t status; 101 | if(flag == 1){ 102 | flag =0; 103 | /** 104 | * Read interrupt information and clear interrupt 105 | * reg Interrupt information register 106 | * ICM42688_INT_STATUS2 Obtain interrupt information of ICM42688_SMD_INT, ICM42688_WOM_X_INT, ICM42688_WOM_Y_INT and ICM42688_WOM_Z_INT and clear them 107 | * ICM42688_INT_STATUS3 Obtain interrupt information of ICM42688_TAP_DET_INT and clear it 108 | * Return interrupt information, return 0 when no interrupt 109 | */ 110 | status= ICM42688.readInterruptStatus(/*reg=*/ ICM42688_INT_STATUS2); 111 | if(status & ICM42688_SMD_INT){ 112 | Serial.println("SMD_INT"); 113 | } 114 | } 115 | } 116 | -------------------------------------------------------------------------------- /examples/tap/tap.ino: -------------------------------------------------------------------------------- 1 | /*! 2 | * @file tap.ino 3 | * @brief Tap detection 4 | * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 5 | * @license The MIT License (MIT) 6 | * @author [yangfeng] 7 | * @version V1.0 8 | * @date 2021-05-13 9 | * @url https://github.com/DFRobot/DFRobot_ICM42688 10 | */ 11 | #include 12 | //Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default internal pull up) 13 | //DFRobot_ICM42688_I2C_L_ADDR 0x68 14 | //DFRobot_ICM42688_I2C_H_ADDR 0x69 15 | //DFRobot_ICM42688_I2C ICM42688(/*i2cAddr = */ DFRobot_ICM42688_I2C_H_ADDR); 16 | DFRobot_ICM42688_SPI ICM42688(/* csPin= */5); 17 | uint8_t flag = 0; 18 | 19 | void interEvent(){ 20 | flag = 1; 21 | } 22 | 23 | void setup() { 24 | int ret; 25 | Serial.begin(9600); 26 | while((ret =ICM42688.begin()) !=0){ 27 | if(ret == -1){ 28 | Serial.println("bus data access error"); 29 | } else 30 | Serial.println("Chip versions do not match"); 31 | delay(1000); 32 | } 33 | Serial.println("ICM42688 begin success!!!"); 34 | #if defined(ESP32) || defined(ESP8266) 35 | //Use D6 pin as interrupt pin by default, or select other non-conflicting pins as external interrupt pin 36 | attachInterrupt(digitalPinToInterrupt(D9)/*Query the interrupt number of the D9 pin*/,interEvent,FALLING); 37 | #elif defined(ARDUINO_SAM_ZERO) 38 | //Use 5 pin as interrupt pin by default, or select other non-conflicting pins as external interrupt pin 39 | attachInterrupt(digitalPinToInterrupt(6)/*Query the interrupt number of the 5 pin*/,interEvent,FALLING); 40 | #else 41 | /* The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers 42 | * --------------------------------------------------------------------------------------- 43 | * | | DigitalPin | 2 | 3 | | 44 | * | Uno, Nano, Mini, other 328-based |--------------------------------------------| 45 | * | | Interrupt No | 0 | 1 | | 46 | * |-------------------------------------------------------------------------------------| 47 | * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | 48 | * | Mega2560 |--------------------------------------------| 49 | * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | 50 | * |-------------------------------------------------------------------------------------| 51 | * | | Pin | 3 | 2 | 0 | 1 | 7 | | 52 | * | Leonardo, other 32u4-based |--------------------------------------------| 53 | * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | 54 | * |-------------------------------------------------------------------------------------- 55 | */ 56 | /* The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers 57 | * --------------------------------------------------------------------------------------------------------------------------------------------- 58 | * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | 59 | * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| 60 | * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | 61 | * |-------------------------------------------------------------------------------------------------------------------------------------------| 62 | */ 63 | attachInterrupt(/*Interrupt No*/0,interEvent,FALLING);//Enable the external interrupt 0, connect INT1/2 to the digital pin of the main control: 64 | //UNO(2), Mega2560(2), Leonardo(3), microbit(P0). 65 | #endif 66 | /** 67 | * Set interrupt mode 68 | * INTPin Interrupt pin : 1 represents using INT1 interrupt pin; 2 represents using INT2 interrupt pin 69 | * INTmode Set interrupt mode, 1 represents interrupt lock mode (polarity remain unchanged after interrupt trigger, and restore after clearing interrupt); 0 represents pulse mode 70 | * INTPolarity Level polarity output by interrupt, 0 represents interrupt pin polarity is LOW when producing interrupt, 1 represents interrupt pin polarity is HIGH when producing interrupt 71 | * INTDriveCircuit 0 represents Open drain 1 represents Push pull 72 | */ 73 | ICM42688.setINTMode(/*INTPin=*/1, /*INTmode=*/0, /*INTPolarity=*/0, /*INTDriveCircuit=*/1); 74 | /** 75 | * Tap detection init 76 | * accelMode Accelerometer operating mode: 0 for operating in low-power mode, 1 for operating in low-noise mode 77 | */ 78 | ICM42688.tapDetectionInit(/* accelMode= */1); 79 | } 80 | void loop() { 81 | uint8_t status; 82 | uint32_t tapNum; 83 | uint8_t tapAxis; 84 | if(flag == 1){ 85 | flag =0; 86 | /** 87 | * Read Interrupt information and clear interrupt 88 | * reg Interrupt information register 89 | * ICM42688_INT_STATUS2 Obtain interrupt information of ICM42688_SMD_INT, ICM42688_WOM_X_INT, ICM42688_WOM_Y_INT and ICM42688_WOM_Z_INT and clear them 90 | * ICM42688_INT_STATUS3 Obtain interrupt information of ICM42688_TAP_DET_INT and clear it 91 | * Return interrupt information, return 0 when no interrupt 92 | */ 93 | status= ICM42688.readInterruptStatus(/* reg= */ICM42688_INT_STATUS3); 94 | if(status & ICM42688_TAP_DET_INT){ 95 | ICM42688.getTapInformation(); //Get tap information 96 | tapNum = ICM42688.numberOfTap(); //Get the number of tap: single-tap TAP_SINGLE or double tap TAP_DOUBLE 97 | tapAxis = ICM42688.axisOfTap(); //Get the axis on which tap occurred: X_AXIS, Y_AXIS or Z_AXIS 98 | if(tapAxis == X_AXIS){ 99 | Serial.print("X axis: "); 100 | } else if(tapAxis == Y_AXIS){ 101 | Serial.print("Y axis: "); 102 | } else if(tapAxis == Z_AXIS){ 103 | Serial.print("Z axis: "); 104 | } 105 | if(tapNum == TAP_SINGLE){ 106 | Serial.println("Single"); 107 | } else if(tapNum == TAP_DOUBLE){ 108 | Serial.println("Double"); 109 | } 110 | } 111 | } 112 | } 113 | -------------------------------------------------------------------------------- /examples/wakeOnMotion/wakeOnMotion.ino: -------------------------------------------------------------------------------- 1 | /*! 2 | * @file wakeOnMotion.ino 3 | * @brief Wake on Motion Detection 4 | * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 5 | * @license The MIT License (MIT) 6 | * @author [yangfeng] 7 | * @version V1.0 8 | * @date 2021-05-13 9 | * @url https://github.com/DFRobot/DFRobot_ICM42688 10 | */ 11 | #include 12 | 13 | //Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68. (SDO default internal pull up) 14 | //DFRobot_ICM42688_I2C_L_ADDR 0x68 15 | //DFRobot_ICM42688_I2C_H_ADDR 0x69 16 | //DFRobot_ICM42688_I2C ICM42688(/*i2cAddr = */ DFRobot_ICM42688_I2C_H_ADDR); 17 | DFRobot_ICM42688_SPI ICM42688(/* csPin= */5); 18 | uint8_t flag = 0; 19 | 20 | void interEvent(){ 21 | flag = 1; 22 | } 23 | 24 | void setup() { 25 | int ret; 26 | Serial.begin(9600); 27 | while((ret =ICM42688.begin()) !=0){ 28 | if(ret == -1){ 29 | Serial.println("bus data access error"); 30 | } else 31 | Serial.println("Chip versions do not match"); 32 | delay(1000); 33 | } 34 | Serial.println("ICM42688 begin success!!!"); 35 | #if defined(ESP32) || defined(ESP8266) 36 | //Use D6 pin as interrupt pin by default, or select other non-conflicting pins as external interrupt pin 37 | attachInterrupt(digitalPinToInterrupt(D9)/*Query the interrupt number of the D9 pin*/,interEvent,FALLING); 38 | #elif defined(ARDUINO_SAM_ZERO) 39 | //Use 5 pin as interrupt pin by default, or select other non-conflicting pins as external interrupt pin 40 | attachInterrupt(digitalPinToInterrupt(6)/*Query the interrupt number of the 5 pin*/,interEvent,FALLING); 41 | #else 42 | /* The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers 43 | * --------------------------------------------------------------------------------------- 44 | * | | DigitalPin | 2 | 3 | | 45 | * | Uno, Nano, Mini, other 328-based |--------------------------------------------| 46 | * | | Interrupt No | 0 | 1 | | 47 | * |-------------------------------------------------------------------------------------| 48 | * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | 49 | * | Mega2560 |--------------------------------------------| 50 | * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | 51 | * |-------------------------------------------------------------------------------------| 52 | * | | Pin | 3 | 2 | 0 | 1 | 7 | | 53 | * | Leonardo, other 32u4-based |--------------------------------------------| 54 | * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | 55 | * |-------------------------------------------------------------------------------------- 56 | */ 57 | /* The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers 58 | * --------------------------------------------------------------------------------------------------------------------------------------------- 59 | * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | 60 | * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| 61 | * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | 62 | * |-------------------------------------------------------------------------------------------------------------------------------------------| 63 | */ 64 | attachInterrupt(/*Interrupt No*/0,interEvent,FALLING);//Enable the external interrupt 0, connect INT1/2 to the digital pin of the main control: 65 | //UNO(2), Mega2560(2), Leonardo(3), microbit(P0). 66 | #endif 67 | /** 68 | * Set interrupt mode 69 | * INTPin Interrupt pin : 1 represents using INT1 interrupt pin; represents using INT2 interrupt pin 70 | * INTmode Set interrupt mode, 1 Interrupt lock mode (polarity remain unchanged when interrupt triggerred, and restore after clearing interrupt); 0 represents pulse mode 71 | * INTPolarity Level polarity output by interrupt, 0 represents interrupt pin polarity is LOW when producing interrupt, 1 represents interrupt pin polarity is HIGH when producing interrupt 72 | * INTDriveCircuit 0 represents Open drain 1 represents Push pull 73 | */ 74 | ICM42688.setINTMode(/* INTPin= */1, /* INTmode= */0, /* INTPolarity= */0, /* INTDriveCircuit= */1); 75 | ICM42688.wakeOnMotionInit(); //Wake on motion init 76 | /** 77 | * Set wake on motion interrupt threshold of axis accelerometer 78 | * axis 79 | * X_AXIS_WOM 80 | * Y_AXIS_WOM 81 | * Z_AXIS_WOM 82 | * ALL 83 | * threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 84 | */ 85 | ICM42688.setWOMTh(/* axis= */ALL,/* threshold= */98); 86 | /** 87 | * Enable WOM interrupt of an axis 88 | * axis 89 | * X_AXIS_WOM 90 | * Y_AXIS_WOM 91 | * Z_AXIS_WOM 92 | */ 93 | ICM42688.setWOMInterrupt(/* axis = */X_AXIS_WOM|Y_AXIS_WOM|Z_AXIS_WOM); 94 | } 95 | void loop() { 96 | uint8_t status; 97 | if(flag == 1){ 98 | flag =0; 99 | /** 100 | * Read interrupt information and clear interrupt 101 | * reg Interrupt information register 102 | * ICM42688_INT_STATUS2 Obtain interrupt information of ICM42688_SMD_INT, ICM42688_WOM_X_INT, ICM42688_WOM_Y_INT and ICM42688_WOM_Z_INT and clear them 103 | * ICM42688_INT_STATUS3 Obtain interrupt information of ICM42688_TAP_DET_INT and clear it 104 | * Return interrupt information, return 0 when no interrupt 105 | */ 106 | status= ICM42688.readInterruptStatus(/*reg=*/ ICM42688_INT_STATUS2); 107 | if(status & ICM42688_WOM_X_INT){ 108 | Serial.println("X_AXIS_WOM "); 109 | } 110 | if(status & ICM42688_WOM_Y_INT){ 111 | Serial.println("Y_AXIS_WOM "); 112 | } 113 | if(status & ICM42688_WOM_Z_INT){ 114 | Serial.println("Z_AXIS_WOM "); 115 | } 116 | } 117 | } 118 | -------------------------------------------------------------------------------- /keywords.txt: -------------------------------------------------------------------------------- 1 | ####################################### 2 | # Syntax Coloring Map For DFRobot_ICM42688 3 | ####################################### 4 | 5 | ####################################### 6 | # Datatypes (KEYWORD1) 7 | ####################################### 8 | 9 | DFRobot_ICM42688 KEYWORD1 10 | DFRobot_ICM42688_I2C KEYWORD1 11 | DFRobot_ICM42688_SPI KEYWORD1 12 | 13 | ####################################### 14 | # Methods and Functions (KEYWORD2) 15 | ####################################### 16 | 17 | begin KEYWORD2 18 | getTemperature KEYWORD2 19 | getAccelDataX KEYWORD2 20 | getAccelDataY KEYWORD2 21 | getAccelDataZ KEYWORD2 22 | getGyroDataX KEYWORD2 23 | getGyroDataY KEYWORD2 24 | getGyroDataZ KEYWORD2 25 | tapDetectionInit KEYWORD2 26 | getTapInformation KEYWORD2 27 | axisOfTap KEYWORD2 28 | numberOfTap KEYWORD2 29 | setWOMTh KEYWORD2 30 | setWOMInterrupt KEYWORD2 31 | enableSMDInterrupt KEYWORD2 32 | readInterruptStatus KEYWORD2 33 | setODRAndFSR KEYWORD2 34 | setFIFODataMode KEYWORD2 35 | startFIFOMode KEYWORD2 36 | sotpFIFOMode KEYWORD2 37 | getFIFOData KEYWORD2 38 | setINTMode KEYWORD2 39 | startGyroMeasure KEYWORD2 40 | startAccelMeasure KEYWORD2 41 | startTempMeasure KEYWORD2 42 | setGyroNotchFilterFHz KEYWORD2 43 | setGyroNFbandwidth KEYWORD2 44 | setGyroNotchFilter KEYWORD2 45 | setAAFBandwidth KEYWORD2 46 | setAAF KEYWORD2 47 | setUIFilter KEYWORD2 48 | wakeOnMotionInit KEYWORD2 49 | 50 | ####################################### 51 | # Constants (LITERAL1) 52 | ####################################### 53 | X_AXIS_WOM LITERAL1 54 | Y_AXIS_WOM LITERAL1 55 | Z_AXIS_WOM LITERAL1 56 | ALL LITERAL1 57 | ICM42688_INT_STATUS2 LITERAL1 58 | ICM42688_INT_STATUS3 LITERAL1 59 | ODR_32KHZ LITERAL1 60 | ODR_16KHZ LITERAL1 61 | ODR_8KHZ LITERAL1 62 | ODR_4KHZ LITERAL1 63 | ODR_2KHZ LITERAL1 64 | ODR_1KHZ LITERAL1 65 | ODR_200HZ LITERAL1 66 | ODR_100HZ LITERAL1 67 | ODR_50HZ LITERAL1 68 | ODR_25KHZ LITERAL1 69 | ODR_12_5KHZ LITERAL1 70 | ODR_6_25KHZ LITERAL1 71 | ODR_3_125HZ LITERAL1 72 | ODR_1_5625HZ LITERAL1 73 | ODR_500HZ LITERAL1 74 | FSR_0 LITERAL1 75 | FSR_1 LITERAL1 76 | FSR_2 LITERAL1 77 | FSR_3 LITERAL1 78 | FSR_4 LITERAL1 79 | FSR_5 LITERAL1 80 | FSR_6 LITERAL1 81 | FSR_7 LITERAL1 82 | GYRO LITERAL1 83 | ACCEL LITERAL1 84 | OFF_MODE LITERAL1 85 | STANDBY_MODE_ONLY_GYRO LITERAL1 86 | LP_MODE_ONLY_ACCEL LITERAL1 87 | LN_MODE LITERAL1 88 | X_AXIS LITERAL1 89 | Y_AXIS LITERAL1 90 | Z_AXIS LITERAL1    91 | DFRobot_ICM42688_I2C_H_ADDR LITERAL1 92 | DFRobot_ICM42688_I2C_L_ADDR LITERAL1 93 | TAP_SINGLE LITERAL1 94 | TAP_DOUBLE LITERAL1 95 | ICM42688_SMD_INT LITERAL1 96 | ICM42688_TAP_DET_INT LITERAL1 97 | ICM42688_WOM_X_INT LITERAL1 98 | ICM42688_WOM_Y_INT LITERAL1 99 | ICM42688_WOM_Z_INT LITERAL1 100 |   -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=DFRobot_ICM42688 2 | version=1.0.0 3 | author=DFRobot 4 | maintainer=Fary DFRobot 5 | sentence=DFRobot_ICM42688 is a sensor library(SKU: SEN0352). 6 | paragraph=The ICM-42688-P is a 6-axis MEMS MotionTracking device that combines a 3-axis gyroscope and a 3-axis accelerometer. It has a configurable host interface that supports I3CSM, I2C and SPI serial communication, features a 2 kB FIFO and 2 programmable interrupts with ultra low-power wake-on-motion support to minimize system power consumption. 7 | category=Sensors 8 | url=https://github.com/DFRobot/DFRobot_ICM42688 9 | architectures=* 10 | -------------------------------------------------------------------------------- /python/raspberrypi/DFRobot_ICM42688.py: -------------------------------------------------------------------------------- 1 | # -*- coding:utf-8 -*- 2 | '''! 3 | @file DFRobot_ICM42688.py 4 | @brief Define basic structure of DFRobot_ICM42688 class, the implementation of basic method. 5 | @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 6 | @license The MIT License (MIT) 7 | @author [yangfeng] 8 | @version V1.0 9 | @date 2021-6-9 10 | @url https://github.com/DFRobot/DFRobot_ICM42688 11 | ''' 12 | 13 | import sys 14 | import smbus 15 | import logging 16 | import numpy as np 17 | from ctypes import * 18 | import spidev 19 | import time 20 | import RPi.GPIO as GPIO 21 | 22 | GPIO.setmode(GPIO.BCM) 23 | GPIO.setwarnings(False) 24 | 25 | logger = logging.getLogger() 26 | logger.setLevel(logging.INFO) #Display all the print information 27 | #logger.setLevel(logging.FATAL)#Use this option if you don't want to display too many prints but only printing errors 28 | ph = logging.StreamHandler() 29 | formatter = logging.Formatter("%(asctime)s - [%(filename)s %(funcName)s]:%(lineno)d - %(levelname)s: %(message)s") 30 | ph.setFormatter(formatter) 31 | logger.addHandler(ph) 32 | 33 | DFRobot_ICM42688_I2C_L_ADDR =0x68 34 | DFRobot_ICM42688_I2C_H_ADDR =0x69 35 | DFRobot_ICM42688_ID =0x47 36 | ICM42688_DEVICE_CONFIG =0x11 37 | ICM42688_DRIVE_CONFIG =0x13 38 | ICM42688_SIGNAL_PATH_RESET =0x4B 39 | ICM42688_PWR_MGMT0 =0x4E 40 | ICM42688_INT_CONFIG =0x14 41 | ICM42688_INT_STATUS =0x2D 42 | ICM42688_INT_STATUS2 =0x37 43 | ICM42688_INT_STATUS3 =0x38 44 | ICM42688_INT_CONFIG0 =0x63 45 | ICM42688_INT_CONFIG1 =0x64 46 | ICM42688_INT_SOURCE0 =0x65 47 | ICM42688_INT_SOURCE1 =0x66 48 | ICM42688_INT_SOURCE3 =0x68 49 | ICM42688_INT_SOURCE4 =0x69 50 | ICM42688_INT_SOURCE6 =0x4D 51 | ICM42688_INT_SOURCE7 =0x4E 52 | ICM42688_INT_SOURCE8 =0x4F 53 | ICM42688_INT_SOURCE9 =0x50 54 | ICM42688_INT_SOURCE10 =0x51 55 | ICM42688_TEMP_DATA1 =0x1D 56 | ICM42688_TEMP_DATA0 =0x1E 57 | ICM42688_ACCEL_DATA_X1 =0x1F 58 | ICM42688_ACCEL_DATA_X0 =0x20 59 | ICM42688_ACCEL_DATA_Y1 =0x21 60 | ICM42688_ACCEL_DATA_Y0 =0x22 61 | ICM42688_ACCEL_DATA_Z1 =0x23 62 | ICM42688_ACCEL_DATA_Z0 =0x24 63 | ICM42688_GYRO_DATA_X1 =0x25 64 | ICM42688_GYRO_DATA_X0 =0x26 65 | ICM42688_GYRO_DATA_Y1 =0x27 66 | ICM42688_GYRO_DATA_Y0 =0x28 67 | ICM42688_GYRO_DATA_Z1 =0x29 68 | ICM42688_GYRO_DATA_Z0 =0x30 69 | ICM42688_TMST_FSYNCH =0x43 70 | ICM42688_TMST_FSYNCL =0x44 71 | ICM42688_GYRO_CONFIG_STATIC2 =0x0B 72 | ICM42688_GYRO_CONFIG_STATIC3 =0x0C 73 | ICM42688_GYRO_CONFIG_STATIC4 =0x0D 74 | ICM42688_GYRO_CONFIG_STATIC5 =0x0E 75 | ICM42688_GYRO_CONFIG_STATIC6 =0x0F 76 | ICM42688_GYRO_CONFIG_STATIC7 =0x10 77 | ICM42688_GYRO_CONFIG_STATIC8 =0x11 78 | ICM42688_GYRO_CONFIG_STATIC9 =0x12 79 | ICM42688_GYRO_CONFIG_STATIC10 =0x13 80 | ICM42688_GYRO_CONFIG0 =0x4F 81 | ICM42688_ACCEL_CONFIG0 =0x50 82 | ICM42688_GYRO_CONFIG1 =0x51 83 | ICM42688_GYRO_ACCEL_CONFIG0 =0x52 84 | ICM42688_ACCEL_CONFIG1 =0x53 85 | ICM42688_TMST_CONFIG =0x54 86 | ICM42688_SMD_CONFIG =0x57 87 | ICM42688_FIFO_CONFIG =0x16 88 | ICM42688_FIFO_COUNTH =0x2E 89 | ICM42688_FIFO_COUNTL =0x2F 90 | ICM42688_FIFO_DATA =0x30 91 | ICM42688_FIFO_CONFIG1 =0x5F 92 | ICM42688_FIFO_CONFIG2 =0x60 93 | ICM42688_FIFO_CONFIG3 =0x61 94 | ICM42688_FIFO_LOST_PKT0 =0x6C 95 | ICM42688_FIFO_LOST_PKT1 =0x6D 96 | ICM42688_FSYNC_CONFIG =0x62 97 | ICM42688_SELF_TEST_CONFIG =0x70 98 | ICM42688_WHO_AM_I =0x75 99 | ICM42688_REG_BANK_SEL =0x76 100 | ICM42688_SENSOR_CONFIG0 =0x03 101 | ICM42688_XG_ST_DATA =0x5F 102 | ICM42688_YG_ST_DATA =0x60 103 | ICM42688_ZG_ST_DATA =0x61 104 | ICM42688_TMSTVAL0 =0x62 105 | ICM42688_TMSTVAL1 =0x63 106 | ICM42688_TMSTVAL2 =0x64 107 | ICM42688_INTF_CONFIG0 =0x4C 108 | ICM42688_INTF_CONFIG1 =0x4D 109 | ICM42688_INTF_CONFIG4 =0x7A 110 | ICM42688_INTF_CONFIG5 =0x7B 111 | ICM42688_INTF_CONFIG6 =0x7C 112 | ICM42688_ACCEL_CONFIG_STATIC2 =0x03 113 | ICM42688_ACCEL_CONFIG_STATIC3 =0x04 114 | ICM42688_ACCEL_CONFIG_STATIC4 =0x05 115 | ICM42688_XA_ST_DATA =0x3B 116 | ICM42688_YA_ST_DATA =0x3C 117 | ICM42688_ZA_ST_DATA =0x3D 118 | ICM42688_APEX_DATA0 =0x31 119 | ICM42688_APEX_DATA1 =0x32 120 | ICM42688_APEX_DATA2 =0x33 121 | ICM42688_APEX_DATA3 =0x34 122 | ICM42688_APEX_DATA4 =0x35 123 | ICM42688_APEX_DATA5 =0x36 124 | ICM42688_APEX_CONFIG0 =0x56 125 | ICM42688_APEX_CONFIG1 =0x40 126 | ICM42688_APEX_CONFIG2 =0x41 127 | ICM42688_APEX_CONFIG3 =0x42 128 | ICM42688_APEX_CONFIG4 =0x43 129 | ICM42688_APEX_CONFIG5 =0x44 130 | ICM42688_APEX_CONFIG6 =0x45 131 | ICM42688_APEX_CONFIG7 =0x46 132 | ICM42688_APEX_CONFIG8 =0x47 133 | ICM42688_APEX_CONFIG9 =0x48 134 | ICM42688_ACCEL_WOM_X_THR =0x4A 135 | ICM42688_ACCEL_WOM_Y_THR =0x4B 136 | ICM42688_ACCEL_WOM_Z_THR =0x4C 137 | ICM42688_OFFSET_USER0 =0x77 138 | ICM42688_OFFSET_USER1 =0x78 139 | ICM42688_OFFSET_USER2 =0x79 140 | ICM42688_OFFSET_USER3 =0x7A 141 | ICM42688_OFFSET_USER4 =0x7B 142 | ICM42688_OFFSET_USER5 =0x7C 143 | ICM42688_OFFSET_USER6 =0x7D 144 | ICM42688_OFFSET_USER7 =0x7E 145 | ICM42688_OFFSET_USER8 =0x7F 146 | ICM42688_STEP_DET_INT =1<<5 147 | ICM42688_STEP_CNT_OVF_INT =1<<4 148 | ICM42688_TILT_DET_INT =1<<3 149 | ICM42688_WAKE_INT =1<<2 150 | ICM42688_SLEEP_INT =1<<1 151 | ICM42688_TAP_DET_INT =1 152 | ICM42688_SMD_INT =1<<3 153 | ICM42688_WOM_Z_INT =1<<2 154 | ICM42688_WOM_Y_INT =1<<1 155 | ICM42688_WOM_X_INT =1 156 | ICM42688_STATUS_WALK =1 157 | ICM42688_STATUS_RUN =2 158 | 159 | 160 | class DFRobot_ICM42688(object): 161 | 162 | 163 | ERR_OK = 0 #No error 164 | ERR_DATA_BUS = -1 #Data bus error 165 | ERR_IC_VERSION = -2 #The chip version not match 166 | 167 | GYRO = 0 168 | ACCEL = 1 169 | ALL = 5 170 | 171 | TMST_DEFAULT_CONFIG_START = 0x23 172 | TMST_VALUE_DIS = 0<<4 173 | TMST_VALUE_EN = 1<<4 174 | TMST_RES_EN_DIS = 0<<3 175 | TMST_RES_EN = 1<<3 176 | TMST_FSYNC_EN = 1<<1 177 | TMST_FSYNC_DIS = 0<<1 178 | TMST_DELTA_EN = 0<<2 179 | TMST_DELTA_DIS = 1<<2 180 | TMST_EN = 1 181 | TMST_DIS = 0 182 | 183 | X_AXIS = 0 184 | Y_AXIS = 2 185 | Z_AXIS = 4 186 | 187 | X_AXIS_WOM = 1 188 | Y_AXIS_WOM = 2 189 | Z_AXIS_WOM = 4 190 | 191 | ODR_32KHZ = 1 192 | ODR_16KHZ = 2 193 | ODR_8KHZ = 3 194 | ODR_4KHZ = 4 195 | ODR_2KHZ = 5 196 | ODR_1KHZ = 6 197 | ODR_200HZ = 7 198 | ODR_100HZ = 8 199 | ODR_50HZ = 9 200 | ODR_25KHZ = 10 201 | ODR_12_5KHZ = 11 202 | ODR_6_25KHZ = 12 203 | ODR_3_125HZ = 13 204 | ODR_1_5625HZ = 14 205 | ODR_500HZ = 15 206 | 207 | FSR_0 = 0 208 | FSR_1 = 1 209 | FSR_2 = 2 210 | FSR_3 = 3 211 | FSR_4 = 4 212 | FSR_5 = 5 213 | FSR_6 = 6 214 | FSR_7 = 7 215 | 216 | LP_MODE_ONLY_ACCEL = 2 217 | LN_MODE = 3 218 | STANDBY_MODE_ONLY_GYRO = 1 219 | OFF_MODE = 0 220 | 221 | TAP_SINGLE = 8 222 | TAP_DOUBLE = 16 223 | 224 | ''' 225 | # -------------------------------------------------------------------------------------------------------------------------------------- ------------------- 226 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 227 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 228 | # | ACCEL_FS_SEL | Reserved | ACCEL_ODR | 229 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 230 | # ACCEL_FS_SEL :Full scale select for accelerometer UI interface output 231 | # 000: ±16g (default) 232 | # 001: ±8g 233 | # 010: ±4g 234 | # 011: ±2g 235 | # 100: Reserved 236 | # 101: Reserved 237 | # 110: Reserved 238 | # 111: Reserved 239 | # ACCEL_ODR :Accelerometer ODR selection for UI interface output 240 | # 0000: Reserved 241 | # 0001: 32kHz (LN mode) 242 | # 0010: 16kHz (LN mode) 243 | # 0011: 8kHz (LN mode) 244 | # 0100: 4kHz (LN mode) 245 | # 0101: 2kHz (LN mode) 246 | # 0110: 1kHz (LN mode) (default) 247 | # 0111: 200Hz (LP or LN mode) 248 | # 1000: 100Hz (LP or LN mode) 249 | # 1001: 50Hz (LP or LN mode) 250 | # 1010: 25Hz (LP or LN mode) 251 | # 1011: 12.5Hz (LP or LN mode) 252 | # 1100: 6.25Hz (LP mode) 253 | # 1101: 3.125Hz (LP mode) 254 | # 1110: 1.5625Hz (LP mode) 255 | # 1111: 500Hz (LP or LN mode) 256 | ''' 257 | class Accel_config0(Structure): 258 | _pack_ = 1 259 | _fields_=[('accel_ODR',c_ubyte,4), 260 | ('reserved',c_ubyte,1), 261 | ('accel_fs_sel',c_ubyte,3)] 262 | def __init__(self, accel_ODR=6, reserved=0, accel_fs_sel=0): 263 | self.accel_ODR = accel_ODR 264 | self.reserved = reserved 265 | self.accel_fs_sel = accel_fs_sel 266 | 267 | def set_list(self, data): 268 | buf = (c_ubyte * len(data))() 269 | for i in range(len(data)): 270 | buf[i] = data[i] 271 | memmove(addressof(self), addressof(buf), len(data)) 272 | 273 | def get_list(self): 274 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 275 | 276 | ''' 277 | # -------------------------------------------------------------------------------------------------------------------------------------- ------------------- 278 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 279 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 280 | # | Reserved | TEMP_DIS | IDLE | GYRO_MODE | ACCEL_MODE | 281 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 282 | # TEMP_DIS : 0: Temperature sensor is enabled (default) 283 | # 1: Temperature sensor is disabled 284 | # IDLE : 0: When the accelerometer and gyroscope are powered off, the chip will enter closure status, because the oscillator power is also cut off 285 | # 1: RC oscillator will not be powered down even if the accelerometer and gyroscope are powered off 286 | # GYRO_MODE :00: Turns gyroscope off (default) 287 | # 01: Places gyroscope in Standby Mode 288 | # 10: Reserved 289 | # 11: Places gyroscope in Low Noise (LN) Mode 290 | # Enable gyroscope for more than 45ms. When OFF status is switched to other statuses, don't write to any register in 200us. 291 | # ACCEL_MODE: 00: Turns accelerometer off (default) 292 | # 01: Turns accelerometer off 293 | # 10: Places accelerometer in Low Power (LP) Mode 294 | # 11: Places accelerometer in Low Noise (LN) Mode 295 | # When OFF status is switched to other statuses, don't write to any register in 200us. 296 | ''' 297 | class Pwrmgmt0(Structure): 298 | _pack_ = 1 299 | _fields_=[('accel_mode',c_ubyte,2), 300 | ('gyro_mode',c_ubyte,2), 301 | ('idle',c_ubyte,1), 302 | ('temp_dis',c_ubyte,1), 303 | ('reserved',c_ubyte,2)] 304 | def __init__(self, accel_mode=0, gyro_mode=0, idle=0,temp_dis =0,reserved = 0): 305 | self.accel_mode = accel_mode 306 | self.gyro_mode = gyro_mode 307 | self.idle = idle 308 | self.temp_dis = temp_dis 309 | self.reserved = reserved 310 | 311 | def set_list(self, data): 312 | buf = (c_ubyte * len(data))() 313 | for i in range(len(data)): 314 | buf[i] = data[i] 315 | memmove(addressof(self), addressof(buf), len(data)) 316 | 317 | def get_list(self): 318 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 319 | 320 | ''' 321 | # -------------------------------------------------------------------------------------------------------------------------------------- ------------------- 322 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 323 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 324 | # | Reserved | ACCEL_LP_CLK_SEL | RTC_MODE | CLKSEL | 325 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 326 | # ACCEL_LP_CLK_SEL : 0: Accelerometer LP mode uses Wake Up oscillator clock 327 | # 1: Accelerometer LP mode uses RC oscillator clock 328 | # RTC_MODE : 0: No input RTC clock is required 329 | # 1: RTC clock input is required 330 | # CLKSEL : 00: Always select internal RC oscillator 331 | # 01: Select PLL when available, else select RC oscillator (default) 332 | # 10: Reserved 333 | # 11: Disable all clocks 334 | ''' 335 | class INTF_Config1(Structure): 336 | _pack_ = 1 337 | _fields_=[('clksel',c_ubyte,2), 338 | ('rtc_Mode',c_ubyte,1), 339 | ('accel_lp_clk_sel',c_ubyte,1), 340 | ('reserved',c_ubyte,4)] 341 | def __init__(self, clksel=1, rtc_Mode=0, accel_lp_clk_sel=0,reserved =9): 342 | self.clksel = clksel 343 | self.rtc_Mode = rtc_Mode 344 | self.accel_lp_clk_sel = accel_lp_clk_sel 345 | self.reserved = reserved 346 | 347 | def set_list(self, data): 348 | buf = (c_ubyte * len(data))() 349 | for i in range(len(data)): 350 | buf[i] = data[i] 351 | memmove(addressof(self), addressof(buf), len(data)) 352 | 353 | def get_list(self): 354 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 355 | 356 | ''' 357 | # -------------------------------------------------------------------------------------------------------------------------------------- ------------------- 358 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 359 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 360 | # | Reserved | ACCEL_UI_FILT_ORD | ACCEL_DEC2_M2_ORD | Reserved | 361 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 362 | # ACCEL_UI_FILT_ORD : Selects order of ACCEL UI filter 363 | # 00: 1st Order 364 | # 01: 2nd Order 365 | # 10: 3rd Order 366 | # 11: Reserved 367 | # ACCEL_DEC2_M2_ORD : Order of Accelerometer DEC2_M2 filter 368 | # 00: Reserved 369 | # 01: Reserved 370 | # 10: 3rd order 371 | # 11: Reserved 372 | ''' 373 | class Accel_config1(Structure): 374 | _pack_ = 1 375 | _fields_=[('reserved',c_ubyte,1), 376 | ('accel_dec2_m2_ORD',c_ubyte,2), 377 | ('accel_ui_filt_ORD',c_ubyte,2), 378 | ('reserved2',c_ubyte,3)] 379 | def __init__(self, reserved=1, accel_dec2_m2_ORD=2, accel_ui_filt_ORD=1,reserved2 =0): 380 | self.reserved = reserved 381 | self.accel_dec2_m2_ORD = accel_dec2_m2_ORD 382 | self.accel_ui_filt_ORD = accel_ui_filt_ORD 383 | self.reserved2 = reserved2 384 | 385 | def set_list(self, data): 386 | buf = (c_ubyte * len(data))() 387 | for i in range(len(data)): 388 | buf[i] = data[i] 389 | memmove(addressof(self), addressof(buf), len(data)) 390 | 391 | def get_list(self): 392 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 393 | 394 | ''' 395 | # 396 | # -------------------------------------------------------------------------------------------------------------------------------------- ------------------- 397 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 398 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 399 | # | ACCEL_UI_FILT_BW | GYRO_UI_FILT_BW | 400 | # ---------------------------------------------------------------------------------------------------------------------------------------------------------- 401 | # ACCEL_UI_FILT_BW : Bandwidth for Accel LPF 402 | # LN Mode: 403 | # 0 BW=ODR/2 404 | # 1 BW=max(400Hz, ODR)/4 (default) 405 | # 2 BW=max(400Hz, ODR)/5 406 | # 3 BW=max(400Hz, ODR)/8 407 | # 4 BW=max(400Hz, ODR)/10 408 | # 5 BW=max(400Hz, ODR)/16 409 | # 6 BW=max(400Hz, ODR)/20 410 | # 7 BW=max(400Hz, ODR)/40 411 | # 8 to 13: Reserved 412 | # 14 Low Latency option: Trivial decimation @ ODR of Dec2 filter output. Dec2 413 | # runs at max(400Hz, ODR) 414 | # 15 Low Latency option: Trivial decimation @ ODR of Dec2 filter output. Dec2 415 | # runs at max(200Hz, 8*ODR) 416 | # LP Mode: 417 | # 0 Reserved 418 | # 1 1x AVG filter (default) 419 | # 2 to 5 Reserved 420 | # 6 16x AVG filter 421 | # 7 to 15 Reserved 422 | # GYRO_UI_FILT_BW :Bandwidth for Gyro LPF 423 | # LN Mode: 424 | # 0 BW=ODR/2 425 | # 1 BW=max(400Hz, ODR)/4 (default) 426 | # 2 BW=max(400Hz, ODR)/5 427 | # 3 BW=max(400Hz, ODR)/8 428 | # 4 BW=max(400Hz, ODR)/10 429 | # 5 BW=max(400Hz, ODR)/16 430 | # 6 BW=max(400Hz, ODR)/20 431 | # 7 BW=max(400Hz, ODR)/40 432 | # 8 to 13: Reserved 433 | # 14 Low Latency option: Trivial decimation @ ODR of Dec2 filter output. Dec2 runs at max(400Hz, ODR) 434 | # 15 Low Latency option: Trivial decimation @ ODR of Dec2 filter output. Dec2 runs at max(200Hz, 8*ODR) 435 | ''' 436 | class Gyro_Accel_Config0(Structure): 437 | _pack_ = 1 438 | _fields_=[('gyro_ui_filt_BW',c_ubyte,4), 439 | ('accel_ui_filt_BW',c_ubyte,4)] 440 | def __init__(self, gyro_ui_filt_BW=1, accel_ui_filt_BW=1): 441 | self.gyro_ui_filt_BW = gyro_ui_filt_BW 442 | self.accel_ui_filt_BW = accel_ui_filt_BW 443 | 444 | def set_list(self, data): 445 | buf = (c_ubyte * len(data))() 446 | for i in range(len(data)): 447 | buf[i] = data[i] 448 | memmove(addressof(self), addressof(buf), len(data)) 449 | 450 | def get_list(self): 451 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 452 | 453 | ''' 454 | # -------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------- 455 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 456 | # ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- 457 | # | Reserved | TAP_TMAX | TAP_TAVG | TAP_TMIN | 458 | # ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- 459 | # TAP_TMAX Tap measurement window (number of samples) Use default value 01b 460 | # TAP_TAVG Tap energy measurement window (number of samples) Use default value 01b 461 | # TAP_TMIN Single tap window (number of samples) Use default value 011b 462 | ''' 463 | class APEX_Config8(Structure): 464 | _pack_ = 1 465 | _fields_=[('tap_tmin',c_ubyte,3), 466 | ('tap_tavg',c_ubyte,2), 467 | ('tap_tmax',c_ubyte,2), 468 | ('reserved',c_ubyte,1)] 469 | def __init__(self, tap_tmin=3, tap_tavg=1, tap_tmax=1, reserved=0): 470 | self.tap_tmin = tap_tmin 471 | self.tap_tavg = tap_tavg 472 | self.tap_tmax = tap_tmax 473 | self.reserved = reserved 474 | 475 | def set_list(self, data): 476 | buf = (c_ubyte * len(data))() 477 | for i in range(len(data)): 478 | buf[i] = data[i] 479 | memmove(addressof(self), addressof(buf), len(data)) 480 | 481 | def get_list(self): 482 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 483 | 484 | ''' 485 | # -------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------- 486 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 487 | # ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- 488 | # | TAP_MIN_JERK_THR | TAP_MAX_PEAK_TOL | 489 | # ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- 490 | # TAP_MIN_JERK_THR Tap Detection minimum jerk threshold. Use default value 010001b 491 | # TAP_MAX_PEAK_TOL Tap Detection maximum peak tolerance. Use default value 01b 492 | ''' 493 | class APEX_Config7(Structure): 494 | _pack_ = 1 495 | _fields_=[('tap_max_peak_tol',c_ubyte,2), 496 | ('tap_min_jerk_thr',c_ubyte,6)] 497 | def __init__(self, tap_max_peak_tol=1, tap_min_jerk_thr=17): 498 | self.tap_max_peak_tol = tap_max_peak_tol 499 | self.tap_min_jerk_thr = tap_min_jerk_thr 500 | 501 | def set_list(self, data): 502 | buf = (c_ubyte * len(data))() 503 | for i in range(len(data)): 504 | buf[i] = data[i] 505 | memmove(addressof(self), addressof(buf), len(data)) 506 | 507 | def get_list(self): 508 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 509 | 510 | ''' 511 | # 512 | # 513 | # --------------------------------------------------------------------------------------------------------------------------------------------- 514 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 515 | # --------------------------------------------------------------------------------------------------------------------------------------------- 516 | # | reversed | STEP_DET_INT_EN | STEP_CNT_OFL_INT_EN | TILT_DET_INT_EN | WAKE_DET_INT_EN | SLEEP_DET_INT_EN | TAP_DET_INT_EN | 517 | # --------------------------------------------------------------------------------------------------------------------------------------------- 518 | ''' 519 | class INTSource(Structure): 520 | _pack_ = 1 521 | _fields_=[('tap_det_int_en',c_ubyte,1), 522 | ('sleep_det_int_en',c_ubyte,1), 523 | ('wake_det_int_en',c_ubyte,1), 524 | ('tilt_det_int_en',c_ubyte,1), 525 | ('step_cnt_ofl_int_en',c_ubyte,1), 526 | ('step_det_int_en',c_ubyte,1), 527 | ('reserved',c_ubyte,2)] 528 | def __init__(self, tap_det_int_en=0, sleep_det_int_en=0, wake_det_int_en=0,tilt_det_int_en =0,step_cnt_ofl_int_en = 0,step_det_int_en = 0): 529 | self.tap_det_int_en = tap_det_int_en 530 | self.sleep_det_int_en = sleep_det_int_en 531 | self.wake_det_int_en = wake_det_int_en 532 | self.tilt_det_int_en = tilt_det_int_en 533 | self.step_cnt_ofl_int_en = step_cnt_ofl_int_en 534 | self.step_det_int_en = step_det_int_en 535 | self.reserved = 0 536 | 537 | def set_list(self, data): 538 | buf = (c_ubyte * len(data))() 539 | for i in range(len(data)): 540 | buf[i] = data[i] 541 | memmove(addressof(self), addressof(buf), len(data)) 542 | 543 | def get_list(self): 544 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 545 | 546 | ''' 547 | # 548 | # 549 | # --------------------------------------------------------------------------------------------------------------------------------------------- 550 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 551 | # --------------------------------------------------------------------------------------------------------------------------------------------- 552 | # | reversed | STEP_DET_INT_EN | STEP_CNT_OFL_INT_EN | TILT_DET_INT_EN | WAKE_DET_INT_EN | SLEEP_DET_INT_EN | TAP_DET_INT_EN | 553 | # --------------------------------------------------------------------------------------------------------------------------------------------- 554 | ''' 555 | class APEX_Config0(Structure): 556 | _pack_ = 1 557 | _fields_=[('dmp_ODR',c_ubyte,2), 558 | ('reserved',c_ubyte,1), 559 | ('R2W_en',c_ubyte,1), 560 | ('tilt_enable',c_ubyte,1), 561 | ('PED_enable',c_ubyte,1), 562 | ('tap_enable',c_ubyte,1), 563 | ('DMP_power_save',c_ubyte,1)] 564 | def __init__(self): 565 | self.dmp_ODR = 0 566 | self.R2W_en = 0 567 | self.tilt_enable = 0 568 | self.PED_enable = 0 569 | self.tap_enable = 0 570 | self.DMP_power_save = 1 571 | self.reserved = 0 572 | 573 | def set_list(self, data): 574 | buf = (c_ubyte * len(data))() 575 | for i in range(len(data)): 576 | buf[i] = data[i] 577 | memmove(addressof(self), addressof(buf), len(data)) 578 | 579 | def get_list(self): 580 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 581 | 582 | ''' 583 | # -------------------------------------------------------------------------------------------------------------------------------------- -------------------- 584 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 585 | # ----------------------------------------------------------------------------------------------------------------------------------------------------------- 586 | # | Reserved | WOM_INT_MODE | WOM_MODE | SMD_MODE | 587 | # ----------------------------------------------------------------------------------------------------------------------------------------------------------- 588 | # WOM_INT_MODE : (Wake on motion) 0: Set WoM interrupt on the OR of all enabled accelerometer thresholds 589 | # 1: Set WoM interrupt on the AND of all enabled accelerometer threshold 590 | # WOM_MODE 0: Initial sample is stored. Future samples are compared to initial sample. 591 | # 1: Compare current sample with previous sample 592 | # SMD_MODE 00: SMD disabled (important motion detector) 593 | # 01: Reserved 594 | # 10: SMD short (1 sec wait) An SMD event is detected when two WOM are detected 1 sec apart 595 | # 11: SMD long (3 sec wait) An SMD event is detected when two WOM are detected 3 sec apart 596 | ''' 597 | class SMD_Config(Structure): 598 | _pack_ = 1 599 | _fields_=[('SMD_mode',c_ubyte,2), 600 | ('WOM_mode',c_ubyte,1), 601 | ('WOM_int_mode',c_ubyte,1), 602 | ('reserved',c_ubyte,4)] 603 | def __init__(self): 604 | self.SMD_mode = 0 605 | self.WOM_mode = 0 606 | self.WOM_int_mode = 0 607 | self.reserved = 0 608 | 609 | def set_list(self, data): 610 | buf = (c_ubyte * len(data))() 611 | for i in range(len(data)): 612 | buf[i] = data[i] 613 | memmove(addressof(self), addressof(buf), len(data)) 614 | 615 | def get_list(self): 616 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 617 | # Configure sensor ODR and full-scale range 618 | class ODR_FSR(Structure): 619 | _pack_ = 1 620 | _fields_=[('ODR',c_ubyte,4), 621 | ('reserved',c_ubyte,1), 622 | ('fs_sel',c_ubyte,3)] 623 | def __init__(self): 624 | self.ODR = 6 625 | self.fs_sel = 0 626 | self.reserved = 0 627 | 628 | def set_list(self, data): 629 | buf = (c_ubyte * len(data))() 630 | for i in range(len(data)): 631 | buf[i] = data[i] 632 | memmove(addressof(self), addressof(buf), len(data)) 633 | 634 | def get_list(self): 635 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 636 | 637 | ''' 638 | # ------------------------------------------------------------------------------------------------------------------------------- 639 | # | b7 | b6 | b5 | b4 | b3 | b2 | b1 | b0 | 640 | # ------------------------------------------------------------------------------------------------------------------------------- 641 | # | reversed | INT2_MODE | INT2_DRIVE_CIRCUIT | INT2_POLARITY | INT1_MODE | INT1_DRIVE_CIRCUIT | INT1_POLARITY | 642 | # ------------------------------------------------------------------------------------------------------------------------------- # INT2_MODE:INT2 interrupt mode 643 | # 0: Pulsed mode 644 | # 1: Latched mode 645 | # INT2_DRIVE_CIRCUIT:INT2 drive circuit 646 | # 0: Open drain 647 | # 1: Push pull 648 | # INT2_POLARITY:INT2 interrupt polarity 649 | # 0: Active low (default) 650 | # 1: Active high 651 | # INT1_MODE:INT1 interrupt mode 652 | # 0: Pulsed mode 653 | # 1: Latched mode 654 | # INT1_DRIVE_CIRCUIT:INT1 drive circuit 655 | # 0: Open drain 656 | # 1: Push pull 657 | # INT1_POLARITY:INT1 interrupt polarity 658 | # 0: Active low (default) 659 | # 1: Active high 660 | ''' 661 | class INT_Config(Structure): 662 | _pack_ = 1 663 | _fields_=[('INT1_polarity',c_ubyte,1), 664 | ('INT1_drive_circuit',c_ubyte,1), 665 | ('INT1_mode',c_ubyte,1), 666 | ('INT1_polarity',c_ubyte,1), 667 | ('INT2_drive_circuit',c_ubyte,1), 668 | ('INT2_mode',c_ubyte,1), 669 | ('reversed',c_ubyte,2)] 670 | def __init__(self): 671 | self.INT1_polarity = 0 672 | self.INT1_drive_circuit = 0 673 | self.INT1_mode = 0 674 | self.INT2_polarity = 0 675 | self.INT2_drive_circuit = 0 676 | self.INT2_mode = 0 677 | self.reversed = 0 678 | 679 | def set_list(self, data): 680 | buf = (c_ubyte * len(data))() 681 | for i in range(len(data)): 682 | buf[i] = data[i] 683 | memmove(addressof(self), addressof(buf), len(data)) 684 | 685 | def get_list(self): 686 | return list(bytearray(string_at(addressof(self),sizeof(self)))) 687 | 688 | 689 | def __init__(self): 690 | self.__gyro_range = 4000/65535.0 691 | self.__accel_range = 0.488 692 | self.FIFO_mode = False 693 | self._Pwrmgmt0 = self.Pwrmgmt0() 694 | self._INT_Config = self.INT_Config() 695 | self._Accel_config0 = self.Accel_config0() 696 | self._INTF_Config1 = self.INTF_Config1() 697 | self._Accel_config1 = self.Accel_config1() 698 | self._Gyro_Accel_Config0 = self.Gyro_Accel_Config0() 699 | self._APEX_Config8 = self.APEX_Config8() 700 | self._APEX_Config7 = self.APEX_Config7() 701 | self._INTSource = self.INTSource() 702 | self._APEX_Config0 = self.APEX_Config0() 703 | self._SMD_Config = self.SMD_Config() 704 | self._ODR_FSR = self.ODR_FSR() 705 | self._INT_pin = 0 706 | 707 | def begin(self): 708 | '''! 709 | @brief Begin function, detect whether the sensor is normally connected 710 | @return Init result 711 | @retval ERR_OK Init succeed 712 | @retval ERR_DATA_BUS Bus data access error 713 | @retval ERR_IC_VERSION The read sensor ID is wrong 714 | ''' 715 | self.bank = 0 716 | self.write_reg(ICM42688_REG_BANK_SEL,[self.bank]) 717 | id = self.read_reg(ICM42688_WHO_AM_I) 718 | if id == None : 719 | logger.warning("ERR_DATA_BUS") 720 | return self.ERR_DATA_BUS 721 | 722 | logger.info("id=%d"%(id)) 723 | 724 | if id != DFRobot_ICM42688_ID: 725 | return self.ERR_IC_VERSION 726 | reset = 1 727 | self.write_reg(ICM42688_DEVICE_CONFIG, [reset]) 728 | time.sleep(0.001) 729 | return self.ERR_OK 730 | 731 | def get_all_measure_data(self): 732 | '''! 733 | @brief Obtain all measurement data 734 | @n Get measured temperature 735 | @n Get accelerometer value on X-axis 736 | @n Get accelerometer value on Y-axis 737 | @n Get accelerometer value on Z-axis 738 | @n Get gyroscope value on X-axis 739 | @n Get gyroscope value on Y-axis 740 | @n Get gyroscope value on Z-axis 741 | @return a value list, content is as follows: 742 | @n Temperature value, unit: ℃ 743 | @n X-axis accelerometer value, unit: mg 744 | @n Y-axis accelerometer value, unit: mg 745 | @n Z-axis accelerometer value, unit: mg 746 | @n X-axis gyroscope value, unit: dps 747 | @n Y-axis gyroscope value, unit: dps 748 | @n Z-axis gyroscope value, unit: dps 749 | ''' 750 | value = [0] * 7 751 | if(self.FIFO_mode): 752 | value[0] = self.__temp/2.07 + 25 753 | value[1] = self.__accel_x * self.__accel_range 754 | value[2] = self.__accel_y * self.__accel_range 755 | value[3] = self.__accel_z * self.__accel_range 756 | value[4] = self.__gyro_x * self.__gyro_range 757 | value[5] = self.__gyro_y * self.__gyro_range 758 | value[6] = self.__gyro_z * self.__gyro_range 759 | else: 760 | data = self._read_multi_reg(ICM42688_TEMP_DATA1, 14) 761 | value[0] = (np.int16((data[0])*256 + data[1]))/132.48 + 25 762 | value[1] = np.int16((data[2])*256 + data[3]) * self.__accel_range 763 | value[2] = np.int16((data[4])*256 + data[5]) * self.__accel_range 764 | value[3] = np.int16((data[6])*256 + data[7]) * self.__accel_range 765 | value[4] = np.int16((data[8])*256 + data[9]) * self.__gyro_range 766 | value[5] = np.int16((data[10])*256 + data[11]) * self.__gyro_range 767 | value[6] = np.int16((data[12])*256 + data[13]) * self.__gyro_range 768 | return value 769 | 770 | def get_temperature(self): 771 | '''! 772 | @brief Get measured temperature 773 | @return Temperature value, unit: ℃ 774 | ''' 775 | value = 0.0 776 | if(self.FIFO_mode): 777 | value = self.__temp/2.07 + 25 778 | else: 779 | data1 = self.read_reg(ICM42688_TEMP_DATA1) 780 | data2 = self.read_reg(ICM42688_TEMP_DATA0) 781 | value = (np.int16((data1)*256 + data2))/132.48 + 25 782 | return value 783 | 784 | def get_accel_x(self): 785 | '''! 786 | @brief Get accelerometer value on X-axis 787 | @return X-axis accelerometer value, unit: mg 788 | ''' 789 | value = 0.0 790 | if(self.FIFO_mode): 791 | value = self.__accel_x 792 | else: 793 | data1 = self.read_reg(ICM42688_ACCEL_DATA_X1) 794 | data2 = self.read_reg(ICM42688_ACCEL_DATA_X0) 795 | value = np.int16((data1)*256 + data2) 796 | 797 | return value*self.__accel_range 798 | 799 | def get_accel_y(self): 800 | '''! 801 | @brief Get accelerometer value on Y-axis 802 | @return Y-axis accelerometer value, unit: mg 803 | ''' 804 | value = 0.0 805 | if(self.FIFO_mode): 806 | value = self.__accel_y 807 | else: 808 | data1 = self.read_reg(ICM42688_ACCEL_DATA_Y1) 809 | data2 = self.read_reg(ICM42688_ACCEL_DATA_Y0) 810 | value = np.int16((data1)*256 + data2) 811 | return value*self.__accel_range 812 | 813 | def get_accel_z(self): 814 | '''! 815 | @brief Get accelerometer value on Z-axis 816 | @return Z-axis accelerometer value, unit: mg 817 | ''' 818 | value = 0.0 819 | if(self.FIFO_mode): 820 | value = self.__accel_z 821 | else: 822 | data1 = self.read_reg(ICM42688_ACCEL_DATA_Z1) 823 | data2 = self.read_reg(ICM42688_ACCEL_DATA_Z0) 824 | value = np.int16((data1)*256 + data2) 825 | return value*self.__accel_range 826 | 827 | def get_gyro_x(self): 828 | '''! 829 | @brief Get gyroscope value on X-axis 830 | @return X-axis gyroscope value, unit: dps 831 | ''' 832 | value = 0.0 833 | if(self.FIFO_mode): 834 | value = self.__gyro_x 835 | else: 836 | data1 = self.read_reg(ICM42688_GYRO_DATA_X1) 837 | data2 = self.read_reg(ICM42688_GYRO_DATA_X1) 838 | value = np.int16((data1)*256 + data2) 839 | return value*self.__gyro_range 840 | 841 | def get_gyro_y(self): 842 | '''! 843 | @brief Get gyroscope value on Y-axis 844 | @return Y-axis gyroscope value, unit: dps 845 | ''' 846 | value = 0.0 847 | if(self.FIFO_mode): 848 | value = self.__gyro_y 849 | else: 850 | data1 = self.read_reg(ICM42688_GYRO_DATA_Y1) 851 | data2 = self.read_reg(ICM42688_GYRO_DATA_Y1) 852 | value = np.int16((data1)*256 + data2) 853 | return value*self.__gyro_range 854 | 855 | def get_gyro_z(self): 856 | '''! 857 | @brief Get gyroscope value on Z-axis 858 | @return Z-axis gyroscope value, unit: dps 859 | ''' 860 | value = 0.0 861 | if(self.FIFO_mode): 862 | value = self.__gyro_z 863 | else: 864 | data1 = self.read_reg(ICM42688_GYRO_DATA_Z1) 865 | data2 = self.read_reg(ICM42688_GYRO_DATA_Z1) 866 | value = np.int16((data1)*256 + data2) 867 | return value*self.__gyro_range 868 | 869 | def tap_detection_init(self,accel_mode): 870 | '''! 871 | @brief Tap detection init 872 | @param accel_mode Accelerometer operating mode 873 | @n 0 represent operating in low-power mode 874 | @n 1 represent operating in low-noise mode 875 | ''' 876 | self.bank = 0 877 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 878 | if(accel_mode == 0): 879 | self._Accel_config0.accel_ODR = 15 880 | self.write_reg(ICM42688_ACCEL_CONFIG0, self._Accel_config0.get_list()) 881 | self._Pwrmgmt0.accel_mode = 2 882 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 883 | time.sleep(0.001) 884 | self._INTF_Config1.accel_lp_clk_sel = 0 885 | self.write_reg(ICM42688_PWR_MGMT0, self._INTF_Config1.get_list()) 886 | self._Accel_config1.accel_ui_filt_ORD = 2 887 | self.write_reg(ICM42688_ACCEL_CONFIG1, self._Accel_config1.get_list()) 888 | self._Gyro_Accel_Config0.accel_ui_filt_BW = 0 889 | self.write_reg(ICM42688_GYRO_ACCEL_CONFIG0, self._Gyro_Accel_Config0.get_list()) 890 | elif(accel_mode == 1): 891 | self._Accel_config0.accel_ODR = 6 892 | self.write_reg(ICM42688_ACCEL_CONFIG0, self._Accel_config0.get_list()) 893 | self._Pwrmgmt0.accel_mode = 3 894 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 895 | time.sleep(0.001) 896 | self._Accel_config1.accel_ui_filt_ORD = 2 897 | self.write_reg(ICM42688_ACCEL_CONFIG1, self._Accel_config1.get_list()) 898 | self._Gyro_Accel_Config0.accel_ui_filt_BW = 0 899 | self.write_reg(ICM42688_GYRO_ACCEL_CONFIG0, self._Gyro_Accel_Config0.get_list()) 900 | else: 901 | logger.warning("accel_mode invalid !") 902 | return 903 | time.sleep(0.001) 904 | self.bank = 4 905 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 906 | self._APEX_Config8.tap_tmin =3 907 | self._APEX_Config8.tap_tavg =3 908 | self._APEX_Config8.tap_tmax =2 909 | self.write_reg(ICM42688_APEX_CONFIG8, self._APEX_Config8.get_list()) 910 | self._APEX_Config7.tap_max_peak_tol = 1 911 | self._APEX_Config7.tap_min_jerk_thr = 17 912 | self.write_reg(ICM42688_APEX_CONFIG7, self._APEX_Config7.get_list()) 913 | time.sleep(0.001) 914 | self._INTSource.tap_det_int_en = 1 915 | if(self._INT_pin == 1): 916 | self.write_reg(ICM42688_INT_SOURCE6, self._INTSource.get_list()) 917 | elif(self._INT_pin == 2): 918 | self.write_reg(ICM42688_INT_SOURCE7, self._INTSource.get_list()) 919 | time.sleep(0.05) 920 | self.bank = 0 921 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 922 | self._APEX_Config0.tap_enable = 1 923 | self.write_reg(ICM42688_APEX_CONFIG0, self._APEX_Config0.get_list()) 924 | 925 | def get_tap_information(self): 926 | '''! 927 | @brief Get tap information 928 | ''' 929 | data = self.read_reg(ICM42688_APEX_DATA4) 930 | self._tap_num = data & 0x18 931 | self._tap_axis = data & 0x06 932 | self._tap_dir = data & 0x01 933 | 934 | 935 | def number_of_tap(self): 936 | '''! 937 | @brief Get the number of tap: single-tap or double tap 938 | @return The number of tap 939 | @retval TAP_SINGLE Single-tap 940 | @retval TAP_DOUBLE Double tap 941 | ''' 942 | return self._tap_num 943 | 944 | def axis_of_tap(self): 945 | '''! 946 | @brief Get the axis on which tap occurred: X-axis, Y-axis, or Z-axis 947 | @return Tap axis 948 | @retval X_AXIS X-axis 949 | @retval Y_AXIS Y-axis 950 | @retval Z_AXIS Z-axis 951 | ''' 952 | return self._tap_axis 953 | 954 | def wake_on_motion_init(self): 955 | '''! 956 | @brief Init wake on motion 957 | ''' 958 | self.bank = 0 959 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 960 | self._Accel_config0.accel_ODR = 9 961 | self.write_reg(ICM42688_ACCEL_CONFIG0, self._Accel_config0.get_list()) 962 | self._Pwrmgmt0.accel_mode = 2 963 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 964 | time.sleep(0.001) 965 | self._INTF_Config1.accel_lp_clk_sel = 0 966 | self.write_reg(ICM42688_INTF_CONFIG1, self._INTF_Config1.get_list()) 967 | time.sleep(0.001) 968 | 969 | def set_wom_thr(self,axis,threshold): 970 | '''! 971 | @brief Set motion interrupt wake on threshold of axis accelerometer 972 | @param axis x/y/z axis 973 | @n X_AXIS_WOM 974 | @n Y_AXIS_WOM 975 | @n Z_AXIS_WOM 976 | @n ALL 977 | @param threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 978 | ''' 979 | self.bank = 4 980 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 981 | if(axis == self.X_AXIS): 982 | self.write_reg(ICM42688_ACCEL_WOM_X_THR, [threshold]) 983 | elif(axis == self.Y_AXIS): 984 | self.write_reg(ICM42688_ACCEL_WOM_Y_THR, [threshold]) 985 | elif(axis == self.Z_AXIS): 986 | self.write_reg(ICM42688_ACCEL_WOM_Z_THR, [threshold]) 987 | elif(axis == self.ALL): 988 | self.write_reg(ICM42688_ACCEL_WOM_X_THR, [threshold]) 989 | self.write_reg(ICM42688_ACCEL_WOM_Y_THR, [threshold]) 990 | self.write_reg(ICM42688_ACCEL_WOM_Z_THR, [threshold]) 991 | time.sleep(0.001) 992 | self.bank = 0 993 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 994 | 995 | def set_wom_interrupt(self,axis): 996 | '''! 997 | @brief Enable wake on interrupt of an axis 998 | @param axis x/y/z axis 999 | @n X_AXIS_WOM 1000 | @n Y_AXIS_WOM 1001 | @n Z_AXIS_WOM 1002 | ''' 1003 | self.bank = 0 1004 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1005 | if(self._INT_pin == 1): 1006 | self.write_reg(ICM42688_INT_SOURCE1, [axis]) 1007 | elif(self._INT_pin == 2): 1008 | self.write_reg(ICM42688_INT_SOURCE4, [axis]) 1009 | time.sleep(0.050) 1010 | self._SMD_Config.SMD_mode = 1 1011 | self._SMD_Config.WOM_mode = 1 1012 | self._SMD_Config.WOM_int_mode = 0 1013 | self.write_reg(ICM42688_SMD_CONFIG, self._SMD_Config.get_list()) 1014 | 1015 | def enable_SMD_interrupt(self,mode): 1016 | '''! 1017 | @brief Set important motion detection mode and enable SMD interrupt 1018 | @param mode 1019 | @n 0: disable SMD 1020 | @n 2 : SMD short (1 sec wait) An SMD event is detected when two WOM are detected 1 sec apart 1021 | @n 3 : SMD long (3 sec wait) An SMD event is detected when two WOM are detected 3 sec apart 1022 | ''' 1023 | self.bank = 0 1024 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1025 | INT = 1<<3 1026 | if(self._INT_pin == 1): 1027 | self.write_reg(ICM42688_INT_SOURCE1, [INT]) 1028 | elif(self._INT_pin == 2): 1029 | self.write_reg(ICM42688_INT_SOURCE4, [INT]) 1030 | time.sleep(0.050) 1031 | self._SMD_Config.SMD_mode = mode 1032 | self._SMD_Config.WOM_mode = 1 1033 | self._SMD_Config.WOM_int_mode = 0 1034 | self.write_reg(ICM42688_SMD_CONFIG, self._SMD_Config.get_list()) 1035 | 1036 | 1037 | def read_interrupt_status(self,reg): 1038 | '''! 1039 | @brief Read interrupt information and clear interrupt 1040 | @param reg Interrupt information register 1041 | @n ICM42688_INT_STATUS2 Obtain interrupt information of SMD_INT, WOM_X_INT, WOM_Y_INT and WOM_Z_INT and clear them 1042 | @n ICM42688_INT_STATUS3 Obtain interrupt information of STEP_DET_INT, STEP_CNT_OVF_INT, TILT_DET_INT, WAKE_INT and TAP_DET_INT and clear them 1043 | @return Interrupt information, return 0 when no interrupt 1044 | ''' 1045 | self.bank = 0 1046 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1047 | return self.read_reg(reg) 1048 | 1049 | def set_ODR_and_FSR(self,who,ODR,FSR): 1050 | '''! 1051 | @brief Set ODR and Full-scale range of gyroscope or accelerometer 1052 | @param who GYRO/ACCEL/ALL 1053 | @n GYRO: indicate only set gyroscope 1054 | @n ACCEL: indicate only set accelerometer 1055 | @param ODR Output data rate 1056 | @n ODR_32KHZ Support: Gyro/Accel(LN mode) 1057 | @n ODR_16KHZ Support: Gyro/Accel(LN mode) 1058 | @n ODR_8KHZ Support: Gyro/Accel(LN mode) 1059 | @n ODR_4KHZ Support: Gyro/Accel(LN mode) 1060 | @n ODR_2KHZ Support: Gyro/Accel(LN mode) 1061 | @n ODR_1KHZ Support: Gyro/Accel(LN mode) 1062 | @n ODR_200HZ Support: Gyro/Accel(LP or LN mode) 1063 | @n ODR_100HZ Support: Gyro/Accel(LP or LN mode) 1064 | @n ODR_50HZ Support: Gyro/Accel(LP or LN mode) 1065 | @n ODR_25KHZ Support: Gyro/Accel(LP or LN mode) 1066 | @n ODR_12_5KHZ Support: Gyro/Accel(LP or LN mode) 1067 | @n ODR_6_25KHZ Support: Accel(LP mode) 1068 | @n ODR_3_125HZ Support: Accel(LP mode) 1069 | @n ODR_1_5625HZ Support: Accel(LP mode) 1070 | @n ODR_500HZ Support: Accel(LP or LN mode) 1071 | @param FSR Full-scale range 1072 | @n FSR_0 Gyro:±2000dps / Accel: ±16g 1073 | @n FSR_1 Gyro:±1000dps / Accel: ±8g 1074 | @n FSR_2 Gyro:±500dps / Accel: ±4g 1075 | @n FSR_3 Gyro:±250dps / Accel: ±2g 1076 | @n FSR_4 Gyro:±125dps / Accel: not optional 1077 | @n FSR_5 Gyro:±62.5dps / Accel: not optional 1078 | @n FSR_6 Gyro:±31.25dps / Accel: not optional 1079 | @n FSR_7 Gyro:±15.625dps / Accel: not optional 1080 | @return Set result 1081 | @retval True indicate the setting succeed 1082 | @retval False indicate selected parameter is wrong 1083 | ''' 1084 | ret = True 1085 | _ODR_FSR = self.ODR_FSR() 1086 | self.bank = 0 1087 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1088 | if(who == self.GYRO): 1089 | if(ODR > self.ODR_12_5KHZ or FSR > self.FSR_7): 1090 | ret = False 1091 | else: 1092 | _ODR_FSR.ODR = ODR 1093 | _ODR_FSR.fs_sel = FSR 1094 | self.write_reg(ICM42688_GYRO_CONFIG0, _ODR_FSR.get_list()) 1095 | if(FSR == self.FSR_0): 1096 | self.__gyroRange = 4000/65535.0 1097 | elif(FSR == self.FSR_1): 1098 | self.__gyroRange = 2000/65535.0 1099 | elif(FSR == self.FSR_2): 1100 | self.__gyroRange = 1000/65535.0 1101 | elif(FSR == self.FSR_3): 1102 | self.__gyroRange = 500/65535.0 1103 | elif(FSR == self.FSR_4): 1104 | self.__gyroRange = 250/65535.0 1105 | elif(FSR == self.FSR_5): 1106 | self.__gyroRange = 125/65535.0 1107 | elif(FSR == self.FSR_6): 1108 | self.__gyroRange = 62.5/65535.0 1109 | elif(FSR == self.FSR_7): 1110 | self.__gyroRange = 31.25/65535.0 1111 | elif(who == self.ACCEL): 1112 | if(ODR > self.ODR_500HZ or FSR > self.FSR_3): 1113 | ret = False 1114 | else: 1115 | _ODR_FSR.ODR = ODR 1116 | _ODR_FSR.fs_sel = FSR 1117 | self.write_reg(ICM42688_ACCEL_CONFIG0, _ODR_FSR.get_list()) 1118 | if(FSR == self.FSR_0): 1119 | self.__gyroRange = 0.488 1120 | elif(FSR == self.FSR_1): 1121 | self.__gyroRange = 0.244 1122 | elif(FSR == self.FSR_2): 1123 | self.__gyroRange = 0.122 1124 | elif(FSR == self.FSR_3): 1125 | self.__gyroRange = 0.061 1126 | return ret 1127 | 1128 | def _set_FIFO_data_mode(self): 1129 | '''! 1130 | @brief Set FIFO data packet format 1131 | ''' 1132 | self.bank = 0 1133 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1134 | mode = 7 1135 | self.write_reg(ICM42688_FIFO_CONFIG1, [mode]) 1136 | 1137 | def start_FIFO_mode(self): 1138 | '''! 1139 | @brief Enable FIFO 1140 | ''' 1141 | self.bank = 0 1142 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1143 | FIFO_mode = True 1144 | self._set_FIFO_data_mode() 1145 | start = 1<<6 1146 | self.write_reg(ICM42688_FIFO_CONFIG, [start]) 1147 | 1148 | 1149 | def get_FIFO_data(self): 1150 | '''! 1151 | @brief Read FIFO data, read temperature, gyroscope and accelerometer data and save them for parsing. 1152 | ''' 1153 | data=[0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0] 1154 | for i in range(0,16): 1155 | data[i] = self.read_reg(ICM42688_FIFO_DATA) 1156 | self.__accel_x = np.int16((data[1])*256 + data[2]) 1157 | self.__accel_y = np.int16((data[3])*256 + data[4]) 1158 | self.__accel_z = np.int16((data[5])*256 + data[6]) 1159 | self.__gyro_x = np.int16((data[7])*256 + data[8]) 1160 | self.__gyro_y = np.int16((data[9])*256 + data[10]) 1161 | self.__gyro_z = np.int16((data[11])*256 + data[12]) 1162 | self.__temp = np.int8(data[13]) 1163 | 1164 | 1165 | def stop_FIFO_mode(self): 1166 | '''! 1167 | @brief Disable FIFO 1168 | ''' 1169 | self.bank = 0 1170 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1171 | start = 1<<7 1172 | self.write_reg(ICM42688_FIFO_CONFIG, [start]) 1173 | 1174 | 1175 | def set_INT_mode(self,INT_pin,INT_mode,INT_polarity,INT_drive_circuit): 1176 | '''! 1177 | @brief Set interrupt mode 1178 | @param INT_pin Interrupt pin 1179 | @n 1 Use INT1 interrupt pin 1180 | @n 2 Use INT2 interrupt pin 1181 | @param INT_mode Set interrupt mode 1182 | @n 1 Interrupt lock mode (polarity remain unchanged when interrupt triggered, and restore after clearing interrupt) 1183 | @n 0 Pulse mode 1184 | @param INT_polarity Level polarity output by interrupt 1185 | @n 0 Interrupt pin polarity is LOW when producing interrupt 1186 | @n 1 Interrupt pin polarity is HIGH when producing interrupt 1187 | @param INT_drive_circuit 1188 | @n 0 Open drain 1189 | @n 1 Push pull 1190 | ''' 1191 | self.bank = 0 1192 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1193 | if(INT_pin == 1): 1194 | self._INT_pin = 1 1195 | self._INT_Config.INT1_polarity = INT_polarity 1196 | self._INT_Config.INT1_drive_circuit =INT_drive_circuit 1197 | self._INT_Config.INT1_mode = INT_mode 1198 | elif(INT_pin == 2): 1199 | self._INT_pin = 2 1200 | self._INT_Config.INT2_polarity = INT_polarity 1201 | self._INT_Config.INT2_drive_circuit =INT_drive_circuit 1202 | self._INT_Config.INT2_mode = INT_mode 1203 | self.write_reg(ICM42688_INT_CONFIG, self._INT_Config.get_list()) 1204 | 1205 | def start_temp_measure(self): 1206 | '''! 1207 | @brief Start thermometer 1208 | ''' 1209 | self.bank = 0 1210 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1211 | self._Pwrmgmt0.tempDis = 0 1212 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 1213 | 1214 | def start_gyro_measure(self,mode): 1215 | '''! 1216 | ' @brief Start gyroscope 1217 | ' @param mode Set gyroscope working mode 1218 | ' @n STANDBY_MODE_ONLY_GYRO 1 Set stanby mode, only support gyroscope 1219 | ' @n LN_MODE 3 Set low-noise mode 1220 | ''' 1221 | self.bank = 0 1222 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1223 | self._Pwrmgmt0.gyro_mode = mode 1224 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 1225 | 1226 | 1227 | def start_accel_measure(self,mode): 1228 | '''! 1229 | @brief Start accelerometer 1230 | @param mode Set accelerometer working mode 1231 | @n LP_MODE_ONLY_ACCEL 2 Set low-power mode, only support accelerometer 1232 | @n LN_MODE 3 Set low-noise mode 1233 | ''' 1234 | self.bank = 0 1235 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1236 | self._Pwrmgmt0.accel_mode = mode 1237 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 1238 | 1239 | def stop_temp_measure(self): 1240 | '''! 1241 | @brief Stop temperature measurement 1242 | ''' 1243 | self.bank = 0 1244 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1245 | self._Pwrmgmt0.tempDis = 1 1246 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 1247 | 1248 | 1249 | def stop_gyro_measure(self): 1250 | '''! 1251 | @brief Stop gyroscope 1252 | ''' 1253 | self.bank = 0 1254 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1255 | self._Pwrmgmt0.gyro_mode = 0 1256 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 1257 | time.sleep(0.001) 1258 | 1259 | 1260 | def stop_accel_measure(self): 1261 | '''! 1262 | @brief Stop accelerometer 1263 | ''' 1264 | self.bank = 0 1265 | self.write_reg(ICM42688_REG_BANK_SEL, [self.bank]) 1266 | self._Pwrmgmt0.accel_mode = 0 1267 | self.write_reg(ICM42688_PWR_MGMT0, self._Pwrmgmt0.get_list()) 1268 | time.sleep(0.001) 1269 | 1270 | 1271 | class DFRobot_ICM42688_I2C(DFRobot_ICM42688): 1272 | def __init__(self, i2c_addr = DFRobot_ICM42688_I2C_H_ADDR,bus = 1): 1273 | self.i2cbus=smbus.SMBus(bus) 1274 | self.i2c_addr = i2c_addr 1275 | super(DFRobot_ICM42688_I2C,self).__init__() 1276 | 1277 | 1278 | def begin(self): 1279 | ''' ! 1280 | @brief Begin function, detect whether the sensor is normally connected 1281 | @retval ERR_OK Init succeed 1282 | @retval ERR_DATA_BUS Bus data read error 1283 | @retval ERR_IC_VERSION The read sensor ID is wrong 1284 | ''' 1285 | return super(DFRobot_ICM42688_I2C,self).begin() 1286 | 1287 | 1288 | def write_reg(self, reg, value): 1289 | '''! 1290 | @brief Write data to register 1291 | @param reg Register address 1292 | @param value Data to be written, list format 1293 | ''' 1294 | self.i2cbus.write_i2c_block_data(self.i2c_addr, reg, value) 1295 | 1296 | 1297 | def read_reg(self, reg): 1298 | '''! 1299 | @brief Read data from register 1300 | @param reg Register address 1301 | @return The read data, list format 1302 | ''' 1303 | self.i2cbus.write_byte(self.i2c_addr,reg) 1304 | rslt = self.i2cbus.read_byte(self.i2c_addr) 1305 | return rslt 1306 | 1307 | def _read_multi_reg(self, reg, length): 1308 | '''! 1309 | @brief read the data from the register 1310 | @param reg register address 1311 | @param length length of data to be read 1312 | @return read data list 1313 | ''' 1314 | return self.i2cbus.read_i2c_block_data(self.i2c_addr, reg, length) 1315 | 1316 | 1317 | class DFRobot_ICM42688_SPI(DFRobot_ICM42688): 1318 | def __init__(self ,cs, bus = 0, dev = 0,speed = 10000000): 1319 | super(DFRobot_ICM42688_SPI, self).__init__() 1320 | self.__cs = cs 1321 | GPIO.setup(self.__cs, GPIO.OUT) 1322 | GPIO.output(self.__cs, GPIO.LOW) 1323 | self.__spi = spidev.SpiDev() 1324 | self.__spi.open(bus, dev) 1325 | self.__spi.no_cs = True 1326 | self.__spi.max_speed_hz = speed 1327 | 1328 | def begin(self): 1329 | '''! 1330 | @brief Begin function, detect whether the sensor is normally connected 1331 | @retval ERR_OK Init succeed 1332 | @n ERR_DATA_BUS Bus data access error 1333 | @n ERR_IC_VERSION The read sensor ID is wrong 1334 | ''' 1335 | return super(DFRobot_ICM42688_SPI,self).begin() 1336 | 1337 | def write_reg(self, reg, data): 1338 | '''! 1339 | @brief writes data to a register 1340 | @param reg register address 1341 | @param data Data to be written 1342 | ''' 1343 | GPIO.output(self.__cs, GPIO.LOW) 1344 | self.__spi.writebytes([reg,data[0]]) 1345 | GPIO.output(self.__cs, GPIO.HIGH) 1346 | 1347 | def read_reg(self, reg): 1348 | '''! 1349 | @brief read the data from the register 1350 | @param reg register address 1351 | @return read data 1352 | ''' 1353 | GPIO.output(self.__cs, GPIO.LOW) 1354 | self.__spi.writebytes([reg | 0x80]) 1355 | data = self.__spi.readbytes(1) 1356 | GPIO.output(self.__cs, GPIO.HIGH) 1357 | return data[0] 1358 | 1359 | def _read_multi_reg(self, reg, length): 1360 | '''! 1361 | @brief read the data from the register 1362 | @param reg register address 1363 | @param length length of data to be read 1364 | @return read data list 1365 | ''' 1366 | GPIO.output(self.__cs, GPIO.LOW) 1367 | self.__spi.writebytes([reg | 0x80]) 1368 | rslt = self.__spi.readbytes(length) 1369 | GPIO.output(self.__cs, GPIO.HIGH) 1370 | return rslt 1371 | -------------------------------------------------------------------------------- /python/raspberrypi/README.md: -------------------------------------------------------------------------------- 1 | # DFRobot_ICM42688 2 | 3 | - [中文版](./README_CN.md) 4 | 5 | The ICM-42688-P is a 6-axis MEMS MotionTracking device that combines a 3-axis gyroscope and a 3-axis accelerometer. It has a configurable host interface that supports I3CSM, I2C and SPI serial communication, features a 2 kB FIFO and 2 programmable interrupts with ultra low-power wake-on-motion support to minimize system power consumption. 6 | 7 | ![产品实物图](../../resources/images/SEN0452.jpg) 8 | 9 | ## Product Link(https://www.dfrobot.com/) 10 | SKU:SEN0452 11 | 12 | ## Table of Contents 13 | 14 | * [Summary](#summary) 15 | * [Installation](#installation) 16 | * [Methods](#methods) 17 | * [Compatibility](#compatibility) 18 | * [History](#history) 19 | * [Credits](#credits) 20 | 21 | 22 | ## Summary 23 | * Get temperature, gyroscope and accelerometer data 24 | * tap detection 25 | * Wake on Motion 26 | * significant Motion Detection 27 | 28 | ## Installation 29 | 30 | To use this library, first download the library to Raspberry Pi, then open the routines folder. To execute one routine, demox.py, type python demox.py on the command line. To execute the get_gyro_accel_temp_data.py routine, for example, you need to type: 31 | 32 | ``` 33 | python get_gyro_accel_temp_data.py 34 | ``` 35 | 36 | ## Methods 37 | 38 | ```python 39 | 40 | def begin(self): 41 | '''! 42 | @brief Begin function, detect whether the sensor is normally connected 43 | @return Init result 44 | @retval ERR_OK Init succeed 45 | @retval ERR_DATA_BUS Bus data read error 46 | @retval ERR_IC_VERSION The read sensor ID is wrong 47 | ''' 48 | 49 | def get_all_measure_data(self): 50 | '''! 51 | @brief Obtain all measurement data 52 | @n Get measured temperature 53 | @n Get accelerometer value on X-axis 54 | @n Get accelerometer value on Y-axis 55 | @n Get accelerometer value on Z-axis 56 | @n Get gyroscope value on X-axis 57 | @n Get gyroscope value on Y-axis 58 | @n Get gyroscope value on Z-axis 59 | @return a value list, content is as follows: 60 | @n Temperature value, unit: ℃ 61 | @n X-axis accelerometer value, unit: mg 62 | @n Y-axis accelerometer value, unit: mg 63 | @n Z-axis accelerometer value, unit: mg 64 | @n X-axis gyroscope value, unit: dps 65 | @n Y-axis gyroscope value, unit: dps 66 | @n Z-axis gyroscope value, unit: dps 67 | ''' 68 | 69 | def get_temperature(self): 70 | '''! 71 | @brief @brief Get measured temperature 72 | @return Temperature value, unit: ℃ 73 | ''' 74 | 75 | def get_accel_x(self): 76 | '''! 77 | @brief Get X-axis accelerometer value 78 | @return X-axis accelerometer value, unit: mg 79 | ''' 80 | 81 | def get_accel_y(self): 82 | '''! 83 | @brief Get Y-axis accelerometer value 84 | @return Y-axis accelerometer value, unit: mg 85 | ''' 86 | 87 | def get_accel_z(self): 88 | '''! 89 | @brief Get Z-axis accelerometer value 90 | @return Z-axis accelerometer value, unit: mg 91 | ''' 92 | 93 | def get_gyro_x(self): 94 | '''! 95 | @brief Get X-axis gyroscope value 96 | @return X-axis gyroscope value, unit: dps 97 | ''' 98 | 99 | def get_gyro_y(self): 100 | '''! 101 | @brief Get Y-axis gyroscope value 102 | @return Y-axis gyroscope value, unit: dps 103 | ''' 104 | 105 | def get_gyro_z(self): 106 | '''! 107 | @brief Get Z-axis gyroscope value 108 | @return Z-axis gyroscope value, unit: dps 109 | ''' 110 | 111 | def tap_detection_init(self,accel_mode): 112 | '''! 113 | @brief Tap detection init 114 | @param accel_mode Accelerometer operating mode 115 | @n 0 for operating in low-power mode 116 | @n 1 for operating in low-noise mode 117 | ''' 118 | 119 | def get_tap_information(self): 120 | '''! 121 | @brief Get tap information 122 | ''' 123 | 124 | 125 | def number_of_tap(self): 126 | '''! 127 | @brief Get the number of tap: single-tap or double tap 128 | @return The number of tap 129 | @retval TAP_SINGLE Single-tap 130 | @retval TAP_DOUBLE Double tap 131 | ''' 132 | 133 | def axis_of_tap(self): 134 | '''! 135 | @brief Get the axis on which the tap occurred: X-axis, Y-axis, or Z-axis 136 | @return Tap axis 137 | @retval X_AXIS X-axis 138 | @retval Y_AXIS Y-axis 139 | @retval Z_AXIS Z-axis 140 | ''' 141 | 142 | def wake_on_motion_init(self): 143 | '''! 144 | @brief Wake on motion init 145 | ''' 146 | 147 | def set_wom_thr(self,axis,threshold): 148 | '''! 149 | @brief Set motion interrupt wake on threshold of axis accelerometer 150 | @param axis x/y/z axis 151 | @n X_AXIS_WOM 152 | @n Y_AXIS_WOM 153 | @n Z_AXIS_WOM 154 | @n ALL 155 | @param threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 156 | ''' 157 | 158 | def set_wom_interrupt(self,axis): 159 | '''! 160 | @brief Enable wake on interrupt of axis 161 | @param axis x/y/z axis 162 | @n X_AXIS_WOM 163 | @n Y_AXIS_WOM 164 | @n Z_AXIS_WOM 165 | ''' 166 | 167 | def enable_SMD_interrupt(self,mode): 168 | '''! 169 | @brief Set important motion detection mode and enable SMD interrupt 170 | @param mode 171 | @n 0: disable SMD 172 | @n 2 : SMD short (1 sec wait) An SMD event is detected when two WOM are detected 1 sec apart 173 | @n 3 : SMD long (3 sec wait) An SMD event is detected when two WOM are detected 3 sec apart 174 | ''' 175 | 176 | def read_interrupt_status(self,reg): 177 | '''! 178 | @brief Read interrupt information and clear interrupt 179 | @param reg Interrupt information register 180 | @n ICM42688_INT_STATUS2 Obtain interrupt information of SMD_INT, WOM_X_INT, WOM_Y_INT and WOM_Z_INT and clear them 181 | @n ICM42688_INT_STATUS3 Obtain interrupt information of STEP_DET_INT, STEP_CNT_OVF_INT, TILT_DET_INT, WAKE_INT and TAP_DET_INT and clear them 182 | @return Interrupt information, return 0 when no interrupt 183 | ''' 184 | 185 | def set_ODR_and_FSR(self,who,ODR,FSR): 186 | '''! 187 | @brief Set ODR and Full-scale range of gyroscope or accelerometer 188 | @param who GYRO/ACCEL/ALL 189 | @n GYRO: indicate only set gyroscope 190 | @n ACCEL: indicate only set accelerometer 191 | @param ODR Output data rate 192 | @n ODR_32KHZ Support: Gyro/Accel(LN mode) 193 | @n ODR_16KHZ Support: Gyro/Accel(LN mode) 194 | @n ODR_8KHZ Support: Gyro/Accel(LN mode) 195 | @n ODR_4KHZ Support: Gyro/Accel(LN mode) 196 | @n ODR_2KHZ Support: Gyro/Accel(LN mode) 197 | @n ODR_1KHZ Support: Gyro/Accel(LN mode) 198 | @n ODR_200HZ Support: Gyro/Accel(LP or LN mode) 199 | @n ODR_100HZ Support: Gyro/Accel(LP or LN mode) 200 | @n ODR_50HZ Support: Gyro/Accel(LP or LN mode) 201 | @n ODR_25KHZ Support: Gyro/Accel(LP or LN mode) 202 | @n ODR_12_5KHZ Support: Gyro/Accel(LP or LN mode) 203 | @n ODR_6_25KHZ Support: Accel(LP mode) 204 | @n ODR_3_125HZ Support: Accel(LP mode) 205 | @n ODR_1_5625HZ Support: Accel(LP mode) 206 | @n ODR_500HZ Support: Accel(LP or LN mode) 207 | @param FSR Full-scale range 208 | @n FSR_0 Gyro:±2000dps / Accel: ±16g 209 | @n FSR_1 Gyro:±1000dps / Accel: ±8g 210 | @n FSR_2 Gyro:±500dps / Accel: ±4g 211 | @n FSR_3 Gyro:±250dps / Accel: ±2g 212 | @n FSR_4 Gyro:±125dps / Accel: not optional 213 | @n FSR_5 Gyro:±62.5dps / Accel: not optional 214 | @n FSR_6 Gyro:±31.25dps / Accel: not optional 215 | @n FSR_7 Gyro:±15.625dps / Accel: not optional 216 | @return Set result 217 | @retval True indicate the setting succeed 218 | @retval False indicate selected parameter is wrong 219 | ''' 220 | 221 | def start_FIFO_mode(self): 222 | '''! 223 | @brief Enable FIFO 224 | ''' 225 | 226 | def get_FIFO_data(self): 227 | '''! 228 | @brief Read FIFO data, read temperature, gyroscope and accelerometer data and save them for parse. 229 | ''' 230 | 231 | def stop_FIFO_mode(self): 232 | '''! 233 | @brief Disable FIFO 234 | ''' 235 | 236 | def set_INT_mode(self,INT_pin,INT_mode,INT_polarity,INT_drive_circuit): 237 | '''! 238 | @brief Set interrupt mode 239 | @param INT_pin Interrupt pin 240 | @n 1 Use INT1 interrupt pin 241 | @n 2 Use INT2 interrupt pin 242 | @param INT_mode Set interrupt mode 243 | @n 1 Interrupt lock mode (remain polarity after interrupt trigger, and restore after clearing interrupt) 244 | @n 0 Pulse mode 245 | @param INT_polarity Level polarity output by interrupt 246 | @n 0 Interrupt pin polarity is LOW when producing interrupt 247 | @n 1 Interrupt pin polarity is HIGH when producing interrupt 248 | @param INT_drive_circuit 249 | @n 0 Open drain 250 | @n 1 Push pull 251 | ''' 252 | 253 | def start_temp_measure(self): 254 | '''! 255 | @brief Start thermometer 256 | ''' 257 | 258 | def start_gyro_measure(self,mode): 259 | '''! 260 | ' @brief Start gyroscope 261 | ' @param mode Set gyroscope working mode 262 | ' @n STANDBY_MODE_ONLY_GYRO 1 Set stanby mode, only support gyroscope 263 | ' @n LN_MODE 3 Set low-noise mode 264 | ''' 265 | 266 | def start_accel_measure(self,mode): 267 | '''! 268 | @brief Start accelerometer 269 | @param mode Set accelerometer working mode 270 | @n LP_MODE_ONLY_ACCEL 2 Set low-power mode, only support accelerometer 271 | @n LN_MODE 3 Set low-noise mode 272 | ''' 273 | 274 | def stop_temp_measure(self): 275 | '''! 276 | @brief Stop temperature measurement 277 | ''' 278 | 279 | def stop_gyro_measure(self): 280 | '''! 281 | @brief Stop gyroscope 282 | ''' 283 | 284 | def stop_accel_measure(self): 285 | '''! 286 | @brief Stop accelerometer 287 | ''' 288 | 289 | ``` 290 | 291 | ## Compatibility 292 | 293 | * RaspberryPi Version 294 | 295 | | Board | Work Well | Work Wrong | Untested | Remarks | 296 | | ------------ | :-------: | :--------: | :------: | ------- | 297 | | RaspberryPi2 | | | √ | | 298 | | RaspberryPi3 | | | √ | | 299 | | RaspberryPi4 | √ | | | | 300 | 301 | * Python Version 302 | 303 | | Python | Work Well | Work Wrong | Untested | Remarks | 304 | | ------- | :-------: | :--------: | :------: | ------- | 305 | | Python2 | √ | | | | 306 | | Python3 | √ | | | | 307 | 308 | 309 | ## History 310 | 311 | - 2021/09/28 - Version 1.0.0 released. 312 | 313 | 314 | ## Credits 315 | 316 | Written by yangfeng(feng.yang@dfrobot.com),2021,(Welcome to our [website](https://www.dfrobot.com/)) 317 | -------------------------------------------------------------------------------- /python/raspberrypi/README_CN.md: -------------------------------------------------------------------------------- 1 | # DFRobot_ICM42688 2 | 3 | - [English Version](./README.md) 4 | 5 | ICM-42688-P是一款6轴MEMS运动跟踪设备,它结合了一个3轴陀螺仪和一个3轴加速度计。它有一个可配置的主机接口,支持I3CSM, I2C和SPI串行通信,具有2 kB的FIFO和2个可编程中断,超低功率动态尾流支持,以最大限度地减少系统功耗。 6 | 7 | ![产品实物图](../../resources/images/SEN0452.jpg) 8 | 9 | 10 | ## 产品链接(https://www.dfrobot.com.cn/) 11 | SKU:SEN0452 12 | 13 | ## 目录 14 | 15 | * [概述](#概述) 16 | * [库安装](#库安装) 17 | * [方法](#方法) 18 | * [兼容性](#兼容性) 19 | * [历史](#历史) 20 | * [创作者](#创作者) 21 | 22 | 23 | ## 概述 24 | 25 | * 获取温度数据、陀螺仪数据、加速计数据 26 | * 敲击检测 27 | * 移动唤醒 28 | * 重要的运动检测 29 | 30 | 31 | ## 库安装 32 | 33 | 要使用这个库,首先将库下载到Raspberry Pi,然后打开例程文件夹。要执行一个例程demox.py,请在命令行中输入python demox.py。例如,要执行get_gyro_accel_temp_data.py例程,你需要输入: 34 | ``` 35 | python get_gyro_accel_temp_data.py 36 | ``` 37 | 38 | ## 方法 39 | 40 | ```python 41 | 42 | def begin(self): 43 | '''! 44 | @brief 开始函数,探测传感器是否正常连接 45 | @return 初始化结果 46 | @retval ERR_OK 初始化成功 47 | @retval ERR_DATA_BUS 总线数据访问错误 48 | @retval ERR_IC_VERSION 读取的传感器ID有误 49 | ''' 50 | 51 | def get_all_measure_data(self): 52 | '''! 53 | @brief Obtain all measurement data 54 | @n Get measured temperature 55 | @n Get accelerometer value on X-axis 56 | @n Get accelerometer value on Y-axis 57 | @n Get accelerometer value on Z-axis 58 | @n Get gyroscope value on X-axis 59 | @n Get gyroscope value on Y-axis 60 | @n Get gyroscope value on Z-axis 61 | @return a value list, content is as follows: 62 | @n Temperature value, unit: ℃ 63 | @n X-axis accelerometer value, unit: mg 64 | @n Y-axis accelerometer value, unit: mg 65 | @n Z-axis accelerometer value, unit: mg 66 | @n X-axis gyroscope value, unit: dps 67 | @n Y-axis gyroscope value, unit: dps 68 | @n Z-axis gyroscope value, unit: dps 69 | ''' 70 | 71 | def get_temperature(self): 72 | '''! 73 | @brief @brief 获取测量温度值 74 | @return 温度值 单位:℃ 75 | ''' 76 | 77 | def get_accel_x(self): 78 | '''! 79 | @brief 获取X轴加速计值 80 | @return X轴加速计值 单位:mg 81 | ''' 82 | 83 | def get_accel_y(self): 84 | '''! 85 | @brief 获取Y轴加速计值 86 | @return Y轴加速计值 单位:mg 87 | ''' 88 | 89 | def get_accel_z(self): 90 | '''! 91 | @brief 获取Z轴加速计值 92 | @return Z轴加速计值 单位:mg 93 | ''' 94 | 95 | def get_gyro_x(self): 96 | '''! 97 | @brief 获取X轴陀螺仪值 98 | @return X轴陀螺仪值 单位:dps 99 | ''' 100 | 101 | def get_gyro_y(self): 102 | '''! 103 | @brief 获取Y轴陀螺仪值 104 | @return Y轴陀螺仪值 单位:dps 105 | ''' 106 | 107 | def get_gyro_z(self): 108 | '''! 109 | @brief 获取Z轴陀螺仪值 110 | @return Z轴陀螺仪值 单位:dps 111 | ''' 112 | 113 | def tap_detection_init(self,accel_mode): 114 | '''! 115 | @brief 敲击事件初始化 116 | @param accel_mode 加速计工作模式 117 | @n 0 代表工作在低功耗模式 118 | @n 1 代表工作在低噪声模式 119 | ''' 120 | 121 | def get_tap_information(self): 122 | '''! 123 | @brief 获取敲击信息 124 | ''' 125 | 126 | 127 | def number_of_tap(self): 128 | '''! 129 | @brief 获取敲击次数,分别是:单击、双击 130 | @return 敲击次数 131 | @retval TAP_SINGLE 单击 132 | @retval TAP_DOUBLE 双击 133 | ''' 134 | 135 | def axis_of_tap(self): 136 | '''! 137 | @brief 获取敲击轴,分别是:X\Y\Z轴 138 | @return 敲击轴 139 | @retval X_AXIS X轴 140 | @retval Y_AXIS Y轴 141 | @retval Z_AXIS Z轴 142 | ''' 143 | 144 | def wake_on_motion_init(self): 145 | '''! 146 | @brief 初始化移动唤醒 147 | ''' 148 | 149 | def set_wom_thr(self,axis,threshold): 150 | '''! 151 | @brief 设置某轴加速度计的运动中断唤醒的阈值 152 | @param axis x/y/z轴 153 | @n X_AXIS_WOM 154 | @n Y_AXIS_WOM 155 | @n Z_AXIS_WOM 156 | @n ALL 157 | @param threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 158 | ''' 159 | 160 | def set_wom_interrupt(self,axis): 161 | '''! 162 | @brief 使能某轴的唤醒中断 163 | @param axis x/y/z轴 164 | @n X_AXIS_WOM 165 | @n Y_AXIS_WOM 166 | @n Z_AXIS_WOM 167 | ''' 168 | 169 | def enable_SMD_interrupt(self,mode): 170 | '''! 171 | @brief 设置重要运动检测模式并且开启SMD中断 172 | @param mode 173 | @n 0: disable SMD 174 | @n 2 : SMD short (1 sec wait) An SMD event is detected when two WOM are detected 1 sec apart 175 | @n 3 : SMD long (3 sec wait) An SMD event is detected when two WOM are detected 3 sec apart 176 | ''' 177 | 178 | def read_interrupt_status(self,reg): 179 | '''! 180 | @brief 读取中断信息,并清除中断 181 | @param reg 中断信息寄存器 182 | @n ICM42688_INT_STATUS2 可以获取SMD_INT、WOM_X_INT、WOM_Y_INT、WOM_Z_INT中断信息并且清除 183 | @n ICM42688_INT_STATUS3 可以获取STEP_DET_INT、STEP_CNT_OVF_INT、TILT_DET_INT、WAKE_INT、TAP_DET_INT中断信息并且清除 184 | @return 中断信息,无中断时返回0。 185 | ''' 186 | 187 | def set_ODR_and_FSR(self,who,ODR,FSR): 188 | '''! 189 | @brief 设置陀螺仪或者加速计的ODR和 Full-scale range 190 | @param who GYRO/ACCEL/ALL 191 | @n GYRO:代表只设置陀螺仪 192 | @n ACCEL:代表只设置加速计 193 | @param ODR 输出数据速率 194 | @n ODR_32KHZ 支持:Gyro/Accel(LN mode) 195 | @n ODR_16KHZ 支持:Gyro/Accel(LN mode) 196 | @n ODR_8KHZ 支持:Gyro/Accel(LN mode) 197 | @n ODR_4KHZ 支持:Gyro/Accel(LN mode) 198 | @n ODR_2KHZ 支持:Gyro/Accel(LN mode) 199 | @n ODR_1KHZ 支持:Gyro/Accel(LN mode) 200 | @n ODR_200HZ 支持:Gyro/Accel(LP or LN mode) 201 | @n ODR_100HZ 支持:Gyro/Accel(LP or LN mode) 202 | @n ODR_50HZ 支持:Gyro/Accel(LP or LN mode) 203 | @n ODR_25KHZ 支持:Gyro/Accel(LP or LN mode) 204 | @n ODR_12_5KHZ 支持:Gyro/Accel(LP or LN mode) 205 | @n ODR_6_25KHZ 支持:Accel(LP mode) 206 | @n ODR_3_125HZ 支持:Accel(LP mode) 207 | @n ODR_1_5625HZ 支持:Accel(LP mode) 208 | @n ODR_500HZ 支持:Accel(LP or LN mode) 209 | @param FSR Full-scale range 210 | @n FSR_0 Gyro:±2000dps / Accel: ±16g 211 | @n FSR_1 Gyro:±1000dps / Accel: ±8g 212 | @n FSR_2 Gyro:±500dps / Accel: ±4g 213 | @n FSR_3 Gyro:±250dps / Accel: ±2g 214 | @n FSR_4 Gyro:±125dps / Accel: 不可选 215 | @n FSR_5 Gyro:±62.5dps / Accel: 不可选 216 | @n FSR_6 Gyro:±31.25dps / Accel: 不可选 217 | @n FSR_7 Gyro:±15.625dps / Accel: 不可选 218 | @return 设置结果 219 | @retval True 设置设置成功 220 | @retval False 选择的参数有误 221 | ''' 222 | 223 | def start_FIFO_mode(self): 224 | '''! 225 | @brief 启用FIFO 226 | ''' 227 | 228 | def get_FIFO_data(self): 229 | '''! 230 | @brief 读取FIFO数据,分别读出温度数据、陀螺仪数据、加速计数据并保存等待解析 231 | ''' 232 | 233 | def stop_FIFO_mode(self): 234 | '''! 235 | @brief 关闭停用FIFO 236 | ''' 237 | 238 | def set_INT_mode(self,INT_pin,INT_mode,INT_polarity,INT_drive_circuit): 239 | '''! 240 | @brief 设置中断模式 241 | @param INT_pin 中断引脚 242 | @n 1 使用INT1中断引脚 243 | @n 2 使用INT2中断引脚 244 | @param INT_mode 设置中断模式 245 | @n 1 中断锁定模式(即中断触发后会保持极性,清除中断后恢复) 246 | @n 0 脉冲模式 247 | @param INT_polarity 中断输出的电平极性 248 | @n 0 产生中断时中断引脚极性为LOW 249 | @n 1 产生中断时中断引脚极性为HIGH 250 | @param INT_drive_circuit 251 | @n 0 Open drain 252 | @n 1 Push pull 253 | ''' 254 | 255 | def start_temp_measure(self): 256 | '''! 257 | @brief 启动温度计 258 | ''' 259 | 260 | def start_gyro_measure(self,mode): 261 | '''! 262 | ' @brief 启动陀螺仪 263 | ' @param mode 设置陀螺仪的工作模式 264 | ' @n STANDBY_MODE_ONLY_GYRO 1 设置为备用模式,仅支持陀螺仪 265 | ' @n LN_MODE 3 设置为低噪声模式 266 | ''' 267 | 268 | def start_accel_measure(self,mode): 269 | '''! 270 | @brief 启动加速计 271 | @param mode 设置加速计的工作模式 272 | @n LP_MODE_ONLY_ACCEL 2 设置为低功耗模式,仅支持加速计 273 | @n LN_MODE 3 设置为低噪声模式 274 | ''' 275 | 276 | def stop_temp_measure(self): 277 | '''! 278 | @brief 关闭温度测量 279 | ''' 280 | 281 | def stop_gyro_measure(self): 282 | '''! 283 | @brief 关闭陀螺仪 284 | ''' 285 | 286 | def stop_accel_measure(self): 287 | '''! 288 | @brief 关闭加速计 289 | ''' 290 | 291 | ``` 292 | 293 | 294 | ## 兼容性 295 | 296 | * RaspberryPi 版本 297 | 298 | | Board | Work Well | Work Wrong | Untested | Remarks | 299 | | ------------ | :-------: | :--------: | :------: | ------- | 300 | | RaspberryPi2 | | | √ | | 301 | | RaspberryPi3 | | | √ | | 302 | | RaspberryPi4 | √ | | | | 303 | 304 | * Python 版本 305 | 306 | | Python | Work Well | Work Wrong | Untested | Remarks | 307 | | ------- | :-------: | :--------: | :------: | ------- | 308 | | Python2 | √ | | | | 309 | | Python3 | √ | | | | 310 | 311 | 312 | ## 历史 313 | 314 | - 2019/06/25 - 1.0.0 版本 315 | 316 | 317 | ## 创作者 318 | 319 | Written by yangfeng(feng.yang@dfrobot.com), 2021. (Welcome to our [website](https://www.dfrobot.com/)) 320 | 321 | -------------------------------------------------------------------------------- /python/raspberrypi/examples/get_data_by_FIFO.py: -------------------------------------------------------------------------------- 1 | # -*- coding:utf-8 -*- 2 | '''! 3 | @file get_data_by_FIFO.py 4 | @brief Get temperature, gyroscope and accelerometer data by FIFO 5 | @n Experimental phenomenon: get data once every second 6 | @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 7 | @license The MIT License (MIT) 8 | @author [yangfeng] 9 | @version V1.0 10 | @date 2021-05-13 11 | @url https://github.com/DFRobot/DFRobot_ICM42688 12 | ''' 13 | import sys 14 | sys.path.append("../") # set system path to top 15 | import time 16 | from DFRobot_ICM42688 import * 17 | 18 | #Use I2C for communication 19 | ''' 20 | #Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default to internal pull up) 21 | #DFRobot_ICM42688_I2C_L_ADDR 0x68 22 | #DFRobot_ICM42688_I2C_H_ADDR 0x69 23 | ''' 24 | #ICM42688 = DFRobot_ICM42688_I2C(i2c_addr = DFRobot_ICM42688_I2C_H_ADDR) 25 | 26 | 27 | #Use SPI for communication 28 | RASPBERRY_PIN_CS = 27 #Chip selection pin when SPI is selected, Use BCM code mode, the code number is 27, corresponding to pin GPIO2 29 | ICM42688 = DFRobot_ICM42688_SPI(RASPBERRY_PIN_CS) 30 | 31 | def setup(): 32 | ret = ICM42688.begin() 33 | while(ret !=0): 34 | if(ret == -1): 35 | print("bus data access error") 36 | else: 37 | print("Chip versions do not match") 38 | time.sleep(1) 39 | ret = ICM42688.begin() 40 | 41 | print("ICM42688 begin success!!!") 42 | ''' 43 | Set ODR and Full-scale range of gyroscope or accelerometer 44 | who GYRO/ACCEL/ALL 45 | GYRO: indicate only set gyroscope 46 | ACCEL: indicate only set accelerometer 47 | ODR Output data rate 48 | ODR_32KHZ Support: Gyro/Accel(LN mode) 49 | ODR_16KHZ Support: Gyro/Accel(LN mode) 50 | ODR_8KHZ Support: Gyro/Accel(LN mode) 51 | ODR_4KHZ Support: Gyro/Accel(LN mode) 52 | ODR_2KHZ Support: Gyro/Accel(LN mode) 53 | ODR_1KHZ Support: Gyro/Accel(LN mode) 54 | ODR_200HZ Support: Gyro/Accel(LP or LN mode) 55 | ODR_100HZ Support: Gyro/Accel(LP or LN mode) 56 | ODR_50HZ Support: Gyro/Accel(LP or LN mode) 57 | ODR_25KHZ Support: Gyro/Accel(LP or LN mode) 58 | ODR_12_5KHZ Support: Gyro/Accel(LP or LN mode) 59 | ODR_6_25KHZ Support: Accel(LP mode) 60 | ODR_3_125HZ Support: Accel(LP mode) 61 | ODR_1_5625HZ Support: Accel(LP mode) 62 | ODR_500HZ Support: Accel(LP or LN mode) 63 | FSR Full-scale range 64 | FSR_0 Gyro:±2000dps / Accel: ±16g 65 | FSR_1 Gyro:±1000dps / Accel: ±8g 66 | FSR_2 Gyro:±500dps / Accel: ±4g 67 | FSR_3 Gyro:±250dps / Accel: ±2g 68 | FSR_4 Gyro:±125dps / Accel: not optional 69 | FSR_5 Gyro:±62.5dps / Accel: not optional 70 | FSR_6 Gyro:±31.25dps / Accel: not optional 71 | FSR_7 Gyro:±15.625dps / Accel: not optional 72 | Return True indicate the setting succeed, Flase indicate selected parameter is wrong 73 | ''' 74 | while(ICM42688.set_ODR_and_FSR(ICM42688.GYRO,ICM42688.ODR_1KHZ,ICM42688.FSR_0)==False): 75 | print("Incorrect parameter passed in") 76 | while(ICM42688.set_ODR_and_FSR(ICM42688.ACCEL,ICM42688.ODR_1KHZ,ICM42688.FSR_0) == False): 77 | print("Incorrect parameter passed in") 78 | ''' 79 | Set gyroscope and accelerometer working mode and start measurement 80 | mode 81 | OFF_MODE 0 Disable 82 | STANDBY_MODE_ONLY_GYRO 1 Set stanby mode, only support gyroscope 83 | LP_MODE_ONLY_ACCEL 2 Set low-power mode, only support accelerometer 84 | LN_MODE 3 Set low-noise mode 85 | Note: The accelerometer needs to be set to work in a mode compatible with the ODR. The gyroscope does not have low power mode. 86 | ''' 87 | ICM42688.start_gyro_measure(mode =ICM42688.LN_MODE) 88 | ICM42688.start_accel_measure(mode = ICM42688.LN_MODE) 89 | #Start temperature measurement 90 | ICM42688.start_temp_measure() 91 | #Adopt FIFO for data buffer 92 | ICM42688.start_FIFO_mode() 93 | 94 | def loop(): 95 | #Read data of a FIFO packet 96 | ICM42688.get_FIFO_data() 97 | #Get temperature, accelerometer and gyroscope data 98 | temp_data= ICM42688.get_temperature() 99 | accel_data_x = ICM42688.get_accel_x() 100 | accel_data_y= ICM42688.get_accel_y() 101 | accel_data_z= ICM42688.get_accel_z() 102 | gyro_data_x= ICM42688.get_gyro_x() 103 | gyro_data_y= ICM42688.get_gyro_y() 104 | gyro_data_z= ICM42688.get_gyro_z() 105 | print("===========================================") 106 | print("Temperature: =%f C"%(temp_data)) 107 | print("Accel_X: =%f mg"%(accel_data_x)) 108 | print("Accel_Y: =%f mg"%(accel_data_y)) 109 | print("Accel_Z: =%f mg"%(accel_data_z)) 110 | print("Gyro_X: =%f dps"%(gyro_data_x)) 111 | print("Gyro_Y: =%f dps"%(gyro_data_y)) 112 | print("Gyro_Z: =%f dps"%(gyro_data_z)) 113 | time.sleep(1) 114 | 115 | if __name__ == "__main__": 116 | setup() 117 | while True: 118 | loop() 119 | -------------------------------------------------------------------------------- /python/raspberrypi/examples/get_gyro_accel_temp_data.py: -------------------------------------------------------------------------------- 1 | # -*- coding:utf-8 -*- 2 | '''! 3 | @file get_gyro_accel_temp_data.py 4 | @brief Get temperature, gyroscope and accelerometer data 5 | @n Experimental phenomenon: get data once every second 6 | @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 7 | @license The MIT License (MIT) 8 | @author [yangfeng] 9 | @version V1.0 10 | @date 2021-05-13 11 | @url https://github.com/DFRobot/DFRobot_ICM42688 12 | ''' 13 | import sys 14 | sys.path.append("../") # set system path to top 15 | import time 16 | from DFRobot_ICM42688 import * 17 | #Use I2C for communication 18 | ''' 19 | #Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default to internal pull up) 20 | #DFRobot_ICM42688_I2C_L_ADDR 0x68 21 | #DFRobot_ICM42688_I2C_H_ADDR 0x69 22 | ''' 23 | #ICM42688 = DFRobot_ICM42688_I2C(i2c_addr = DFRobot_ICM42688_I2C_H_ADDR) 24 | 25 | 26 | #Use SPI for communication 27 | RASPBERRY_PIN_CS = 27 #Chip selection pin when SPI is selected, BCM code mode, the code number is 27, corresponding to pin GPIO2 28 | ICM42688 = DFRobot_ICM42688_SPI(RASPBERRY_PIN_CS) 29 | 30 | def setup(): 31 | ret = ICM42688.begin() 32 | while(ret !=0): 33 | if(ret == -1): 34 | print("bus data access error") 35 | else: 36 | print("Chip versions do not match") 37 | time.sleep(1) 38 | ret = ICM42688.begin() 39 | 40 | print("ICM42688 begin success!!!") 41 | ''' 42 | Set ODR and Full-scale range of gyroscope or accelerometer 43 | who GYRO/ACCEL/ALL 44 | GYRO: indicate only set gyroscope 45 | ACCEL: indicate only set accelerometer 46 | ODR Output data rate 47 | ODR_32KHZ Support: Gyro/Accel(LN mode) 48 | ODR_16KHZ Support: Gyro/Accel(LN mode) 49 | ODR_8KHZ Support: Gyro/Accel(LN mode) 50 | ODR_4KHZ Support: Gyro/Accel(LN mode) 51 | ODR_2KHZ Support: Gyro/Accel(LN mode) 52 | ODR_1KHZ Support: Gyro/Accel(LN mode) 53 | ODR_200HZ Support: Gyro/Accel(LP or LN mode) 54 | ODR_100HZ Support: Gyro/Accel(LP or LN mode) 55 | ODR_50HZ Support: Gyro/Accel(LP or LN mode) 56 | ODR_25KHZ Support: Gyro/Accel(LP or LN mode) 57 | ODR_12_5KHZ Support: Gyro/Accel(LP or LN mode) 58 | ODR_6_25KHZ Support: Accel(LP mode) 59 | ODR_3_125HZ Support: Accel(LP mode) 60 | ODR_1_5625HZ Support: Accel(LP mode) 61 | ODR_500HZ Support: Accel(LP or LN mode) 62 | FSR Full-scale range 63 | FSR_0 Gyro:±2000dps / Accel: ±16g 64 | FSR_1 Gyro:±1000dps / Accel: ±8g 65 | FSR_2 Gyro:±500dps / Accel: ±4g 66 | FSR_3 Gyro:±250dps / Accel: ±2g 67 | FSR_4 Gyro:±125dps / Accel: not optional 68 | FSR_5 Gyro:±62.5dps / Accel: not optional 69 | FSR_6 Gyro:±31.25dps / Accel: not optional 70 | FSR_7 Gyro:±15.625dps / Accel: not optional 71 | Return True indicate the setting succeed, Flase indicate selected parameter is wrong 72 | ''' 73 | while(ICM42688.set_ODR_and_FSR(ICM42688.GYRO,ICM42688.ODR_1KHZ,ICM42688.FSR_0)==False): 74 | print("Incorrect parameter passed in") 75 | while(ICM42688.set_ODR_and_FSR(ICM42688.ACCEL,ICM42688.ODR_1KHZ,ICM42688.FSR_0) == False): 76 | print("Incorrect parameter passed in") 77 | 78 | ''' 79 | Set gyroscope and accelerometer working mode and start measurement 80 | mode 81 | OFF_MODE 0 Disable 82 | STANDBY_MODE_ONLY_GYRO 1 Set stanby mode, only support gyroscope 83 | LP_MODE_ONLY_ACCEL 2 Set low-power mode, only support accelerometer 84 | LN_MODE 3 Set low-noise mode 85 | NOte: The accelerometer needs to be set to work in a mode compatible with the ODR. The gyroscope does not have low power mode. 86 | ''' 87 | ICM42688.start_gyro_measure(mode =ICM42688.LN_MODE) 88 | ICM42688.start_accel_measure(mode = ICM42688.LN_MODE) 89 | #Start temperature measurement 90 | ICM42688.start_temp_measure() 91 | 92 | def loop(): 93 | ''' 94 | Get temperature, accelerometer and gyroscope data 95 | Two methods of data acquisition: 96 | Obtain all measurement data at one time, which can effectively shorten communication time 97 | Single measurement data acquisition, only get the data you need 98 | ''' 99 | measure_data = ICM42688.get_all_measure_data() 100 | print("===========================================") 101 | print("Temperature: = %f C"%(measure_data[0])) 102 | print("Accel_X: = %f mg"%(measure_data[1])) 103 | print("Accel_Y: = %f mg"%(measure_data[2])) 104 | print("Accel_Z: = %f mg"%(measure_data[3])) 105 | print("Gyro_X: = %f dps"%(measure_data[4])) 106 | print("Gyro_Y: = %f dps"%(measure_data[5])) 107 | print("Gyro_Z: = %f dps"%(measure_data[6])) 108 | time.sleep(1) 109 | 110 | temp_data= ICM42688.get_temperature() 111 | accel_data_x = ICM42688.get_accel_x() 112 | accel_data_y= ICM42688.get_accel_y() 113 | accel_data_z= ICM42688.get_accel_z() 114 | gyro_data_x= ICM42688.get_gyro_x() 115 | gyro_data_y= ICM42688.get_gyro_y() 116 | gyro_data_z= ICM42688.get_gyro_z() 117 | print("===========================================") 118 | print("Temperature: = %f C"%(temp_data)) 119 | print("Accel_X: = %f mg"%(accel_data_x)) 120 | print("Accel_Y: = %f mg"%(accel_data_y)) 121 | print("Accel_Z: = %f mg"%(accel_data_z)) 122 | print("Gyro_X: = %f dps"%(gyro_data_x)) 123 | print("Gyro_Y: = %f dps"%(gyro_data_y)) 124 | print("Gyro_Z: = %f dps"%(gyro_data_z)) 125 | time.sleep(1) 126 | 127 | if __name__ == "__main__": 128 | setup() 129 | while True: 130 | loop() 131 | -------------------------------------------------------------------------------- /python/raspberrypi/examples/significan_motion_det.py: -------------------------------------------------------------------------------- 1 | # -*- coding:utf-8 -*- 2 | '''! 3 | @file significan_motion_det.py 4 | @brief Significant Motion Detection 5 | @n Experimental phenomenon: detect important motion interrupt, at an interval of 3s 6 | @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 7 | @licence The MIT License (MIT) 8 | @author [yangfeng] 9 | @version V1.0 10 | @date 2021-05-13 11 | @url https://github.com/DFRobot/DFRobot_ICM42688 12 | ''' 13 | import sys 14 | sys.path.append("../") # set system path to top 15 | import time 16 | from DFRobot_ICM42688 import * 17 | import RPi.GPIO as GPIO 18 | 19 | 20 | #Use I2C for communication 21 | ''' 22 | #Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default to internal pull up) 23 | #DFRobot_ICM42688_I2C_L_ADDR 0x68 24 | #DFRobot_ICM42688_I2C_H_ADDR 0x69 25 | ''' 26 | #ICM42688 = DFRobot_ICM42688_I2C(i2c_addr = DFRobot_ICM42688_I2C_H_ADDR) 27 | 28 | 29 | #Use SPI for communication 30 | RASPBERRY_PIN_CS = 27 #Chip selection pin when SPI is selected, BCM code mode, the code number is 27, corresponding to pin GPIO2 31 | ICM42688 = DFRobot_ICM42688_SPI(RASPBERRY_PIN_CS) 32 | 33 | global flag 34 | flag =0 35 | 36 | def int_callback(channel): 37 | global flag 38 | flag = 1 39 | 40 | def setup(): 41 | ret = ICM42688.begin() 42 | while(ret !=0): 43 | if(ret == -1): 44 | print("bus data access error") 45 | else: 46 | print("Chip versions do not match") 47 | time.sleep(1) 48 | ret = ICM42688.begin() 49 | 50 | print("ICM42688 begin success!!!") 51 | #Configure IO interface interrupt to be triggered on falling edge 52 | gpio_int = 26 53 | GPIO.setmode(GPIO.BCM) 54 | GPIO.setup(gpio_int, GPIO.IN) 55 | GPIO.add_event_detect(gpio_int, GPIO.FALLING, callback=int_callback) 56 | 57 | ''' 58 | Set interrupt mode 59 | INT_pin Interrupt :1 represents using INT1 interrupt pin; 2 represents using INT2 interrupt pin 60 | INT_mode Set interrupt mode, 1 represents interrupt lock mode (polarity remain unchanged when interrupt triggerred, and restore after clearing interrupt); 0 represents pulse mode 61 | INT_polarity Level polarity output by interrupt, 0 represents interrupt pin polarity is LOW when producing interrupt, 1 represents interrupt pin polarity is HIGH when producing interrupt 62 | INT_drive_circuit 0 represents Open drain 1 represents Push pull 63 | Note: Interrupt output polarity of the sensor needs to be set in line with the config controller interrupt detection mode above 64 | ''' 65 | ICM42688.set_INT_mode(INT_pin=2, INT_mode=0, INT_polarity=0, INT_drive_circuit=1) 66 | # Init motion wake on basic config, basic config of the WOM is the same as SWD, directly use ICM42688.wake_on_motion_init() 67 | ICM42688.wake_on_motion_init() 68 | ''' 69 | Set motion interrupt wake on threshold of axis accelerometer 70 | axis 71 | X_AXIS_WOM 72 | Y_AXIS_WOM 73 | Z_AXIS_WOM 74 | ALL 75 | threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 76 | ''' 77 | ICM42688.set_wom_thr(axis=ICM42688.ALL,threshold=98) 78 | ''' 79 | Set important motion detection mode and enable SMD interrupt 80 | mode 0: disable SMD 81 | 2 : SMD short (1 sec wait) An SMD event is detected when two WOM are detected 1 sec apart 82 | 3 : SMD long (3 sec wait) An SMD event is detected when two WOM are detected 3 sec apart 83 | ''' 84 | ICM42688.enable_SMD_interrupt(mode=3) 85 | 86 | def loop(): 87 | global flag 88 | if(flag == 1): 89 | flag = 0 90 | ''' 91 | Read interrupt information and clear interrupt 92 | reg Interrupt information register 93 | ICM42688_INT_STATUS2 Obtain interrupt information of SMD_INT, WOM_X_INT, WOM_Y_INT and WOM_Z_INT and clear them 94 | ICM42688_INT_STATUS3 Obtain interrupt information of STEP_DET_INT, STEP_CNT_OVF_INT, TILT_DET_INT, WAKE_INT and TAP_DET_INT and clear them 95 | Return interrupt information, return 0 when no interrupt 96 | 97 | ''' 98 | status= ICM42688.read_interrupt_status(reg= ICM42688_INT_STATUS2) 99 | if(status & ICM42688_SMD_INT): 100 | print("SMD_INT") 101 | 102 | if __name__ == "__main__": 103 | setup() 104 | while True: 105 | loop() 106 | -------------------------------------------------------------------------------- /python/raspberrypi/examples/tap.py: -------------------------------------------------------------------------------- 1 | # -*- coding:utf-8 -*- 2 | '''! 3 | @file DFRobot_Sensor.py 4 | @brief Tap detection 5 | @n Experimental phenomenon: determine tap event on each axis by interrupt 6 | @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 7 | @license The MIT License (MIT) 8 | @author [yangfeng] 9 | @version V1.0 10 | @date 2021-05-13 11 | @url https://github.com/DFRobot/DFRobot_ICM42688 12 | ''' 13 | import sys 14 | sys.path.append("../") # set system path to top 15 | import time 16 | from DFRobot_ICM42688 import * 17 | import RPi.GPIO as GPIO 18 | 19 | 20 | #Use I2C for communication 21 | ''' 22 | #Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default to internal pull up) 23 | #DFRobot_ICM42688_I2C_L_ADDR 0x68 24 | #DFRobot_ICM42688_I2C_H_ADDR 0x69 25 | ''' 26 | #ICM42688 = DFRobot_ICM42688_I2C(i2c_addr = DFRobot_ICM42688_I2C_H_ADDR) 27 | 28 | 29 | #Use SPI for communication 30 | RASPBERRY_PIN_CS = 27 #Chip selection pin when SPI is selected, BCM code mode, the code number is 27, corresponding to pin GPIO2 31 | ICM42688 = DFRobot_ICM42688_SPI(RASPBERRY_PIN_CS) 32 | 33 | global flag 34 | flag =0 35 | 36 | def int_callback(channel): 37 | global flag 38 | flag = 1 39 | 40 | def setup(): 41 | ret = ICM42688.begin() 42 | while(ret !=0): 43 | if(ret == -1): 44 | print("bus data access error") 45 | else: 46 | print("Chip versions do not match") 47 | time.sleep(1) 48 | ret = ICM42688.begin() 49 | 50 | #Configure IO interface interrupt to be triggered by falling edge 51 | print("ICM42688 begin success!!!") 52 | gpio_int = 26 53 | GPIO.setmode(GPIO.BCM) 54 | GPIO.setup(gpio_int, GPIO.IN) 55 | GPIO.add_event_detect(gpio_int, GPIO.FALLING, callback=int_callback) 56 | 57 | 58 | ''' 59 | Set interrupt mode 60 | INT_pin Interrupt pin : 1 represents using INT1 interrupt pin; 2 represents using INT2 interrupt pin 61 | INT_mode Set interrupt mode, 1 represents interrupt lock mode (polarity remain unchanged when interrupt triggered, and restore after clearing interrupt); 0 represents pulse mode 62 | INT_polarity Level polarity output by interrupt, 0 represents interrupt pin polarity is LOW when producing interrupt, 1 represents interrupt pin polarity is HIGH when producing interrupt 63 | INT_drive_circuit 0 represents Open drain 1 represents Push pull 64 | Note: Polarity output by sensor interrupt needs to be set in line with the config controller interrupt detection mode above 65 | ''' 66 | ICM42688.set_INT_mode(INT_pin=1, INT_mode=0, INT_polarity=0, INT_drive_circuit=1) 67 | ''' 68 | Tap detection init 69 | accel_mode Accelerometer operating mode: 0 for operating in low-power mode, 1 for operating in low-noise mode 70 | ''' 71 | ICM42688.tap_detection_init(accel_mode= 1) 72 | 73 | def loop(): 74 | global flag 75 | if(flag == 1): 76 | flag = 0 77 | ''' 78 | Read interrupt information and clear interrupt 79 | reg Interrupt information register 80 | ICM42688_INT_STATUS2 Obtain interrupt information of SMD_INT, WOM_X_INT, WOM_Y_INT and WOM_Z_INT and clear them 81 | ICM42688_INT_STATUS3 Obtain interrupt information of STEP_DET_INT, STEP_CNT_OVF_INT, TILT_DET_INT, WAKE_INT and TAP_DET_INT and clear them 82 | Interrupt information, return 0 when no interrupt 83 | ''' 84 | status= ICM42688.read_interrupt_status(reg= ICM42688_INT_STATUS3) 85 | if(status & ICM42688_TAP_DET_INT): 86 | #Get tap information 87 | ICM42688.get_tap_information() 88 | # Get the number of tap: single-tap or double tap 89 | tap_num = ICM42688.number_of_tap() 90 | #Get the axis on which tap occurred: X-axis, Y-axis, or Z-axis 91 | tap_axis = ICM42688.axis_of_tap() 92 | if(tap_axis == ICM42688.X_AXIS): 93 | print("X axis: "), 94 | elif(tap_axis == ICM42688.Y_AXIS): 95 | print("Y axis: "), 96 | elif(tap_axis == ICM42688.Z_AXIS): 97 | print("Z axis: "), 98 | if(tap_num == ICM42688.TAP_SINGLE): 99 | print("Single") 100 | elif(tap_num == ICM42688.TAP_DOUBLE): 101 | print("Double") 102 | 103 | if __name__ == "__main__": 104 | setup() 105 | while True: 106 | loop() 107 | -------------------------------------------------------------------------------- /python/raspberrypi/examples/wake_on_motion_det.py: -------------------------------------------------------------------------------- 1 | # -*- coding:utf-8 -*- 2 | '''! 3 | @file wake_on_motion_det.py 4 | @brief Wake on Motion Detection 5 | @n Experimental phenomenon: detect motion wake-on event on each axis through interrupt 6 | @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) 7 | @licence The MIT License (MIT) 8 | @author [yangfeng] 9 | @version V1.0 10 | @date 2021-05-13 11 | @url https://github.com/DFRobot/DFRobot_ICM42688 12 | ''' 13 | import sys 14 | sys.path.append("../") # set system path to top 15 | import time 16 | from DFRobot_ICM42688 import * 17 | import RPi.GPIO as GPIO 18 | 19 | 20 | #Use I2C for communication 21 | ''' 22 | #Device I2C address is decided by SDO, SDO pull up, address is 0x69, SDO pull down, address is 0x68 (SDO default internal pull up) 23 | #DFRobot_ICM42688_I2C_L_ADDR 0x68 24 | #DFRobot_ICM42688_I2C_H_ADDR 0x69 25 | ''' 26 | #ICM42688 = DFRobot_ICM42688_I2C(i2c_addr = DFRobot_ICM42688_I2C_H_ADDR) 27 | 28 | 29 | #Use SPI for communication 30 | RASPBERRY_PIN_CS = 27 #Chip selection pin when SPI is selected, BCM code mode, the code number is 27, corresponding to pin GPIO2 31 | ICM42688 = DFRobot_ICM42688_SPI(RASPBERRY_PIN_CS) 32 | 33 | global flag 34 | flag =0 35 | 36 | def int_callback(channel): 37 | global flag 38 | flag = 1 39 | 40 | def setup(): 41 | ret = ICM42688.begin() 42 | while(ret !=0): 43 | if(ret == -1): 44 | print("bus data access error") 45 | else: 46 | print("Chip versions do not match") 47 | time.sleep(1) 48 | ret = ICM42688.begin() 49 | 50 | print("ICM42688 begin success!!!") 51 | #Configure IO interface interrupt to be triggered by falling edge 52 | gpio_int = 26 53 | GPIO.setmode(GPIO.BCM) 54 | GPIO.setup(gpio_int, GPIO.IN) 55 | GPIO.add_event_detect(gpio_int, GPIO.FALLING, callback=int_callback) 56 | 57 | ''' 58 | Set interrupt mode 59 | INT_pin Interrupt pin : 1 represents using INT1 interrupt pin; 2 represents using INT2 interrupt pin 60 | INT_mode Set interrupt mode, 1 represents interrupt lock mode (polarity remain unchanged when interrupt triggered, and restore after clearing interrupt); 0 represents pulse mode 61 | INT_polarity Level polarity output by interrupt, 0 represents interrupt pin polarity is LOW when producing interrupt, 1 represents interrupt pin polarity is HIGH when producing interrupt 62 | INT_drive_circuit 0 represents Open drain 1 represents Push pull 63 | Note: Polarity output by sensor interrupt needs to be set in line with the config controller interrupt detection mode above 64 | ''' 65 | ICM42688.set_INT_mode(INT_pin=1, INT_mode=0, INT_polarity=0, INT_drive_circuit=1) 66 | # Init motion wake on basic config, basic config of the WOM is same as SWD, directly use ICM42688.wake_on_motion_init() 67 | ICM42688.wake_on_motion_init() 68 | ''' 69 | Set motion interrupt wake on threshold of axis accelerometer 70 | axis 71 | X_AXIS_WOM 72 | Y_AXIS_WOM 73 | Z_AXIS_WOM 74 | ALL 75 | threshold Range(0-255) [WoM thresholds are expressed in fixed “mg” independent of the selected Range [0g : 1g]; Resolution 1g/256=~3.9mg] 76 | ''' 77 | ICM42688.set_wom_thr(axis=ICM42688.ALL,threshold=98) 78 | ''' 79 | Enable WOM interrupt of an axis 80 | axis 81 | X_AXIS_WOM 82 | Y_AXIS_WOM 83 | Z_AXIS_WOM 84 | ''' 85 | ICM42688.set_wom_interrupt(axis = ICM42688.X_AXIS_WOM|ICM42688.Y_AXIS_WOM|ICM42688.Z_AXIS_WOM) 86 | 87 | def loop(): 88 | global flag 89 | if(flag == 1): 90 | flag = 0 91 | ''' 92 | Read interrupt information and clear interrupt 93 | reg Interrupt information register 94 | ICM42688_INT_STATUS2 Obtain interrupt information of SMD_INT, WOM_X_INT, WOM_Y_INT and WOM_Z_INT and clear them 95 | ICM42688_INT_STATUS3 Obtain interrupt information of STEP_DET_INT, STEP_CNT_OVF_INT, TILT_DET_INT, WAKE_INT and TAP_DET_INT and clear them 96 | Interrupt information, return 0 when no interrupt 97 | ''' 98 | status= ICM42688.read_interrupt_status(reg= ICM42688_INT_STATUS2) 99 | if(status & ICM42688_WOM_X_INT): 100 | print("X_AXIS_WOM ") 101 | if(status & ICM42688_WOM_Y_INT): 102 | print("Y_AXIS_WOM ") 103 | if(status & ICM42688_WOM_Z_INT): 104 | print("Z_AXIS_WOM ") 105 | 106 | if __name__ == "__main__": 107 | setup() 108 | while True: 109 | loop() 110 | -------------------------------------------------------------------------------- /resources/images/SEN0245svg1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DFRobot/DFRobot_ICM42688/e2c9a0ebe983cb7aa218c1ba19c48c8aac6e8c4d/resources/images/SEN0245svg1.png --------------------------------------------------------------------------------