/* 06/29/2017 Copyright Tlera Corporation * * Created by Kris Winer * * * Library may be used freely and without limit with attribution. * */ #include "USFS.h" USFS::USFS(uint8_t intPin, bool passThru) { pinMode(intPin, INPUT); _intPin = intPin; _passThru = passThru; } void USFS::getChipID() { // Read SENtral device information uint16_t ROM1 = readByte(EM7180_ADDRESS, EM7180_ROMVersion1); uint16_t ROM2 = readByte(EM7180_ADDRESS, EM7180_ROMVersion2); Serial.print("EM7180 ROM Version: 0x"); Serial.print(ROM1, HEX); Serial.println(ROM2, HEX); Serial.println("Should be: 0xE609"); uint16_t RAM1 = readByte(EM7180_ADDRESS, EM7180_RAMVersion1); uint16_t RAM2 = readByte(EM7180_ADDRESS, EM7180_RAMVersion2); Serial.print("EM7180 RAM Version: 0x"); Serial.print(RAM1); Serial.println(RAM2); uint8_t PID = readByte(EM7180_ADDRESS, EM7180_ProductID); Serial.print("EM7180 ProductID: 0x"); Serial.print(PID, HEX); Serial.println(" Should be: 0x80"); uint8_t RID = readByte(EM7180_ADDRESS, EM7180_RevisionID); Serial.print("EM7180 RevisionID: 0x"); Serial.print(RID, HEX); Serial.println(" Should be: 0x02"); } void USFS::loadfwfromEEPROM() { // Check which sensors can be detected by the EM7180 uint8_t featureflag = readByte(EM7180_ADDRESS, EM7180_FeatureFlags); if(featureflag & 0x01) Serial.println("A barometer is installed"); if(featureflag & 0x02) Serial.println("A humidity sensor is installed"); if(featureflag & 0x04) Serial.println("A temperature sensor is installed"); if(featureflag & 0x08) Serial.println("A custom sensor is installed"); if(featureflag & 0x10) Serial.println("A second custom sensor is installed"); if(featureflag & 0x20) Serial.println("A third custom sensor is installed"); delay(1000); // give some time to read the screen // Check SENtral status, make sure EEPROM upload of firmware was accomplished byte STAT = (readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x01); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x01) Serial.println("EEPROM detected on the sensor bus!"); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x02) Serial.println("EEPROM uploaded config file!"); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x04) Serial.println("EEPROM CRC incorrect!"); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x08) Serial.println("EM7180 in initialized state!"); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x10) Serial.println("No EEPROM detected!"); int count = 0; while(!STAT) { writeByte(EM7180_ADDRESS, EM7180_ResetRequest, 0x01); delay(500); count++; STAT = (readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x01); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x01) Serial.println("EEPROM detected on the sensor bus!"); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x02) Serial.println("EEPROM uploaded config file!"); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x04) Serial.println("EEPROM CRC incorrect!"); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x08) Serial.println("EM7180 in initialized state!"); if(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x10) Serial.println("No EEPROM detected!"); if(count > 10) break; } if(!(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x04)) Serial.println("EEPROM upload successful!"); } uint8_t USFS::checkEM7180Status(){ // Check event status register, way to check data ready by polling rather than interrupt uint8_t c = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register and interrupt return c; } uint8_t USFS::checkEM7180Errors(){ uint8_t c = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); // check error register return c; } void USFS::initEM7180(uint8_t accBW, uint8_t gyroBW, uint16_t accFS, uint16_t gyroFS, uint16_t magFS, uint8_t QRtDiv, uint8_t magRt, uint8_t accRt, uint8_t gyroRt, uint8_t baroRt) { uint16_t EM7180_mag_fs, EM7180_acc_fs, EM7180_gyro_fs; // EM7180 sensor full scale ranges uint8_t param[4]; // Enter EM7180 initialized state writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x00); // set SENtral in initialized state to configure registers writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x00); // make sure pass through mode is off writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x01); // Force initialize writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x00); // set SENtral in initialized state to configure registers //Setup LPF bandwidth (BEFORE setting ODR's) writeByte(EM7180_ADDRESS, EM7180_ACC_LPF_BW, accBW); // accBW = 3 = 41Hz writeByte(EM7180_ADDRESS, EM7180_GYRO_LPF_BW, gyroBW); // gyroBW = 3 = 41Hz // Set accel/gyro/mag desired ODR rates writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, QRtDiv); // quat rate = gyroRt/(1 QRTDiv) writeByte(EM7180_ADDRESS, EM7180_MagRate, magRt); // 0x64 = 100 Hz writeByte(EM7180_ADDRESS, EM7180_AccelRate, accRt); // 200/10 Hz, 0x14 = 200 Hz writeByte(EM7180_ADDRESS, EM7180_GyroRate, gyroRt); // 200/10 Hz, 0x14 = 200 Hz writeByte(EM7180_ADDRESS, EM7180_BaroRate, 0x80 | baroRt); // set enable bit and set Baro rate to 25 Hz, rate = baroRt/2, 0x32 = 25 Hz // Configure operating mode writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // read scale sensor data // Enable interrupt to host upon certain events // choose host interrupts when any sensor updated (0x40), new gyro data (0x20), new accel data (0x10), // new mag data (0x08), quaternions updated (0x04), an error occurs (0x02), or the SENtral needs to be reset(0x01) writeByte(EM7180_ADDRESS, EM7180_EnableEvents, 0x07); // Enable EM7180 run mode writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x01); // set SENtral in normal run mode delay(100); // EM7180 parameter adjustments Serial.println("Beginning Parameter Adjustments"); // Read sensor default FS values from parameter space writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x4A); // Request to read parameter 74 writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); // Request parameter transfer process byte param_xfer = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); while(!(param_xfer==0x4A)) { param_xfer = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); } param[0] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); param[1] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); param[2] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); param[3] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte3); EM7180_mag_fs = ((int16_t)(param[1]<<8) | param[0]); EM7180_acc_fs = ((int16_t)(param[3]<<8) | param[2]); Serial.print("Magnetometer Default Full Scale Range: +/-"); Serial.print(EM7180_mag_fs); Serial.println("uT"); Serial.print("Accelerometer Default Full Scale Range: +/-"); Serial.print(EM7180_acc_fs); Serial.println("g"); writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x4B); // Request to read parameter 75 param_xfer = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); while(!(param_xfer==0x4B)) { param_xfer = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); } param[0] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); param[1] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); param[2] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); param[3] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte3); EM7180_gyro_fs = ((int16_t)(param[1]<<8) | param[0]); Serial.print("Gyroscope Default Full Scale Range: +/-"); Serial.print(EM7180_gyro_fs); Serial.println("dps"); writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //End parameter transfer writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // re-enable algorithm //Disable stillness mode for balancing robot application EM7180_set_integer_param (0x49, 0x00); //Write desired sensor full scale ranges to the EM7180 EM7180_set_mag_acc_FS (magFS, accFS); // 1000 uT == 0x3E8, 8 g == 0x08 EM7180_set_gyro_FS (gyroFS); // 2000 dps == 0x7D0 // Read sensor new FS values from parameter space writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x4A); // Request to read parameter 74 writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); // Request parameter transfer process param_xfer = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); while(!(param_xfer==0x4A)) { param_xfer = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); } param[0] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); param[1] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); param[2] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); param[3] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte3); EM7180_mag_fs = ((int16_t)(param[1]<<8) | param[0]); EM7180_acc_fs = ((int16_t)(param[3]<<8) | param[2]); Serial.print("Magnetometer New Full Scale Range: +/-"); Serial.print(EM7180_mag_fs); Serial.println("uT"); Serial.print("Accelerometer New Full Scale Range: +/-"); Serial.print(EM7180_acc_fs); Serial.println("g"); writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x4B); // Request to read parameter 75 param_xfer = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); while(!(param_xfer==0x4B)) { param_xfer = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); } param[0] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); param[1] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); param[2] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); param[3] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte3); EM7180_gyro_fs = ((int16_t)(param[1]<<8) | param[0]); Serial.print("Gyroscope New Full Scale Range: +/-"); Serial.print(EM7180_gyro_fs); Serial.println("dps"); writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //End parameter transfer writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // re-enable algorithm // Read EM7180 status uint8_t runStatus = readByte(EM7180_ADDRESS, EM7180_RunStatus); if(runStatus & 0x01) Serial.println(" EM7180 run status = normal mode"); uint8_t algoStatus = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); if(algoStatus & 0x01) Serial.println(" EM7180 standby status"); if(algoStatus & 0x02) Serial.println(" EM7180 algorithm slow"); if(algoStatus & 0x04) Serial.println(" EM7180 in stillness mode"); if(algoStatus & 0x08) Serial.println(" EM7180 mag calibration completed"); if(algoStatus & 0x10) Serial.println(" EM7180 magnetic anomaly detected"); if(algoStatus & 0x20) Serial.println(" EM7180 unreliable sensor data"); uint8_t passthruStatus = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); if(passthruStatus & 0x01) Serial.print(" EM7180 in passthru mode!"); uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); if(eventStatus & 0x01) Serial.println(" EM7180 CPU reset"); if(eventStatus & 0x02) Serial.println(" EM7180 Error"); if(eventStatus & 0x04) Serial.println(" EM7180 new quaternion result"); if(eventStatus & 0x08) Serial.println(" EM7180 new mag result"); if(eventStatus & 0x10) Serial.println(" EM7180 new accel result"); if(eventStatus & 0x20) Serial.println(" EM7180 new gyro result"); delay(1000); // give some time to read the screen // Check sensor status uint8_t sensorStatus = readByte(EM7180_ADDRESS, EM7180_SensorStatus); Serial.print(" EM7180 sensor status = "); Serial.println(sensorStatus); if(sensorStatus & 0x01) Serial.print("Magnetometer not acknowledging!"); if(sensorStatus & 0x02) Serial.print("Accelerometer not acknowledging!"); if(sensorStatus & 0x04) Serial.print("Gyro not acknowledging!"); if(sensorStatus & 0x10) Serial.print("Magnetometer ID not recognized!"); if(sensorStatus & 0x20) Serial.print("Accelerometer ID not recognized!"); if(sensorStatus & 0x40) Serial.print("Gyro ID not recognized!"); Serial.print("Actual MagRate = "); Serial.print(readByte(EM7180_ADDRESS, EM7180_ActualMagRate)); Serial.println(" Hz"); Serial.print("Actual AccelRate = "); Serial.print(10*readByte(EM7180_ADDRESS, EM7180_ActualAccelRate)); Serial.println(" Hz"); Serial.print("Actual GyroRate = "); Serial.print(10*readByte(EM7180_ADDRESS, EM7180_ActualGyroRate)); Serial.println(" Hz"); Serial.print("Actual BaroRate = "); Serial.print(readByte(EM7180_ADDRESS, EM7180_ActualBaroRate)); Serial.println(" Hz"); } float USFS::uint32_reg_to_float (uint8_t *buf) { union { uint32_t ui32; float f; } u; u.ui32 = (((uint32_t)buf[0]) + (((uint32_t)buf[1]) << 8) + (((uint32_t)buf[2]) << 16) + (((uint32_t)buf[3]) << 24)); return u.f; } float USFS::int32_reg_to_float (uint8_t *buf) { union { int32_t i32; float f; } u; u.i32 = (((int32_t)buf[0]) + (((int32_t)buf[1]) << 8) + (((int32_t)buf[2]) << 16) + (((int32_t)buf[3]) << 24)); return u.f; } void USFS::float_to_bytes (float param_val, uint8_t *buf) { union { float f; uint8_t comp[sizeof(float)]; } u; u.f = param_val; for (uint8_t i=0; i < sizeof(float); i++) { buf[i] = u.comp[i]; } //Convert to LITTLE ENDIAN for (uint8_t i=0; i < sizeof(float); i++) { buf[i] = buf[(sizeof(float)-1) - i]; } } void USFS::EM7180_set_gyro_FS (uint16_t gyro_fs) { uint8_t bytes[4], STAT; bytes[0] = gyro_fs & (0xFF); bytes[1] = (gyro_fs >> 8) & (0xFF); bytes[2] = 0x00; bytes[3] = 0x00; writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, bytes[0]); //Gyro LSB writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, bytes[1]); //Gyro MSB writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, bytes[2]); //Unused writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, bytes[3]); //Unused writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0xCB); //Parameter 75; 0xCB is 75 decimal with the MSB set high to indicate a paramter write processs writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); //Request parameter transfer procedure STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); //Check the parameter acknowledge register and loop until the result matches parameter request byte while(!(STAT==0xCB)) { STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); } writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //Parameter request = 0 to end parameter transfer process writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm } void USFS::EM7180_set_mag_acc_FS (uint16_t mag_fs, uint16_t acc_fs) { uint8_t bytes[4], STAT; bytes[0] = mag_fs & (0xFF); bytes[1] = (mag_fs >> 8) & (0xFF); bytes[2] = acc_fs & (0xFF); bytes[3] = (acc_fs >> 8) & (0xFF); writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, bytes[0]); //Mag LSB writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, bytes[1]); //Mag MSB writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, bytes[2]); //Acc LSB writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, bytes[3]); //Acc MSB writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0xCA); //Parameter 74; 0xCA is 74 decimal with the MSB set high to indicate a paramter write processs writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); //Request parameter transfer procedure STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); //Check the parameter acknowledge register and loop until the result matches parameter request byte while(!(STAT==0xCA)) { STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); } writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //Parameter request = 0 to end parameter transfer process writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm } void USFS::EM7180_set_integer_param (uint8_t param, uint32_t param_val) { uint8_t bytes[4], STAT; bytes[0] = param_val & (0xFF); bytes[1] = (param_val >> 8) & (0xFF); bytes[2] = (param_val >> 16) & (0xFF); bytes[3] = (param_val >> 24) & (0xFF); param = param | 0x80; //Parameter is the decimal value with the MSB set high to indicate a paramter write processs writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, bytes[0]); //Param LSB writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, bytes[1]); writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, bytes[2]); writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, bytes[3]); //Param MSB writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); //Request parameter transfer procedure STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); //Check the parameter acknowledge register and loop until the result matches parameter request byte while(!(STAT==param)) { STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); } writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //Parameter request = 0 to end parameter transfer process writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm } void USFS::EM7180_set_float_param (uint8_t param, float param_val) { uint8_t bytes[4], STAT; float_to_bytes (param_val, &bytes[0]); param = param | 0x80; //Parameter is the decimal value with the MSB set high to indicate a paramter write processs writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, bytes[0]); //Param LSB writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, bytes[1]); writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, bytes[2]); writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, bytes[3]); //Param MSB writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); //Request parameter transfer procedure STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); //Check the parameter acknowledge register and loop until the result matches parameter request byte while(!(STAT==param)) { STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); } writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //Parameter request = 0 to end parameter transfer process writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm } void USFS::readSENtralQuatData(float * destination) { uint8_t rawData[16]; // x/y/z quaternion register data stored here readBytes(EM7180_ADDRESS, EM7180_QX, 16, &rawData[0]); // Read the sixteen raw data registers into data array destination[1] = uint32_reg_to_float (&rawData[0]); destination[2] = uint32_reg_to_float (&rawData[4]); destination[3] = uint32_reg_to_float (&rawData[8]); destination[0] = uint32_reg_to_float (&rawData[12]); // SENtral stores quats as qx, qy, qz, q0! } void USFS::readSENtralAccelData(int16_t * destination) { uint8_t rawData[6]; // x/y/z accel register data stored here readBytes(EM7180_ADDRESS, EM7180_AX, 6, &rawData[0]); // Read the six raw data registers into data array destination[0] = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value destination[1] = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]); destination[2] = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]); } void USFS::readSENtralGyroData(int16_t * destination) { uint8_t rawData[6]; // x/y/z gyro register data stored here readBytes(EM7180_ADDRESS, EM7180_GX, 6, &rawData[0]); // Read the six raw data registers sequentially into data array destination[0] = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value destination[1] = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]); destination[2] = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]); } void USFS::readSENtralMagData(int16_t * destination) { uint8_t rawData[6]; // x/y/z gyro register data stored here readBytes(EM7180_ADDRESS, EM7180_MX, 6, &rawData[0]); // Read the six raw data registers sequentially into data array destination[0] = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value destination[1] = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]); destination[2] = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]); } float USFS::getMres(uint8_t Mscale) { switch (Mscale) { // Possible magnetometer scales (and their register bit settings) are: // 14 bit resolution (0) and 16 bit resolution (1) case MFS_14BITS: _mRes = 10.*4912./8190.; // Proper scale to return milliGauss return _mRes; break; case MFS_16BITS: _mRes = 10.*4912./32760.0; // Proper scale to return milliGauss return _mRes; break; } } float USFS::getGres(uint8_t Gscale) { switch (Gscale) { // Possible gyro scales (and their register bit settings) are: // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: case GFS_250DPS: _gRes = 250.0/32768.0; return _gRes; break; case GFS_500DPS: _gRes = 500.0/32768.0; return _gRes; break; case GFS_1000DPS: _gRes = 1000.0/32768.0; return _gRes; break; case GFS_2000DPS: _gRes = 2000.0/32768.0; return _gRes; break; } } float USFS::getAres(uint8_t Ascale) { switch (Ascale) { // Possible accelerometer scales (and their register bit settings) are: // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: case AFS_2G: _aRes = 2.0/32768.0; return _aRes; break; case AFS_4G: _aRes = 4.0/32768.0; return _aRes; break; case AFS_8G: _aRes = 8.0/32768.0; return _aRes; break; case AFS_16G: _aRes = 16.0/32768.0; return _aRes; break; } } void USFS::readAccelData(int16_t * destination) { uint8_t rawData[6]; // x/y/z accel register data stored here readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a signed 16-bit value destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ; destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; } void USFS::readGyroData(int16_t * destination) { uint8_t rawData[6]; // x/y/z gyro register data stored here readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a signed 16-bit value destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ; destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; } void USFS::readMagData(int16_t * destination) { uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array uint8_t c = rawData[6]; // End data read by reading ST2 register if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data destination[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn the MSB and LSB into a signed 16-bit value destination[1] = ((int16_t)rawData[3] << 8) | rawData[2] ; // Data stored as little Endian destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; } } } int16_t USFS::readTempData() { uint8_t rawData[2]; // x/y/z gyro register data stored here readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array return ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a 16-bit value } void USFS::initAK8963(uint8_t Mscale, uint8_t Mmode, float * destination) { _Mmode = Mmode; // First extract the factory calibration for each magnetometer axis uint8_t rawData[3]; // x/y/z gyro calibration data stored here writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer delay(20); writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode delay(20); readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values destination[0] = (float)(rawData[0] - 128)/256. + 1.; // Return x-axis sensitivity adjustment values, etc. destination[1] = (float)(rawData[1] - 128)/256. + 1.; destination[2] = (float)(rawData[2] - 128)/256. + 1.; _fuseROMx = destination[0]; _fuseROMy = destination[1]; _fuseROMz = destination[2]; writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer delay(20); // Configure the magnetometer for continuous read and highest resolution // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register, // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR delay(20); } void USFS::initMPU9250(uint8_t Ascale, uint8_t Gscale) { // wake up device writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors delay(100); // Wait for all registers to reset // get stable time source writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Auto select clock source to be PLL gyroscope reference if ready else delay(200); // Configure Gyro and Thermometer // Disable FSYNC and set thermometer and gyro bandwidth to 41 and 42 Hz, respectively; // minimum delay time for this setting is 5.9 ms, which means sensor fusion update rates cannot // be higher than 1 / 0.0059 = 170 Hz // DLPF_CFG = bits 2:0 = 011; this limits the sample rate to 1000 Hz for both // With the MPU9250, it is possible to get gyro sample rates of 32 kHz (!), 8 kHz, or 1 kHz writeByte(MPU9250_ADDRESS, CONFIG, 0x03); // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; a rate consistent with the filter update rate // determined inset in CONFIG above // Set gyroscope full scale range // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); // get current GYRO_CONFIG register value // c = c & ~0xE0; // Clear self-test bits [7:5] c = c & ~0x02; // Clear Fchoice bits [1:0] c = c & ~0x18; // Clear AFS bits [4:3] c = c | Gscale << 3; // Set full scale range for the gyro // c =| 0x00; // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c ); // Write new GYRO_CONFIG value to register // Set accelerometer full-scale range configuration c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); // get current ACCEL_CONFIG register value // c = c & ~0xE0; // Clear self-test bits [7:5] c = c & ~0x18; // Clear AFS bits [4:3] c = c | Ascale << 3; // Set full scale range for the accelerometer writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c); // Write new ACCEL_CONFIG register value // Set accelerometer sample rate configuration // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); // get current ACCEL_CONFIG2 register value c = c & ~0x0F; // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) c = c | 0x03; // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c); // Write new ACCEL_CONFIG2 register value // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting // Configure Interrupts and Bypass Enable // Set interrupt pin active high, push-pull, hold interrupt pin level HIGH until interrupt cleared, // clear on read of INT_STATUS, and enable I2C_BYPASS_EN so additional chips // can join the I2C bus and all can be controlled by the Arduino as master writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt delay(100); } // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) { uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data uint16_t ii, packet_count, fifo_count; int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; // reset device writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device delay(100); // get stable time source; Auto select clock source to be PLL gyroscope reference if ready // else use the internal oscillator, bits 2:0 = 001 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); delay(200); // Configure device for bias calculation writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP delay(15); // Configure MPU6050 gyro and accelerometer for bias calculation writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec uint16_t accelsensitivity = 16384; // = 16384 LSB/g // Configure FIFO to capture accelerometer and gyro data for bias calculation writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9150) delay(40); // accumulate 40 samples in 40 milliseconds = 480 bytes // At end of sample accumulation, turn off FIFO sensor read writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count fifo_count = ((uint16_t)data[0] << 8) | data[1]; packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging for (ii = 0; ii < packet_count; ii++) { int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases accel_bias[1] += (int32_t) accel_temp[1]; accel_bias[2] += (int32_t) accel_temp[2]; gyro_bias[0] += (int32_t) gyro_temp[0]; gyro_bias[1] += (int32_t) gyro_temp[1]; gyro_bias[2] += (int32_t) gyro_temp[2]; } accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases accel_bias[1] /= (int32_t) packet_count; accel_bias[2] /= (int32_t) packet_count; gyro_bias[0] /= (int32_t) packet_count; gyro_bias[1] /= (int32_t) packet_count; gyro_bias[2] /= (int32_t) packet_count; if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation else {accel_bias[2] += (int32_t) accelsensitivity;} // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup data[0] = (-gyro_bias[0]/4 >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; data[3] = (-gyro_bias[1]/4) & 0xFF; data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; data[5] = (-gyro_bias[2]/4) & 0xFF; // Push gyro biases to hardware registers writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); // Output scaled gyro biases for display in the main program dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that // the accelerometer biases calculated above must be divided by 8. int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values accel_bias_reg[0] = (int32_t) (((int16_t)data[0] << 8) | data[1]); readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); accel_bias_reg[1] = (int32_t) (((int16_t)data[0] << 8) | data[1]); readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); accel_bias_reg[2] = (int32_t) (((int16_t)data[0] << 8) | data[1]); uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis for(ii = 0; ii < 3; ii++) { if((accel_bias_reg[ii] & mask)) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit } // Construct total accelerometer bias, including calculated average accelerometer bias from above accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) accel_bias_reg[1] -= (accel_bias[1]/8); accel_bias_reg[2] -= (accel_bias[2]/8); data[0] = (accel_bias_reg[0] >> 8) & 0xFE; data[1] = (accel_bias_reg[0]) & 0xFE; data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers data[2] = (accel_bias_reg[1] >> 8) & 0xFE; data[3] = (accel_bias_reg[1]) & 0xFE; data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers data[4] = (accel_bias_reg[2] >> 8) & 0xFE; data[5] = (accel_bias_reg[2]) & 0xFE; data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers // Apparently this is not working for the acceleration biases in the MPU-9250 // Are we handling the temperature correction bit properly? // Push accelerometer biases to hardware registers /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); */ // Output scaled accelerometer biases for display in the main program dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; } void USFS::magcalMPU9250(float * dest1, float * dest2) { uint16_t ii = 0, sample_count = 0; int32_t mag_bias[3] = {0, 0, 0}, mag_scale[3] = {0, 0, 0}; int16_t mag_max[3] = {0x8000, 0x8000, 0x8000}, mag_min[3] = {0x7FFF, 0x7FFF, 0x7FFF}, mag_temp[3] = {0, 0, 0}; Serial.println("Mag Calibration: Wave device in a figure eight until done!"); delay(4000); if(_Mmode == 0x02) sample_count = 128; if(_Mmode == 0x06) sample_count = 1500; for(ii = 0; ii < sample_count; ii++) { readMagData(mag_temp); // Read the mag data for (int jj = 0; jj < 3; jj++) { if(mag_temp[jj] > mag_max[jj]) mag_max[jj] = mag_temp[jj]; if(mag_temp[jj] < mag_min[jj]) mag_min[jj] = mag_temp[jj]; } if(_Mmode == 0x02) delay(135); // at 8 Hz ODR, new mag data is available every 125 ms if(_Mmode == 0x06) delay(12); // at 100 Hz ODR, new mag data is available every 10 ms } // Serial.println("mag x min/max:"); Serial.println(mag_max[0]); Serial.println(mag_min[0]); // Serial.println("mag y min/max:"); Serial.println(mag_max[1]); Serial.println(mag_min[1]); // Serial.println("mag z min/max:"); Serial.println(mag_max[2]); Serial.println(mag_min[2]); // Get hard iron correction mag_bias[0] = (mag_max[0] + mag_min[0])/2; // get average x mag bias in counts mag_bias[1] = (mag_max[1] + mag_min[1])/2; // get average y mag bias in counts mag_bias[2] = (mag_max[2] + mag_min[2])/2; // get average z mag bias in counts dest1[0] = (float) mag_bias[0]*_mRes*_fuseROMx; // save mag biases in G for main program dest1[1] = (float) mag_bias[1]*_mRes*_fuseROMy; dest1[2] = (float) mag_bias[2]*_mRes*_fuseROMz; // Get soft iron correction estimate mag_scale[0] = (mag_max[0] - mag_min[0])/2; // get average x axis max chord length in counts mag_scale[1] = (mag_max[1] - mag_min[1])/2; // get average y axis max chord length in counts mag_scale[2] = (mag_max[2] - mag_min[2])/2; // get average z axis max chord length in counts float avg_rad = mag_scale[0] + mag_scale[1] + mag_scale[2]; avg_rad /= 3.0; dest2[0] = avg_rad/((float)mag_scale[0]); dest2[1] = avg_rad/((float)mag_scale[1]); dest2[2] = avg_rad/((float)mag_scale[2]); Serial.println("Mag Calibration done!"); } // Accelerometer and gyroscope self test; check calibration wrt factory settings void USFS::MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass { uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; uint8_t selfTest[6]; int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3]; float factoryTrim[6]; uint8_t FS = 0; writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1< 128) { count = 128; Serial.print("Page count cannot be more than 128 bytes!"); } uint8_t temp[2] = {data_address1, data_address2}; Wire.transfer(device_address, &temp[0], 2, NULL, 0); Wire.transfer(device_address, &dest[0], count, NULL, 0); } uint8_t USFS::M24512DFMreadByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2) { uint8_t data; // `data` will store the register data Wire.beginTransmission(device_address); // Initialize the Tx buffer Wire.write(data_address1); // Put slave register address in Tx buffer Wire.write(data_address2); // Put slave register address in Tx buffer Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive Wire.requestFrom(device_address, 1); // Read one byte from slave register address data = Wire.read(); // Fill Rx buffer with result return data; // Return data read from slave register } void USFS::M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) { uint8_t temp[2] = {data_address1, data_address2}; Wire.transfer(device_address, &temp[0], 2, dest, count); } // I2C communication with the MS5637 is a little different from that with the MPU9250 and most other sensors // For the MS5637, we write commands, and the MS5637 sends data in response, rather than directly reading // MS5637 registers void USFS::MS5637Reset() { uint8_t temp[1] = {MS5637_RESET}; Wire.transfer(MS5637_ADDRESS, &temp[0], 1, NULL, 0); } void USFS::MS5637PromRead(uint16_t * destination) { uint8_t data[2] = {0,0}; uint8_t temp[1]; for (uint8_t ii = 0; ii < 7; ii++) { temp[0] = 0xA0 | ii << 1; Wire.transfer(MS5637_ADDRESS, &temp[0], 1, data, 2); destination[ii] = (uint16_t) (((uint16_t) data[0] << 8) | data[1]); // construct PROM data for return to main program } } uint32_t USFS::MS5637Read(uint8_t CMD, uint8_t OSR) // temperature data read { uint8_t data[3] = {0,0,0}; uint8_t temp[2] = {CMD | OSR, 0x00}; // Put pressure conversion, ADC read commands in Tx buffer Wire.transfer(MS5637_ADDRESS, &temp[0], 1, NULL, 0); switch (OSR) { case ADC_256: delay(1); break; // delay for conversion to complete case ADC_512: delay(3); break; case ADC_1024: delay(4); break; case ADC_2048: delay(6); break; case ADC_4096: delay(10); break; case ADC_8192: delay(20); break; } Wire.transfer(MS5637_ADDRESS, &temp[1], 1, data, 3); return (uint32_t) (((uint32_t) data[0] << 16) | (uint32_t) data[1] << 8 | data[2]); // construct PROM data for return to main program } unsigned char USFS::MS5637checkCRC(uint16_t * n_prom) // calculate checksum from PROM register contents { int cnt; unsigned int n_rem = 0; unsigned char n_bit; n_prom[0] = ((n_prom[0]) & 0x0FFF); // replace CRC byte by 0 for checksum calculation n_prom[7] = 0; for(cnt = 0; cnt < 16; cnt++) { if(cnt%2==1) n_rem ^= (unsigned short) ((n_prom[cnt>>1]) & 0x00FF); else n_rem ^= (unsigned short) (n_prom[cnt>>1]>>8); for(n_bit = 8; n_bit > 0; n_bit--) { if(n_rem & 0x8000) n_rem = (n_rem<<1) ^ 0x3000; else n_rem = (n_rem<<1); } } n_rem = ((n_rem>>12) & 0x000F); return (n_rem ^ 0x00); } void USFS::I2Cscan() { // scan for i2c devices byte error, address; int nDevices; Serial.println("Scanning..."); nDevices = 0; for(address = 1; address < 127; address++ ) { // The i2c_scanner uses the return value of // the Write.endTransmisstion to see if // a device did acknowledge to the address. error = Wire.transfer(address, NULL, 0, NULL, 0); if (error == 0) { Serial.print("I2C device found at address 0x"); if (address<16) Serial.print("0"); Serial.print(address,HEX); Serial.println(" !"); nDevices++; } else if (error==4) { Serial.print("Unknown error at address 0x"); if (address<16) Serial.print("0"); Serial.println(address,HEX); } } if (nDevices == 0) Serial.println("No I2C devices found\n"); else Serial.println("done\n"); } // I2C read/write functions for the MPU9250 sensors void USFS::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) { uint8_t temp[2]; temp[0] = subAddress; temp[1] = data; Wire.transfer(address, &temp[0], 2, NULL, 0); } uint8_t USFS::readByte(uint8_t address, uint8_t subAddress) { uint8_t temp[1]; Wire.transfer(address, &subAddress, 1, &temp[0], 1); return temp[0]; } void USFS::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) { Wire.transfer(address, &subAddress, 1, dest, count); } // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! __attribute__((optimize("O3"))) void USFS::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) { float q1 = _q[0], q2 = _q[1], q3 = _q[2], q4 = _q[3]; // short name local variable for readability float norm; float hx, hy, _2bx, _2bz; float s1, s2, s3, s4; float qDot1, qDot2, qDot3, qDot4; // Auxiliary variables to avoid repeated arithmetic float _2q1mx; float _2q1my; float _2q1mz; float _2q2mx; float _4bx; float _4bz; float _2q1 = 2.0f * q1; float _2q2 = 2.0f * q2; float _2q3 = 2.0f * q3; float _2q4 = 2.0f * q4; float _2q1q3 = 2.0f * q1 * q3; float _2q3q4 = 2.0f * q3 * q4; float q1q1 = q1 * q1; float q1q2 = q1 * q2; float q1q3 = q1 * q3; float q1q4 = q1 * q4; float q2q2 = q2 * q2; float q2q3 = q2 * q3; float q2q4 = q2 * q4; float q3q3 = q3 * q3; float q3q4 = q3 * q4; float q4q4 = q4 * q4; // Normalise accelerometer measurement norm = sqrt(ax * ax + ay * ay + az * az); if (norm == 0.0f) return; // handle NaN norm = 1.0f/norm; ax *= norm; ay *= norm; az *= norm; // Normalise magnetometer measurement norm = sqrt(mx * mx + my * my + mz * mz); if (norm == 0.0f) return; // handle NaN norm = 1.0f/norm; mx *= norm; my *= norm; mz *= norm; // Reference direction of Earth's magnetic field _2q1mx = 2.0f * q1 * mx; _2q1my = 2.0f * q1 * my; _2q1mz = 2.0f * q1 * mz; _2q2mx = 2.0f * q2 * mx; hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; _2bx = sqrt(hx * hx + hy * hy); _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; _4bx = 2.0f * _2bx; _4bz = 2.0f * _2bz; // Gradient decent algorithm corrective step s1 = -_2q3 * (2.0f * q2q4 - _2q1q3 - ax) + _2q2 * (2.0f * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); s2 = _2q4 * (2.0f * q2q4 - _2q1q3 - ax) + _2q1 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q2 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + _2bz * q4 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); s3 = -_2q1 * (2.0f * q2q4 - _2q1q3 - ax) + _2q4 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q3 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); s4 = _2q2 * (2.0f * q2q4 - _2q1q3 - ax) + _2q3 * (2.0f * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude norm = 1.0f/norm; s1 *= norm; s2 *= norm; s3 *= norm; s4 *= norm; // Compute rate of change of quaternion qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - _beta * s1; qDot2 = 0.5f * ( q1 * gx + q3 * gz - q4 * gy) - _beta * s2; qDot3 = 0.5f * ( q1 * gy - q2 * gz + q4 * gx) - _beta * s3; qDot4 = 0.5f * ( q1 * gz + q2 * gy - q3 * gx) - _beta * s4; // Integrate to yield quaternion q1 += qDot1 * _deltat; q2 += qDot2 * _deltat; q3 += qDot3 * _deltat; q4 += qDot4 * _deltat; norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion norm = 1.0f/norm; _q[0] = q1 * norm; _q[1] = q2 * norm; _q[2] = q3 * norm; _q[3] = q4 * norm; } // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and // measured ones. void USFS::MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) { float q1 = _q[0], q2 = _q[1], q3 = _q[2], q4 = _q[3]; // short name local variable for readability float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method float norm; float hx, hy, bx, bz; float vx, vy, vz, wx, wy, wz; float ex, ey, ez; float pa, pb, pc; // Auxiliary variables to avoid repeated arithmetic float q1q1 = q1 * q1; float q1q2 = q1 * q2; float q1q3 = q1 * q3; float q1q4 = q1 * q4; float q2q2 = q2 * q2; float q2q3 = q2 * q3; float q2q4 = q2 * q4; float q3q3 = q3 * q3; float q3q4 = q3 * q4; float q4q4 = q4 * q4; // Normalise accelerometer measurement norm = sqrt(ax * ax + ay * ay + az * az); if (norm == 0.0f) return; // handle NaN norm = 1.0f / norm; // use reciprocal for division ax *= norm; ay *= norm; az *= norm; // Normalise magnetometer measurement norm = sqrt(mx * mx + my * my + mz * mz); if (norm == 0.0f) return; // handle NaN norm = 1.0f / norm; // use reciprocal for division mx *= norm; my *= norm; mz *= norm; // Reference direction of Earth's magnetic field hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); bx = sqrt((hx * hx) + (hy * hy)); bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); // Estimated direction of gravity and magnetic field vx = 2.0f * (q2q4 - q1q3); vy = 2.0f * (q1q2 + q3q4); vz = q1q1 - q2q2 - q3q3 + q4q4; wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); // Error is cross product between estimated direction and measured direction of gravity ex = (ay * vz - az * vy) + (my * wz - mz * wy); ey = (az * vx - ax * vz) + (mz * wx - mx * wz); ez = (ax * vy - ay * vx) + (mx * wy - my * wx); if (_Ki > 0.0f) { eInt[0] += ex; // accumulate integral error eInt[1] += ey; eInt[2] += ez; } else { eInt[0] = 0.0f; // prevent integral wind up eInt[1] = 0.0f; eInt[2] = 0.0f; } // Apply feedback terms gx = gx + _Kp * ex + _Ki * eInt[0]; gy = gy + _Kp * ey + _Ki * eInt[1]; gz = gz + _Kp * ez + _Ki * eInt[2]; // Integrate rate of change of quaternion pa = q2; pb = q3; pc = q4; q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * _deltat); q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * _deltat); q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * _deltat); q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * _deltat); // Normalise quaternion norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); norm = 1.0f / norm; _q[0] = q1 * norm; _q[1] = q2 * norm; _q[2] = q3 * norm; _q[3] = q4 * norm; }