diff --git a/.github/workflows/build.yaml b/.github/workflows/build.yaml index 75ddc8d..26f90ef 100644 --- a/.github/workflows/build.yaml +++ b/.github/workflows/build.yaml @@ -33,6 +33,14 @@ jobs: run: cd examples/MPU9250 && arduino-cli compile --fqbn esp8266:esp8266:nodemcuv2 - name: Build MPU9250 example for Arduino Nano run: cd examples/MPU9250 && arduino-cli compile --fqbn arduino:avr:nano + - name: Build ICM20948 example for ESP32 + run: cd examples/ICM20948 && arduino-cli compile --fqbn esp32:esp32:esp32 + - name: Build ICM20948 example for ESP32 D1 Mini + run: cd examples/ICM20948 && arduino-cli compile --fqbn esp32:esp32:d1_mini32 + - name: Build ICM20948 example for ESP8266 + run: cd examples/ICM20948 && arduino-cli compile --fqbn esp8266:esp8266:nodemcuv2 + - name: Build ICM20948 example for Arduino Nano + run: cd examples/ICM20948 && arduino-cli compile --fqbn arduino:avr:nano - name: Build SBUS example for ESP32 run: cd examples/SBUS && arduino-cli compile --fqbn esp32:esp32:esp32 - name: Build SBUS example for ESP32 D1 Mini diff --git a/ICM20948.cpp b/ICM20948.cpp new file mode 100644 index 0000000..e81399e --- /dev/null +++ b/ICM20948.cpp @@ -0,0 +1,845 @@ +/* + * Code based on: https://github.com/wollewald/ICM20948_WE. + * Author: Wolfgang (Wolle) Ewald. + * License: MIT (see LICENSE file). + * Further information can be found on: + * https://wolles-elektronikkiste.de/icm-20948-9-achsensensor-teil-i (German) + * https://wolles-elektronikkiste.de/en/icm-20948-9-axis-sensor-part-i (English) +*/ + +#include "ICM20948.h" + +/************ Basic Settings ************/ + +bool ICM20948::begin() { + if (useSPI) { + _spi->begin(); + if (csPin == -1) { + // use default CS pin + #ifdef ESP32 + csPin = _spi->pinSS(); + #else + csPin = SS; + #endif + } + pinMode(csPin, OUTPUT); + digitalWrite(csPin, HIGH); + mySPISettings = SPISettings(7000000, MSBFIRST, SPI_MODE0); + } + currentBank = 0; + + reset(); + if (whoAmI() != ICM20948_WHO_AM_I_CONTENT) { + delay(2000); + if (whoAmI() != ICM20948_WHO_AM_I_CONTENT){ + log("Error: incorrect WHO_AM_I value: 0x%02X", whoAmI()); + return false; + } + } + + accRangeFactor = 1.0; + gyrRangeFactor = 1.0; + fifoType = ICM20948_FIFO_ACC; + + sleep(false); + writeRegister8(2, ICM20948_ODR_ALIGN_EN, 1); // aligns ODR + + initMagnetometer(); + + return true; +} + +uint8_t ICM20948::whoAmI() { + return readRegister8(0, ICM20948_WHO_AM_I); +} + +void ICM20948::enableAcc(bool enAcc) { + regVal = readRegister8(0, ICM20948_PWR_MGMT_2); + if (enAcc) { + regVal &= ~ICM20948_ACC_EN; + } else { + regVal |= ICM20948_ACC_EN; + } + writeRegister8(0, ICM20948_PWR_MGMT_2, regVal); +} + +bool ICM20948::setAccelRange(const AccelRange range) { + int accRange; + switch (range) { + case ACCEL_RANGE_MIN: + case ACCEL_RANGE_2G: + accRange = ICM20948_ACC_RANGE_2G; + break; + case ACCEL_RANGE_4G: + accRange = ICM20948_ACC_RANGE_4G; + break; + case ACCEL_RANGE_8G: + accRange = ICM20948_ACC_RANGE_8G; + break; + case ACCEL_RANGE_16G: + accRange = ICM20948_ACC_RANGE_16G; + break; + default: + log("Unsupported accel range: %d", range); + return false; + } + regVal = readRegister8(2, ICM20948_ACCEL_CONFIG); + regVal &= ~(0x06); + regVal |= (accRange<<1); + writeRegister8(2, ICM20948_ACCEL_CONFIG, regVal); + accRangeFactor = 1<(((buffer[0]) << 8) | buffer[1]) * 1.0; + y = static_cast(((buffer[2]) << 8) | buffer[3]) * 1.0; + z = static_cast(((buffer[4]) << 8) | buffer[5]) * 1.0; + // raw to g + x = x * accRangeFactor / 16384.0; + y = y * accRangeFactor / 16384.0; + z = z * accRangeFactor / 16384.0; + // convert to m/s^2 + static constexpr float G = 9.80665f; + x = x * G; + y = y * G; + z = z * G; + // orient axes to match MPU9250 library + // TODO: switch to internal accel and gyro axes + double tmp = x; + x = y; + y = tmp; + z = -z; +} + +float ICM20948::getTemp() const { + int16_t rawTemp = static_cast(((buffer[12]) << 8) | buffer[13]); + float tmp = (rawTemp*1.0 - ICM20948_ROOM_TEMP_OFFSET)/ICM20948_T_SENSITIVITY + 21.0; + return tmp; +} + +void ICM20948::getGyro(float& x, float& y, float& z) const { + x = (int16_t)(((buffer[6]) << 8) | buffer[7]) * 1.0; + y = (int16_t)(((buffer[8]) << 8) | buffer[9]) * 1.0; + z = (int16_t)(((buffer[10]) << 8) | buffer[11]) * 1.0; + // raw to dps + x = x * gyrRangeFactor * 250.0 / 32768.0; + y = y * gyrRangeFactor * 250.0 / 32768.0; + z = z * gyrRangeFactor * 250.0 / 32768.0; + // convert to rad/s + x = x * DEG_TO_RAD; + y = y * DEG_TO_RAD; + z = z * DEG_TO_RAD; + // orient axes to match MPU9250 library + // TODO: switch to internal accel and gyro axes + double tmp = x; + x = y; + y = tmp; + z = -z; +} + +void ICM20948::getMag(float& x, float& y, float& z) const { + x = static_cast((buffer[15]) << 8) | buffer[14]; + y = static_cast((buffer[17]) << 8) | buffer[16]; + z = static_cast((buffer[19]) << 8) | buffer[18]; + // correct values + x = x * AK09916_MAG_LSB; + y = y * AK09916_MAG_LSB; + z = z * AK09916_MAG_LSB; + // orient axes to match MPU9250 library + // TODO: switch to internal accel and gyro axes + double tmp = x; + x = -y; + y = tmp; + z = z; +} + + +/********* Power, Sleep, Standby *********/ + +void ICM20948::enableCycle(ICM20948_cycle cycle){ + regVal = readRegister8(0, ICM20948_LP_CONFIG); + regVal &= 0x0F; + regVal |= cycle; + + writeRegister8(0, ICM20948_LP_CONFIG, regVal); +} + +void ICM20948::enableLowPower(bool enLP) { // vielleicht besser privat???? + regVal = readRegister8(0, ICM20948_PWR_MGMT_1); + if (enLP) { + regVal |= ICM20948_LP_EN; + } else { + regVal &= ~ICM20948_LP_EN; + } + writeRegister8(0, ICM20948_PWR_MGMT_1, regVal); +} + +void ICM20948::setGyrAverageInCycleMode(ICM20948_gyroAvgLowPower avg) { + writeRegister8(2, ICM20948_GYRO_CONFIG_2, avg); +} + +void ICM20948::setAccAverageInCycleMode(ICM20948_accAvgLowPower avg) { + writeRegister8(2, ICM20948_ACCEL_CONFIG_2, avg); +} + +void ICM20948::sleep(bool sleep) { + regVal = readRegister8(0, ICM20948_PWR_MGMT_1); + if(sleep) { + regVal |= ICM20948_SLEEP; + } else { + regVal &= ~ICM20948_SLEEP; + } + writeRegister8(0, ICM20948_PWR_MGMT_1, regVal); +} + +/************** Interrupts ***************/ + +void ICM20948::setIntPinPolarity(ICM20948_intPinPol pol) { + regVal = readRegister8(0, ICM20948_INT_PIN_CFG); + if (pol) { + regVal |= ICM20948_INT1_ACTL; + } else { + regVal &= ~ICM20948_INT1_ACTL; + } + writeRegister8(0, ICM20948_INT_PIN_CFG, regVal); +} + +void ICM20948::enableIntLatch(bool latch) { + regVal = readRegister8(0, ICM20948_INT_PIN_CFG); + if (latch) { + regVal |= ICM20948_INT_1_LATCH_EN; + } else { + regVal &= ~ICM20948_INT_1_LATCH_EN; + } + writeRegister8(0, ICM20948_INT_PIN_CFG, regVal); +} + +void ICM20948::enableClearIntByAnyRead(bool clearByAnyRead) { + regVal = readRegister8(0, ICM20948_INT_PIN_CFG); + if (clearByAnyRead){ + regVal |= ICM20948_INT_ANYRD_2CLEAR; + } else { + regVal &= ~ICM20948_INT_ANYRD_2CLEAR; + } + writeRegister8(0, ICM20948_INT_PIN_CFG, regVal); +} + +void ICM20948::setFSyncIntPolarity(ICM20948_intPinPol pol) { + regVal = readRegister8(0, ICM20948_INT_PIN_CFG); + if (pol) { + regVal |= ICM20948_ACTL_FSYNC; + } else{ + regVal &= ~ICM20948_ACTL_FSYNC; + } + writeRegister8(0, ICM20948_INT_PIN_CFG, regVal); +} + +void ICM20948::enableInterrupt(ICM20948_intType intType) { + switch(intType){ + case ICM20948_FSYNC_INT: + regVal = readRegister8(0, ICM20948_INT_PIN_CFG); + regVal |= ICM20948_FSYNC_INT_MODE_EN; + writeRegister8(0, ICM20948_INT_PIN_CFG, regVal); // enable FSYNC as interrupt pin + regVal = readRegister8(0, ICM20948_INT_ENABLE); + regVal |= 0x80; + writeRegister8(0, ICM20948_INT_ENABLE, regVal); // enable wake on FSYNC interrupt + break; + + case ICM20948_WOM_INT: + regVal = readRegister8(0, ICM20948_INT_ENABLE); + regVal |= 0x08; + writeRegister8(0, ICM20948_INT_ENABLE, regVal); + regVal = readRegister8(2, ICM20948_ACCEL_INTEL_CTRL); + regVal |= 0x02; + writeRegister8(2, ICM20948_ACCEL_INTEL_CTRL, regVal); + break; + + case ICM20948_DMP_INT: + regVal = readRegister8(0, ICM20948_INT_ENABLE); + regVal |= 0x02; + writeRegister8(0, ICM20948_INT_ENABLE, regVal); + break; + + case ICM20948_DATA_READY_INT: + writeRegister8(0, ICM20948_INT_ENABLE_1, 0x01); + break; + + case ICM20948_FIFO_OVF_INT: + writeRegister8(0, ICM20948_INT_ENABLE_2, 0x01); + break; + + case ICM20948_FIFO_WM_INT: + writeRegister8(0, ICM20948_INT_ENABLE_3, 0x01); + break; + } +} + +void ICM20948::disableInterrupt(ICM20948_intType intType) { + switch (intType) { + case ICM20948_FSYNC_INT: + regVal = readRegister8(0, ICM20948_INT_PIN_CFG); + regVal &= ~ICM20948_FSYNC_INT_MODE_EN; + writeRegister8(0, ICM20948_INT_PIN_CFG, regVal); + regVal = readRegister8(0, ICM20948_INT_ENABLE); + regVal &= ~(0x80); + writeRegister8(0, ICM20948_INT_ENABLE, regVal); + break; + + case ICM20948_WOM_INT: + regVal = readRegister8(0, ICM20948_INT_ENABLE); + regVal &= ~(0x08); + writeRegister8(0, ICM20948_INT_ENABLE, regVal); + regVal = readRegister8(2, ICM20948_ACCEL_INTEL_CTRL); + regVal &= ~(0x02); + writeRegister8(2, ICM20948_ACCEL_INTEL_CTRL, regVal); + break; + + case ICM20948_DMP_INT: + regVal = readRegister8(0, ICM20948_INT_ENABLE); + regVal &= ~(0x02); + writeRegister8(0, ICM20948_INT_ENABLE, regVal); + break; + + case ICM20948_DATA_READY_INT: + writeRegister8(0, ICM20948_INT_ENABLE_1, 0x00); + break; + + case ICM20948_FIFO_OVF_INT: + writeRegister8(0, ICM20948_INT_ENABLE_2, 0x00); + break; + + case ICM20948_FIFO_WM_INT: + writeRegister8(0, ICM20948_INT_ENABLE_3, 0x00); + break; + } +} + +uint8_t ICM20948::readAndClearInterrupts() { + uint8_t intSource = 0; + regVal = readRegister8(0, ICM20948_I2C_MST_STATUS); + if (regVal & 0x80) { + intSource |= 0x01; + } + regVal = readRegister8(0, ICM20948_INT_STATUS); + if (regVal & 0x08) { + intSource |= 0x02; + } + if (regVal & 0x02) { + intSource |= 0x04; + } + regVal = readRegister8(0, ICM20948_INT_STATUS_1); + if (regVal & 0x01) { + intSource |= 0x08; + } + regVal = readRegister8(0, ICM20948_INT_STATUS_2); + if (regVal & 0x01) { + intSource |= 0x10; + } + regVal = readRegister8(0, ICM20948_INT_STATUS_3); + if (regVal & 0x01) { + intSource |= 0x20; + } + return intSource; +} + +bool ICM20948::checkInterrupt(uint8_t source, ICM20948_intType type) { + source &= type; + return source; +} + +void ICM20948::setWakeOnMotionThreshold(uint8_t womThresh, ICM20948_womCompEn womCompEn) { + regVal = readRegister8(2, ICM20948_ACCEL_INTEL_CTRL); + if(womCompEn) { + regVal |= 0x01; + } else { + regVal &= ~(0x01); + } + writeRegister8(2, ICM20948_ACCEL_INTEL_CTRL, regVal); + writeRegister8(2, ICM20948_ACCEL_WOM_THR, womThresh); +} + +/***************** FIFO ******************/ + +void ICM20948::enableFifo(bool fifo) { + regVal = readRegister8(0, ICM20948_USER_CTRL); + if (fifo) { + regVal |= ICM20948_FIFO_EN; + } else { + regVal &= ~ICM20948_FIFO_EN; + } + writeRegister8(0, ICM20948_USER_CTRL, regVal); +} + +void ICM20948::setFifoMode(ICM20948_fifoMode mode) { + if (mode) { + regVal = 0x01; + } else { + regVal = 0x00; + } + writeRegister8(0, ICM20948_FIFO_MODE, regVal); +} + +void ICM20948::startFifo(ICM20948_fifoType fifo) { + fifoType = fifo; + writeRegister8(0, ICM20948_FIFO_EN_2, fifoType); +} + +void ICM20948::stopFifo() { + writeRegister8(0, ICM20948_FIFO_EN_2, 0); +} + +void ICM20948::resetFifo() { + writeRegister8(0, ICM20948_FIFO_RST, 0x01); + writeRegister8(0, ICM20948_FIFO_RST, 0x00); +} + +int16_t ICM20948::getFifoCount() { + int16_t regVal16 = static_cast(readRegister16(0, ICM20948_FIFO_COUNT)); + return regVal16; +} + +int16_t ICM20948::getNumberOfFifoDataSets() { + int16_t numberOfSets = getFifoCount(); + + if ((fifoType == ICM20948_FIFO_ACC) || (fifoType == ICM20948_FIFO_GYR)) { + numberOfSets /= 6; + } else if (fifoType==ICM20948_FIFO_ACC_GYR) { + numberOfSets /= 12; + } + + return numberOfSets; +} + +void ICM20948::findFifoBegin() { + uint16_t count = getFifoCount(); + int16_t start = 0; + + if ((fifoType == ICM20948_FIFO_ACC) || (fifoType == ICM20948_FIFO_GYR)) { + start = count%6; + for(int i=0; i(readAK09916Register16(AK09916_WIA_1)); +} + +void ICM20948::setMagOpMode(AK09916_opMode opMode) { + writeAK09916Register8(AK09916_CNTL_2, opMode); + delay(10); + if(opMode!=AK09916_PWR_DOWN){ + enableMagDataRead(AK09916_HXL, 0x08); + } +} + +void ICM20948::resetMag() { + writeAK09916Register8(AK09916_CNTL_3, 0x01); + delay(100); +} + +/************************************************ + Private Functions +*************************************************/ + +void ICM20948::setClockToAutoSelect() { + regVal = readRegister8(0, ICM20948_PWR_MGMT_1); + regVal |= 0x01; + writeRegister8(0, ICM20948_PWR_MGMT_1, regVal); + delay(10); +} + +void ICM20948::switchBank(uint8_t newBank) { + if (newBank != currentBank) { + currentBank = newBank; + if (!useSPI) { + _wire->beginTransmission(i2cAddress); + _wire->write(ICM20948_REG_BANK_SEL); + _wire->write(currentBank<<4); + _wire->endTransmission(); + } else { + _spi->beginTransaction(mySPISettings); + digitalWrite(csPin, LOW); + _spi->transfer(ICM20948_REG_BANK_SEL); + _spi->transfer(currentBank<<4); + digitalWrite(csPin, HIGH); + _spi->endTransaction(); + } + } +} + +void ICM20948::writeRegister8(uint8_t bank, uint8_t reg, uint8_t val) { + switchBank(bank); + + if (!useSPI) { + _wire->beginTransmission(i2cAddress); + _wire->write(reg); + _wire->write(val); + _wire->endTransmission(); + } else { + _spi->beginTransaction(mySPISettings); + digitalWrite(csPin, LOW); + _spi->transfer(reg); + _spi->transfer(val); + digitalWrite(csPin, HIGH); + _spi->endTransaction(); + } +} + +void ICM20948::writeRegister16(uint8_t bank, uint8_t reg, int16_t val) { + switchBank(bank); + int8_t MSByte = static_cast((val>>8) & 0xFF); + uint8_t LSByte = val & 0xFF; + + if (!useSPI) { + _wire->beginTransmission(i2cAddress); + _wire->write(reg); + _wire->write(MSByte); + _wire->write(LSByte); + _wire->endTransmission(); + } else { + _spi->beginTransaction(mySPISettings); + digitalWrite(csPin, LOW); + _spi->transfer(reg); + _spi->transfer(val); + digitalWrite(csPin, HIGH); + _spi->endTransaction(); + } +} + +uint8_t ICM20948::readRegister8(uint8_t bank, uint8_t reg) { + switchBank(bank); + uint8_t regValue = 0; + + if(!useSPI){ + _wire->beginTransmission(i2cAddress); + _wire->write(reg); + _wire->endTransmission(false); + _wire->requestFrom(i2cAddress, static_cast(1)); + if(_wire->available()){ + regValue = _wire->read(); + } + } else { + reg |= 0x80; + _spi->beginTransaction(mySPISettings); + digitalWrite(csPin, LOW); + _spi->transfer(reg); + regValue = _spi->transfer(0x00); + digitalWrite(csPin, HIGH); + _spi->endTransaction(); + } + return regValue; +} + +int16_t ICM20948::readRegister16(uint8_t bank, uint8_t reg) { + switchBank(bank); + uint8_t MSByte = 0, LSByte = 0; + int16_t reg16Val = 0; + + if (!useSPI) { + _wire->beginTransmission(i2cAddress); + _wire->write(reg); + _wire->endTransmission(false); + _wire->requestFrom(i2cAddress, static_cast(2)); + if(_wire->available()){ + MSByte = _wire->read(); + LSByte = _wire->read(); + } + } else { + reg = reg | 0x80; + _spi->beginTransaction(mySPISettings); + digitalWrite(csPin, LOW); + _spi->transfer(reg); + MSByte = _spi->transfer(0x00); + LSByte = _spi->transfer(0x00); + digitalWrite(csPin, HIGH); + _spi->endTransaction(); + } + reg16Val = (MSByte<<8) + LSByte; + return reg16Val; +} + +void ICM20948::readAllData(uint8_t* data) { + switchBank(0); + + if(!useSPI){ + _wire->beginTransmission(i2cAddress); + _wire->write(ICM20948_ACCEL_OUT); + _wire->endTransmission(false); + _wire->requestFrom(i2cAddress, static_cast(20)); + if(_wire->available()){ + for(int i=0; i<20; i++){ + data[i] = _wire->read(); + } + } + } + else{ + uint8_t reg = ICM20948_ACCEL_OUT | 0x80; + _spi->beginTransaction(mySPISettings); + digitalWrite(csPin, LOW); + _spi->transfer(reg); + for(int i=0; i<20; i++){ + data[i] = _spi->transfer(0x00); + } + digitalWrite(csPin, HIGH); + _spi->endTransaction(); + } +} + +void ICM20948::writeAK09916Register8(uint8_t reg, uint8_t val) { + writeRegister8(3, ICM20948_I2C_SLV0_ADDR, AK09916_ADDRESS); // write AK09916 + writeRegister8(3, ICM20948_I2C_SLV0_REG, reg); // define AK09916 register to be written to + writeRegister8(3, ICM20948_I2C_SLV0_DO, val); +} + + +uint8_t ICM20948::readAK09916Register8(uint8_t reg) { + enableMagDataRead(reg, 0x01); + enableMagDataRead(AK09916_HXL, 0x08); + regVal = readRegister8(0, ICM20948_EXT_SLV_SENS_DATA_00); + return regVal; +} + +int16_t ICM20948::readAK09916Register16(uint8_t reg) { + int16_t regValue = 0; + enableMagDataRead(reg, 0x02); + regValue = readRegister16(0, ICM20948_EXT_SLV_SENS_DATA_00); + enableMagDataRead(AK09916_HXL, 0x08); + return regValue; +} + +void ICM20948::reset() { + writeRegister8(0, ICM20948_PWR_MGMT_1, ICM20948_RESET); + delay(10); // wait for registers to reset +} + +void ICM20948::enableI2CMaster() { + writeRegister8(0, ICM20948_USER_CTRL, ICM20948_I2C_MST_EN); //enable I2C master + writeRegister8(3, ICM20948_I2C_MST_CTRL, 0x07); // set I2C clock to 345.60 kHz + delay(10); +} + +void ICM20948::i2cMasterReset() { + uint8_t regVal = readRegister8(0, ICM20948_USER_CTRL); + regVal |= ICM20948_I2C_MST_RST; + writeRegister8(0, ICM20948_USER_CTRL, regVal); + delay(10); +} + +void ICM20948::enableMagDataRead(uint8_t reg, uint8_t bytes) { + writeRegister8(3, ICM20948_I2C_SLV0_ADDR, AK09916_ADDRESS | AK09916_READ); // read AK09916 + writeRegister8(3, ICM20948_I2C_SLV0_REG, reg); // define AK09916 register to be read + writeRegister8(3, ICM20948_I2C_SLV0_CTRL, 0x80 | bytes); //enable read | number of byte + delay(10); +} diff --git a/ICM20948.h b/ICM20948.h new file mode 100644 index 0000000..da4438d --- /dev/null +++ b/ICM20948.h @@ -0,0 +1,308 @@ +/* + * Code based on: https://github.com/wollewald/ICM20948_WE. + * Author: Wolfgang (Wolle) Ewald. + * License: MIT (see LICENSE file). + * Further information can be found on: + * https://wolles-elektronikkiste.de/icm-20948-9-achsensensor-teil-i (German) + * https://wolles-elektronikkiste.de/en/icm-20948-9-axis-sensor-part-i (English) +*/ + +#pragma once + +#include "Arduino.h" +#include +#include + +#include "IMU.h" +#include "logger.h" + +/* Enums */ + +typedef enum ICM20948_CYCLE { + ICM20948_NO_CYCLE = 0x00, + ICM20948_GYR_CYCLE = 0x10, + ICM20948_ACC_CYCLE = 0x20, + ICM20948_ACC_GYR_CYCLE = 0x30, + ICM20948_ACC_GYR_I2C_MST_CYCLE = 0x70 +} ICM20948_cycle; + +typedef enum ICM20948_INT_PIN_POL { + ICM20948_ACT_HIGH, ICM20948_ACT_LOW +} ICM20948_intPinPol; + +typedef enum ICM20948_INT_TYPE { + ICM20948_FSYNC_INT = 0x01, + ICM20948_WOM_INT = 0x02, + ICM20948_DMP_INT = 0x04, + ICM20948_DATA_READY_INT = 0x08, + ICM20948_FIFO_OVF_INT = 0x10, + ICM20948_FIFO_WM_INT = 0x20 +} ICM20948_intType; + +typedef enum ICM20948_FIFO_TYPE { + ICM20948_FIFO_ACC = 0x10, + ICM20948_FIFO_GYR = 0x0E, + ICM20948_FIFO_ACC_GYR = 0x1E +} ICM20948_fifoType; + +typedef enum ICM20948_FIFO_MODE_CHOICE { + ICM20948_CONTINUOUS, ICM20948_STOP_WHEN_FULL +} ICM20948_fifoMode; + +typedef enum ICM20948_GYRO_RANGE { + ICM20948_GYRO_RANGE_250, ICM20948_GYRO_RANGE_500, ICM20948_GYRO_RANGE_1000, ICM20948_GYRO_RANGE_2000 +} ICM20948_gyroRange; + +typedef enum ICM20948_DLPF { + ICM20948_DLPF_0, ICM20948_DLPF_1, ICM20948_DLPF_2, ICM20948_DLPF_3, ICM20948_DLPF_4, ICM20948_DLPF_5, + ICM20948_DLPF_6, ICM20948_DLPF_7, ICM20948_DLPF_OFF +} ICM20948_dlpf; + +typedef enum ICM20948_GYRO_AVG_LOW_PWR { + ICM20948_GYR_AVG_1, ICM20948_GYR_AVG_2, ICM20948_GYR_AVG_4, ICM20948_GYR_AVG_8, ICM20948_GYR_AVG_16, + ICM20948_GYR_AVG_32, ICM20948_GYR_AVG_64, ICM20948_GYR_AVG_128 +} ICM20948_gyroAvgLowPower; + +typedef enum ICM20948_ACC_RANGE { + ICM20948_ACC_RANGE_2G, ICM20948_ACC_RANGE_4G, ICM20948_ACC_RANGE_8G, ICM20948_ACC_RANGE_16G +} ICM20948_accRange; + +typedef enum ICM20948_ACC_AVG_LOW_PWR { + ICM20948_ACC_AVG_4, ICM20948_ACC_AVG_8, ICM20948_ACC_AVG_16, ICM20948_ACC_AVG_32 +} ICM20948_accAvgLowPower; + +typedef enum ICM20948_WOM_COMP { + ICM20948_WOM_COMP_DISABLE, ICM20948_WOM_COMP_ENABLE +} ICM20948_womCompEn; + +typedef enum AK09916_OP_MODE { + AK09916_PWR_DOWN = 0x00, + AK09916_TRIGGER_MODE = 0x01, + AK09916_CONT_MODE_10HZ = 0x02, + AK09916_CONT_MODE_20HZ = 0x04, + AK09916_CONT_MODE_50HZ = 0x06, + AK09916_CONT_MODE_100HZ = 0x08 +} AK09916_opMode; + +class ICM20948 : public IMUInterface, public Logger +{ +public: + /* constants */ + + static constexpr uint8_t AK09916_ADDRESS {0x0C}; + + /* Registers ICM20948 USER BANK 0*/ + static constexpr uint8_t ICM20948_WHO_AM_I {0x00}; + static constexpr uint8_t ICM20948_USER_CTRL {0x03}; + static constexpr uint8_t ICM20948_LP_CONFIG {0x05}; + static constexpr uint8_t ICM20948_PWR_MGMT_1 {0x06}; + static constexpr uint8_t ICM20948_PWR_MGMT_2 {0x07}; + static constexpr uint8_t ICM20948_INT_PIN_CFG {0x0F}; + static constexpr uint8_t ICM20948_INT_ENABLE {0x10}; + static constexpr uint8_t ICM20948_INT_ENABLE_1 {0x11}; + static constexpr uint8_t ICM20948_INT_ENABLE_2 {0x12}; + static constexpr uint8_t ICM20948_INT_ENABLE_3 {0x13}; + static constexpr uint8_t ICM20948_I2C_MST_STATUS {0x17}; + static constexpr uint8_t ICM20948_INT_STATUS {0x19}; + static constexpr uint8_t ICM20948_INT_STATUS_1 {0x1A}; + static constexpr uint8_t ICM20948_INT_STATUS_2 {0x1B}; + static constexpr uint8_t ICM20948_INT_STATUS_3 {0x1C}; + static constexpr uint8_t ICM20948_DELAY_TIME_H {0x28}; + static constexpr uint8_t ICM20948_DELAY_TIME_L {0x29}; + static constexpr uint8_t ICM20948_ACCEL_OUT {0x2D}; // accel data registers begin + static constexpr uint8_t ICM20948_GYRO_OUT {0x33}; // gyro data registers begin + static constexpr uint8_t ICM20948_TEMP_OUT {0x39}; + static constexpr uint8_t ICM20948_EXT_SLV_SENS_DATA_00{0x3B}; + static constexpr uint8_t ICM20948_EXT_SLV_SENS_DATA_01{0x3C}; + static constexpr uint8_t ICM20948_FIFO_EN_1 {0x66}; + static constexpr uint8_t ICM20948_FIFO_EN_2 {0x67}; + static constexpr uint8_t ICM20948_FIFO_RST {0x68}; + static constexpr uint8_t ICM20948_FIFO_MODE {0x69}; + static constexpr uint8_t ICM20948_FIFO_COUNT {0x70}; + static constexpr uint8_t ICM20948_FIFO_R_W {0x72}; + static constexpr uint8_t ICM20948_DATA_RDY_STATUS {0x74}; + static constexpr uint8_t ICM20948_FIFO_CFG {0x76}; + + /* Registers ICM20948 USER BANK 1*/ + static constexpr uint8_t ICM20948_SELF_TEST_X_GYRO {0x02}; + static constexpr uint8_t ICM20948_SELF_TEST_Y_GYRO {0x03}; + static constexpr uint8_t ICM20948_SELF_TEST_Z_GYRO {0x04}; + static constexpr uint8_t ICM20948_SELF_TEST_X_ACCEL {0x0E}; + static constexpr uint8_t ICM20948_SELF_TEST_Y_ACCEL {0x0F}; + static constexpr uint8_t ICM20948_SELF_TEST_Z_ACCEL {0x10}; + static constexpr uint8_t ICM20948_XA_OFFS_H {0x14}; + static constexpr uint8_t ICM20948_XA_OFFS_L {0x15}; + static constexpr uint8_t ICM20948_YA_OFFS_H {0x17}; + static constexpr uint8_t ICM20948_YA_OFFS_L {0x18}; + static constexpr uint8_t ICM20948_ZA_OFFS_H {0x1A}; + static constexpr uint8_t ICM20948_ZA_OFFS_L {0x1B}; + static constexpr uint8_t ICM20948_TIMEBASE_CORR_PLL {0x28}; + + /* Registers ICM20948 USER BANK 2*/ + static constexpr uint8_t ICM20948_GYRO_SMPLRT_DIV {0x00}; + static constexpr uint8_t ICM20948_GYRO_CONFIG_1 {0x01}; + static constexpr uint8_t ICM20948_GYRO_CONFIG_2 {0x02}; + static constexpr uint8_t ICM20948_XG_OFFS_USRH {0x03}; + static constexpr uint8_t ICM20948_XG_OFFS_USRL {0x04}; + static constexpr uint8_t ICM20948_YG_OFFS_USRH {0x05}; + static constexpr uint8_t ICM20948_YG_OFFS_USRL {0x06}; + static constexpr uint8_t ICM20948_ZG_OFFS_USRH {0x07}; + static constexpr uint8_t ICM20948_ZG_OFFS_USRL {0x08}; + static constexpr uint8_t ICM20948_ODR_ALIGN_EN {0x09}; + static constexpr uint8_t ICM20948_ACCEL_SMPLRT_DIV_1 {0x10}; + static constexpr uint8_t ICM20948_ACCEL_SMPLRT_DIV_2 {0x11}; + static constexpr uint8_t ICM20948_ACCEL_INTEL_CTRL {0x12}; + static constexpr uint8_t ICM20948_ACCEL_WOM_THR {0x13}; + static constexpr uint8_t ICM20948_ACCEL_CONFIG {0x14}; + static constexpr uint8_t ICM20948_ACCEL_CONFIG_2 {0x15}; + static constexpr uint8_t ICM20948_FSYNC_CONFIG {0x52}; + static constexpr uint8_t ICM20948_TEMP_CONFIG {0x53}; + static constexpr uint8_t ICM20948_MOD_CTRL_USR {0x54}; + + /* Registers ICM20948 USER BANK 3*/ + static constexpr uint8_t ICM20948_I2C_MST_ODR_CFG {0x00}; + static constexpr uint8_t ICM20948_I2C_MST_CTRL {0x01}; + static constexpr uint8_t ICM20948_I2C_MST_DELAY_CTRL {0x02}; + static constexpr uint8_t ICM20948_I2C_SLV0_ADDR {0x03}; + static constexpr uint8_t ICM20948_I2C_SLV0_REG {0x04}; + static constexpr uint8_t ICM20948_I2C_SLV0_CTRL {0x05}; + static constexpr uint8_t ICM20948_I2C_SLV0_DO {0x06}; + + /* Registers ICM20948 ALL BANKS */ + static constexpr uint8_t ICM20948_REG_BANK_SEL {0x7F}; + + /* Registers AK09916 */ + static constexpr uint8_t AK09916_WIA_1 {0x00}; // Who I am, Company ID + static constexpr uint8_t AK09916_WIA_2 {0x01}; // Who I am, Device ID + static constexpr uint8_t AK09916_STATUS_1 {0x10}; + static constexpr uint8_t AK09916_HXL {0x11}; + static constexpr uint8_t AK09916_HXH {0x12}; + static constexpr uint8_t AK09916_HYL {0x13}; + static constexpr uint8_t AK09916_HYH {0x14}; + static constexpr uint8_t AK09916_HZL {0x15}; + static constexpr uint8_t AK09916_HZH {0x16}; + static constexpr uint8_t AK09916_STATUS_2 {0x18}; + static constexpr uint8_t AK09916_CNTL_2 {0x31}; + static constexpr uint8_t AK09916_CNTL_3 {0x32}; + + /* Register Bits */ + static constexpr uint8_t ICM20948_RESET {0x80}; + static constexpr uint8_t ICM20948_I2C_MST_EN {0x20}; + static constexpr uint8_t ICM20948_SLEEP {0x40}; + static constexpr uint8_t ICM20948_LP_EN {0x20}; + static constexpr uint8_t ICM20948_BYPASS_EN {0x02}; + static constexpr uint8_t ICM20948_GYR_EN {0x07}; + static constexpr uint8_t ICM20948_ACC_EN {0x38}; + static constexpr uint8_t ICM20948_FIFO_EN {0x40}; + static constexpr uint8_t ICM20948_INT1_ACTL {0x80}; + static constexpr uint8_t ICM20948_INT_1_LATCH_EN {0x20}; + static constexpr uint8_t ICM20948_ACTL_FSYNC {0x08}; + static constexpr uint8_t ICM20948_INT_ANYRD_2CLEAR {0x10}; + static constexpr uint8_t ICM20948_FSYNC_INT_MODE_EN {0x06}; + static constexpr uint8_t AK09916_16_BIT {0x10}; + static constexpr uint8_t AK09916_OVF {0x08}; + static constexpr uint8_t AK09916_READ {0x80}; + + /* Others */ + static constexpr uint16_t AK09916_WHO_AM_I_1 {0x4809}; + static constexpr uint16_t AK09916_WHO_AM_I_2 {0x0948}; + static constexpr uint8_t ICM20948_WHO_AM_I_CONTENT{0xEA}; + static constexpr float ICM20948_ROOM_TEMP_OFFSET {0.0}; + static constexpr float ICM20948_T_SENSITIVITY {333.87}; + static constexpr float AK09916_MAG_LSB {0.1495}; + static constexpr uint8_t ICM20948_I2C_MST_RST {0x02}; + + /* Constructors */ + ICM20948(uint8_t addr = 0x68) : _wire{&Wire}, i2cAddress{addr}, useSPI{false} {} + ICM20948(TwoWire *w, uint8_t addr = 0x68) : _wire{w}, i2cAddress{addr}, useSPI{false} {} + ICM20948(SPIClass& s, int cs = -1) : _spi{&s}, csPin{cs}, useSPI{true} {} + + bool begin() override; + void reset() override; + uint8_t whoAmI() override; + const char* getModel() const override { return "ICM20948"; } + void enableAcc(bool enAcc); + bool setAccelRange(const AccelRange range) override; + void setAccRange(ICM20948_accRange accRange); + void setAccDLPF(ICM20948_dlpf dlpf); + void setAccSampleRateDivider(uint16_t accSplRateDiv); + void enableGyr(bool enGyr); + bool setGyroRange(const GyroRange range) override; + void setGyrRange(ICM20948_gyroRange gyroRange); + void setGyrDLPF(ICM20948_dlpf dlpf); + void setGyrSampleRateDivider(uint8_t gyrSplRateDiv); + void setTempDLPF(ICM20948_dlpf dlpf); + bool setDLPF(const DLPF dlpf) override; + void setI2CMstSampleRate(uint8_t rateExp); + void setSPIClockSpeed(unsigned long clock); + bool setRate(const Rate rate) override; + + /* Results */ + bool read() override; + void waitForData() override; + void getAccel(float& x, float& y, float& z) const override; + float getTemp() const override; + void getGyro(float& x, float& y, float& z) const override; + void getMag(float& x, float& y, float& z) const override; + + /* Power, Sleep, Standby */ + void enableCycle(ICM20948_cycle cycle); + void enableLowPower(bool enLP); + void setGyrAverageInCycleMode(ICM20948_gyroAvgLowPower avg); + void setAccAverageInCycleMode(ICM20948_accAvgLowPower avg); + void sleep(bool sleep); + + /* Interrupts */ + void setIntPinPolarity(ICM20948_intPinPol pol); + void enableIntLatch(bool latch); + void enableClearIntByAnyRead(bool clearByAnyRead); + void setFSyncIntPolarity(ICM20948_intPinPol pol); + void enableInterrupt(ICM20948_intType intType); + void disableInterrupt(ICM20948_intType intType); + uint8_t readAndClearInterrupts(); + bool checkInterrupt(uint8_t source, ICM20948_intType type); + void setWakeOnMotionThreshold(uint8_t womThresh, ICM20948_womCompEn womCompEn); + + /* FIFO */ + void enableFifo(bool fifo); + void setFifoMode(ICM20948_fifoMode mode); + void startFifo(ICM20948_fifoType fifo); + void stopFifo(); + void resetFifo(); + int16_t getFifoCount(); + int16_t getNumberOfFifoDataSets(); + void findFifoBegin(); + + /* Magnetometer */ + bool initMagnetometer(); + uint16_t whoAmIMag(); + void setMagOpMode(AK09916_opMode opMode); + void resetMag(); + +protected: + TwoWire *_wire; + SPIClass *_spi; + SPISettings mySPISettings; + uint8_t i2cAddress; + uint8_t currentBank; + uint8_t buffer[20]; + uint8_t accRangeFactor; + uint8_t gyrRangeFactor; + uint8_t regVal; // intermediate storage of register values + ICM20948_fifoType fifoType; + int csPin; + bool useSPI; + void setClockToAutoSelect(); + void switchBank(uint8_t newBank); + void writeRegister8(uint8_t bank, uint8_t reg, uint8_t val); + void writeRegister16(uint8_t bank, uint8_t reg, int16_t val); + uint8_t readRegister8(uint8_t bank, uint8_t reg); + int16_t readRegister16(uint8_t bank, uint8_t reg); + void readAllData(uint8_t* data); + void writeAK09916Register8(uint8_t reg, uint8_t val); + uint8_t readAK09916Register8(uint8_t reg); + int16_t readAK09916Register16(uint8_t reg); + void enableI2CMaster(); + void i2cMasterReset(); + void enableMagDataRead(uint8_t reg, uint8_t bytes); +}; diff --git a/IMU.h b/IMU.h new file mode 100644 index 0000000..0327fb7 --- /dev/null +++ b/IMU.h @@ -0,0 +1,56 @@ +#pragma once + +#include "Arduino.h" +#include "Wire.h" +#include "SPI.h" + +// IMU driver interface + +class IMUInterface { +public: + enum DLPF { + DLPF_OFF, + DLPF_MAX, + DLPF_100HZ_APPROX, + DLPF_50HZ_APPROX, + DLPF_5HZ_APPROX, + DLPF_MIN + }; + enum AccelRange { + ACCEL_RANGE_MIN, + ACCEL_RANGE_2G, + ACCEL_RANGE_4G, + ACCEL_RANGE_8G, + ACCEL_RANGE_16G, + ACCEL_RANGE_MAX + }; + enum GyroRange { + GYRO_RANGE_MIN, + GYRO_RANGE_250DPS, + GYRO_RANGE_500DPS, + GYRO_RANGE_1000DPS, + GYRO_RANGE_2000DPS, + GYRO_RANGE_MAX + }; + enum Rate { + RATE_MIN, + RATE_50HZ_APPROX, + RATE_1KHZ_APPROX, + RATE_8KHZ_APPROX, + RATE_MAX + }; + virtual bool begin() = 0; + virtual void reset() = 0; + virtual uint8_t whoAmI() = 0; + virtual bool read() = 0; + virtual void waitForData() = 0; + virtual void getAccel(float& x, float& y, float& z) const = 0; + virtual void getGyro(float& x, float& y, float& z) const = 0; + virtual void getMag(float& x, float& y, float& z) const = 0; + virtual float getTemp() const = 0; + virtual bool setRate(const Rate rate) = 0; + virtual bool setAccelRange(const AccelRange range) = 0; + virtual bool setGyroRange(const GyroRange range) = 0; + virtual bool setDLPF(const DLPF dlpf) = 0; + virtual const char* getModel() const = 0; +}; diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..289dc1b --- /dev/null +++ b/LICENSE @@ -0,0 +1,73 @@ +The MIT License (MIT) + +Copyright (c) 2024 Oleg Kalachev + +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: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +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. + +================================================================================ + +Bolder Flight libraries license: + +The MIT License (MIT) + +Copyright (c) 2022 Bolder Flight Systems Inc + +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: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +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. + +================================================================================ + +ICM20948_WE library license: + +MIT License + +Copyright (c) 2021 Wolfgang (Wolle) Ewald + +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: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +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. diff --git a/LICENSE.md b/LICENSE.md deleted file mode 100644 index 3aefdce..0000000 --- a/LICENSE.md +++ /dev/null @@ -1,10 +0,0 @@ -The MIT License (MIT) - -Copyright (c) 2022 Bolder Flight Systems Inc - -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: - -The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. - -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. - diff --git a/MPU9250.cpp b/MPU9250.cpp index 1abb464..1741ba2 100644 --- a/MPU9250.cpp +++ b/MPU9250.cpp @@ -194,29 +194,27 @@ bool MPU9250::setAccelRange(const AccelRange range) { spi_clock_ = SPI_CFG_CLOCK_; /* Check input is valid and set requested range and scale */ switch (range) { - case ACCEL_RANGE_2G: { - requested_accel_range_ = range; + case ACCEL_RANGE_MIN: + case ACCEL_RANGE_2G: + requested_accel_range_ = 0x00; requested_accel_scale_ = 2.0f / 32767.5f; break; - } - case ACCEL_RANGE_4G: { - requested_accel_range_ = range; + case ACCEL_RANGE_4G: + requested_accel_range_ = 0x08; requested_accel_scale_ = 4.0f / 32767.5f; break; - } - case ACCEL_RANGE_8G: { - requested_accel_range_ = range; + case ACCEL_RANGE_8G: + requested_accel_range_ = 0x10; requested_accel_scale_ = 8.0f / 32767.5f; break; - } - case ACCEL_RANGE_16G: { - requested_accel_range_ = range; + case ACCEL_RANGE_MAX: + case ACCEL_RANGE_16G: + requested_accel_range_ = 0x18; requested_accel_scale_ = 16.0f / 32767.5f; break; - } - default: { + default: + log("Unsupported accel range: %d", range); return false; - } } /* Try setting the requested range */ if (!WriteRegister(ACCEL_CONFIG_, requested_accel_range_)) { @@ -224,7 +222,7 @@ bool MPU9250::setAccelRange(const AccelRange range) { return false; } /* Update stored range and scale */ - accel_range_ = requested_accel_range_; + accel_range_ = range; accel_scale_ = requested_accel_scale_; return true; } @@ -232,29 +230,26 @@ bool MPU9250::setGyroRange(const GyroRange range) { spi_clock_ = SPI_CFG_CLOCK_; /* Check input is valid and set requested range and scale */ switch (range) { - case GYRO_RANGE_250DPS: { - requested_gyro_range_ = range; + case GYRO_RANGE_MIN: + case GYRO_RANGE_250DPS: + requested_gyro_range_ = 0x00; requested_gyro_scale_ = 250.0f / 32767.5f; break; - } - case GYRO_RANGE_500DPS: { - requested_gyro_range_ = range; + case GYRO_RANGE_500DPS: + requested_gyro_range_ = 0x08; requested_gyro_scale_ = 500.0f / 32767.5f; break; - } - case GYRO_RANGE_1000DPS: { - requested_gyro_range_ = range; + case GYRO_RANGE_1000DPS: + requested_gyro_range_ = 0x10; requested_gyro_scale_ = 1000.0f / 32767.5f; break; - } - case GYRO_RANGE_2000DPS: { - requested_gyro_range_ = range; + case GYRO_RANGE_2000DPS: + requested_gyro_range_ = 0x18; requested_gyro_scale_ = 2000.0f / 32767.5f; break; - } - default: { + default: + log("Unsupported gyro range: %d", range); return false; - } } /* Try setting the requested range */ if (!WriteRegister(GYRO_CONFIG_, requested_gyro_range_)) { @@ -262,7 +257,7 @@ bool MPU9250::setGyroRange(const GyroRange range) { return false; } /* Update stored range and scale */ - gyro_range_ = requested_gyro_range_; + gyro_range_ = range; gyro_scale_ = requested_gyro_scale_; return true; } @@ -305,6 +300,28 @@ bool MPU9250::setSrd(const uint8_t srd) { srd_ = srd; return true; } +bool MPU9250::setDLPF(const DLPF dlpf) { + DlpfBandwidth val; + switch (dlpf) { + case DLPF_OFF: + log("Disabling DLPF is not yet implemented"); + return false; + case DLPF_MAX: + val = DLPF_BANDWIDTH_184HZ; + break; + case DLPF_100HZ_APPROX: + val = DLPF_BANDWIDTH_92HZ; + break; + case DLPF_50HZ_APPROX: + val = DLPF_BANDWIDTH_41HZ; + break; + case DLPF_MIN: + case DLPF_5HZ_APPROX: + val = DLPF_BANDWIDTH_5HZ; + break; + } + return setDlpfBandwidth(val); +} bool MPU9250::setDlpfBandwidth(const DlpfBandwidth dlpf) { spi_clock_ = SPI_CFG_CLOCK_; /* Check input is valid and set requested dlpf */ @@ -471,7 +488,22 @@ void MPU9250::getMag(float& x, float& y, float& z) const { y = mag_[1]; z = mag_[2]; } -const char* MPU9250::getType() const { +bool MPU9250::setRate(const Rate rate) { + // TODO: consider DLPF setting (8 Khz possible without DLPF) + switch (rate) { + case RATE_MIN: + return setSrd(255); // ~4 Hz + case RATE_50HZ_APPROX: + return setSrd(19); // 50 Hz + case RATE_MAX: + case RATE_1KHZ_APPROX: + return setSrd(0); // 1 kHz + default: + log("Unsupported rate setting"); + return false; + } +} +const char* MPU9250::getModel() const { switch (who_am_i_) { case WHOAMI_MPU6500_: return "MPU-6500"; case WHOAMI_MPU9250_: return "MPU-9250"; diff --git a/MPU9250.h b/MPU9250.h index fa550fb..171a73b 100644 --- a/MPU9250.h +++ b/MPU9250.h @@ -35,10 +35,11 @@ #include #include "core/core.h" #endif +#include "IMU.h" #include "invensense_imu.h" // NOLINT #include "logger.h" -class MPU9250 : public Logger { +class MPU9250 : public IMUInterface, public Logger { public: /* Sensor and filter settings */ enum I2cAddr : uint8_t { @@ -53,18 +54,6 @@ class MPU9250 : public Logger { DLPF_BANDWIDTH_10HZ = 0x05, DLPF_BANDWIDTH_5HZ = 0x06 }; - enum AccelRange : int8_t { - ACCEL_RANGE_2G = 0x00, - ACCEL_RANGE_4G = 0x08, - ACCEL_RANGE_8G = 0x10, - ACCEL_RANGE_16G = 0x18 - }; - enum GyroRange : int8_t { - GYRO_RANGE_250DPS = 0x00, - GYRO_RANGE_500DPS = 0x08, - GYRO_RANGE_1000DPS = 0x10, - GYRO_RANGE_2000DPS = 0x18 - }; enum WomRate : int8_t { WOM_RATE_0_24HZ = 0x00, WOM_RATE_0_49HZ = 0x01, @@ -88,7 +77,7 @@ class MPU9250 : public Logger { imu_(&spi, cs) {} void config(TwoWire *i2c, const I2cAddr addr); void config(SPIClass *spi, const uint8_t cs); - bool begin(); + bool begin() override; bool enableDrdyInt(); bool disableDrdyInt(); bool setAccelRange(const AccelRange range); @@ -97,29 +86,22 @@ class MPU9250 : public Logger { inline GyroRange gyro_range() const {return gyro_range_;} bool setSrd(const uint8_t srd); inline uint8_t srd() const {return srd_;} + bool setDLPF(const DLPF dlpf) override; bool setDlpfBandwidth(const DlpfBandwidth dlpf); inline DlpfBandwidth dlpf_bandwidth() const {return dlpf_bandwidth_;} bool enableWom(int16_t threshold_mg, const WomRate wom_rate); - void reset(); - bool read(); - void waitForData(); - void getAccel(float& x, float& y, float& z) const; - void getGyro(float& x, float& y, float& z) const; - void getMag(float& x, float& y, float& z) const; - const char* getType() const; + void reset() override; + bool read() override; + void waitForData() override; + void getAccel(float& x, float& y, float& z) const override; + void getGyro(float& x, float& y, float& z) const override; + void getMag(float& x, float& y, float& z) const override; + bool setRate(const Rate rate) override; + const char* getModel() const override; inline bool new_imu_data() const {return new_imu_data_;} - inline float accel_x_mps2() const {return accel_[0];} - inline float accel_y_mps2() const {return accel_[1];} - inline float accel_z_mps2() const {return accel_[2];} - inline float gyro_x_radps() const {return gyro_[0];} - inline float gyro_y_radps() const {return gyro_[1];} - inline float gyro_z_radps() const {return gyro_[2];} inline bool new_mag_data() const {return new_mag_data_;} - inline float mag_x_ut() const {return mag_[0];} - inline float mag_y_ut() const {return mag_[1];} - inline float mag_z_ut() const {return mag_[2];} - inline float die_temp_c() const {return temp_;} - inline uint8_t whoAmI() const {return who_am_i_;} + inline float getTemp() const override {return temp_;} + inline uint8_t whoAmI() override {return who_am_i_;} private: InvensenseImu imu_; @@ -132,8 +114,9 @@ class MPU9250 : public Logger { static constexpr int32_t SPI_CFG_CLOCK_ = 1000000; static constexpr int32_t SPI_READ_CLOCK_ = 15000000; /* Configuration */ - AccelRange accel_range_, requested_accel_range_; - GyroRange gyro_range_, requested_gyro_range_; + AccelRange accel_range_; + GyroRange gyro_range_; + uint8_t requested_accel_range_, requested_gyro_range_; DlpfBandwidth dlpf_bandwidth_, requested_dlpf_; float accel_scale_, requested_accel_scale_; float gyro_scale_, requested_gyro_scale_; diff --git a/README.md b/README.md index ed442cb..ad6b716 100644 --- a/README.md +++ b/README.md @@ -6,8 +6,11 @@ Based on: * [Bolder Flight InvenSense-IMU library](https://github.com/bolderflight/invensense-imu). Original author: Brian Taylor (brian.taylor@bolderflight.com). * [Bolder Flight SBUS library](https://github.com/bolderflight/sbus). Original author: Brian Taylor (brian.taylor@bolderflight.com). +* [ICM20948_WE Arduino library](https://github.com/wollewald/ICM20948_WE/). Original author: Wolfgang Ewald (wolfgang.ewald@wolles-elektronikkiste.de). -## MPU-9250/MPU-6500 IMU +## IMU + +### MPU-9250/MPU-6500 Example for SPI-connected IMU: @@ -45,6 +48,16 @@ Notice, that MPU6500 does not include a magnetometer, so magnetometer data will You can also use `` header and `MPU6500` class, which is an alias for `MPU9250` class. +### ICM-20948 + +The ICM-20948 IMU driver has the same interface. Only the declaration is changed in the example above: + +```cpp +#include + +ICM20948 IMU(SPI); +``` + ### Connection Connecting GY-91 board to ESP32 using VSPI: @@ -65,6 +78,15 @@ Connecting MPU-92.65 board to ESP32 using VSPI: * AD0 (MISO) → IO19 * NCS → IO5 +Connecting ICM-20948 board to ESP32 using VSPI: + +* VCC → 3V3 +* GND → GND +* SCL → IO18 +* SDA (MOSI) → IO23 +* NCS → IO5 +* AD0 (MISO) → IO19 + ### Logging By default, the library logs some of the errors to the serial output. On ESP32, the default serial port is determined by the Core Debug Output mechanism, thus can be changed using `setDebugOutput` method: diff --git a/examples/ICM20948/ICM20948.ino b/examples/ICM20948/ICM20948.ino new file mode 100644 index 0000000..c818002 --- /dev/null +++ b/examples/ICM20948/ICM20948.ino @@ -0,0 +1,28 @@ +#include +#include + +ICM20948 IMU(SPI); // no need to specify CS pin, the default pin is used automatically + +void setup() { + Serial.begin(115200); + bool success = IMU.begin(); + if (!success) { + while (1) { + Serial.println("Failed to initialize IMU"); + delay(5000); + } + } +} + +void loop() { + float gx, gy, gz, ax, ay, az, mx, my, mz; + IMU.waitForData(); // blockingly read the data, use IMU.read() for non-blocking read + IMU.getGyro(gx, gy, gz); + IMU.getAccel(ax, ay, az); + IMU.getMag(mx, my, mz); + // Print data for Serial Plotter: + Serial.print("gx:"); Serial.print(gx); Serial.print(" gy:"); Serial.print(gy); Serial.print(" gz:"); Serial.print(gz); + Serial.print(" ax:"); Serial.print(ax); Serial.print(" ay:"); Serial.print(ay); Serial.print(" az:"); Serial.print(az); + Serial.print(" mx:"); Serial.print(mx); Serial.print(" my:"); Serial.print(my); Serial.print(" mz:"); Serial.println(mz); + delay(50); // slow down the output +}