From bead561819696153b03cdff0c9808db6e82fce29 Mon Sep 17 00:00:00 2001 From: Daniel Peter Chokola Date: Mon, 18 Jan 2021 16:34:56 -0500 Subject: [PATCH] import EM7180/LSM6DSM/LIS2MDL/LPS22HB sources into STM32CubeIDE-compatible directory structure updated README.md maintained source code attribution --- .../USFS.h => Drivers/EM7180/Inc/em7180.h | 50 +- .../LIS2MDL.h => Drivers/EM7180/Inc/lis2mdl.h | 25 +- .../LPS22HB.h => Drivers/EM7180/Inc/lps22hb.h | 25 +- .../LSM6DSM.h => Drivers/EM7180/Inc/lsm6dsm.h | 25 +- .../USFS.cpp => Drivers/EM7180/Src/em7180.c | 331 +-- .../EM7180/Src/lis2mdl.c | 29 +- .../EM7180/Src/lps22hb.c | 29 +- .../EM7180/Src/lsm6dsm.c | 29 +- EM7180_BMI160_AK8963C.ino | 1362 ----------- EM7180_BMX055_BMP280.ino | 1805 --------------- EM7180_BMX055_MS5637_BasicAHRS_t3.ino | 1650 -------------- .../EM7180_LSM6DSM_LIS2MDL_LPS22HB_ESP32.ino | 593 ----- EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.cpp | 173 -- EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.h | 48 - EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.cpp | 175 -- EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.h | 75 - EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.cpp | 60 - EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.h | 73 - EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.cpp | 225 -- EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.h | 180 -- EM7180_LSM6DSM_LIS2MDL_LPS22HB/Readme.md | 1 - EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.cpp | 670 ------ EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.h | 126 -- ...7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly.ino | 701 ------ .../MadgwickFilter.ino | 97 - .../Readme.md | 2 - EM7180_LSM9DS0_LPS25H.ino | 1641 -------------- EM7180_LSM9DS0_MS5637_t3.ino | 1455 ------------ EM7180_MPU6500_AK8963C_BMP280.ino | 1779 --------------- EM7180_MPU9250_BMP280.ino | 1872 --------------- EM7180_MPU9250_MS5637.ino | 1906 ---------------- FirmwareUpload.ino | 382 ---- README.md | 22 +- WarmStart/EM7180_MPU9250_BMP280_M24512DFC_WS | 1774 --------------- WarmStart/Globals.h | 524 ----- WarmStart/Readme.md | 1 - WarmStart/quaternionFilters | 195 -- ...80_MPU9250_BMP280_M24512DFC_WS_Acc_Cal.ino | 1997 ----------------- WarmStartandAccelCal/Global.h | 523 ----- WarmStartandAccelCal/quaternionFilters | 195 -- quaternionFilters.ino | 194 -- 41 files changed, 299 insertions(+), 22720 deletions(-) rename EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/USFS.h => Drivers/EM7180/Inc/em7180.h (94%) rename EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LIS2MDL.h => Drivers/EM7180/Inc/lis2mdl.h (82%) rename EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LPS22HB.h => Drivers/EM7180/Inc/lps22hb.h (82%) rename EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LSM6DSM.h => Drivers/EM7180/Inc/lsm6dsm.h (93%) rename EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/USFS.cpp => Drivers/EM7180/Src/em7180.c (94%) rename EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LIS2MDL.cpp => Drivers/EM7180/Src/lis2mdl.c (94%) rename EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LPS22HB.cpp => Drivers/EM7180/Src/lps22hb.c (90%) rename EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LSM6DSM.cpp => Drivers/EM7180/Src/lsm6dsm.c (95%) delete mode 100644 EM7180_BMI160_AK8963C.ino delete mode 100644 EM7180_BMX055_BMP280.ino delete mode 100644 EM7180_BMX055_MS5637_BasicAHRS_t3.ino delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/EM7180_LSM6DSM_LIS2MDL_LPS22HB_ESP32.ino delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.cpp delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.h delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.cpp delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.h delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.cpp delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.h delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.cpp delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.h delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/Readme.md delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.cpp delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.h delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly.ino delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/MadgwickFilter.ino delete mode 100644 EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/Readme.md delete mode 100644 EM7180_LSM9DS0_LPS25H.ino delete mode 100644 EM7180_LSM9DS0_MS5637_t3.ino delete mode 100644 EM7180_MPU6500_AK8963C_BMP280.ino delete mode 100644 EM7180_MPU9250_BMP280.ino delete mode 100644 EM7180_MPU9250_MS5637.ino delete mode 100644 FirmwareUpload.ino delete mode 100644 WarmStart/EM7180_MPU9250_BMP280_M24512DFC_WS delete mode 100644 WarmStart/Globals.h delete mode 100644 WarmStart/Readme.md delete mode 100644 WarmStart/quaternionFilters delete mode 100644 WarmStartandAccelCal/EM71280_MPU9250_BMP280_M24512DFC_WS_Acc_Cal.ino delete mode 100644 WarmStartandAccelCal/Global.h delete mode 100644 WarmStartandAccelCal/quaternionFilters delete mode 100644 quaternionFilters.ino diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/USFS.h b/Drivers/EM7180/Inc/em7180.h similarity index 94% rename from EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/USFS.h rename to Drivers/EM7180/Inc/em7180.h index 0b75520..2a109ca 100644 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/USFS.h +++ b/Drivers/EM7180/Inc/em7180.h @@ -1,8 +1,22 @@ -#ifndef USFS_h -#define USFSh_h +/* + * em7180.h + * + * Created on: Jan 18, 2021 + * Author: Daniel Peter Chokola + * + * Adapted From: + * EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly + * by: Kris Winer + * 06/29/2017 Copyright Tlera Corporation + * + * Library may be used freely and without limit with attribution. + */ -#include "Arduino.h" -#include "Wire.h" +#ifndef EM7180_H_ +#define EM7180_H_ + +/* Includes */ +#include // See MS5637-02BA03 Low Voltage Barometric Pressure Sensor Data Sheet #define MS5637_RESET 0x1E @@ -10,7 +24,7 @@ #define MS5637_CONVERT_D2 0x50 #define MS5637_ADC_READ 0x00 -// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in +// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in // above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map // //Magnetometer Registers @@ -32,8 +46,8 @@ #define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value #define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value -#define SELF_TEST_X_GYRO 0x00 -#define SELF_TEST_Y_GYRO 0x01 +#define SELF_TEST_X_GYRO 0x00 +#define SELF_TEST_Y_GYRO 0x01 #define SELF_TEST_Z_GYRO 0x02 /*#define X_FINE_GAIN 0x03 // [7:0] fine gain @@ -47,7 +61,7 @@ #define ZA_OFFSET_L_TC 0x0B */ #define SELF_TEST_X_ACCEL 0x0D -#define SELF_TEST_Y_ACCEL 0x0E +#define SELF_TEST_Y_ACCEL 0x0E #define SELF_TEST_Z_ACCEL 0x0F #define SELF_TEST_A 0x10 @@ -63,15 +77,15 @@ #define GYRO_CONFIG 0x1B #define ACCEL_CONFIG 0x1C #define ACCEL_CONFIG2 0x1D -#define LP_ACCEL_ODR 0x1E -#define WOM_THR 0x1F +#define LP_ACCEL_ODR 0x1E +#define WOM_THR 0x1F #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms #define FIFO_EN 0x23 -#define I2C_MST_CTRL 0x24 +#define I2C_MST_CTRL 0x24 #define I2C_SLV0_ADDR 0x25 #define I2C_SLV0_REG 0x26 #define I2C_SLV0_CTRL 0x27 @@ -147,7 +161,7 @@ #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank #define DMP_REG 0x6F // Register in DMP from which to read or to which to write #define DMP_REG_1 0x70 -#define DMP_REG_2 0x71 +#define DMP_REG_2 0x71 #define FIFO_COUNTH 0x72 #define FIFO_COUNTL 0x73 #define FIFO_R_W 0x74 @@ -183,7 +197,7 @@ #define EM7180_BaroTIME 0x2C // start of two-byte MS5637 pressure timestamp, 16-bit unsigned #define EM7180_Temp 0x2E // start of two-byte MS5637 temperature data, 16-bit signed interger #define EM7180_TempTIME 0x30 // start of two-byte MS5637 temperature timestamp, 16-bit unsigned -#define EM7180_QRateDivisor 0x32 // uint8_t +#define EM7180_QRateDivisor 0x32 // uint8_t #define EM7180_EnableEvents 0x33 #define EM7180_HostControl 0x34 #define EM7180_EventStatus 0x35 @@ -221,10 +235,10 @@ #define EM7180_RevisionID 0x91 #define EM7180_RunStatus 0x92 #define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 +#define EM7180_UploadData 0x96 #define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E +#define EM7180_ResetRequest 0x9B +#define EM7180_PassThruStatus 0x9E #define EM7180_PassThruControl 0xA0 #define EM7180_ACC_LPF_BW 0x5B //Register GP36 #define EM7180_GYRO_LPF_BW 0x5C //Register GP37 @@ -261,7 +275,7 @@ class USFS { - public: + public: USFS(uint8_t intPin, bool passThru); float getAres(uint8_t Ascale); float getGres(uint8_t Gscale); @@ -325,4 +339,4 @@ class USFS float _Ki; }; -#endif +#endif /* EM7180_H_ */ diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LIS2MDL.h b/Drivers/EM7180/Inc/lis2mdl.h similarity index 82% rename from EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LIS2MDL.h rename to Drivers/EM7180/Inc/lis2mdl.h index bc7a255..dfecc03 100644 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LIS2MDL.h +++ b/Drivers/EM7180/Inc/lis2mdl.h @@ -1,13 +1,18 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LIS2MDL is a low power magnetometer, here used as 3 DoF in a 9 DoF absolute orientation solution. - - Library may be used freely and without limit with attribution. - -*/ +/* + * lis2mdl.c + * The LIS2MDL is a low power magnetometer, here used as 3 DoF in a 10 DoF + * absolute orientation solution. + * + * Created on: Jan 18, 2021 + * Author: Daniel Peter Chokola + * + * Adapted From: + * EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly + * by: Kris Winer + * 09/23/2017 Copyright Tlera Corporation + * + * Library may be used freely and without limit with attribution. + */ #ifndef LIS2MDL_h #define LIS2MDL_h diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LPS22HB.h b/Drivers/EM7180/Inc/lps22hb.h similarity index 82% rename from EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LPS22HB.h rename to Drivers/EM7180/Inc/lps22hb.h index 05fbb32..bba1ff1 100644 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LPS22HB.h +++ b/Drivers/EM7180/Inc/lps22hb.h @@ -1,13 +1,18 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LPS22HB is a low power barometerr. - - Library may be used freely and without limit with attribution. - -*/ +/* + * lps22hb.h + * The LPS22HB is a low power barometer, here used as 1 DoF in a 10 DoF + * absolute orientation solution. + * + * Created on: Jan 18, 2021 + * Author: Daniel Peter Chokola + * + * Adapted From: + * EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly + * by: Kris Winer + * 09/23/2017 Copyright Tlera Corporation + * + * Library may be used freely and without limit with attribution. + */ #ifndef LPS22HB_h #define LPS22HB_h diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LSM6DSM.h b/Drivers/EM7180/Inc/lsm6dsm.h similarity index 93% rename from EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LSM6DSM.h rename to Drivers/EM7180/Inc/lsm6dsm.h index 936dd79..1d10f65 100644 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LSM6DSM.h +++ b/Drivers/EM7180/Inc/lsm6dsm.h @@ -1,13 +1,18 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LSM6DSM is a sensor hub with embedded accel and gyro, here used as 6 DoF in a 9 DoF absolute orientation solution. - - Library may be used freely and without limit with attribution. - -*/ +/* + * lsm6dsm.h + * The LSM6DSM is a sensor hub with embedded accelerometer and gyroscope, here + * used as 6 DoF in a 10 DoF absolute orientation solution. + * + * Created on: Jan 18, 2021 + * Author: Daniel Peter Chokola + * + * Adapted From: + * EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly + * by: Kris Winer + * 09/23/2017 Copyright Tlera Corporation + * + * Library may be used freely and without limit with attribution. + */ #ifndef LSM6DSM_h #define LSM6DSM_h diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/USFS.cpp b/Drivers/EM7180/Src/em7180.c similarity index 94% rename from EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/USFS.cpp rename to Drivers/EM7180/Src/em7180.c index 9968d13..7581595 100644 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/USFS.cpp +++ b/Drivers/EM7180/Src/em7180.c @@ -1,18 +1,25 @@ -/* 06/29/2017 Copyright Tlera Corporation - * - * Created by Kris Winer - * - * +/* + * em7180.c + * + * Created on: Jan 18, 2021 + * Author: Daniel Peter Chokola + * + * Adapted From: + * EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly + * by: Kris Winer + * 06/29/2017 Copyright Tlera Corporation + * * Library may be used freely and without limit with attribution. - * */ -#include "USFS.h" + +/* Includes */ +#include "em7180.h" USFS::USFS(uint8_t intPin, bool passThru) { pinMode(intPin, INPUT); _intPin = intPin; - _passThru = passThru; + _passThru = passThru; } void USFS::getChipID() @@ -40,7 +47,7 @@ void USFS::getChipID() 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 @@ -53,8 +60,8 @@ void USFS::getChipID() int count = 0; while(!STAT) { writeByte(EM7180_ADDRESS, EM7180_ResetRequest, 0x01); - delay(500); - count++; + 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!"); @@ -63,7 +70,7 @@ void USFS::getChipID() 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!"); } @@ -77,18 +84,18 @@ void USFS::getChipID() 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]; + 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 @@ -111,7 +118,7 @@ void USFS::getChipID() // 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 @@ -140,14 +147,14 @@ void USFS::getChipID() 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 @@ -177,7 +184,7 @@ void USFS::getChipID() 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"); @@ -196,10 +203,10 @@ 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"); - +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); @@ -209,11 +216,11 @@ if(eventStatus & 0x20) Serial.println(" EM7180 new gyro result"); 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"); + + 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) @@ -355,8 +362,8 @@ 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]); + 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) @@ -364,8 +371,8 @@ 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]); + 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) @@ -373,8 +380,8 @@ 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]); + 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) { @@ -397,7 +404,7 @@ 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). + // 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; @@ -422,7 +429,7 @@ 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). + // 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; @@ -449,8 +456,8 @@ 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] ; + destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ; + destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; } @@ -459,8 +466,8 @@ 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] ; + destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ; + destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; } void USFS::readMagData(int16_t * destination) @@ -472,7 +479,7 @@ void USFS::readMagData(int16_t * destination) 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] ; + destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; } } } @@ -480,27 +487,27 @@ void USFS::readMagData(int16_t * destination) 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 + 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 + 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.; + 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 + 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, @@ -511,60 +518,60 @@ void USFS::initAK8963(uint8_t Mscale, uint8_t Mmode, float * destination) 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 + 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); - + delay(200); + // Configure Gyro and Thermometer - // Disable FSYNC and set thermometer and gyro bandwidth to 41 and 42 Hz, respectively; + // 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); + 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 + 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 & ~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 & ~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 + 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 & ~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, + // 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 + // 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_PIN_CFG, 0x22); writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt delay(100); } @@ -573,20 +580,20 @@ void USFS::initMPU9250(uint8_t Ascale, uint8_t Gscale) // 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 + + // 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_1, 0x01); writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); - delay(200); + delay(200); // Configure device for bias calculation writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts @@ -596,18 +603,18 @@ void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) 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, 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 @@ -616,24 +623,24 @@ void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) 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] ) ; + 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; @@ -641,10 +648,10 @@ void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) 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 @@ -652,7 +659,7 @@ void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) 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]); @@ -660,9 +667,9 @@ void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) 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[0] = (float) gyro_bias[0]/(float) gyrosensitivity; dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; @@ -679,19 +686,19 @@ void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) 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 @@ -701,7 +708,7 @@ void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) 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 @@ -713,25 +720,25 @@ void USFS::accelgyrocalMPU9250(float * dest1, float * dest2) 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[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) +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 + 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]; @@ -748,11 +755,11 @@ void USFS::magcalMPU9250(float * dest1, float * dest2) 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; - + 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 @@ -764,7 +771,7 @@ void USFS::magcalMPU9250(float * dest1, float * dest2) 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!"); } @@ -779,7 +786,7 @@ void USFS::MPU9250SelfTest(float * destination) // Should return percent deviati 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) + if(count > 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); + 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 + 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 + 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); + Wire.transfer(device_address, &temp[0], 2, dest, count); } @@ -944,16 +951,16 @@ void USFS::SENtralPassThroughMode() void USFS::MS5637Reset() { uint8_t temp[1] = {MS5637_RESET}; - Wire.transfer(MS5637_ADDRESS, &temp[0], 1, NULL, 0); + 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); + 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 } } @@ -962,8 +969,8 @@ void USFS::SENtralPassThroughMode() { 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); - + Wire.transfer(MS5637_ADDRESS, &temp[0], 1, NULL, 0); + switch (OSR) { case ADC_256: delay(1); break; // delay for conversion to complete @@ -973,8 +980,8 @@ void USFS::SENtralPassThroughMode() case ADC_4096: delay(10); break; case ADC_8192: delay(20); break; } - - Wire.transfer(MS5637_ADDRESS, &temp[1], 1, data, 3); + + 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 } @@ -985,7 +992,7 @@ unsigned char USFS::MS5637checkCRC(uint16_t * n_prom) // calculate checksum fro 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++) @@ -1012,7 +1019,7 @@ void USFS::I2Cscan() Serial.println("Scanning..."); nDevices = 0; - for(address = 1; address < 127; address++ ) + for(address = 1; address < 127; address++ ) { // The i2c_scanner uses the return value of // the Write.endTransmisstion to see if @@ -1022,48 +1029,48 @@ void USFS::I2Cscan() if (error == 0) { Serial.print("I2C device found at address 0x"); - if (address<16) + if (address<16) Serial.print("0"); Serial.print(address,HEX); Serial.println(" !"); nDevices++; } - else if (error==4) + else if (error==4) { Serial.print("Unknown error at address 0x"); - if (address<16) + 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"); + Serial.println("done\n"); } // I2C read/write functions for the MPU9250 sensors - void USFS::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) + 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); + Wire.transfer(address, &temp[0], 2, NULL, 0); } - uint8_t USFS::readByte(uint8_t address, uint8_t subAddress) + 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) + void USFS::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) { - Wire.transfer(address, &subAddress, 1, dest, count); + Wire.transfer(address, &subAddress, 1, dest, count); } // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" @@ -1163,11 +1170,11 @@ __attribute__((optimize("O3"))) void USFS::MadgwickQuaternionUpdate(float ax, fl _q[3] = q4 * norm; } - - - + + + // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and - // measured ones. + // 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 @@ -1188,7 +1195,7 @@ __attribute__((optimize("O3"))) void USFS::MadgwickQuaternionUpdate(float ax, fl float q2q4 = q2 * q4; float q3q3 = q3 * q3; float q3q4 = q3 * q4; - float q4q4 = q4 * q4; + float q4q4 = q4 * q4; // Normalise accelerometer measurement norm = sqrt(ax * ax + ay * ay + az * az); @@ -1218,7 +1225,7 @@ __attribute__((optimize("O3"))) void USFS::MadgwickQuaternionUpdate(float ax, fl 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); + 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); @@ -1258,5 +1265,5 @@ __attribute__((optimize("O3"))) void USFS::MadgwickQuaternionUpdate(float ax, fl _q[1] = q2 * norm; _q[2] = q3 * norm; _q[3] = q4 * norm; - - } + + } diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LIS2MDL.cpp b/Drivers/EM7180/Src/lis2mdl.c similarity index 94% rename from EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LIS2MDL.cpp rename to Drivers/EM7180/Src/lis2mdl.c index d217362..beed34e 100644 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LIS2MDL.cpp +++ b/Drivers/EM7180/Src/lis2mdl.c @@ -1,15 +1,20 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LIS2MDL is a low power magnetometer, here used as 3 DoF in a 9 DoF absolute orientation solution. - - Library may be used freely and without limit with attribution. - -*/ - -#include "LIS2MDL.h" +/* + * lis2mdl.c + * The LIS2MDL is a low power magnetometer, here used as 3 DoF in a 10 DoF + * absolute orientation solution. + * + * Created on: Jan 18, 2021 + * Author: Daniel Peter Chokola + * + * Adapted From: + * EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly + * by: Kris Winer + * 09/23/2017 Copyright Tlera Corporation + * + * Library may be used freely and without limit with attribution. + */ + +#include "lis2mdl.h" LIS2MDL::LIS2MDL(uint8_t intPin) { diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LPS22HB.cpp b/Drivers/EM7180/Src/lps22hb.c similarity index 90% rename from EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LPS22HB.cpp rename to Drivers/EM7180/Src/lps22hb.c index 9917483..463969e 100644 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LPS22HB.cpp +++ b/Drivers/EM7180/Src/lps22hb.c @@ -1,15 +1,20 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LPS22HB is a low power barometerr. - - Library may be used freely and without limit with attribution. - -*/ - -#include "LPS22HB.h" +/* + * lps22hb.c + * The LPS22HB is a low power barometer, here used as 1 DoF in a 10 DoF + * absolute orientation solution. + * + * Created on: Jan 18, 2021 + * Author: Daniel Peter Chokola + * + * Adapted From: + * EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly + * by: Kris Winer + * 09/23/2017 Copyright Tlera Corporation + * + * Library may be used freely and without limit with attribution. + */ + +#include "lps22hb.h" #include "Wire.h" LPS22H::LPS22H(uint8_t intPin) diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LSM6DSM.cpp b/Drivers/EM7180/Src/lsm6dsm.c similarity index 95% rename from EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LSM6DSM.cpp rename to Drivers/EM7180/Src/lsm6dsm.c index da2ef5d..33d8ac4 100644 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/LSM6DSM.cpp +++ b/Drivers/EM7180/Src/lsm6dsm.c @@ -1,15 +1,20 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LSM6DSM is a sensor hub with embedded accel and gyro, here used as 6 DoF in a 9 DoF absolute orientation solution. - - Library may be used freely and without limit with attribution. - -*/ - -#include "LSM6DSM.h" +/* + * lsm6dsm.c + * The LSM6DSM is a sensor hub with embedded accelerometer and gyroscope, here + * used as 6 DoF in a 10 DoF absolute orientation solution. + * + * Created on: Jan 18, 2021 + * Author: Daniel Peter Chokola + * + * Adapted From: + * EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly + * by: Kris Winer + * 09/23/2017 Copyright Tlera Corporation + * + * Library may be used freely and without limit with attribution. + */ + +#include "lsm6dsm.h" LSM6DSM::LSM6DSM(uint8_t intPin1, uint8_t intPin2) { diff --git a/EM7180_BMI160_AK8963C.ino b/EM7180_BMI160_AK8963C.ino deleted file mode 100644 index 287d4ea..0000000 --- a/EM7180_BMI160_AK8963C.ino +++ /dev/null @@ -1,1362 +0,0 @@ -* EM7180_BMI160_AK8963C_t3 Basic Example Code - by: Kris Winer - date: April 20, 2016 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the BMI160 and AK8963C, and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DFC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the BMI160+AK8963C 9-axis motion sensor (accel/gyro/mag) as slave, and an M24512DFC - 512kbit (64 kByte) EEPROM as slave all connected via I2C. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - - SDA and SCL has external pull-up resistors (to 3.3V). - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - - Note: All the sensors on this board are I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensors are not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ -#include -#include - -// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in -// above document; the MPU6500 and MPU9250 are virtually identical but the latter has a different register map -// -//Magnetometer Registers -#define AK8963_ADDRESS 0x0C -#define WHO_AM_I_AK8963 0x00 // should return 0x48 -#define INFO 0x01 -#define AK8963_ST1 0x02 // data ready status bit 0 -#define AK8963_XOUT_L 0x03 // data -#define AK8963_XOUT_H 0x04 -#define AK8963_YOUT_L 0x05 -#define AK8963_YOUT_H 0x06 -#define AK8963_ZOUT_L 0x07 -#define AK8963_ZOUT_H 0x08 -#define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 -#define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 -#define AK8963_ASTC 0x0C // Self test control -#define AK8963_I2CDIS 0x0F // I2C disable -#define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value -#define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value -#define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value - -// Bosch BMI160 accel/gyro -// see https://ae-bst.resource.bosch.com/media/_tech/media/datasheets/BST-BMI160-DS000-07.pdf -// -#define BMI160_CHIP_ID 0x00 -#define BMI160_ERR_REG 0x02 -#define BMI160_PMU_STATUS 0x03 -#define BMI160_GYRO_DATA 0x0C // 0x04 - 0x17 0x0C is start of gyro data -#define BMI160_ACCEL_DATA 0x12 // 0x04 - 0x17 0x12 is start of accel data -#define BMI160_SENSORTIME 0x18 // 0x18 - 0x1A -#define BMI160_STATUS 0x1B -#define BMI160_INT_STATUS 0x1C // 0x1C - 0x1F -#define BMI160_TEMPERATURE 0x20 // 0x20 - 0x21 -#define BMI160_FIFO_LENGTH 0x22 // 0x22 - 0x23 -#define BMI160_FIFO_DATA 0x24 // 1024 bytes -#define BMI160_ACC_CONF 0x40 -#define BMI160_ACC_RANGE 0x41 -#define BMI160_GYR_CONF 0x42 -#define BMI160_GYR_RANGE 0x43 -#define BMI160_MAG_CONF 0x44 -#define BMI160_FIFO_DOWNS 0x45 -#define BMI160_FIFO_CONFIG 0x46 // 0x46 - 0x47 -#define BMI160_MAG_IF 0x4B // 0x4B - 0x4F -#define BMI160_INT_EN 0x50 // 0x50 - 0x52 -#define BMI160_INT_OUT_CTRL 0x53 -#define BMI160_INT_LATCH 0x54 -#define BMI160_INT_MAP 0x55 // 0x55 - 0x57 -#define BMI160_INT_DATA 0x58 // 0x58 - 0x59 -#define BMI160_INT_LOWHIGH 0x5A // 0x5A - 0x5E -#define BMI160_INT_MOTION 0x5F // 0x5F - 0x62 -#define BMI160_INT_TAP 0x63 // 0x63 - 0x64 -#define BMI160_INT_ORIENT 0x65 // 0x65 - 0x66 -#define BMI160_INT_FLAT 0x67 // 0x67 - 0x68 -#define BMI160_FOC_CONF 0x69 -#define BMI160_CONF 0x6A -#define BMI160_IF_CONF 0x6B -#define BMI160_PMU_TRIGGER 0x6C -#define BMI160_SELF_TEST 0x6D -#define BMI160_NV_CONF 0x70 -#define BMI160_OFFSET 0x71 // 0x71 - 0x77 -#define BMI160_OFFSET_CONF 0x77 -#define BMI160_STEP_CNT 0x78 // 0x78 - 0x79 -#define BMI160_STEP_CONF 0x7A // 0x7A - 0x7B -#define BMI160_CMD 0x7E - - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 - -// Using the Teensy Mini Add-On board, BMX055 SDO1 = SDO2 = CSB3 = GND as designed -// Seven-bit BMX055 device addresses are ACC = 0x18, GYRO = 0x68, MAG = 0x10 -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page -#define BMI160_ADDRESS 0x68 // Device address when ADO = 0 -#define AK8963_ADDRESS 0x0C // Address of magnetometer - -#define SerialDebug true // set to true to get Serial output for debugging - -// Set initial input parameters -#define AFS_2G 0x03 -#define AFS_4G 0x05 -#define AFS_8G 0x08 -#define AFS_16G 0x0C - -enum AODR { - Arate0 = 0, - Arate1Hz, // really 25/32 - Arate2Hz, // really 25/16 - Arate3Hz, // really 25/8 - Arate6_25Hz, - Arate12_5Hz, - Arate25Hz, - Arate50Hz, - Arate100Hz, - Arate200Hz, - Arate400Hz, - Arate800Hz, - Arate1600Hz -}; - -enum ABW { - ABW_4X = 0, // 4 times oversampling ~ 10% of ODR - ABW_2X, // 2 times oversampling ~ 20% of ODR - ABW_1X // 1 times oversampling ~ 40% of ODR -}; - -enum Gscale { - GFS_2000DPS = 0, - GFS_1000DPS, - GFS_500DPS, - GFS_250DPS, - GFS_125DPS -}; - -enum GODR { - Grate25Hz = 6, - Grate50Hz, - Grate100Hz, - Grate200Hz, - Grate400Hz, - Grate800Hz, - Grate1600Hz, - Grate3200Hz -}; - -enum GBW { - GBW_4X = 0, // 4 times oversampling ~ 10% of ODR - GBW_2X, // 2 times oversampling ~ 20% of ODR - GBW_1X // 1 times oversampling ~ 40% of ODR -}; - -enum Mscale { - MFS_14BITS = 0, // 0.6 mG per LSB - MFS_16BITS // 0.15 mG per LSB -}; - -// -// Specify sensor full scale -uint8_t Gscale = GFS_250DPS, GODR = Grate200Hz, GBW = GBW_2X; -uint8_t Ascale = AFS_2G, AODR = Arate200Hz, ABW = ABW_2X; -uint8_t Mscale = MFS_16BITS; // Choose either 14-bit or 16-bit magnetometer resolution -uint8_t Mmode = 0x06; // 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read -float aRes, gRes, mRes; // scale resolutions per LSB for the sensors - -// Pin definitions -int myLed = 13; // LED on the Teensy 3.1 - -// BMI160 variables -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output -float Quat[4] = {0, 0, 0, 0}; // quaternion data register -float magCalibration[3] = {0, 0, 0}; // Factory mag calibration and mag bias -float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag -int16_t tempCount; // temperature raw count output -float temperature; // Stores the BMX055 internal chip temperature in degrees Celsius -float SelfTest[6]; // holds results of gyro and accelerometer self test - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Ki 0.0f - -uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval -uint8_t param[4]; // used for param transfer -uint16_t EM7180_mag_fs, EM7180_acc_fs, EM7180_gyro_fs; // EM7180 sensor full scale ranges - -float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -bool passThru = true; - -void setup() -{ - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(5000); - Serial.begin(38400); - - I2Cscan(); // should detect SENtral at 0x28 - - // 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"); - - 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 > 3) break; - } - - if(!(readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x04)) Serial.println("EEPROM upload successful!"); - delay(1000); // give some time to read the screen - - // Set up the SENtral as sensor bus in normal operating mode -if(!passThru) { -// 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 -// Set accel/gyro/mage desired ODR rates -writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 100 Hz -writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x1E); // 30 Hz -writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x0A); // 100/10 Hz -writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x14); // 200/10 Hz - -// Configure operating mode -writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // read scale sensor data - -// Enable interrupt to host upon certain events -// choose interrupts when 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 - EM7180_set_integer_param (0x49, 0x00); - - //Write desired sensor full scale ranges to the EM7180 - EM7180_set_mag_acc_FS (0x3E8, 0x08); // 1000 uT, 8 g - EM7180_set_gyro_FS (0x7D0); // 2000 dps - - // 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.println("Magnetometer not acknowledging!"); - if(sensorStatus & 0x02) Serial.println("Accelerometer not acknowledging!"); - if(sensorStatus & 0x04) Serial.println("Gyro not acknowledging!"); - if(sensorStatus & 0x10) Serial.println("Magnetometer ID not recognized!"); - if(sensorStatus & 0x20) Serial.println("Accelerometer ID not recognized!"); - if(sensorStatus & 0x40) Serial.println("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"); - - delay(1000); // give some time to read the screen - - } - - // If pass through mode desired, set it up here - if(passThru) { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - -// Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - // Read the WHO_AM_I register, this is a good test of communication - Serial.println("BMI160 6-axis motion sensor..."); - byte c = readByte(BMI160_ADDRESS, BMI160_CHIP_ID); - Serial.print("BMI160 "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0xD1, HEX); - - delay(1000); - - // Read the WHO_AM_I register of the magnetometer, this is a good test of communication - byte d = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for AK8963 - Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x48, HEX); - - delay(1000); - - if ((c == 0xD1) && (d == 0x48) ) // WHO_AM_I should always be ACC/GYRO = 0xD1, MAG = 0x48 - { - Serial.println("BMI160 and AK8963C are online..."); - - delay(1000); - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - getMres(); - - Serial.println(" Calibrate gyro and accel"); - accelgyrofastcalBMI160(accelBias, gyroBias); // Calibrate gyro and accelerometers, load biases in bias registers - Serial.println("accel biases (mg)"); Serial.println(3.9*accelBias[0]); Serial.println(3.9*accelBias[1]); Serial.println(3.9*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(0.061*gyroBias[0]); Serial.println(0.061*gyroBias[1]); Serial.println(0.061*gyroBias[2]); - delay(1000); - - initBMI160(); - Serial.println("BMI160 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - - // Check power status of BMI160 - uint8_t pwr_status = readByte(BMI160_ADDRESS, BMI160_PMU_STATUS); - uint8_t acc_pwr = (pwr_status & 0x30) >> 4; - if (acc_pwr == 0x00) Serial.println("Accel Suspend Mode"); - if (acc_pwr == 0x01) Serial.println("Accel Normal Mode"); - if (acc_pwr == 0x02) Serial.println("Accel Low Power Mode"); - uint8_t gyr_pwr = (pwr_status & 0x0C) >> 2; - if (gyr_pwr == 0x00) Serial.println("Gyro Suspend Mode"); - if (gyr_pwr == 0x01) Serial.println("Gyro Normal Mode"); - if (gyr_pwr == 0x03) Serial.println("Gyro Fast Start Up Mode"); - delay(1000); - - - BMI160SelfTest(SelfTest); // Start by performing self test and reporting values - Serial.println("result of self test should be at least 2 g!"); - Serial.print("x-axis self test: acceleration delta is : "); Serial.print(SelfTest[0],1); Serial.println(" g"); - Serial.print("y-axis self test: acceleration delta is : "); Serial.print(SelfTest[1],1); Serial.println(" g"); - Serial.print("z-axis self test: acceleration delta is : "); Serial.print(SelfTest[2],1); Serial.println(" g"); - delay(1000); - - AK8963SelfTest(); - - // Get magnetometer calibration from AK8963 ROM - initAK8963(magCalibration); Serial.println("AK8963 initialized for active data mode...."); // Initialize device for active mode read of magnetometer - if(SerialDebug) { - Serial.println("Calibration values: "); - Serial.print("X-Axis sensitivity adjustment value "); Serial.println(magCalibration[0], 2); - Serial.print("Y-Axis sensitivity adjustment value "); Serial.println(magCalibration[1], 2); - Serial.print("Z-Axis sensitivity adjustment value "); Serial.println(magCalibration[2], 2); - } - - magcalAK8963(magBias); - Serial.println("mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]); - delay(1000); // add delay to see results before serial spew of data - } - else - { - Serial.print("Could not connect to BMI160: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } -} -} - - -void loop() -{ - - if(!passThru) { - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - if(eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); -if(errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus == 0x14) Serial.print("Gyro failure!"); - if(errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus == 0x30) Serial.print("Math error!"); - if(errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if(eventStatus & 0x10) { // new acceleration data available - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) { // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus & 0x08) { // new mag data available - readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - mx = (float)magCount[0]*0.305176; // get actual G value - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) { // new quaternion data available - readSENtralQuatData(Quat); - } - } - - if(passThru) { - if (readByte(BMI160_ADDRESS, BMI160_STATUS) & 0x40) { // check if new gyro data - readAccelGyroData(gyroCount, accelCount); // Read the x/y/z adc values - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*aRes; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes; - az = (float)accelCount[2]*aRes; - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes; - gz = (float)gyroCount[2]*gRes; - } - if (readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // Check magnetometer data ready bit - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - // Temperature-compensated magnetic field is in 16 LSB/microTesla - mx = (float)magCount[0]*mRes*magCalibration[0] - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes*magCalibration[1] - magBias[1]; - mz = (float)magCount[2]*mRes*magCalibration[2] - magBias[2]; - } - } - - - // keep track of rates - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - // Check to make sure the EM7180 is running properly - // 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"); - - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Use NED orientaton convention where N is direction of arrow on the board - // AK8963C has N = -y, E = -x, and D = -z if top of board == North - // BMI160 has N = x, E - -y, and D - -z for the gyro, and opposite by convention for the accel - // This rotation can be modified to allow any convenient orientation convention. - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(-ax, ay, az, gx*PI/180.0f, -gy*PI/180.0f, -gz*PI/180.0f, -my, -mx, -mz); -// if(passThru)MahonyQuaternionUpdate(-ax, ay, az, gx*PI/180.0f, -gy*PI/180.0f, -gz*PI/180.0f, -my, -mx, -mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - if (delt_t > 500) { // update LCD once per half-second independent of read rate - - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print( (int)mx); - Serial.print(" my = "); Serial.print( (int)my); - Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG"); - - Serial.println("Software quaternions:"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Quat[0]); - Serial.print(" Qx = "); Serial.print(Quat[1]); - Serial.print(" Qy = "); Serial.print(Quat[2]); - Serial.print(" Qz = "); Serial.println(Quat[3]); - } - - - tempCount = readTempData(); // Read the gyro adc values - temperature = ((float) tempCount) / 512.0 + 23.0; // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade - Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - - - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(yaw < 0) yaw += 360.0f; // Ensure yaw stays between 0 and 360 - roll *= 180.0f / PI; - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(Yaw < 0) Yaw += 360.0f ; // Ensure yaw stays between 0 and 360 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 260) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - // - - if(SerialDebug) { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } - -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== - -float 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; -} - -void 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 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 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 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 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]); -} - -void getMres() { - 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.*4219./8190.; // Proper scale to return milliGauss - break; - case MFS_16BITS: - mRes = 10.*4219./32760.0; // Proper scale to return milliGauss - break; - } -} - -void getGres() { - switch (Gscale) - { - // Possible gyro scales (and their register bit settings) are: - // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). - case GFS_125DPS: - gRes = 125.0/32768.0; - break; - case GFS_250DPS: - gRes = 250.0/32768.0; - break; - case GFS_500DPS: - gRes = 500.0/32768.0; - break; - case GFS_1000DPS: - gRes = 1000.0/32768.0; - break; - case GFS_2000DPS: - gRes = 2000.0/32768.0; - break; - } -} - -void getAres() { - switch (Ascale) - { - // Possible accelerometer scales (and their register bit settings) are: - // 2 Gs (00), 4 Gs (05), 8 Gs (08), and 16 Gs (0C). - case AFS_2G: - aRes = 2.0/32768.0; - break; - case AFS_4G: - aRes = 4.0/32768.0; - break; - case AFS_8G: - aRes = 8.0/32768.0; - break; - case AFS_16G: - aRes = 16.0/32768.0; - break; - } -} - - -void readAccelGyroData(int16_t * dest1, int16_t * dest2) -{ - uint8_t rawData[12]; // x/y/z accel register data stored here - readBytes(BMI160_ADDRESS, BMI160_GYRO_DATA, 12, &rawData[0]); // Read the twelve raw data registers into data array - dest1[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn gyro MSB and LSB into a signed 16-bit value - dest1[1] = ((int16_t)rawData[3] << 8) | rawData[2] ; - dest1[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; - - dest2[0] = ((int16_t)rawData[7] << 8) | rawData[6] ; // Turn accel MSB and LSB into a signed 16-bit value - dest2[1] = ((int16_t)rawData[9] << 8) | rawData[8] ; - dest2[2] = ((int16_t)rawData[11] << 8) | rawData[10] ; -} - - -void 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 readTempData() -{ - uint8_t rawData[2]; // x/y/z gyro register data stored here - readBytes(BMI160_ADDRESS, BMI160_TEMPERATURE, 2, &rawData[0]); // Read the two raw data registers sequentially into data array - return ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn the MSB and LSB into a 16-bit value -} - - -void initAK8963(float * destination) -{ - // First extract the factory calibration for each magnetometer axis - uint8_t rawData[3]; // x/y/z mag 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.; - 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 AK8963SelfTest() -{ - int16_t SelfTestData[3]; // x/y/z self test result stored here - writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer - delay(20); - - writeByte(AK8963_ADDRESS, AK8963_ASTC, 0x40); // Enable self test - writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x18); // enter self test mode, use 16-bit data - - while(!(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01)); // wait for data ready bit - readMagData(SelfTestData); - - writeByte(AK8963_ADDRESS, AK8963_ASTC, 0x00); // Disable self test - writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer - delay(20); - - Serial.print("x-axis self test = "); Serial.print(SelfTestData[0]); Serial.println(" should be +/- 200"); - Serial.print("y-axis self test = "); Serial.print(SelfTestData[1]); Serial.println(" should be +/- 200"); - Serial.print("z-axis self test = "); Serial.print(SelfTestData[2]); Serial.println(" should be -3200 to -800"); -} - - -void initBMI160() -{ - // configure accel and gyro - writeByte(BMI160_ADDRESS, BMI160_CMD, 0x11); // Set accel in normal mode operation - delay(50); // Wait for accel to reset - writeByte(BMI160_ADDRESS, BMI160_CMD, 0x15); // Set gyro in normal mode operation - delay(100); // Wait for gyro to reset - // Define accel full scale and sample rate - writeByte(BMI160_ADDRESS, BMI160_ACC_RANGE, Ascale); - writeByte(BMI160_ADDRESS, BMI160_ACC_CONF, ABW << 4 | AODR); - // Define gyro full scale and sample rate - writeByte(BMI160_ADDRESS, BMI160_GYR_RANGE, Gscale); - writeByte(BMI160_ADDRESS, BMI160_GYR_CONF, GBW << 4 | GODR); -} - - -void accelgyrofastcalBMI160(float * dest1, float * dest2) -{ - uint8_t rawData[7] = {0, 0, 0, 0, 0, 0, 0}; - - writeByte(BMI160_ADDRESS, BMI160_FOC_CONF, 0x4 | 0x30 | 0x0C | 0x01); // Enable gyro cal and accel cal with 0, 0, 1 as reference - delay(20); - writeByte(BMI160_ADDRESS, BMI160_CMD, 0x03); // start fast calibration - delay(50); - if(readByte(BMI160_ADDRESS, BMI160_ERR_REG) & 0x40) { // check if dropped command - Serial.println("Dropped fast offset compensation command!"); - return; - } - - while(!(readByte(BMI160_ADDRESS, BMI160_STATUS) & 0x08)); // wait for fast compensation data ready bit - if((readByte(BMI160_ADDRESS, BMI160_STATUS) & 0x08)) { - - readBytes(BMI160_ADDRESS, BMI160_OFFSET, 7, &rawData[0]); // Read the seven raw data registers into data array - dest1[0] = (float)(((int16_t)(rawData[0] << 8 ) | 0x00) >> 8); // Turn accel offset into a signed 8-bit value - dest1[1] = (float)(((int16_t)(rawData[1] << 8 ) | 0x00) >> 8); - dest1[2] = (float)(((int16_t)(rawData[2] << 8 ) | 0x00) >> 8); - - dest2[0] = (float)((((int16_t)(rawData[7] & 0x03) << 8) | rawData[3]) >> 6); // Turn gyro offset MSB and LSB into a signed 10-bit value - dest2[1] = (float)((((int16_t)(rawData[7] & 0x0C) << 8) | rawData[4]) >> 6); - dest2[2] = (float)((((int16_t)(rawData[7] & 0x30) << 8) | rawData[5]) >> 6); - - writeByte(BMI160_ADDRESS, BMI160_OFFSET_CONF, 0x40); // enable use of offset registers in data output - } - else { - Serial.println("couldn't get offsets!"); - } -} - - - -void magcalAK8963(float * dest1) -{ - uint16_t ii = 0, sample_count = 0; - int32_t mag_bias[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); - - sample_count = 512; - 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]; - } - delay(11); // 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]); - - 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*magCalibration[0]; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1]; - dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2]; - - Serial.println("Mag Calibration done!"); -} - - -void BMI160SelfTest(float * destination) -{ - uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; - uint16_t selfTestp[3], selfTestm[3]; - -// Enable Gyro Self Test - writeByte(BMI160_ADDRESS, BMI160_SELF_TEST, 0x10); // Enable Gyro Self Test - delay(100); - uint8_t result = readByte(BMI160_ADDRESS, BMI160_STATUS); - if(result & 0x02) { - Serial.println("Gyro Self test passed!"); - } - else { - Serial.println("Gyro Self test failed!"); - } - // disable self test - writeByte(BMI160_ADDRESS, BMI160_SELF_TEST, 0x00 ); // disable Self Test - delay(100); - -// Configure for Accel Self test - writeByte(BMI160_ADDRESS, BMI160_ACC_RANGE, AFS_8G); // set range to 8 g - writeByte(BMI160_ADDRESS, BMI160_ACC_CONF, 0x2C ); // Configure accel for Self Test - -// Enable Accel Self Test-positive deflection - writeByte(BMI160_ADDRESS, BMI160_SELF_TEST, 0x08 | 0x04 | 0x01 ); // Enable accel Self Test positive - delay(100); - readBytes(BMI160_ADDRESS, BMI160_ACCEL_DATA, 6, &rawData[0]); // Read the six raw data registers into data array - selfTestp[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn accel MSB and LSB into a signed 16-bit value - selfTestp[1] = ((int16_t)rawData[3] << 8) | rawData[2] ; - selfTestp[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; - - // disable self test - writeByte(BMI160_ADDRESS, BMI160_SELF_TEST, 0x00 ); // disable Self Test - delay(100); - -// Enable Accel Self Test-negative deflection - writeByte(BMI160_ADDRESS, BMI160_SELF_TEST, 0x08 | 0x01 ); // Enable accel Self Test negative - delay(100); - readBytes(BMI160_ADDRESS, BMI160_ACCEL_DATA, 6, &rawData[0]); // Read the six raw data registers into data array - selfTestm[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn accel MSB and LSB into a signed 16-bit value - selfTestm[1] = ((int16_t)rawData[3] << 8) | rawData[2] ; - selfTestm[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; - -// Serial.println(selfTestp[0]);Serial.println(selfTestp[1]);Serial.println(selfTestp[2]); - // Serial.println(selfTestm[0]);Serial.println(selfTestm[1]);Serial.println(selfTestm[2]); - - destination[0] = (float)(selfTestp[0] - selfTestm[0])*8./32768.; //construct differences between positve and negative defection, should be ~2 g - destination[1] = (float)(selfTestp[1] - selfTestm[1])*8./32768.; - destination[2] = (float)(selfTestp[2] - selfTestm[2])*8./32768.; - - // disable self test - writeByte(BMI160_ADDRESS, BMI160_SELF_TEST, 0x00 ); // disable Self Test - delay(100); - - writeByte(BMI160_ADDRESS, BMI160_ACC_RANGE, Ascale); // set range to original value - writeByte(BMI160_ADDRESS, BMI160_ACC_CONF, ABW << 4 | AODR); // return accel to original configuration -// End self tests -} - - -void SENtralPassThroughMode() -{ - // First put SENtral in standby mode - uint8_t c = readByte(EM7180_ADDRESS, EM7180_AlgorithmControl); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, c | 0x01); -// c = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); -// Serial.print("c = "); Serial.println(c); -// Verify standby status -// if(readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus) & 0x01) { - Serial.println("SENtral in standby mode"); - // Place SENtral in pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - if(readByte(EM7180_ADDRESS, EM7180_PassThruStatus) & 0x01) { - Serial.println("SENtral in pass-through mode"); - } - else { - Serial.println("ERROR! SENtral not in pass-through mode!"); - } - } - - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - - void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - - void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - if(count > 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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 MPU6500 and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - -void 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 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 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 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 -} diff --git a/EM7180_BMX055_BMP280.ino b/EM7180_BMX055_BMP280.ino deleted file mode 100644 index 0bd202e..0000000 --- a/EM7180_BMX055_BMP280.ino +++ /dev/null @@ -1,1805 +0,0 @@ -/* EM7180_BMX055_BMP280_t3 Basic Example Code - by: Kris Winer - date: December 24, 2014 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the BMX055, and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DRC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the BMX-055 9-axis motion sensor (accel/gyro/mag) as slave, an BMP280 pressure/temperature sensor, and an M24512DRC - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral can use the pressure data in the sensor fusion - yet and there is a driver for the BMP280 in the SENtral firmware. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The BMP280 is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+BMX055+MS5637+M24512DFM Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: The BMX055 is an I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ -//#include "Wire.h" -#include -#include - -// BMP280 registers -#define BMP280_TEMP_XLSB 0xFC -#define BMP280_TEMP_LSB 0xFB -#define BMP280_TEMP_MSB 0xFA -#define BMP280_PRESS_XLSB 0xF9 -#define BMP280_PRESS_LSB 0xF8 -#define BMP280_PRESS_MSB 0xF7 -#define BMP280_CONFIG 0xF5 -#define BMP280_CTRL_MEAS 0xF4 -#define BMP280_STATUS 0xF3 -#define BMP280_RESET 0xE0 -#define BMP280_ID 0xD0 // should be 0x58 -#define BMP280_CALIB00 0x88 - -// BMX055 data sheet http://ae-bst.resource.bosch.com/media/products/dokumente/bmx055/BST-BMX055-DS000-01v2.pdf -// The BMX055 is a conglomeration of three separate motion sensors packaged together but -// addressed and communicated with separately by design -// Accelerometer registers -#define BMX055_ACC_WHOAMI 0x00 // should return 0xFA -//#define BMX055_ACC_Reserved 0x01 -#define BMX055_ACC_D_X_LSB 0x02 -#define BMX055_ACC_D_X_MSB 0x03 -#define BMX055_ACC_D_Y_LSB 0x04 -#define BMX055_ACC_D_Y_MSB 0x05 -#define BMX055_ACC_D_Z_LSB 0x06 -#define BMX055_ACC_D_Z_MSB 0x07 -#define BMX055_ACC_D_TEMP 0x08 -#define BMX055_ACC_INT_STATUS_0 0x09 -#define BMX055_ACC_INT_STATUS_1 0x0A -#define BMX055_ACC_INT_STATUS_2 0x0B -#define BMX055_ACC_INT_STATUS_3 0x0C -//#define BMX055_ACC_Reserved 0x0D -#define BMX055_ACC_FIFO_STATUS 0x0E -#define BMX055_ACC_PMU_RANGE 0x0F -#define BMX055_ACC_PMU_BW 0x10 -#define BMX055_ACC_PMU_LPW 0x11 -#define BMX055_ACC_PMU_LOW_POWER 0x12 -#define BMX055_ACC_D_HBW 0x13 -#define BMX055_ACC_BGW_SOFTRESET 0x14 -//#define BMX055_ACC_Reserved 0x15 -#define BMX055_ACC_INT_EN_0 0x16 -#define BMX055_ACC_INT_EN_1 0x17 -#define BMX055_ACC_INT_EN_2 0x18 -#define BMX055_ACC_INT_MAP_0 0x19 -#define BMX055_ACC_INT_MAP_1 0x1A -#define BMX055_ACC_INT_MAP_2 0x1B -//#define BMX055_ACC_Reserved 0x1C -//#define BMX055_ACC_Reserved 0x1D -#define BMX055_ACC_INT_SRC 0x1E -//#define BMX055_ACC_Reserved 0x1F -#define BMX055_ACC_INT_OUT_CTRL 0x20 -#define BMX055_ACC_INT_RST_LATCH 0x21 -#define BMX055_ACC_INT_0 0x22 -#define BMX055_ACC_INT_1 0x23 -#define BMX055_ACC_INT_2 0x24 -#define BMX055_ACC_INT_3 0x25 -#define BMX055_ACC_INT_4 0x26 -#define BMX055_ACC_INT_5 0x27 -#define BMX055_ACC_INT_6 0x28 -#define BMX055_ACC_INT_7 0x29 -#define BMX055_ACC_INT_8 0x2A -#define BMX055_ACC_INT_9 0x2B -#define BMX055_ACC_INT_A 0x2C -#define BMX055_ACC_INT_B 0x2D -#define BMX055_ACC_INT_C 0x2E -#define BMX055_ACC_INT_D 0x2F -#define BMX055_ACC_FIFO_CONFIG_0 0x30 -//#define BMX055_ACC_Reserved 0x31 -#define BMX055_ACC_PMU_SELF_TEST 0x32 -#define BMX055_ACC_TRIM_NVM_CTRL 0x33 -#define BMX055_ACC_BGW_SPI3_WDT 0x34 -//#define BMX055_ACC_Reserved 0x35 -#define BMX055_ACC_OFC_CTRL 0x36 -#define BMX055_ACC_OFC_SETTING 0x37 -#define BMX055_ACC_OFC_OFFSET_X 0x38 -#define BMX055_ACC_OFC_OFFSET_Y 0x39 -#define BMX055_ACC_OFC_OFFSET_Z 0x3A -#define BMX055_ACC_TRIM_GPO 0x3B -#define BMX055_ACC_TRIM_GP1 0x3C -//#define BMX055_ACC_Reserved 0x3D -#define BMX055_ACC_FIFO_CONFIG_1 0x3E -#define BMX055_ACC_FIFO_DATA 0x3F - -// BMX055 Gyroscope Registers -#define BMX055_GYRO_WHOAMI 0x00 // should return 0x0F -//#define BMX055_GYRO_Reserved 0x01 -#define BMX055_GYRO_RATE_X_LSB 0x02 -#define BMX055_GYRO_RATE_X_MSB 0x03 -#define BMX055_GYRO_RATE_Y_LSB 0x04 -#define BMX055_GYRO_RATE_Y_MSB 0x05 -#define BMX055_GYRO_RATE_Z_LSB 0x06 -#define BMX055_GYRO_RATE_Z_MSB 0x07 -//#define BMX055_GYRO_Reserved 0x08 -#define BMX055_GYRO_INT_STATUS_0 0x09 -#define BMX055_GYRO_INT_STATUS_1 0x0A -#define BMX055_GYRO_INT_STATUS_2 0x0B -#define BMX055_GYRO_INT_STATUS_3 0x0C -//#define BMX055_GYRO_Reserved 0x0D -#define BMX055_GYRO_FIFO_STATUS 0x0E -#define BMX055_GYRO_RANGE 0x0F -#define BMX055_GYRO_BW 0x10 -#define BMX055_GYRO_LPM1 0x11 -#define BMX055_GYRO_LPM2 0x12 -#define BMX055_GYRO_RATE_HBW 0x13 -#define BMX055_GYRO_BGW_SOFTRESET 0x14 -#define BMX055_GYRO_INT_EN_0 0x15 -#define BMX055_GYRO_INT_EN_1 0x16 -#define BMX055_GYRO_INT_MAP_0 0x17 -#define BMX055_GYRO_INT_MAP_1 0x18 -#define BMX055_GYRO_INT_MAP_2 0x19 -#define BMX055_GYRO_INT_SRC_1 0x1A -#define BMX055_GYRO_INT_SRC_2 0x1B -#define BMX055_GYRO_INT_SRC_3 0x1C -//#define BMX055_GYRO_Reserved 0x1D -#define BMX055_GYRO_FIFO_EN 0x1E -//#define BMX055_GYRO_Reserved 0x1F -//#define BMX055_GYRO_Reserved 0x20 -#define BMX055_GYRO_INT_RST_LATCH 0x21 -#define BMX055_GYRO_HIGH_TH_X 0x22 -#define BMX055_GYRO_HIGH_DUR_X 0x23 -#define BMX055_GYRO_HIGH_TH_Y 0x24 -#define BMX055_GYRO_HIGH_DUR_Y 0x25 -#define BMX055_GYRO_HIGH_TH_Z 0x26 -#define BMX055_GYRO_HIGH_DUR_Z 0x27 -//#define BMX055_GYRO_Reserved 0x28 -//#define BMX055_GYRO_Reserved 0x29 -//#define BMX055_GYRO_Reserved 0x2A -#define BMX055_GYRO_SOC 0x31 -#define BMX055_GYRO_A_FOC 0x32 -#define BMX055_GYRO_TRIM_NVM_CTRL 0x33 -#define BMX055_GYRO_BGW_SPI3_WDT 0x34 -//#define BMX055_GYRO_Reserved 0x35 -#define BMX055_GYRO_OFC1 0x36 -#define BMX055_GYRO_OFC2 0x37 -#define BMX055_GYRO_OFC3 0x38 -#define BMX055_GYRO_OFC4 0x39 -#define BMX055_GYRO_TRIM_GP0 0x3A -#define BMX055_GYRO_TRIM_GP1 0x3B -#define BMX055_GYRO_BIST 0x3C -#define BMX055_GYRO_FIFO_CONFIG_0 0x3D -#define BMX055_GYRO_FIFO_CONFIG_1 0x3E - -// BMX055 magnetometer registers -#define BMX055_MAG_WHOAMI 0x40 // should return 0x32 -#define BMX055_MAG_Reserved 0x41 -#define BMX055_MAG_XOUT_LSB 0x42 -#define BMX055_MAG_XOUT_MSB 0x43 -#define BMX055_MAG_YOUT_LSB 0x44 -#define BMX055_MAG_YOUT_MSB 0x45 -#define BMX055_MAG_ZOUT_LSB 0x46 -#define BMX055_MAG_ZOUT_MSB 0x47 -#define BMX055_MAG_ROUT_LSB 0x48 -#define BMX055_MAG_ROUT_MSB 0x49 -#define BMX055_MAG_INT_STATUS 0x4A -#define BMX055_MAG_PWR_CNTL1 0x4B -#define BMX055_MAG_PWR_CNTL2 0x4C -#define BMX055_MAG_INT_EN_1 0x4D -#define BMX055_MAG_INT_EN_2 0x4E -#define BMX055_MAG_LOW_THS 0x4F -#define BMX055_MAG_HIGH_THS 0x50 -#define BMX055_MAG_REP_XY 0x51 -#define BMX055_MAG_REP_Z 0x52 -/* Trim Extended Registers */ -#define BMM050_DIG_X1 0x5D // needed for magnetic field calculation -#define BMM050_DIG_Y1 0x5E -#define BMM050_DIG_Z4_LSB 0x62 -#define BMM050_DIG_Z4_MSB 0x63 -#define BMM050_DIG_X2 0x64 -#define BMM050_DIG_Y2 0x65 -#define BMM050_DIG_Z2_LSB 0x68 -#define BMM050_DIG_Z2_MSB 0x69 -#define BMM050_DIG_Z1_LSB 0x6A -#define BMM050_DIG_Z1_MSB 0x6B -#define BMM050_DIG_XYZ1_LSB 0x6C -#define BMM050_DIG_XYZ1_MSB 0x6D -#define BMM050_DIG_Z3_LSB 0x6E -#define BMM050_DIG_Z3_MSB 0x6F -#define BMM050_DIG_XY2 0x70 -#define BMM050_DIG_XY1 0x71 - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 - -// Using the Teensy Mini Add-On board, BMX055 SDO1 = SDO2 = CSB3 = GND as designed -// Seven-bit BMX055 device addresses are ACC = 0x18, GYRO = 0x68, MAG = 0x10 -#define BMX055_ACC_ADDRESS 0x18 // Address of BMX055 accelerometer -#define BMX055_GYRO_ADDRESS 0x68 // Address of BMX055 gyroscope -#define BMX055_MAG_ADDRESS 0x10 // Address of BMX055 magnetometer -#define BMP280_ADDRESS 0x76 // Address of BMP280 altimeter -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page - -#define SerialDebug true // set to true to get Serial output for debugging - -// Set initial input parameters -// define X055 ACC full scale options -#define AFS_2G 0x03 -#define AFS_4G 0x05 -#define AFS_8G 0x08 -#define AFS_16G 0x0C - -enum ACCBW { // define BMX055 accelerometer bandwidths - ABW_8Hz, // 7.81 Hz, 64 ms update time - ABW_16Hz, // 15.63 Hz, 32 ms update time - ABW_31Hz, // 31.25 Hz, 16 ms update time - ABW_63Hz, // 62.5 Hz, 8 ms update time - ABW_125Hz, // 125 Hz, 4 ms update time - ABW_250Hz, // 250 Hz, 2 ms update time - ABW_500Hz, // 500 Hz, 1 ms update time - ABW_100Hz // 1000 Hz, 0.5 ms update time -}; - -enum Gscale { - GFS_2000DPS = 0, - GFS_1000DPS, - GFS_500DPS, - GFS_250DPS, - GFS_125DPS -}; - -enum GODRBW { - G_2000Hz523Hz = 0, // 2000 Hz ODR and unfiltered (bandwidth 523Hz) - G_2000Hz230Hz, - G_1000Hz116Hz, - G_400Hz47Hz, - G_200Hz23Hz, - G_100Hz12Hz, - G_200Hz64Hz, - G_100Hz32Hz // 100 Hz ODR and 32 Hz bandwidth -}; - -enum MODR { - MODR_10Hz = 0, // 10 Hz ODR - MODR_2Hz , // 2 Hz ODR - MODR_6Hz , // 6 Hz ODR - MODR_8Hz , // 8 Hz ODR - MODR_15Hz , // 15 Hz ODR - MODR_20Hz , // 20 Hz ODR - MODR_25Hz , // 25 Hz ODR - MODR_30Hz // 30 Hz ODR -}; - -enum Mmode { - lowPower = 0, // rms noise ~1.0 microTesla, 0.17 mA power - Regular , // rms noise ~0.6 microTesla, 0.5 mA power - enhancedRegular , // rms noise ~0.5 microTesla, 0.8 mA power - highAccuracy // rms noise ~0.3 microTesla, 4.9 mA power -}; - -enum Posr { - P_OSR_00 = 0, // no op - P_OSR_01, - P_OSR_02, - P_OSR_04, - P_OSR_08, - P_OSR_16 -}; - -enum Tosr { - T_OSR_00 = 0, // no op - T_OSR_01, - T_OSR_02, - T_OSR_04, - T_OSR_08, - T_OSR_16 -}; - -enum IIRFilter { - full = 0, // bandwidth at full sample rate - BW0_223ODR, - BW0_092ODR, - BW0_042ODR, - BW0_021ODR // bandwidth at 0.021 x sample rate -}; - -enum Mode { - BMP280Sleep = 0, - forced, - forced2, - normal -}; - -enum SBy { - t_00_5ms = 0, - t_62_5ms, - t_125ms, - t_250ms, - t_500ms, - t_1000ms, - t_2000ms, - t_4000ms, -}; - -// Specify BMP280 configuration -uint8_t Posr = P_OSR_16, Tosr = T_OSR_02, Mode = normal, IIRFilter = BW0_042ODR, SBy = t_62_5ms; // set pressure amd temperature output data rate -// t_fine carries fine temperature as global value for BMP280 -int32_t t_fine; - -uint8_t Gscale = GFS_125DPS; // set gyro full scale -uint8_t GODRBW = G_200Hz23Hz; // set gyro ODR and bandwidth -uint8_t Ascale = AFS_2G; // set accel full scale -uint8_t ACCBW = 0x08 | ABW_16Hz; // Choose bandwidth for accelerometer -uint8_t Mmode = Regular; // Choose magnetometer operation mode -uint8_t MODR = MODR_10Hz; // set magnetometer data rate -float aRes, gRes, mRes; // scale resolutions per LSB for the sensors - -// Parameters to hold BMX055 trim values -signed char dig_x1; -signed char dig_y1; -signed char dig_x2; -signed char dig_y2; -uint16_t dig_z1; -int16_t dig_z2; -int16_t dig_z3; -int16_t dig_z4; -unsigned char dig_xy1; -signed char dig_xy2; -uint16_t dig_xyz1; - -// Pin definitions -int myLed = 13; // LED on the Teensy 3.1 - -// BMP280 compensation parameters -uint16_t dig_T1, dig_P1; -int16_t dig_T2, dig_T3, dig_P2, dig_P3, dig_P4, dig_P5, dig_P6, dig_P7, dig_P8, dig_P9; -double Temperature, Pressure; // stores BMP280 pressures sensor pressure and temperature -int32_t rawPress, rawTemp; // pressure and temperature raw count output for BMP280 - -// BMX055 variables -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 13/15-bit signed magnetometer sensor output -float Quat[4] = {0, 0, 0, 0}; // quaternion data register -float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag -int16_t tempCount; // temperature raw count output -float temperature; // Stores the BMX055 internal chip temperature in degrees Celsius -float SelfTest[6]; // holds results of gyro and accelerometer self test - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Ki 0.0f - -uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval -uint8_t param[4]; // used for param transfer -uint16_t EM7180_mag_fs, EM7180_acc_fs, EM7180_gyro_fs; // EM7180 sensor full scale ranges - -float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -bool passThru = false; - -void setup() -{ -// Wire.begin(); -// TWBR = 12; // 400 kbit/sec I2C speed for Pro Mini - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(5000); - Serial.begin(38400); - - I2Cscan(); // should detect SENtral at 0x28 - - // 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"); - - 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!"); - delay(1000); // give some time to read the screen - - // Set up the SENtral as sensor bus in normal operating mode -if(!passThru) { -// 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 -// Set accel/gyro/mage desired ODR rates -writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 100 Hz -writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x1E); // 30 Hz -writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x0A); // 100/10 Hz -writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x14); // 200/10 Hz -// Configure operating mode -writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // read scale sensor data -// Enable interrupt to host upon certain events -// choose interrupts when 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 - EM7180_set_integer_param (0x49, 0x00); - - //Write desired sensor full scale ranges to the EM7180 - EM7180_set_mag_acc_FS (0x3E8, 0x08); // 1000 uT, 8 g - EM7180_set_gyro_FS (0x7D0); // 2000 dps - - // 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"); - - delay(1000); // give some time to read the screen - - } - - // If pass through mode desired, set it up here - if(passThru) { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - -// Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - delay(1000); - - // Read the BMX-055 WHO_AM_I registers, this is a good test of communication - Serial.println("BMX055 accelerometer..."); - byte c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_WHOAMI); // Read ACC WHO_AM_I register for BMX055 - Serial.print("BMX055 ACC"); Serial.print(" I AM 0x"); Serial.print(c, HEX); Serial.print(" I should be 0x"); Serial.println(0xFA, HEX); - - delay(1000); - - Serial.println("BMX055 gyroscope..."); - byte d = readByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_WHOAMI); // Read GYRO WHO_AM_I register for BMX055 - Serial.print("BMX055 GYRO"); Serial.print(" I AM 0x"); Serial.print(d, HEX); Serial.print(" I should be 0x"); Serial.println(0x0F, HEX); - - delay(1000); - - Serial.println("BMX055 magnetometer..."); - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x01); // wake up magnetometer first thing - delay(100); - byte e = readByte(BMX055_MAG_ADDRESS, BMX055_MAG_WHOAMI); // Read MAG WHO_AM_I register for BMX055 - Serial.print("BMX055 MAG"); Serial.print(" I AM 0x"); Serial.print(e, HEX); Serial.print(" I should be 0x"); Serial.println(0x32, HEX); - - delay(1000); - - if ((c == 0xFA) && (d == 0x0F) && (e == 0x32)) // WHO_AM_I should always be ACC = 0xFA, GYRO = 0x0F, MAG = 0x32 - { - Serial.println("BMX055 is online..."); - - delay(1000); - - initBMX055(); - Serial.println("BMX055 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - - delay(1000); - - // Read the WHO_AM_I register of the BMP280 this is a good test of communication - byte f = readByte(BMP280_ADDRESS, BMP280_ID); // Read WHO_AM_I register for BMP280 - Serial.print("BMP280 "); - Serial.print("I AM "); - Serial.print(f, HEX); - Serial.print(" I should be "); - Serial.println(0x58, HEX); - Serial.println(" "); - - delay(1000); - - writeByte(BMP280_ADDRESS, BMP280_RESET, 0xB6); // reset BMP280 before initilization - delay(100); - - BMP280Init(); // Initialize BMP280 altimeter - Serial.println("Calibration coeficients:"); - Serial.print("dig_T1 ="); - Serial.println(dig_T1); - Serial.print("dig_T2 ="); - Serial.println(dig_T2); - Serial.print("dig_T3 ="); - Serial.println(dig_T3); - Serial.print("dig_P1 ="); - Serial.println(dig_P1); - Serial.print("dig_P2 ="); - Serial.println(dig_P2); - Serial.print("dig_P3 ="); - Serial.println(dig_P3); - Serial.print("dig_P4 ="); - Serial.println(dig_P4); - Serial.print("dig_P5 ="); - Serial.println(dig_P5); - Serial.print("dig_P6 ="); - Serial.println(dig_P6); - Serial.print("dig_P7 ="); - Serial.println(dig_P7); - Serial.print("dig_P8 ="); - Serial.println(dig_P8); - Serial.print("dig_P9 ="); - Serial.println(dig_P9); - - delay(1000); - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - // magnetometer resolution is 1 microTesla/16 counts or 1/1.6 milliGauss/count - mRes = 1./1.6; - trimBMX055(); // read the magnetometer calibration data - - delay(1000); - - - fastcompaccelBMX055(accelBias); - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - magcalBMX055(magBias); - Serial.println("mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]); - - } - else - { - Serial.print("Could not connect to BMX055: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } -} -} - - -void loop() -{ - if(!passThru) { - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - if(eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if(errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus == 0x14) Serial.print("Gyro failure!"); - if(errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus == 0x30) Serial.print("Math error!"); - if(errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if(eventStatus & 0x10) { // new acceleration data available - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) { // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus & 0x08) { // new mag data available - readSENtralMagData(magCount); - - // Calculate the magnetometer values in milliGauss - // Temperature-compensated magnetic field is in 32768 LSB/10 microTesla - mx = (float)magCount[0]*0.32768; // get actual magnetometer value in mGauss - my = (float)magCount[1]*0.32768; - mz = (float)magCount[2]*0.32768; - } - - if(readByte(EM7180_ADDRESS, EM7180_EventStatus) & 0x04) { // new quaternion data available - readSENtralQuatData(Quat); - } - } - - if(passThru) { - // If intPin goes high, all data registers have new data -// if (digitalRead(intACC2)) { // On interrupt, read data - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*aRes; // + accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes; // + accelBias[1]; - az = (float)accelCount[2]*aRes; // + accelBias[2]; - // } -// if (digitalRead(intGYRO2)) { // On interrupt, read data - readGyroData(gyroCount); // Read the x/y/z adc values - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes; - gz = (float)gyroCount[2]*gRes; - // } -// if (digitalRead(intDRDYM)) { // On interrupt, read data - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - // Temperature-compensated magnetic field is in 16 LSB/microTesla - mx = (float)magCount[0]*mRes - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes - magBias[1]; - mz = (float)magCount[2]*mRes - magBias[2]; - // } - } - - - // keep track of rates - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer is aligned with the -y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ up) is aligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // For the BMX-055, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like - // in the MPU9250 sensor. This rotation can be modified to allow any convenient orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate( -ax, ay, -az, -gx*PI/180.0f, gy*PI/180.0f, -gz*PI/180.0f, my, mx, -mz); -// if(passThru)MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, mx, mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - if (delt_t > 1000) { // update LCD once per half-second independent of read rate - - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print( (int)mx); - Serial.print(" my = "); Serial.print( (int)my); - Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG"); - - Serial.println("Software quaternions:"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Quat[3]); - Serial.print(" Qx = "); Serial.print(Quat[0]); - Serial.print(" Qy = "); Serial.print(Quat[1]); - Serial.print(" Qz = "); Serial.println(Quat[2]); - } - - -// tempCount = readTempData(); // Read the gyro adc values -// temperature = ((float) tempCount) / 333.87 + 21.0; // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade -// Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - if(passThru) { - rawPress = readBMP280Pressure(); - Pressure = (float) bmp280_compensate_P(rawPress)/25600.; // Pressure in mbar - rawTemp = readBMP280Temperature(); - Temperature = (float) bmp280_compensate_T(rawTemp)/100.; - - float altitude = 145366.45f*(1.0f - pow((Pressure/1013.25f), 0.190284f)); - - if(SerialDebug) { - Serial.println("BMP280:"); - Serial.print("Altimeter temperature = "); - Serial.print( Temperature, 2); - Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); - Serial.print(9.*Temperature/5. + 32., 2); - Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); - Serial.print(Pressure, 2); - Serial.println(" mbar");// pressure in millibar - Serial.print("Altitude = "); - Serial.print(altitude, 2); - Serial.println(" feet"); - Serial.println(" "); - } - } - - - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - roll *= 180.0f / PI; - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 260) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - // - - if(SerialDebug) { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - - Serial.print(millis()/1000);Serial.print(","); - Serial.print(yaw, 2); Serial.print(",");Serial.print(pitch, 2); Serial.print(",");Serial.print(roll, 2); Serial.print(","); - Serial.print(Yaw, 2); Serial.print(",");Serial.print(Pitch, 2); Serial.print(",");Serial.print(Roll, 2); Serial.println(","); - - /* - display.clearDisplay(); - - display.setCursor(0, 0); display.print(" x y z "); - - display.setCursor(0, 8); display.print((int)(1000*ax)); - display.setCursor(24, 8); display.print((int)(1000*ay)); - display.setCursor(48, 8); display.print((int)(1000*az)); - display.setCursor(72, 8); display.print("mg"); - - // tempCount = readACCTempData(); // Read the gyro adc values - // temperature = ((float) tempCount) / 2.0 + 23.0; // Gyro chip temperature in degrees Centigrade - // display.setCursor(64, 0); display.print(9.*temperature/5. + 32., 0); display.print("F"); - - display.setCursor(0, 16); display.print((int)(gx)); - display.setCursor(24, 16); display.print((int)(gy)); - display.setCursor(48, 16); display.print((int)(gz)); - display.setCursor(66, 16); display.print("o/s"); - - display.setCursor(0, 24); display.print((int)(mx)); - display.setCursor(24, 24); display.print((int)(my)); - display.setCursor(48, 24); display.print((int)(mz)); - display.setCursor(72, 24); display.print("mG"); - - display.setCursor(0, 32); display.print((int)(yaw)); - display.setCursor(24, 32); display.print((int)(pitch)); - display.setCursor(48, 32); display.print((int)(roll)); - display.setCursor(66, 32); display.print("ypr"); - - -// display.setCursor(0, 40); display.print(altitude, 0); display.print("ft"); -// display.setCursor(68, 0); display.print(9.*Temperature/5. + 32., 0); - display.setCursor(42, 40); display.print((float) sumCount / (1000.*sum), 2); display.print("kHz"); - display.display(); -*/ - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } - -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== - -void getGres() { - switch (Gscale) - { - // Possible gyro scales (and their register bit settings) are: - // 125 DPS (100), 250 DPS (011), 500 DPS (010), 1000 DPS (001), and 2000 DPS (000). - case GFS_125DPS: - gRes = 124.87/32768.0; // per data sheet, not exactly 125!? - break; - case GFS_250DPS: - gRes = 249.75/32768.0; - break; - case GFS_500DPS: - gRes = 499.5/32768.0; - break; - case GFS_1000DPS: - gRes = 999.0/32768.0; - break; - case GFS_2000DPS: - gRes = 1998.0/32768.0; - break; - } -} - -void getAres() { - switch (Ascale) - { - // Possible accelerometer scales (and their register bit settings) are: - // 2 Gs (0011), 4 Gs (0101), 8 Gs (1000), and 16 Gs (1100). - // BMX055 ACC data is signed 12 bit - case AFS_2G: - aRes = 2.0/2048.0; - break; - case AFS_4G: - aRes = 4.0/2048.0; - break; - case AFS_8G: - aRes = 8.0/2048.0; - break; - case AFS_16G: - aRes = 16.0/2048.0; - break; - } -} - -float 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; -} - - -void 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 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 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 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 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 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[0] = uint32_reg_to_float (&rawData[0]); - destination[1] = uint32_reg_to_float (&rawData[4]); - destination[2] = uint32_reg_to_float (&rawData[8]); - destination[3] = uint32_reg_to_float (&rawData[12]); - -} - -void 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 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 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]); -} - -void readAccelData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z accel register data stored here - readBytes(BMX055_ACC_ADDRESS, BMX055_ACC_D_X_LSB, 6, &rawData[0]); // Read the six raw data registers into data array - if((rawData[0] & 0x01) && (rawData[2] & 0x01) && (rawData[4] & 0x01)) { // Check that all 3 axes have new data - destination[0] = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]) >> 4; // Turn the MSB and LSB into a signed 12-bit value - destination[1] = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]) >> 4; - destination[2] = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]) >> 4; - } -} - -void readGyroData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z gyro register data stored here - readBytes(BMX055_GYRO_ADDRESS, BMX055_GYRO_RATE_X_LSB, 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 readMagData(int16_t * magData) -{ - int16_t mdata_x = 0, mdata_y = 0, mdata_z = 0, temp = 0; - uint16_t data_r = 0; - uint8_t rawData[8]; // x/y/z hall magnetic field data, and Hall resistance data - readBytes(BMX055_MAG_ADDRESS, BMX055_MAG_XOUT_LSB, 8, &rawData[0]); // Read the eight raw data registers sequentially into data array - if(rawData[6] & 0x01) { // Check if data ready status bit is set - mdata_x = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]) >> 3; // 13-bit signed integer for x-axis field - mdata_y = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]) >> 3; // 13-bit signed integer for y-axis field - mdata_z = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]) >> 1; // 15-bit signed integer for z-axis field - data_r = (uint16_t) (((uint16_t)rawData[7] << 8) | rawData[6]) >> 2; // 14-bit unsigned integer for Hall resistance - - // calculate temperature compensated 16-bit magnetic fields - temp = ((int16_t)(((uint16_t)((((int32_t)dig_xyz1) << 14)/(data_r != 0 ? data_r : dig_xyz1))) - ((uint16_t)0x4000))); - magData[0] = ((int16_t)((((int32_t)mdata_x) * - ((((((((int32_t)dig_xy2) * ((((int32_t)temp) * ((int32_t)temp)) >> 7)) + - (((int32_t)temp) * ((int32_t)(((int16_t)dig_xy1) << 7)))) >> 9) + - ((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_x2) + ((int16_t)0xA0)))) >> 12)) >> 13)) + - (((int16_t)dig_x1) << 3); - - temp = ((int16_t)(((uint16_t)((((int32_t)dig_xyz1) << 14)/(data_r != 0 ? data_r : dig_xyz1))) - ((uint16_t)0x4000))); - magData[1] = ((int16_t)((((int32_t)mdata_y) * - ((((((((int32_t)dig_xy2) * ((((int32_t)temp) * ((int32_t)temp)) >> 7)) + - (((int32_t)temp) * ((int32_t)(((int16_t)dig_xy1) << 7)))) >> 9) + - ((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_y2) + ((int16_t)0xA0)))) >> 12)) >> 13)) + - (((int16_t)dig_y1) << 3); - magData[2] = (((((int32_t)(mdata_z - dig_z4)) << 15) - ((((int32_t)dig_z3) * ((int32_t)(((int16_t)data_r) - - ((int16_t)dig_xyz1))))>>2))/(dig_z2 + ((int16_t)(((((int32_t)dig_z1) * ((((int16_t)data_r) << 1)))+(1<<15))>>16)))); - } - } - -int16_t readACCTempData() -{ - uint8_t c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_D_TEMP); // Read the raw data register - return ((int16_t)((int16_t)c << 8)) >> 8 ; // Turn the byte into a signed 8-bit integer -} - -void SENtralPassThroughMode() -{ - // First put SENtral in standby mode - uint8_t c = readByte(EM7180_ADDRESS, EM7180_AlgorithmControl); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, c | 0x01); -// c = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); -// Serial.print("c = "); Serial.println(c); -// Verify standby status -// if(readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus) & 0x01) { - Serial.println("SENtral in standby mode"); - // Place SENtral in pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - if(readByte(EM7180_ADDRESS, EM7180_PassThruStatus) & 0x01) { - Serial.println("SENtral in pass-through mode"); - } - else { - Serial.println("ERROR! SENtral not in pass-through mode!"); - } - -// } -// else { Serial.println("ERROR! SENtral not in standby mode!"); -// } - - } - - - - -void trimBMX055() // get trim values for magnetometer sensitivity -{ - uint8_t rawData[2]; //placeholder for 2-byte trim data - dig_x1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_X1); - dig_x2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_X2); - dig_y1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_Y1); - dig_y2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_Y2); - dig_xy1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_XY1); - dig_xy2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_XY2); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z1_LSB, 2, &rawData[0]); - dig_z1 = (uint16_t) (((uint16_t)rawData[1] << 8) | rawData[0]); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z2_LSB, 2, &rawData[0]); - dig_z2 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z3_LSB, 2, &rawData[0]); - dig_z3 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z4_LSB, 2, &rawData[0]); - dig_z4 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_XYZ1_LSB, 2, &rawData[0]); - dig_xyz1 = (uint16_t) (((uint16_t)rawData[1] << 8) | rawData[0]); -} - - -void initBMX055() -{ - // start with all sensors in default mode with all registers reset - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_BGW_SOFTRESET, 0xB6); // reset accelerometer - delay(1000); // Wait for all registers to reset - - // Configure accelerometer - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_PMU_RANGE, Ascale & 0x0F); // Set accelerometer full range - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_PMU_BW, ACCBW & 0x0F); // Set accelerometer bandwidth - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_D_HBW, 0x00); // Use filtered data - -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_EN_1, 0x10); // Enable ACC data ready interrupt -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_OUT_CTRL, 0x04); // Set interrupts push-pull, active high for INT1 and INT2 -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_MAP_1, 0x02); // Define INT1 (intACC1) as ACC data ready interrupt -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_MAP_1, 0x80); // Define INT2 (intACC2) as ACC data ready interrupt - -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_BGW_SPI3_WDT, 0x06); // Set watchdog timer for 50 ms - - // Configure Gyro - // start by resetting gyro, better not since it ends up in sleep mode?! -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BGW_SOFTRESET, 0xB6); // reset gyro -// delay(100); - // Three power modes, 0x00 Normal, - // set bit 7 to 1 for suspend mode, set bit 5 to 1 for deep suspend mode - // sleep duration in fast-power up from suspend mode is set by bits 1 - 3 - // 000 for 2 ms, 111 for 20 ms, etc. -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_LPM1, 0x00); // set GYRO normal mode -// set GYRO sleep duration for fast power-up mode to 20 ms, for duty cycle of 50% -// writeByte(BMX055_ACC_ADDRESS, BMX055_GYRO_LPM1, 0x0E); - // set bit 7 to 1 for fast-power-up mode, gyro goes quickly to normal mode upon wake up -// can set external wake-up interrupts on bits 5 and 4 -// auto-sleep wake duration set in bits 2-0, 001 4 ms, 111 40 ms -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_LPM2, 0x00); // set GYRO normal mode -// set gyro to fast wake up mode, will sleep for 20 ms then run normally for 20 ms -// and collect data for an effective ODR of 50 Hz, other duty cycles are possible but there -// is a minimum wake duration determined by the bandwidth duration, e.g., > 10 ms for 23Hz gyro bandwidth -// writeByte(BMX055_ACC_ADDRESS, BMX055_GYRO_LPM2, 0x87); - - writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_RANGE, Gscale); // set GYRO FS range - writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BW, GODRBW); // set GYRO ODR and Bandwidth - -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_EN_0, 0x80); // enable data ready interrupt -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_EN_1, 0x04); // select push-pull, active high interrupts -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_MAP_1, 0x80); // select INT3 (intGYRO1) as GYRO data ready interrupt - -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BGW_SPI3_WDT, 0x06); // Enable watchdog timer for I2C with 50 ms window - - -// Configure magnetometer -writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x82); // Softreset magnetometer, ends up in sleep mode -delay(100); -writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x01); // Wake up magnetometer -delay(100); - -writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL2, MODR << 3); // Normal mode -//writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL2, MODR << 3 | 0x02); // Forced mode - -//writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_INT_EN_2, 0x84); // Enable data ready pin interrupt, active high - -// Set up four standard configurations for the magnetometer - switch (Mmode) - { - case lowPower: - // Low-power - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x01); // 3 repetitions (oversampling) - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x02); // 3 repetitions (oversampling) - break; - case Regular: - // Regular - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x04); // 9 repetitions (oversampling) - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x16); // 15 repetitions (oversampling) - break; - case enhancedRegular: - // Enhanced Regular - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x07); // 15 repetitions (oversampling) - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x22); // 27 repetitions (oversampling) - break; - case highAccuracy: - // High Accuracy - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x17); // 47 repetitions (oversampling) - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x51); // 83 repetitions (oversampling) - break; - } -} - -void fastcompaccelBMX055(float * dest1) -{ - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x80); // set all accel offset compensation registers to zero - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_SETTING, 0x20); // set offset targets to 0, 0, and +1 g for x, y, z axes - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x20); // calculate x-axis offset - - byte c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - while(!(c & 0x10)) { // check if fast calibration complete - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - delay(10); -} - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x40); // calculate y-axis offset - - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - while(!(c & 0x10)) { // check if fast calibration complete - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - delay(10); -} - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x60); // calculate z-axis offset - - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - while(!(c & 0x10)) { // check if fast calibration complete - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - delay(10); -} - - int8_t compx = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_X); - int8_t compy = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_Y); - int8_t compz = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_Z); - - dest1[0] = (float) compx/128.; // accleration bias in g - dest1[1] = (float) compy/128.; // accleration bias in g - dest1[2] = (float) compz/128.; // accleration bias in g -} -/* -// 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 accelgyrocalBMX055(float * dest1, float * dest2) -{ - uint8_t data[6] = {0, 0, 0, 0, 0, 0}; - int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; - uint16_t samples, ii; - - Serial.println("Calibrating gyro..."); - - // First get gyro bias - byte c = readByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G); - writeByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G, c | 0x40); // Enable gyro FIFO - delay(200); // Wait for change to take effect - writeByte(BMX055G_ADDRESS, BMX055G_FIFO_CTRL_REG_G, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples - delay(1000); // delay 1000 milliseconds to collect FIFO samples - - samples = (readByte(BMX055G_ADDRESS, BMX055G_FIFO_SRC_REG_G) & 0x1F); // Read number of stored samples - - for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO - int16_t gyro_temp[3] = {0, 0, 0}; - readBytes(BMX055G_ADDRESS, BMX055G_OUT_X_L_G, 6, &data[0]); - gyro_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO - gyro_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]); - gyro_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]); - - gyro_bias[0] += (int32_t) gyro_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases - gyro_bias[1] += (int32_t) gyro_temp[1]; - gyro_bias[2] += (int32_t) gyro_temp[2]; - } - - gyro_bias[0] /= samples; // average the data - gyro_bias[1] /= samples; - gyro_bias[2] /= samples; - - dest1[0] = (float)gyro_bias[0]*gRes; // Properly scale the data to get deg/s - dest1[1] = (float)gyro_bias[1]*gRes; - dest1[2] = (float)gyro_bias[2]*gRes; - - c = readByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G); - writeByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G, c & ~0x40); //Disable gyro FIFO - delay(200); - writeByte(BMX055G_ADDRESS, BMX055G_FIFO_CTRL_REG_G, 0x00); // Enable gyro bypass mode - - Serial.println("Calibrating accel..."); - - // now get the accelerometer bias - c = readByte(BMX055XM_ADDRESS, BMX055XM_CTRL_REG0_XM); - writeByte(BMX055XM_ADDRESS, BMX055XM_CTRL_REG0_XM, c | 0x40); // Enable gyro FIFO - delay(200); // Wait for change to take effect - writeByte(BMX055XM_ADDRESS, BMX055XM_FIFO_CTRL_REG, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples - delay(1000); // delay 1000 milliseconds to collect FIFO samples - - samples = (readByte(BMX055XM_ADDRESS, BMX055XM_FIFO_SRC_REG) & 0x1F); // Read number of stored samples - - for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO - int16_t accel_temp[3] = {0, 0, 0}; - readBytes(BMX055XM_ADDRESS, BMX055XM_OUT_X_L_A, 6, &data[0]); - accel_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO - accel_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]); - accel_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]); - - 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]; - } - - accel_bias[0] /= samples; // average the data - accel_bias[1] /= samples; - accel_bias[2] /= samples; - - if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) (1.0/aRes);} // Remove gravity from the z-axis accelerometer bias calculation - else {accel_bias[2] += (int32_t) (1.0/aRes);} - - dest2[0] = (float)accel_bias[0]*aRes; // Properly scale the data to get g - dest2[1] = (float)accel_bias[1]*aRes; - dest2[2] = (float)accel_bias[2]*aRes; - - c = readByte(BMX055XM_ADDRESS, BMX055XM_CTRL_REG0_XM); - writeByte(BMX055XM_ADDRESS, BMX055XM_CTRL_REG0_XM, c & ~0x40); //Disable accel FIFO - delay(200); - writeByte(BMX055XM_ADDRESS, BMX055XM_FIFO_CTRL_REG, 0x00); // Enable accel bypass mode -} -*/ -void magcalBMX055(float * dest1) -{ - uint16_t ii = 0, sample_count = 0; - int32_t mag_bias[3] = {0, 0, 0}; - int16_t mag_max[3] = {0, 0, 0}, mag_min[3] = {0, 0, 0}; - - Serial.println("Mag Calibration: Wave device in a figure eight until done!"); - delay(4000); - - sample_count = 128; - for(ii = 0; ii < sample_count; ii++) { - int16_t mag_temp[3] = {0, 0, 0}; - readMagData(mag_temp); - 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]; - } - delay(105); // at 10 Hz ODR, new mag data is available every 100 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]); - - 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; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes; - dest1[2] = (float) mag_bias[2]*mRes; - - /* //write biases to accelerometermagnetometer offset registers as counts); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_X_REG_L_M, (int16_t) mag_bias[0] & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_X_REG_H_M, ((int16_t)mag_bias[0] >> 8) & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_Y_REG_L_M, (int16_t) mag_bias[1] & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_Y_REG_H_M, ((int16_t)mag_bias[1] >> 8) & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_Z_REG_L_M, (int16_t) mag_bias[2] & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_Z_REG_H_M, ((int16_t)mag_bias[2] >> 8) & 0xFF); - */ - Serial.println("Mag Calibration done!"); -} - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - - void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - - void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - if(count > 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - - - -int32_t readBMP280Temperature() -{ - uint8_t rawData[3]; // 20-bit pressure register data stored here - readBytes(BMP280_ADDRESS, BMP280_TEMP_MSB, 3, &rawData[0]); - return (int32_t) (((int32_t) rawData[0] << 16 | (int32_t) rawData[1] << 8 | rawData[2]) >> 4); -} - -int32_t readBMP280Pressure() -{ - uint8_t rawData[3]; // 20-bit pressure register data stored here - readBytes(BMP280_ADDRESS, BMP280_PRESS_MSB, 3, &rawData[0]); - return (int32_t) (((int32_t) rawData[0] << 16 | (int32_t) rawData[1] << 8 | rawData[2]) >> 4); -} - -void BMP280Init() -{ - // Configure the BMP280 - // Set T and P oversampling rates and sensor mode - writeByte(BMP280_ADDRESS, BMP280_CTRL_MEAS, Tosr << 5 | Posr << 2 | Mode); - // Set standby time interval in normal mode and bandwidth - writeByte(BMP280_ADDRESS, BMP280_CONFIG, SBy << 5 | IIRFilter << 2); - // Read and store calibration data - uint8_t calib[24]; - readBytes(BMP280_ADDRESS, BMP280_CALIB00, 24, &calib[0]); - dig_T1 = (uint16_t)(((uint16_t) calib[1] << 8) | calib[0]); - dig_T2 = ( int16_t)((( int16_t) calib[3] << 8) | calib[2]); - dig_T3 = ( int16_t)((( int16_t) calib[5] << 8) | calib[4]); - dig_P1 = (uint16_t)(((uint16_t) calib[7] << 8) | calib[6]); - dig_P2 = ( int16_t)((( int16_t) calib[9] << 8) | calib[8]); - dig_P3 = ( int16_t)((( int16_t) calib[11] << 8) | calib[10]); - dig_P4 = ( int16_t)((( int16_t) calib[13] << 8) | calib[12]); - dig_P5 = ( int16_t)((( int16_t) calib[15] << 8) | calib[14]); - dig_P6 = ( int16_t)((( int16_t) calib[17] << 8) | calib[16]); - dig_P7 = ( int16_t)((( int16_t) calib[19] << 8) | calib[18]); - dig_P8 = ( int16_t)((( int16_t) calib[21] << 8) | calib[20]); - dig_P9 = ( int16_t)((( int16_t) calib[23] << 8) | calib[22]); -} - -// Returns temperature in DegC, resolution is 0.01 DegC. Output value of -// “5123” equals 51.23 DegC. -int32_t bmp280_compensate_T(int32_t adc_T) -{ - int32_t var1, var2, T; - var1 = ((((adc_T >> 3) - ((int32_t)dig_T1 << 1))) * ((int32_t)dig_T2)) >> 11; - var2 = (((((adc_T >> 4) - ((int32_t)dig_T1)) * ((adc_T >> 4) - ((int32_t)dig_T1))) >> 12) * ((int32_t)dig_T3)) >> 14; - t_fine = var1 + var2; - T = (t_fine * 5 + 128) >> 8; - return T; -} - -// Returns pressure in Pa as unsigned 32 bit integer in Q24.8 format (24 integer bits and 8 -//fractional bits). -//Output value of “24674867” represents 24674867/256 = 96386.2 Pa = 963.862 hPa -uint32_t bmp280_compensate_P(int32_t adc_P) -{ - long long var1, var2, p; - var1 = ((long long)t_fine) - 128000; - var2 = var1 * var1 * (long long)dig_P6; - var2 = var2 + ((var1*(long long)dig_P5)<<17); - var2 = var2 + (((long long)dig_P4)<<35); - var1 = ((var1 * var1 * (long long)dig_P3)>>8) + ((var1 * (long long)dig_P2)<<12); - var1 = (((((long long)1)<<47)+var1))*((long long)dig_P1)>>33; - if(var1 == 0) - { - return 0; - // avoid exception caused by division by zero - } - p = 1048576 - adc_P; - p = (((p<<31) - var2)*3125)/var1; - var1 = (((long long)dig_P9) * (p>>13) * (p>>13)) >> 25; - var2 = (((long long)dig_P8) * p)>> 19; - p = ((p + var1 + var2) >> 8) + (((long long)dig_P7)<<4); - return (uint32_t)p; -} - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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 and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} diff --git a/EM7180_BMX055_MS5637_BasicAHRS_t3.ino b/EM7180_BMX055_MS5637_BasicAHRS_t3.ino deleted file mode 100644 index 1588a2d..0000000 --- a/EM7180_BMX055_MS5637_BasicAHRS_t3.ino +++ /dev/null @@ -1,1650 +0,0 @@ -/* EM7180_BMX055_MS5637_t3 Basic Example Code - by: Kris Winer - date: December 24, 2014 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the BMX0655, and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DFMC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the BMX-055 9-axis motion sensor (accel/gyro/mag) as slave, an MS5637 pressure/temperature sensor, and an M24512DFM - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral cannot use the pressure data in the sensor fusion - yet and there is currently no driver for the MS5637 in the SENtral firmware. However, like the MAX21100, the SENtral - can be toggled into a bypass mode where the pressure sensor (and EEPROM and BMX055) may be read directly by the - Teensy 3.1 host micrcontroller. If the read rate is infrequent enough (2 Hz is sufficient since pressure and temperature - do not change very fast), then the sensor fusion rate is not significantly affected. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The MS5637 is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+BMX055+MS5637+M24512DFM Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: The BMX055 is an I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ -//#include "Wire.h" -#include -#include -#include -#include - -// Using NOKIA 5110 monochrome 84 x 48 pixel display -// pin 7 - Serial clock out (SCLK) -// pin 6 - Serial data out (DIN) -// pin 5 - Data/Command select (D/C) -// pin 3 - LCD chip select (SCE) -// pin 4 - LCD reset (RST) -Adafruit_PCD8544 display = Adafruit_PCD8544(7, 6, 5, 3, 4); - -// See MS5637-02BA03 Low Voltage Barometric Pressure Sensor Data Sheet http://www.meas-spec.com/downloads/MS5637-02BA03.pdf -#define MS5637_RESET 0x1E -#define MS5637_CONVERT_D1 0x40 -#define MS5637_CONVERT_D2 0x50 -#define MS5637_ADC_READ 0x00 - -// BMX055 data sheet http://ae-bst.resource.bosch.com/media/products/dokumente/bmx055/BST-BMX055-DS000-01v2.pdf -// The BMX055 is a conglomeration of three separate motion sensors packaged together but -// addressed and communicated with separately by design -// Accelerometer registers -#define BMX055_ACC_WHOAMI 0x00 // should return 0xFA -//#define BMX055_ACC_Reserved 0x01 -#define BMX055_ACC_D_X_LSB 0x02 -#define BMX055_ACC_D_X_MSB 0x03 -#define BMX055_ACC_D_Y_LSB 0x04 -#define BMX055_ACC_D_Y_MSB 0x05 -#define BMX055_ACC_D_Z_LSB 0x06 -#define BMX055_ACC_D_Z_MSB 0x07 -#define BMX055_ACC_D_TEMP 0x08 -#define BMX055_ACC_INT_STATUS_0 0x09 -#define BMX055_ACC_INT_STATUS_1 0x0A -#define BMX055_ACC_INT_STATUS_2 0x0B -#define BMX055_ACC_INT_STATUS_3 0x0C -//#define BMX055_ACC_Reserved 0x0D -#define BMX055_ACC_FIFO_STATUS 0x0E -#define BMX055_ACC_PMU_RANGE 0x0F -#define BMX055_ACC_PMU_BW 0x10 -#define BMX055_ACC_PMU_LPW 0x11 -#define BMX055_ACC_PMU_LOW_POWER 0x12 -#define BMX055_ACC_D_HBW 0x13 -#define BMX055_ACC_BGW_SOFTRESET 0x14 -//#define BMX055_ACC_Reserved 0x15 -#define BMX055_ACC_INT_EN_0 0x16 -#define BMX055_ACC_INT_EN_1 0x17 -#define BMX055_ACC_INT_EN_2 0x18 -#define BMX055_ACC_INT_MAP_0 0x19 -#define BMX055_ACC_INT_MAP_1 0x1A -#define BMX055_ACC_INT_MAP_2 0x1B -//#define BMX055_ACC_Reserved 0x1C -//#define BMX055_ACC_Reserved 0x1D -#define BMX055_ACC_INT_SRC 0x1E -//#define BMX055_ACC_Reserved 0x1F -#define BMX055_ACC_INT_OUT_CTRL 0x20 -#define BMX055_ACC_INT_RST_LATCH 0x21 -#define BMX055_ACC_INT_0 0x22 -#define BMX055_ACC_INT_1 0x23 -#define BMX055_ACC_INT_2 0x24 -#define BMX055_ACC_INT_3 0x25 -#define BMX055_ACC_INT_4 0x26 -#define BMX055_ACC_INT_5 0x27 -#define BMX055_ACC_INT_6 0x28 -#define BMX055_ACC_INT_7 0x29 -#define BMX055_ACC_INT_8 0x2A -#define BMX055_ACC_INT_9 0x2B -#define BMX055_ACC_INT_A 0x2C -#define BMX055_ACC_INT_B 0x2D -#define BMX055_ACC_INT_C 0x2E -#define BMX055_ACC_INT_D 0x2F -#define BMX055_ACC_FIFO_CONFIG_0 0x30 -//#define BMX055_ACC_Reserved 0x31 -#define BMX055_ACC_PMU_SELF_TEST 0x32 -#define BMX055_ACC_TRIM_NVM_CTRL 0x33 -#define BMX055_ACC_BGW_SPI3_WDT 0x34 -//#define BMX055_ACC_Reserved 0x35 -#define BMX055_ACC_OFC_CTRL 0x36 -#define BMX055_ACC_OFC_SETTING 0x37 -#define BMX055_ACC_OFC_OFFSET_X 0x38 -#define BMX055_ACC_OFC_OFFSET_Y 0x39 -#define BMX055_ACC_OFC_OFFSET_Z 0x3A -#define BMX055_ACC_TRIM_GPO 0x3B -#define BMX055_ACC_TRIM_GP1 0x3C -//#define BMX055_ACC_Reserved 0x3D -#define BMX055_ACC_FIFO_CONFIG_1 0x3E -#define BMX055_ACC_FIFO_DATA 0x3F - -// BMX055 Gyroscope Registers -#define BMX055_GYRO_WHOAMI 0x00 // should return 0x0F -//#define BMX055_GYRO_Reserved 0x01 -#define BMX055_GYRO_RATE_X_LSB 0x02 -#define BMX055_GYRO_RATE_X_MSB 0x03 -#define BMX055_GYRO_RATE_Y_LSB 0x04 -#define BMX055_GYRO_RATE_Y_MSB 0x05 -#define BMX055_GYRO_RATE_Z_LSB 0x06 -#define BMX055_GYRO_RATE_Z_MSB 0x07 -//#define BMX055_GYRO_Reserved 0x08 -#define BMX055_GYRO_INT_STATUS_0 0x09 -#define BMX055_GYRO_INT_STATUS_1 0x0A -#define BMX055_GYRO_INT_STATUS_2 0x0B -#define BMX055_GYRO_INT_STATUS_3 0x0C -//#define BMX055_GYRO_Reserved 0x0D -#define BMX055_GYRO_FIFO_STATUS 0x0E -#define BMX055_GYRO_RANGE 0x0F -#define BMX055_GYRO_BW 0x10 -#define BMX055_GYRO_LPM1 0x11 -#define BMX055_GYRO_LPM2 0x12 -#define BMX055_GYRO_RATE_HBW 0x13 -#define BMX055_GYRO_BGW_SOFTRESET 0x14 -#define BMX055_GYRO_INT_EN_0 0x15 -#define BMX055_GYRO_INT_EN_1 0x16 -#define BMX055_GYRO_INT_MAP_0 0x17 -#define BMX055_GYRO_INT_MAP_1 0x18 -#define BMX055_GYRO_INT_MAP_2 0x19 -#define BMX055_GYRO_INT_SRC_1 0x1A -#define BMX055_GYRO_INT_SRC_2 0x1B -#define BMX055_GYRO_INT_SRC_3 0x1C -//#define BMX055_GYRO_Reserved 0x1D -#define BMX055_GYRO_FIFO_EN 0x1E -//#define BMX055_GYRO_Reserved 0x1F -//#define BMX055_GYRO_Reserved 0x20 -#define BMX055_GYRO_INT_RST_LATCH 0x21 -#define BMX055_GYRO_HIGH_TH_X 0x22 -#define BMX055_GYRO_HIGH_DUR_X 0x23 -#define BMX055_GYRO_HIGH_TH_Y 0x24 -#define BMX055_GYRO_HIGH_DUR_Y 0x25 -#define BMX055_GYRO_HIGH_TH_Z 0x26 -#define BMX055_GYRO_HIGH_DUR_Z 0x27 -//#define BMX055_GYRO_Reserved 0x28 -//#define BMX055_GYRO_Reserved 0x29 -//#define BMX055_GYRO_Reserved 0x2A -#define BMX055_GYRO_SOC 0x31 -#define BMX055_GYRO_A_FOC 0x32 -#define BMX055_GYRO_TRIM_NVM_CTRL 0x33 -#define BMX055_GYRO_BGW_SPI3_WDT 0x34 -//#define BMX055_GYRO_Reserved 0x35 -#define BMX055_GYRO_OFC1 0x36 -#define BMX055_GYRO_OFC2 0x37 -#define BMX055_GYRO_OFC3 0x38 -#define BMX055_GYRO_OFC4 0x39 -#define BMX055_GYRO_TRIM_GP0 0x3A -#define BMX055_GYRO_TRIM_GP1 0x3B -#define BMX055_GYRO_BIST 0x3C -#define BMX055_GYRO_FIFO_CONFIG_0 0x3D -#define BMX055_GYRO_FIFO_CONFIG_1 0x3E - -// BMX055 magnetometer registers -#define BMX055_MAG_WHOAMI 0x40 // should return 0x32 -#define BMX055_MAG_Reserved 0x41 -#define BMX055_MAG_XOUT_LSB 0x42 -#define BMX055_MAG_XOUT_MSB 0x43 -#define BMX055_MAG_YOUT_LSB 0x44 -#define BMX055_MAG_YOUT_MSB 0x45 -#define BMX055_MAG_ZOUT_LSB 0x46 -#define BMX055_MAG_ZOUT_MSB 0x47 -#define BMX055_MAG_ROUT_LSB 0x48 -#define BMX055_MAG_ROUT_MSB 0x49 -#define BMX055_MAG_INT_STATUS 0x4A -#define BMX055_MAG_PWR_CNTL1 0x4B -#define BMX055_MAG_PWR_CNTL2 0x4C -#define BMX055_MAG_INT_EN_1 0x4D -#define BMX055_MAG_INT_EN_2 0x4E -#define BMX055_MAG_LOW_THS 0x4F -#define BMX055_MAG_HIGH_THS 0x50 -#define BMX055_MAG_REP_XY 0x51 -#define BMX055_MAG_REP_Z 0x52 -/* Trim Extended Registers */ -#define BMM050_DIG_X1 0x5D // needed for magnetic field calculation -#define BMM050_DIG_Y1 0x5E -#define BMM050_DIG_Z4_LSB 0x62 -#define BMM050_DIG_Z4_MSB 0x63 -#define BMM050_DIG_X2 0x64 -#define BMM050_DIG_Y2 0x65 -#define BMM050_DIG_Z2_LSB 0x68 -#define BMM050_DIG_Z2_MSB 0x69 -#define BMM050_DIG_Z1_LSB 0x6A -#define BMM050_DIG_Z1_MSB 0x6B -#define BMM050_DIG_XYZ1_LSB 0x6C -#define BMM050_DIG_XYZ1_MSB 0x6D -#define BMM050_DIG_Z3_LSB 0x6E -#define BMM050_DIG_Z3_MSB 0x6F -#define BMM050_DIG_XY2 0x70 -#define BMM050_DIG_XY1 0x71 - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 - -// Using the Teensy Mini Add-On board, BMX055 SDO1 = SDO2 = CSB3 = GND as designed -// Seven-bit BMX055 device addresses are ACC = 0x18, GYRO = 0x68, MAG = 0x10 -#define BMX055_ACC_ADDRESS 0x18 // Address of BMX055 accelerometer -#define BMX055_GYRO_ADDRESS 0x68 // Address of BMX055 gyroscope -#define BMX055_MAG_ADDRESS 0x10 // Address of BMX055 magnetometer -#define MS5637_ADDRESS 0x76 // Address of MS5637 altimeter -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page - -#define SerialDebug true // set to true to get Serial output for debugging - -// Set initial input parameters -// define X055 ACC full scale options -#define AFS_2G 0x03 -#define AFS_4G 0x05 -#define AFS_8G 0x08 -#define AFS_16G 0x0C - -enum ACCBW { // define BMX055 accelerometer bandwidths - ABW_8Hz, // 7.81 Hz, 64 ms update time - ABW_16Hz, // 15.63 Hz, 32 ms update time - ABW_31Hz, // 31.25 Hz, 16 ms update time - ABW_63Hz, // 62.5 Hz, 8 ms update time - ABW_125Hz, // 125 Hz, 4 ms update time - ABW_250Hz, // 250 Hz, 2 ms update time - ABW_500Hz, // 500 Hz, 1 ms update time - ABW_100Hz // 1000 Hz, 0.5 ms update time -}; - -enum Gscale { - GFS_2000DPS = 0, - GFS_1000DPS, - GFS_500DPS, - GFS_250DPS, - GFS_125DPS -}; - -enum GODRBW { - G_2000Hz523Hz = 0, // 2000 Hz ODR and unfiltered (bandwidth 523Hz) - G_2000Hz230Hz, - G_1000Hz116Hz, - G_400Hz47Hz, - G_200Hz23Hz, - G_100Hz12Hz, - G_200Hz64Hz, - G_100Hz32Hz // 100 Hz ODR and 32 Hz bandwidth -}; - -enum MODR { - MODR_10Hz = 0, // 10 Hz ODR - MODR_2Hz , // 2 Hz ODR - MODR_6Hz , // 6 Hz ODR - MODR_8Hz , // 8 Hz ODR - MODR_15Hz , // 15 Hz ODR - MODR_20Hz , // 20 Hz ODR - MODR_25Hz , // 25 Hz ODR - MODR_30Hz // 30 Hz ODR -}; - -enum Mmode { - lowPower = 0, // rms noise ~1.0 microTesla, 0.17 mA power - Regular , // rms noise ~0.6 microTesla, 0.5 mA power - enhancedRegular , // rms noise ~0.5 microTesla, 0.8 mA power - highAccuracy // rms noise ~0.3 microTesla, 4.9 mA power -}; - -// MS5637 pressure sensor sample rates -#define ADC_256 0x00 // define pressure and temperature conversion rates -#define ADC_512 0x02 -#define ADC_1024 0x04 -#define ADC_2048 0x06 -#define ADC_4096 0x08 -#define ADC_8192 0x0A -#define ADC_D1 0x40 -#define ADC_D2 0x50 - -// Specify sensor full scale -uint8_t OSR = ADC_8192; // set pressure amd temperature oversample rate -uint8_t Gscale = GFS_125DPS; // set gyro full scale -uint8_t GODRBW = G_200Hz23Hz; // set gyro ODR and bandwidth -uint8_t Ascale = AFS_2G; // set accel full scale -uint8_t ACCBW = 0x08 & ABW_16Hz; // Choose bandwidth for accelerometer -uint8_t Mmode = Regular; // Choose magnetometer operation mode -uint8_t MODR = MODR_10Hz; // set magnetometer data rate -float aRes, gRes, mRes; // scale resolutions per LSB for the sensors - -// Parameters to hold BMX055 trim values -signed char dig_x1; -signed char dig_y1; -signed char dig_x2; -signed char dig_y2; -uint16_t dig_z1; -int16_t dig_z2; -int16_t dig_z3; -int16_t dig_z4; -unsigned char dig_xy1; -signed char dig_xy2; -uint16_t dig_xyz1; - -// Pin definitions -int myLed = 13; // LED on the Teensy 3.1 - -// MS5637 variables -uint16_t Pcal[8]; // calibration constants from MS5637 PROM registers -unsigned char nCRC; // calculated check sum to ensure PROM integrity -uint32_t D1 = 0, D2 = 0; // raw MS5637 pressure and temperature data -double dT, OFFSET, SENS, T2, OFFSET2, SENS2; // First order and second order corrections for raw S5637 temperature and pressure data -double Temperature, Pressure; // stores MS5637 pressures sensor pressure and temperature - -// BMX055 variables -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 13/15-bit signed magnetometer sensor output -float Quat[4] = {0, 0, 0, 0}; // quaternion data register -float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag -int16_t tempCount; // temperature raw count output -float temperature; // Stores the BMX055 internal chip temperature in degrees Celsius -float SelfTest[6]; // holds results of gyro and accelerometer self test - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Ki 0.0f - -uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval - -float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -bool passThru = false; - -void setup() -{ -// Wire.begin(); -// TWBR = 12; // 400 kbit/sec I2C speed for Pro Mini - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(5000); - Serial.begin(38400); - - I2Cscan(); // should detect SENtral at 0x28 - - // 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"); - - 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!"); - delay(1000); // give some time to read the screen - - // Set up the SENtral as sensor bus in normal operating mode -if(!passThru) { -// 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 -// Set accel/gyro/mage desired ODR rates -writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 100 Hz -writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x1E); // 30 Hz -writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x0A); // 100/10 Hz -writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x14); // 200/10 Hz -// Configure operating mode -writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // read scale sensor data -// Enable interrupt to host upon certain events -// choose interrupts when 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); - -// 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"); - - delay(1000); // give some time to read the screen - - } - - // If pass through mode desired, set it up here - if(passThru) { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - -// Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - display.begin(); // Initialize the display - display.setContrast(58); // Set the contrast - -// Start device display with ID of sensor - display.clearDisplay(); - display.setTextSize(2); - display.setCursor(0,0); display.print("BMX055"); - display.setTextSize(1); - display.setCursor(0, 20); display.print("9-DOF 16-bit"); - display.setCursor(0, 30); display.print("motion sensor"); - display.setCursor(20,40); display.print("1 mg LSB"); - display.display(); - delay(1000); - -// Set up for data display - display.setTextSize(1); // Set text size to normal, 2 is twice normal etc. - display.setTextColor(BLACK); // Set pixel color; 1 on the monochrome screen - display.clearDisplay(); // clears the screen and buffer - - // Read the BMX-055 WHO_AM_I registers, this is a good test of communication - Serial.println("BMX055 accelerometer..."); - byte c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_WHOAMI); // Read ACC WHO_AM_I register for BMX055 - Serial.print("BMX055 ACC"); Serial.print(" I AM 0x"); Serial.print(c, HEX); Serial.print(" I should be 0x"); Serial.println(0xFA, HEX); - display.setCursor(20,0); display.print("BMX055 ACC"); - display.setCursor(0,10); display.print("I AM"); - display.setCursor(0,20); display.print("0x"); display.print(c, HEX); - display.setCursor(0,30); display.print("I Should Be"); - display.setCursor(0,40); display.print("0x"); display.print(0xFA, HEX); - display.display(); - delay(1000); - - display.clearDisplay(); // clears the screen and buffer - Serial.println("BMX055 gyroscope..."); - byte d = readByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_WHOAMI); // Read GYRO WHO_AM_I register for BMX055 - Serial.print("BMX055 GYRO"); Serial.print(" I AM 0x"); Serial.print(d, HEX); Serial.print(" I should be 0x"); Serial.println(0x0F, HEX); - display.setCursor(0, 0); display.print("BMX055 GYRO"); - display.setCursor(0,10); display.print("I AM"); - display.setCursor(0,20); display.print("0x"); display.print(d, HEX); - display.setCursor(0,30); display.print("I Should Be"); - display.setCursor(0,40); display.print("0x"); display.print(0x0F, HEX); - display.display(); - delay(1000); - - Serial.println("BMX055 magnetometer..."); - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x01); // wake up magnetometer first thing - delay(100); - byte e = readByte(BMX055_MAG_ADDRESS, BMX055_MAG_WHOAMI); // Read MAG WHO_AM_I register for BMX055 - Serial.print("BMX055 MAG"); Serial.print(" I AM 0x"); Serial.print(e, HEX); Serial.print(" I should be 0x"); Serial.println(0x32, HEX); - display.clearDisplay(); // clears the screen and buffer - display.setCursor(0, 0); display.print("BMX055 MAG"); - display.setCursor(0,10); display.print("I AM"); - display.setCursor(0,20); display.print("0x"); display.print(e, HEX); - display.setCursor(0,30); display.print("I Should Be"); - display.setCursor(0,40); display.print("0x"); display.print(0x32, HEX); - display.display(); - delay(1000); - - if ((c == 0xFA) && (d == 0x0F) && (e == 0x32)) // WHO_AM_I should always be ACC = 0xFA, GYRO = 0x0F, MAG = 0x32 - { - Serial.println("BMX055 is online..."); - display.clearDisplay(); // clears the screen and buffer - display.setCursor(0, 0); display.print("BMX055 online"); - display.setCursor(0,10); display.print("configuring"); - display.display(); - delay(1000); - - initBMX055(); - Serial.println("BMX055 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - display.clearDisplay(); // clears the screen and buffer - display.setCursor(0, 0); display.print("BMX055 online"); - display.setCursor(0,10); display.print("initialized"); - display.display(); - delay(1000); - - // Reset the MS5637 pressure sensor - MS5637Reset(); - delay(100); - Serial.println("MS5637 pressure sensor reset..."); - // Read PROM data from MS5637 pressure sensor - MS5637PromRead(Pcal); - Serial.println("PROM data read:"); - Serial.print("C0 = "); Serial.println(Pcal[0]); - unsigned char refCRC = Pcal[0] >> 12; - Serial.print("C1 = "); Serial.println(Pcal[1]); - Serial.print("C2 = "); Serial.println(Pcal[2]); - Serial.print("C3 = "); Serial.println(Pcal[3]); - Serial.print("C4 = "); Serial.println(Pcal[4]); - Serial.print("C5 = "); Serial.println(Pcal[5]); - Serial.print("C6 = "); Serial.println(Pcal[6]); - - nCRC = MS5637checkCRC(Pcal); //calculate checksum to ensure integrity of MS5637 calibration data - Serial.print("Checksum = "); Serial.print(nCRC); Serial.print(" , should be "); Serial.println(refCRC); - - display.clearDisplay(); - display.setCursor(20,0); display.print("MS5637"); - display.setCursor(0,10); display.print("CRC is "); display.setCursor(50,10); display.print(nCRC); - display.setCursor(0,20); display.print("Should be "); display.setCursor(50,30); display.print(refCRC); - display.display(); - delay(1000); - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - // magnetometer resolution is 1 microTesla/16 counts or 1/1.6 milliGauss/count - mRes = 1./1.6; - trimBMX055(); // read the magnetometer calibration data - display.clearDisplay(); - display.setCursor(0, 0); display.print("BMX055 Res"); - display.setCursor(0,10); display.print("ACC "); display.setCursor(50,10); display.print(1000.*aRes, 2); - display.setCursor(0,20); display.print("GYRO "); display.setCursor(50,20); display.print(1000.*gRes, 2); -// display.setCursor(0,30); display.print("MAG "); display.setCursor(50,30); display.print((int)dig_x1); - display.display(); - delay(1000); - - - fastcompaccelBMX055(accelBias); - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - magcalBMX055(magBias); - Serial.println("mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]); - - } - else - { - Serial.print("Could not connect to BMX055: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } -} -} - - -void loop() -{ - if(!passThru) { - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - if(eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if(errorStatus & 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus & 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus & 0x14) Serial.print("Gyro failure!"); - if(errorStatus & 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus & 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus & 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus & 0x30) Serial.print("Math error!"); - if(errorStatus & 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if(eventStatus & 0x10) { // new acceleration data available - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) { // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus & 0x08) { // new mag data available - readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - mx = (float)magCount[0]*0.305176; // get actual G value - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) { // new quaternion data available - readSENtralQuatData(Quat); - } - } - - if(passThru) { - // If intPin goes high, all data registers have new data -// if (digitalRead(intACC2)) { // On interrupt, read data - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*aRes; // + accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes; // + accelBias[1]; - az = (float)accelCount[2]*aRes; // + accelBias[2]; - // } -// if (digitalRead(intGYRO2)) { // On interrupt, read data - readGyroData(gyroCount); // Read the x/y/z adc values - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes; - gz = (float)gyroCount[2]*gRes; - // } -// if (digitalRead(intDRDYM)) { // On interrupt, read data - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - // Temperature-compensated magnetic field is in 16 LSB/microTesla - mx = (float)magCount[0]*mRes - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes - magBias[1]; - mz = (float)magCount[2]*mRes - magBias[2]; - // } - } - - - // keep track of rates - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer is aligned with the -y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ up) is aligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // For the BMX-055, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like - // in the MPU9250 sensor. This rotation can be modified to allow any convenient orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, mx, mz); -// if(passThru)MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, mx, mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - if (delt_t > 500) { // update LCD once per half-second independent of read rate - - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print( (int)mx); - Serial.print(" my = "); Serial.print( (int)my); - Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG"); - - Serial.println("Software quaternions:"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Quat[3]); - Serial.print(" Qx = "); Serial.print(Quat[0]); - Serial.print(" Qy = "); Serial.print(Quat[1]); - Serial.print(" Qz = "); Serial.println(Quat[2]); - } - - -// tempCount = readTempData(); // Read the gyro adc values -// temperature = ((float) tempCount) / 333.87 + 21.0; // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade -// Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - if(passThru) { - D1 = MS5637Read(ADC_D1, OSR); // get raw pressure value - D2 = MS5637Read(ADC_D2, OSR); // get raw temperature value - dT = D2 - Pcal[5]*pow(2,8); // calculate temperature difference from reference - OFFSET = Pcal[2]*pow(2, 17) + dT*Pcal[4]/pow(2,6); - SENS = Pcal[1]*pow(2,16) + dT*Pcal[3]/pow(2,7); - - Temperature = (2000 + (dT*Pcal[6])/pow(2, 23))/100; // First-order Temperature in degrees Centigrade -// -// Second order corrections - if(Temperature > 20) - { - T2 = 5*dT*dT/pow(2, 38); // correction for high temperatures - OFFSET2 = 0; - SENS2 = 0; - } - if(Temperature < 20) // correction for low temperature - { - T2 = 3*dT*dT/pow(2, 33); - OFFSET2 = 61*(100*Temperature - 2000)*(100*Temperature - 2000)/16; - SENS2 = 29*(100*Temperature - 2000)*(100*Temperature - 2000)/16; - } - if(Temperature < -15) // correction for very low temperature - { - OFFSET2 = OFFSET2 + 17*(100*Temperature + 1500)*(100*Temperature + 1500); - SENS2 = SENS2 + 9*(100*Temperature + 1500)*(100*Temperature + 1500); - } - // End of second order corrections - // - Temperature = Temperature - T2/100; - OFFSET = OFFSET - OFFSET2; - SENS = SENS - SENS2; - - Pressure = (((D1*SENS)/pow(2, 21) - OFFSET)/pow(2, 15))/100; // Pressure in mbar or kPa - - float altitude = 145366.45*(1. - pow((Pressure/1013.25), 0.190284)); - - if(SerialDebug) { - Serial.print("Digital temperature value = "); Serial.print( (float)Temperature, 2); Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Digital temperature value = "); Serial.print(9.*(float) Temperature/5. + 32., 2); Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Digital pressure value = "); Serial.print((float) Pressure, 2); Serial.println(" mbar");// pressure in millibar - Serial.print("Altitude = "); Serial.print(altitude, 2); Serial.println(" feet"); - } - } - - - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - roll *= 180.0f / PI; - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 260) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - // - - if(SerialDebug) { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - /* - display.clearDisplay(); - - display.setCursor(0, 0); display.print(" x y z "); - - display.setCursor(0, 8); display.print((int)(1000*ax)); - display.setCursor(24, 8); display.print((int)(1000*ay)); - display.setCursor(48, 8); display.print((int)(1000*az)); - display.setCursor(72, 8); display.print("mg"); - - // tempCount = readACCTempData(); // Read the gyro adc values - // temperature = ((float) tempCount) / 2.0 + 23.0; // Gyro chip temperature in degrees Centigrade - // display.setCursor(64, 0); display.print(9.*temperature/5. + 32., 0); display.print("F"); - - display.setCursor(0, 16); display.print((int)(gx)); - display.setCursor(24, 16); display.print((int)(gy)); - display.setCursor(48, 16); display.print((int)(gz)); - display.setCursor(66, 16); display.print("o/s"); - - display.setCursor(0, 24); display.print((int)(mx)); - display.setCursor(24, 24); display.print((int)(my)); - display.setCursor(48, 24); display.print((int)(mz)); - display.setCursor(72, 24); display.print("mG"); - - display.setCursor(0, 32); display.print((int)(yaw)); - display.setCursor(24, 32); display.print((int)(pitch)); - display.setCursor(48, 32); display.print((int)(roll)); - display.setCursor(66, 32); display.print("ypr"); - - -// display.setCursor(0, 40); display.print(altitude, 0); display.print("ft"); -// display.setCursor(68, 0); display.print(9.*Temperature/5. + 32., 0); - display.setCursor(42, 40); display.print((float) sumCount / (1000.*sum), 2); display.print("kHz"); - display.display(); -*/ - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } - -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== - -void getGres() { - switch (Gscale) - { - // Possible gyro scales (and their register bit settings) are: - // 125 DPS (100), 250 DPS (011), 500 DPS (010), 1000 DPS (001), and 2000 DPS (000). - case GFS_125DPS: - gRes = 124.87/32768.0; // per data sheet, not exactly 125!? - break; - case GFS_250DPS: - gRes = 249.75/32768.0; - break; - case GFS_500DPS: - gRes = 499.5/32768.0; - break; - case GFS_1000DPS: - gRes = 999.0/32768.0; - break; - case GFS_2000DPS: - gRes = 1998.0/32768.0; - break; - } -} - -void getAres() { - switch (Ascale) - { - // Possible accelerometer scales (and their register bit settings) are: - // 2 Gs (0011), 4 Gs (0101), 8 Gs (1000), and 16 Gs (1100). - // BMX055 ACC data is signed 12 bit - case AFS_2G: - aRes = 2.0/2048.0; - break; - case AFS_4G: - aRes = 4.0/2048.0; - break; - case AFS_8G: - aRes = 8.0/2048.0; - break; - case AFS_16G: - aRes = 16.0/2048.0; - break; - } -} - -float 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; -} - -void 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[0] = uint32_reg_to_float (&rawData[0]); - destination[1] = uint32_reg_to_float (&rawData[4]); - destination[2] = uint32_reg_to_float (&rawData[8]); - destination[3] = uint32_reg_to_float (&rawData[12]); - -} - -void 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 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 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]); -} - -void readAccelData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z accel register data stored here - readBytes(BMX055_ACC_ADDRESS, BMX055_ACC_D_X_LSB, 6, &rawData[0]); // Read the six raw data registers into data array - if((rawData[0] & 0x01) && (rawData[2] & 0x01) && (rawData[4] & 0x01)) { // Check that all 3 axes have new data - destination[0] = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]) >> 4; // Turn the MSB and LSB into a signed 12-bit value - destination[1] = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]) >> 4; - destination[2] = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]) >> 4; - } -} - -void readGyroData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z gyro register data stored here - readBytes(BMX055_GYRO_ADDRESS, BMX055_GYRO_RATE_X_LSB, 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 readMagData(int16_t * magData) -{ - int16_t mdata_x = 0, mdata_y = 0, mdata_z = 0, temp = 0; - uint16_t data_r = 0; - uint8_t rawData[8]; // x/y/z hall magnetic field data, and Hall resistance data - readBytes(BMX055_MAG_ADDRESS, BMX055_MAG_XOUT_LSB, 8, &rawData[0]); // Read the eight raw data registers sequentially into data array - if(rawData[6] & 0x01) { // Check if data ready status bit is set - mdata_x = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]) >> 3; // 13-bit signed integer for x-axis field - mdata_y = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]) >> 3; // 13-bit signed integer for y-axis field - mdata_z = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]) >> 1; // 15-bit signed integer for z-axis field - data_r = (uint16_t) (((uint16_t)rawData[7] << 8) | rawData[6]) >> 2; // 14-bit unsigned integer for Hall resistance - - // calculate temperature compensated 16-bit magnetic fields - temp = ((int16_t)(((uint16_t)((((int32_t)dig_xyz1) << 14)/(data_r != 0 ? data_r : dig_xyz1))) - ((uint16_t)0x4000))); - magData[0] = ((int16_t)((((int32_t)mdata_x) * - ((((((((int32_t)dig_xy2) * ((((int32_t)temp) * ((int32_t)temp)) >> 7)) + - (((int32_t)temp) * ((int32_t)(((int16_t)dig_xy1) << 7)))) >> 9) + - ((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_x2) + ((int16_t)0xA0)))) >> 12)) >> 13)) + - (((int16_t)dig_x1) << 3); - - temp = ((int16_t)(((uint16_t)((((int32_t)dig_xyz1) << 14)/(data_r != 0 ? data_r : dig_xyz1))) - ((uint16_t)0x4000))); - magData[1] = ((int16_t)((((int32_t)mdata_y) * - ((((((((int32_t)dig_xy2) * ((((int32_t)temp) * ((int32_t)temp)) >> 7)) + - (((int32_t)temp) * ((int32_t)(((int16_t)dig_xy1) << 7)))) >> 9) + - ((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_y2) + ((int16_t)0xA0)))) >> 12)) >> 13)) + - (((int16_t)dig_y1) << 3); - magData[2] = (((((int32_t)(mdata_z - dig_z4)) << 15) - ((((int32_t)dig_z3) * ((int32_t)(((int16_t)data_r) - - ((int16_t)dig_xyz1))))>>2))/(dig_z2 + ((int16_t)(((((int32_t)dig_z1) * ((((int16_t)data_r) << 1)))+(1<<15))>>16)))); - } - } - -int16_t readACCTempData() -{ - uint8_t c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_D_TEMP); // Read the raw data register - return ((int16_t)((int16_t)c << 8)) >> 8 ; // Turn the byte into a signed 8-bit integer -} - -void SENtralPassThroughMode() -{ - // First put SENtral in standby mode - uint8_t c = readByte(EM7180_ADDRESS, EM7180_AlgorithmControl); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, c | 0x01); -// c = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); -// Serial.print("c = "); Serial.println(c); -// Verify standby status -// if(readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus) & 0x01) { - Serial.println("SENtral in standby mode"); - // Place SENtral in pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - if(readByte(EM7180_ADDRESS, EM7180_PassThruStatus) & 0x01) { - Serial.println("SENtral in pass-through mode"); - } - else { - Serial.println("ERROR! SENtral not in pass-through mode!"); - } - -// } -// else { Serial.println("ERROR! SENtral not in standby mode!"); -// } - - } - - - - -void trimBMX055() // get trim values for magnetometer sensitivity -{ - uint8_t rawData[2]; //placeholder for 2-byte trim data - dig_x1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_X1); - dig_x2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_X2); - dig_y1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_Y1); - dig_y2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_Y2); - dig_xy1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_XY1); - dig_xy2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_XY2); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z1_LSB, 2, &rawData[0]); - dig_z1 = (uint16_t) (((uint16_t)rawData[1] << 8) | rawData[0]); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z2_LSB, 2, &rawData[0]); - dig_z2 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z3_LSB, 2, &rawData[0]); - dig_z3 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z4_LSB, 2, &rawData[0]); - dig_z4 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); - readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_XYZ1_LSB, 2, &rawData[0]); - dig_xyz1 = (uint16_t) (((uint16_t)rawData[1] << 8) | rawData[0]); -} - - -void initBMX055() -{ - // start with all sensors in default mode with all registers reset - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_BGW_SOFTRESET, 0xB6); // reset accelerometer - delay(1000); // Wait for all registers to reset - - // Configure accelerometer - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_PMU_RANGE, Ascale & 0x0F); // Set accelerometer full range - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_PMU_BW, ACCBW & 0x0F); // Set accelerometer bandwidth - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_D_HBW, 0x00); // Use filtered data - -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_EN_1, 0x10); // Enable ACC data ready interrupt -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_OUT_CTRL, 0x04); // Set interrupts push-pull, active high for INT1 and INT2 -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_MAP_1, 0x02); // Define INT1 (intACC1) as ACC data ready interrupt -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_MAP_1, 0x80); // Define INT2 (intACC2) as ACC data ready interrupt - -// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_BGW_SPI3_WDT, 0x06); // Set watchdog timer for 50 ms - - // Configure Gyro - // start by resetting gyro, better not since it ends up in sleep mode?! -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BGW_SOFTRESET, 0xB6); // reset gyro -// delay(100); - // Three power modes, 0x00 Normal, - // set bit 7 to 1 for suspend mode, set bit 5 to 1 for deep suspend mode - // sleep duration in fast-power up from suspend mode is set by bits 1 - 3 - // 000 for 2 ms, 111 for 20 ms, etc. -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_LPM1, 0x00); // set GYRO normal mode -// set GYRO sleep duration for fast power-up mode to 20 ms, for duty cycle of 50% -// writeByte(BMX055_ACC_ADDRESS, BMX055_GYRO_LPM1, 0x0E); - // set bit 7 to 1 for fast-power-up mode, gyro goes quickly to normal mode upon wake up -// can set external wake-up interrupts on bits 5 and 4 -// auto-sleep wake duration set in bits 2-0, 001 4 ms, 111 40 ms -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_LPM2, 0x00); // set GYRO normal mode -// set gyro to fast wake up mode, will sleep for 20 ms then run normally for 20 ms -// and collect data for an effective ODR of 50 Hz, other duty cycles are possible but there -// is a minimum wake duration determined by the bandwidth duration, e.g., > 10 ms for 23Hz gyro bandwidth -// writeByte(BMX055_ACC_ADDRESS, BMX055_GYRO_LPM2, 0x87); - - writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_RANGE, Gscale); // set GYRO FS range - writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BW, GODRBW); // set GYRO ODR and Bandwidth - -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_EN_0, 0x80); // enable data ready interrupt -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_EN_1, 0x04); // select push-pull, active high interrupts -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_MAP_1, 0x80); // select INT3 (intGYRO1) as GYRO data ready interrupt - -// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BGW_SPI3_WDT, 0x06); // Enable watchdog timer for I2C with 50 ms window - - -// Configure magnetometer -writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x82); // Softreset magnetometer, ends up in sleep mode -delay(100); -writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x01); // Wake up magnetometer -delay(100); - -writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL2, MODR << 3); // Normal mode -//writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL2, MODR << 3 | 0x02); // Forced mode - -//writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_INT_EN_2, 0x84); // Enable data ready pin interrupt, active high - -// Set up four standard configurations for the magnetometer - switch (Mmode) - { - case lowPower: - // Low-power - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x01); // 3 repetitions (oversampling) - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x02); // 3 repetitions (oversampling) - break; - case Regular: - // Regular - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x04); // 9 repetitions (oversampling) - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x16); // 15 repetitions (oversampling) - break; - case enhancedRegular: - // Enhanced Regular - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x07); // 15 repetitions (oversampling) - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x22); // 27 repetitions (oversampling) - break; - case highAccuracy: - // High Accuracy - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x17); // 47 repetitions (oversampling) - writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x51); // 83 repetitions (oversampling) - break; - } -} - -void fastcompaccelBMX055(float * dest1) -{ - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x80); // set all accel offset compensation registers to zero - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_SETTING, 0x20); // set offset targets to 0, 0, and +1 g for x, y, z axes - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x20); // calculate x-axis offset - - byte c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - while(!(c & 0x10)) { // check if fast calibration complete - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - delay(10); -} - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x40); // calculate y-axis offset - - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - while(!(c & 0x10)) { // check if fast calibration complete - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - delay(10); -} - writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x60); // calculate z-axis offset - - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - while(!(c & 0x10)) { // check if fast calibration complete - c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL); - delay(10); -} - - int8_t compx = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_X); - int8_t compy = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_Y); - int8_t compz = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_Z); - - dest1[0] = (float) compx/128.; // accleration bias in g - dest1[1] = (float) compy/128.; // accleration bias in g - dest1[2] = (float) compz/128.; // accleration bias in g -} -/* -// 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 accelgyrocalBMX055(float * dest1, float * dest2) -{ - uint8_t data[6] = {0, 0, 0, 0, 0, 0}; - int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; - uint16_t samples, ii; - - Serial.println("Calibrating gyro..."); - - // First get gyro bias - byte c = readByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G); - writeByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G, c | 0x40); // Enable gyro FIFO - delay(200); // Wait for change to take effect - writeByte(BMX055G_ADDRESS, BMX055G_FIFO_CTRL_REG_G, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples - delay(1000); // delay 1000 milliseconds to collect FIFO samples - - samples = (readByte(BMX055G_ADDRESS, BMX055G_FIFO_SRC_REG_G) & 0x1F); // Read number of stored samples - - for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO - int16_t gyro_temp[3] = {0, 0, 0}; - readBytes(BMX055G_ADDRESS, BMX055G_OUT_X_L_G, 6, &data[0]); - gyro_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO - gyro_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]); - gyro_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]); - - gyro_bias[0] += (int32_t) gyro_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases - gyro_bias[1] += (int32_t) gyro_temp[1]; - gyro_bias[2] += (int32_t) gyro_temp[2]; - } - - gyro_bias[0] /= samples; // average the data - gyro_bias[1] /= samples; - gyro_bias[2] /= samples; - - dest1[0] = (float)gyro_bias[0]*gRes; // Properly scale the data to get deg/s - dest1[1] = (float)gyro_bias[1]*gRes; - dest1[2] = (float)gyro_bias[2]*gRes; - - c = readByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G); - writeByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G, c & ~0x40); //Disable gyro FIFO - delay(200); - writeByte(BMX055G_ADDRESS, BMX055G_FIFO_CTRL_REG_G, 0x00); // Enable gyro bypass mode - - Serial.println("Calibrating accel..."); - - // now get the accelerometer bias - c = readByte(BMX055XM_ADDRESS, BMX055XM_CTRL_REG0_XM); - writeByte(BMX055XM_ADDRESS, BMX055XM_CTRL_REG0_XM, c | 0x40); // Enable gyro FIFO - delay(200); // Wait for change to take effect - writeByte(BMX055XM_ADDRESS, BMX055XM_FIFO_CTRL_REG, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples - delay(1000); // delay 1000 milliseconds to collect FIFO samples - - samples = (readByte(BMX055XM_ADDRESS, BMX055XM_FIFO_SRC_REG) & 0x1F); // Read number of stored samples - - for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO - int16_t accel_temp[3] = {0, 0, 0}; - readBytes(BMX055XM_ADDRESS, BMX055XM_OUT_X_L_A, 6, &data[0]); - accel_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO - accel_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]); - accel_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]); - - 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]; - } - - accel_bias[0] /= samples; // average the data - accel_bias[1] /= samples; - accel_bias[2] /= samples; - - if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) (1.0/aRes);} // Remove gravity from the z-axis accelerometer bias calculation - else {accel_bias[2] += (int32_t) (1.0/aRes);} - - dest2[0] = (float)accel_bias[0]*aRes; // Properly scale the data to get g - dest2[1] = (float)accel_bias[1]*aRes; - dest2[2] = (float)accel_bias[2]*aRes; - - c = readByte(BMX055XM_ADDRESS, BMX055XM_CTRL_REG0_XM); - writeByte(BMX055XM_ADDRESS, BMX055XM_CTRL_REG0_XM, c & ~0x40); //Disable accel FIFO - delay(200); - writeByte(BMX055XM_ADDRESS, BMX055XM_FIFO_CTRL_REG, 0x00); // Enable accel bypass mode -} -*/ -void magcalBMX055(float * dest1) -{ - uint16_t ii = 0, sample_count = 0; - int32_t mag_bias[3] = {0, 0, 0}; - int16_t mag_max[3] = {0, 0, 0}, mag_min[3] = {0, 0, 0}; - - Serial.println("Mag Calibration: Wave device in a figure eight until done!"); - delay(4000); - - sample_count = 128; - for(ii = 0; ii < sample_count; ii++) { - int16_t mag_temp[3] = {0, 0, 0}; - readMagData(mag_temp); - 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]; - } - delay(105); // at 10 Hz ODR, new mag data is available every 100 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]); - - 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; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes; - dest1[2] = (float) mag_bias[2]*mRes; - - /* //write biases to accelerometermagnetometer offset registers as counts); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_X_REG_L_M, (int16_t) mag_bias[0] & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_X_REG_H_M, ((int16_t)mag_bias[0] >> 8) & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_Y_REG_L_M, (int16_t) mag_bias[1] & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_Y_REG_H_M, ((int16_t)mag_bias[1] >> 8) & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_Z_REG_L_M, (int16_t) mag_bias[2] & 0xFF); - writeByte(BMX055M_ADDRESS, BMX055M_OFFSET_Z_REG_H_M, ((int16_t)mag_bias[2] >> 8) & 0xFF); - */ - Serial.println("Mag Calibration done!"); -} - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - - void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - - void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - if(count > 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - - - - -// 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 MS5637Reset() - { - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(MS5637_RESET); // Put reset command in Tx buffer - Wire.endTransmission(); // Send the Tx buffer - } - - void MS5637PromRead(uint16_t * destination) - { - uint8_t data[2] = {0,0}; - for (uint8_t ii = 0; ii < 7; ii++) { - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(0xA0 | ii << 1); // Put PROM address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(MS5637_ADDRESS, 2); // Read two bytes from slave PROM address - while (Wire.available()) { - data[i++] = Wire.read(); } // Put read results in the Rx buffer - destination[ii] = (uint16_t) (((uint16_t) data[0] << 8) | data[1]); // construct PROM data for return to main program - } - } - - uint32_t MS5637Read(uint8_t CMD, uint8_t OSR) // temperature data read - { - uint8_t data[3] = {0,0,0}; - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(CMD | OSR); // Put pressure conversion command in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - - 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.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(0x00); // Put ADC read command in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(MS5637_ADDRESS, 3); // Read three bytes from slave PROM address - while (Wire.available()) { - data[i++] = Wire.read(); } // Put read results in the Rx buffer - 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 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); -} - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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 and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/EM7180_LSM6DSM_LIS2MDL_LPS22HB_ESP32.ino b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/EM7180_LSM6DSM_LIS2MDL_LPS22HB_ESP32.ino deleted file mode 100644 index 701e12b..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/EM7180_LSM6DSM_LIS2MDL_LPS22HB_ESP32.ino +++ /dev/null @@ -1,593 +0,0 @@ -#include "LSM6DSM.h" -#include "LIS2MDL.h" -#include "LPS22HB.h" -#include "USFS.h" - -#define I2C_BUS Wire // Define the I2C bus (Wire instance) you wish to use - -I2Cdev i2c_0(&I2C_BUS); // Instantiate the I2Cdev object and point to the desired I2C bus - -bool SerialDebug = true; // set to true to get Serial output for debugging -bool passThru = false; - -#define myLed 5 -#define pinGND 12 -#define pin3V3 13 - -void EM7180intHandler(); -void myinthandler1(); -void myinthandler2(); -void myinthandler3(); - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float pi = 3.141592653589793238462643383279502884f; -float GyroMeasError = pi * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = pi * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -float beta = sqrtf(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrtf(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -uint32_t delt_t = 0; // used to control display output rate -uint32_t sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float a12, a22, a31, a32, a33; // rotation matrix coefficients for Euler angles and gravity components -float A112, A22, A31, A32, A33; // rotation matrix coefficients for Hardware Euler angles and gravity components -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval -float lin_ax, lin_ay, lin_az; // linear acceleration (acceleration with gravity component subtracted) -float lin_Ax, lin_Ay, lin_Az; // Hardware linear acceleration (acceleration with gravity component subtracted) -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float Q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // hardware quaternion data register -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -//LSM6DSM definitions -#define LSM6DSM_intPin1 10 // interrupt1 pin definitions, significant motion -#define LSM6DSM_intPin2 9 // interrupt2 pin definitions, data ready - -/* Specify sensor parameters (sample rate is twice the bandwidth) - * choices are: - AFS_2G, AFS_4G, AFS_8G, AFS_16G - GFS_245DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS - AODR_12_5Hz, AODR_26Hz, AODR_52Hz, AODR_104Hz, AODR_208Hz, AODR_416Hz, AODR_833Hz, AODR_1660Hz, AODR_3330Hz, AODR_6660Hz - GODR_12_5Hz, GODR_26Hz, GODR_52Hz, GODR_104Hz, GODR_208Hz, GODR_416Hz, GODR_833Hz, GODR_1660Hz, GODR_3330Hz, GODR_6660Hz -*/ -uint8_t Ascale = AFS_2G, Gscale = GFS_245DPS, AODR = AODR_208Hz, GODR = GODR_416Hz; - -float aRes, gRes; // scale resolutions per LSB for the accel and gyro sensor2 -float accelBias[3] = {-0.00499, 0.01540, 0.02902}, gyroBias[3] = {-0.50, 0.14, 0.28}; // offset biases for the accel and gyro -int16_t LSM6DSMData[7]; // Stores the 16-bit signed sensor output -float Gtemperature; // Stores the real internal gyro temperature in degrees Celsius -float ax, ay, az, gx, gy, gz; // variables to hold latest accel/gyro data values - -bool newLSM6DSMData = false; -bool newLSM6DSMTap = false; - -LSM6DSM LSM6DSM(LSM6DSM_intPin1, LSM6DSM_intPin2, &i2c_0); // instantiate LSM6DSM class - - -//LIS2MDL definitions -#define LIS2MDL_intPin 8 // interrupt for magnetometer data ready - -/* Specify sensor parameters (sample rate is twice the bandwidth) - * choices are: MODR_10Hz, MOIDR_20Hz, MODR_50 Hz and MODR_100Hz -*/ -uint8_t MODR = MODR_100Hz; - -float mRes = 0.0015f; // mag sensitivity -float magBias[3] = {0,0,0}, magScale[3] = {0,0,0}; // Bias corrections for magnetometer -int16_t LIS2MDLData[4]; // Stores the 16-bit signed sensor output -float Mtemperature; // Stores the real internal chip temperature in degrees Celsius -float mx, my, mz; // variables to hold latest mag data values -uint8_t LIS2MDLstatus; - -bool newLIS2MDLData = false; - -LIS2MDL LIS2MDL(LIS2MDL_intPin, &i2c_0); // instantiate LIS2MDL class - - -// LPS22H definitions -uint8_t LPS22H_intPin = 5; - -/* Specify sensor parameters (sample rate is twice the bandwidth) - Choices are P_1Hz, P_10Hz P_25 Hz, P_50Hz, and P_75Hz - */ -uint8_t PODR = P_25Hz; // set pressure amd temperature output data rate -uint8_t LPS22Hstatus; -float temperature, pressure, altitude; - -bool newLPS22HData = false; - -LPS22H LPS22H(LPS22H_intPin, &i2c_0); - - -const uint8_t USFS_intPin = 27; -bool newEM7180Data = false; -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output -int16_t tempCount, rawPressure, rawTemperature; // temperature raw count output -float Temperature, Pressure, Altitude; // temperature in degrees Celsius, pressure in mbar -float Ax, Ay, Az, Gx, Gy, Gz, Mx, My, Mz; // variables to hold latest sensor data values - - -/* Choose EM7180, LSM6DSM, LIS2MDL sample rates and bandwidths - Choices are: - accBW, gyroBW 0x00 = 250 Hz, 0x01 = 184 Hz, 0x02 = 92 Hz, 0x03 = 41 Hz, 0x04 = 20 Hz, 0x05 = 10 Hz, 0x06 = 5 Hz, 0x07 = no filter (3600 Hz) - QRtDiv 0x00, 0x01, 0x02, etc quat rate = gyroRt/(1 + QRtDiv) - magRt 8 Hz = 0x08 or 100 Hz 0x64 - accRt, gyroRt 1000, 500, 250, 200, 125, 100, 50 Hz enter by choosing desired rate - and dividing by 10, so 200 Hz would be 200/10 = 20 = 0x14 - sample rate of barometer is baroRt/2 so for 25 Hz enter 50 = 0x32 - LSM6DSM accel/gyro rates 0f 833 Hz set Rt variables to 0x53 -*/ -uint8_t accBW = 0x03, gyroBW = 0x03, QRtDiv = 0x03, magRt = 0x64, accRt = 0x53, gyroRt = 0x53, baroRt = 0x32; -/* - Choose sensor full ranges - Choices are 2, 4, 8, 16 g for accFS, 250, 500, 1000, and 2000 dps for gyro FS and 1000 uT for magFS expressed as HEX values -*/ -uint16_t accFS = 0x02, gyroFS = 0x7D0, magFS = 0x3E8; - -USFS USFS(USFS_intPin, passThru, &i2c_0); - - -void setup() { - Serial.begin(115200); - delay(4000); - - // Configure led - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); // start with led on - - pinMode(pinGND, OUTPUT); - digitalWrite(pinGND, LOW); - - pinMode(pin3V3, OUTPUT); - digitalWrite(pin3V3, HIGH); - - pinMode(USFS_intPin, INPUT); - - Wire.begin(16, 15, 400000); //(SDA, SCL) (21,22) are default on ESP32, 400 kHz I2C clock - delay(1000); - - i2c_0.I2Cscan(); // which I2C device are on the bus? - - if(!passThru) - { - // Initialize the USFS - USFS.getChipID(); // check ROM/RAM version of EM7180 - USFS.loadfwfromEEPROM(); // load EM7180 firmware from EEPROM - USFS.initEM7180(accBW, gyroBW, accFS, gyroFS, magFS, QRtDiv, magRt, accRt, gyroRt, baroRt); // set MPU and MS5637 sensor parameters - } // end of "if(!passThru)" handling - - if(passThru) - { - // Read the LSM6DSM Chip ID register, this is a good test of communication - Serial.println("LSM6DSM accel/gyro..."); - byte c = LSM6DSM.getChipID(); // Read CHIP_ID register for LSM6DSM - Serial.print("LSM6DSM "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x6A, HEX); - Serial.println(" "); - delay(1000); - - // Read the LIS2MDL Chip ID register, this is a good test of communication - Serial.println("LIS2MDL mag..."); - byte d = LIS2MDL.getChipID(); // Read CHIP_ID register for LSM6DSM - Serial.print("LIS2MDL "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x40, HEX); - Serial.println(" "); - delay(1000); - - Serial.println("LPS22HB barometer..."); - uint8_t e = LPS22H.getChipID(); - Serial.print("LPS25H "); Serial.print("I AM "); Serial.print(e, HEX); Serial.print(" I should be "); Serial.println(0xB1, HEX); - delay(1000); - - - if(c == 0x6A && d == 0x40 && e == 0xB1) // check if all I2C sensors have acknowledged - { - Serial.println("LSM6DSM and LIS2MDL and LPS22HB are online..."); Serial.println(" "); - - digitalWrite(myLed, LOW); - - LSM6DSM.reset(); // software reset LSM6DSM to default registers - - // get sensor resolutions, only need to do this once - aRes = LSM6DSM.getAres(Ascale); - gRes = LSM6DSM.getGres(Gscale); - - LSM6DSM.init(Ascale, Gscale, AODR, GODR); - - LSM6DSM.selfTest(); - - LSM6DSM.offsetBias(gyroBias, accelBias); - Serial.println("accel biases (mg)"); Serial.println(1000.0f * accelBias[0]); Serial.println(1000.0f * accelBias[1]); Serial.println(1000.0f * accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - delay(1000); - - LIS2MDL.reset(); // software reset LIS2MDL to default registers - - mRes = 0.0015f; // fixed sensitivity and full scale (+/- 49.152 Gauss); - - LIS2MDL.init(MODR); - - LIS2MDL.selfTest(); - - LIS2MDL.offsetBias(magBias, magScale); - Serial.println("mag biases (mG)"); Serial.println(1000.0f * magBias[0]); Serial.println(1000.0f * magBias[1]); Serial.println(1000.0f * magBias[2]); - Serial.println("mag scale (mG)"); Serial.println(magScale[0]); Serial.println(magScale[1]); Serial.println(magScale[2]); - delay(2000); // add delay to see results before serial spew of data - - LPS22H.Init(PODR); // Initialize LPS22H altimeter - delay(1000); - - digitalWrite(myLed, HIGH); - - } - else - { - if(c != 0x6A) Serial.println(" LSM6DSM not functioning!"); - if(d != 0x40) Serial.println(" LIS2MDL not functioning!"); - if(e != 0xB1) Serial.println(" LPS22HB not functioning!"); - - while(1){}; - } - } // end of "if(passThru)" handling - - - if(!passThru) - { - attachInterrupt(USFS_intPin, EM7180intHandler, RISING); // define interrupt for INT pin output of EM7180 - - USFS.checkEM7180Status(); - } - - if(passThru) - { - attachInterrupt(LSM6DSM_intPin2, myinthandler1, RISING); // define interrupt for intPin2 output of LSM6DSM - attachInterrupt(LIS2MDL_intPin , myinthandler2, RISING); // define interrupt for intPin output of LIS2MDL - attachInterrupt(LPS22H_intPin , myinthandler3, RISING); // define interrupt for intPin output of LPS22HB - - LIS2MDLstatus = LIS2MDL.status(); // read status register to clear interrupt before main loop - } - - digitalWrite(myLed, LOW); // turn led off when successfully through setup - -} - -/* End of setup */ - -void loop() { - - if(passThru) - { - // If intPin goes high, either all data registers have new data - if(newLSM6DSMData == true) { // On interrupt, read data - newLSM6DSMData = false; // reset newData flag - - LSM6DSM.readData(LSM6DSMData); // INT2 cleared on any read - - // Now we'll calculate the accleration value into actual g's - ax = (float)LSM6DSMData[4]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)LSM6DSMData[5]*aRes - accelBias[1]; - az = (float)LSM6DSMData[6]*aRes - accelBias[2]; - - // Calculate the gyro value into actual degrees per second - gx = (float)LSM6DSMData[1]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set - gy = (float)LSM6DSMData[2]*gRes - gyroBias[1]; - gz = (float)LSM6DSMData[3]*gRes - gyroBias[2]; - - for(uint8_t i = 0; i < 10; i++) { // iterate a fixed number of times per data read cycle - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - USFS.MadgwickQuaternionUpdate(-ax, ay, az, gx*pi/180.0f, -gy*pi/180.0f, -gz*pi/180.0f, mx, my, -mz); - } - - } - - // If intPin goes high, either all data registers have new data - if(newLIS2MDLData == true) { // On interrupt, read data - newLIS2MDLData = false; // reset newData flag - - LIS2MDLstatus = LIS2MDL.status(); - - if(LIS2MDLstatus & 0x08) // if all axes have new data ready - { - LIS2MDL.readData(LIS2MDLData); - - // Now we'll calculate the accleration value into actual G's - mx = (float)LIS2MDLData[0]*mRes - magBias[0]; // get actual G value - my = (float)LIS2MDLData[1]*mRes - magBias[1]; - mz = (float)LIS2MDLData[2]*mRes - magBias[2]; - mx *= magScale[0]; - my *= magScale[1]; - mz *= magScale[2]; - } - } - } // end of "if(passThru)" handling - - if(!passThru) - { - /*EM7180*/ - // If intpin goes high, all data registers have new data - if (newEM7180Data == true) { // On interrupt, read data - newEM7180Data = false; // reset newData flag - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = USFS.checkEM7180Status(); // reading clears the register - - // Check for errors - if (eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = USFS.checkEM7180Errors(); - if (errorStatus != 0x00) { // is there an error? - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if (errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if (errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if (errorStatus == 0x14) Serial.print("Gyro failure!"); - if (errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if (errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if (errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if (errorStatus == 0x30) Serial.print("Math error!"); - if (errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if (eventStatus & 0x10) { // new acceleration data available - USFS.readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - Ax = (float)accelCount[0] * 0.000488f; // get actual g value - Ay = (float)accelCount[1] * 0.000488f; - Az = (float)accelCount[2] * 0.000488f; - } - - if (eventStatus & 0x20) { // new gyro data available - USFS.readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - Gx = (float)gyroCount[0] * 0.153f; // get actual dps value - Gy = (float)gyroCount[1] * 0.153f; - Gz = (float)gyroCount[2] * 0.153f; - } - - if (eventStatus & 0x08) { // new mag data available - USFS.readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - Mx = (float)magCount[0] * 0.305176f; // get actual G value - My = (float)magCount[1] * 0.305176f; - Mz = (float)magCount[2] * 0.305176f; - } - - if (eventStatus & 0x04) { // new quaternion data available - USFS.readSENtralQuatData(Q); - } - - // get MS5637 pressure - if (eventStatus & 0x40) { // new baro data available - rawPressure = USFS.readSENtralBaroData(); - Pressure = (float)rawPressure * 0.01f + 1013.25f; // pressure in mBar - - // get MS5637 temperature - rawTemperature = USFS.readSENtralTempData(); - Temperature = (float) rawTemperature * 0.01f; // temperature in degrees C - } - } - } // end of "if(!passThru)" handling - - // end sensor interrupt handling - - if(passThru) - { - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print((int)1000*mx); - Serial.print(" my = "); Serial.print((int)1000*my); - Serial.print(" mz = "); Serial.print((int)1000*mz); Serial.println(" mG"); - - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - } - - // get pressure and temperature from the LPS22HB - LPS22Hstatus = LPS22H.status(); - - if(LPS22Hstatus & 0x01) { // if new pressure data available - pressure = (float) LPS22H.readAltimeterPressure()/4096.0f; - temperature = (float) LPS22H.readAltimeterTemperature()/100.0f; - - altitude = 145366.45f*(1.0f - pow((pressure/1013.25f), 0.190284f)); - - if(SerialDebug) { - Serial.print("Altimeter temperature = "); Serial.print( temperature, 2); Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); Serial.print(9.0f*temperature/5.0f + 32.0f, 2); Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); Serial.print(pressure, 2); Serial.println(" mbar");// pressure in millibar - Serial.print("Altitude = "); Serial.print(altitude, 2); Serial.println(" feet"); - } - } - - Gtemperature = ((float) LSM6DSMData[0]) / 256.0f + 25.0f; // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade - if(SerialDebug) { - Serial.print("Gyro temperature is "); Serial.print(Gtemperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - } - - LIS2MDLData[3] = LIS2MDL.readTemperature(); - Mtemperature = ((float) LIS2MDLData[3]) / 8.0f + 25.0f; // Mag chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade - if(SerialDebug) { - Serial.print("Mag temperature is "); Serial.print(Mtemperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - } - - a12 = 2.0f * (q[1] * q[2] + q[0] * q[3]); - a22 = q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]; - a31 = 2.0f * (q[0] * q[1] + q[2] * q[3]); - a32 = 2.0f * (q[1] * q[3] - q[0] * q[2]); - a33 = q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]; - pitch = -asinf(a32); - roll = atan2f(a31, a33); - yaw = atan2f(a12, a22); - pitch *= 180.0f / pi; - yaw *= 180.0f / pi; - yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(yaw < 0) yaw += 360.0f; // Ensure yaw stays between 0 and 360 - roll *= 180.0f / pi; - lin_ax = ax + a31; - lin_ay = ay + a32; - lin_az = az - a33; - - if(SerialDebug) { - Serial.print("Yaw, Pitch, Roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Grav_x, Grav_y, Grav_z: "); - Serial.print(-a31*1000.0f, 2); - Serial.print(", "); - Serial.print(-a32*1000.0f, 2); - Serial.print(", "); - Serial.print(a33*1000.0f, 2); Serial.println(" mg"); - Serial.print("Lin_ax, Lin_ay, Lin_az: "); - Serial.print(lin_ax*1000.0f, 2); - Serial.print(", "); - Serial.print(lin_ay*1000.0f, 2); - Serial.print(", "); - Serial.print(lin_az*1000.0f, 2); Serial.println(" mg"); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - -// Serial.print(millis()/1000);Serial.print(","); -// Serial.print(yaw, 2); Serial.print(","); Serial.print(pitch, 2); Serial.print(","); Serial.print(roll, 2); Serial.print(","); Serial.println(Pressure, 2); - - sumCount = 0; - sum = 0; - - } // end of "if(passThru)" handling - - if(!passThru) - { - - if (SerialDebug) { - Serial.print("Ax = "); Serial.print((int)1000 * Ax); - Serial.print(" Ay = "); Serial.print((int)1000 * Ay); - Serial.print(" Az = "); Serial.print((int)1000 * Az); Serial.println(" mg"); - Serial.print("Gx = "); Serial.print( Gx, 2); - Serial.print(" Gy = "); Serial.print( Gy, 2); - Serial.print(" Gz = "); Serial.print( Gz, 2); Serial.println(" deg/s"); - Serial.print("Mx = "); Serial.print( (int)Mx); - Serial.print(" My = "); Serial.print( (int)My); - Serial.print(" Mz = "); Serial.print( (int)Mz); Serial.println(" mG"); - - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Q[0]); - Serial.print(" Qx = "); Serial.print(Q[1]); - Serial.print(" Qy = "); Serial.print(Q[2]); - Serial.print(" Qz = "); Serial.println(Q[3]); - } - - //Hardware AHRS: - A112 = 2.0f * (Q[1] * Q[2] + Q[0] * Q[3]); - A22 = Q[0] * Q[0] + Q[1] * Q[1] - Q[2] * Q[2] - Q[3] * Q[3]; - A31 = 2.0f * (Q[0] * Q[1] + Q[2] * Q[3]); - A32 = 2.0f * (Q[1] * Q[3] - Q[0] * Q[2]); - A33 = Q[0] * Q[0] - Q[1] * Q[1] - Q[2] * Q[2] + Q[3] * Q[3]; - Pitch = -asinf(A32); - Roll = atan2f(A31, A33); - Yaw = atan2f(A112, A22); - Pitch *= 180.0f / pi; - Yaw *= 180.0f / pi; - Yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if (Yaw < 0) Yaw += 360.0f ; // Ensure yaw stays between 0 and 360 - Roll *= 180.0f / pi; - lin_Ax = Ax + A31; - lin_Ay = Ay + A32; - lin_Az = Az - A33; - - if (SerialDebug) { - Serial.print("Hardware Yaw, pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.print("Hardware Grav_x, Grav_y, Grav_z: "); - Serial.print(-A31 * 1000, 2); - Serial.print(", "); - Serial.print(-A32 * 1000, 2); - Serial.print(", "); - Serial.print(A33 * 1000, 2); Serial.println(" mg"); - Serial.print("Hardware Lin_ax, Lin_ay, Lin_az: "); - Serial.print(lin_Ax * 1000, 2); - Serial.print(", "); - Serial.print(lin_Ay * 1000, 2); - Serial.print(", "); - Serial.print(lin_Az * 1000, 2); Serial.println(" mg"); - - Serial.println("MS5637:"); - Serial.print("Altimeter temperature = "); - Serial.print(Temperature, 2); - Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); - Serial.print(9.0f * Temperature / 5.0f + 32.0f, 2); - Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); - Serial.print(Pressure, 2); - Serial.println(" mbar");// pressure in millibar - Altitude = 145366.45f * (1.0f - powf(((Pressure) / 1013.25f), 0.190284f)); - Serial.print("Altitude = "); - Serial.print(Altitude, 2); - Serial.println(" feet"); - Serial.println(" "); - } - - } // end of "if(!passThru)" handling - - digitalWrite(myLed, HIGH); delay(1); digitalWrite(myLed, LOW); // flash led for 10 milliseconds - delay(500); - -} //end of loop - -/* End of main loop */ - - -void myinthandler1() -{ - newLSM6DSMData = true; -} - -void myinthandler2() -{ - newLIS2MDLData = true; -} - -void myinthandler3() -{ - newLPS22HData = true; -} - -void EM7180intHandler() -{ - newEM7180Data = true; -} - - - - diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.cpp b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.cpp deleted file mode 100644 index dbbb036..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.cpp +++ /dev/null @@ -1,173 +0,0 @@ -/* - * Copyright (c) 2018 Tlera Corp. All rights reserved. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to - * deal with 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: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimers. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimers in the - * documentation and/or other materials provided with the distribution. - * 3. Neither the name of Tlera Corp, nor the names of its contributors - * may be used to endorse or promote products derived from this Software - * without specific prior written permission. - * - * 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 - * CONTRIBUTORS 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 - * WITH THE SOFTWARE. - */ - -#include "Arduino.h" -#include "I2Cdev.h" - -I2Cdev::I2Cdev(TwoWire* i2c_bus) // Class constructor -{ - _i2c_bus = i2c_bus; -} - -I2Cdev::~I2Cdev() // Class destructor -{ -} - -/** -* @fn: readByte(uint8_t address, uint8_t subAddress) -* -* @brief: Read one byte from an I2C device -* -* @params: I2C slave device address, Register subAddress -* @returns: unsigned short read -*/ -uint8_t I2Cdev::readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data = 0; // `data` will store the register data - _i2c_bus->beginTransmission(address); // Initialize the Tx buffer - _i2c_bus->write(subAddress); // Put slave register address in Tx buffer - _i2c_bus->endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - _i2c_bus->requestFrom(address, 1); // Read one byte from slave register address - data = _i2c_bus->read(); // Fill Rx buffer with result - return data; // Return data read from slave register - -} - - -/** -* @fn: readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -* -* @brief: Read multiple bytes from an I2C device -* -* @params: I2C slave device address, Register subAddress, number of btes to be read, aray to store the read data -* @returns: void -*/ -void I2Cdev::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - _i2c_bus->beginTransmission(address); // Initialize the Tx buffer - _i2c_bus->write(subAddress); // Put slave register address in Tx buffer - _i2c_bus->endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - _i2c_bus->requestFrom(address, count); // Read bytes from slave register address - while (_i2c_bus->available()) { - dest[i++] = _i2c_bus->read(); } // Put read results in the Rx buffer -} - - -/** -* @fn: writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data) -* -* @brief: Write one byte to an I2C device -* -* @params: I2C slave device address, Register subAddress, data to be written -* @returns: void -*/ -void I2Cdev::writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data) -{ - _i2c_bus->beginTransmission(devAddr); // Initialize the Tx buffer - _i2c_bus->write(regAddr); // Put slave register address in Tx buffer - _i2c_bus->write(data); // Put data in Tx buffer - _i2c_bus->endTransmission(); // Send the Tx buffer -} - - -/** -* @fn: writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t data) -* -* @brief: Write multiple bytes to an I2C device -* -* @params: I2C slave device address, Register subAddress, byte count, data array to be written -* @returns: void -*/ -void I2Cdev::writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t count, uint8_t *dest) -{ - uint8_t temp[1 + count]; - - temp[0] = regAddr; - for (uint8_t ii = 0; ii < count; ii++) - { - temp[ii + 1] = dest[ii]; - } - - _i2c_bus->beginTransmission(devAddr); // Initialize the Tx buffer - - for (uint8_t jj = 0; jj < count + 1; jj++) - { - _i2c_bus->write(temp[jj]); // Put data in Tx buffer - } - - _i2c_bus->endTransmission(); // Send the Tx buffer -} - - - -/** -* @fn:I2Cscan() -* @brief: Scan the I2C bus for active I2C slave devices -* -* @params: void -* @returns: void -*/ -void I2Cdev::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 Wire.endTransmisstion to see if a device did acknowledge to the address. - _i2c_bus->beginTransmission(address); - error = _i2c_bus->endTransmission(); - - 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("I2C scan complete\n"); -} - diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.h b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.h deleted file mode 100644 index cc546af..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/I2Cdev.h +++ /dev/null @@ -1,48 +0,0 @@ -/* - * Copyright (c) 2018 Tlera Corp. All rights reserved. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to - * deal with 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: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimers. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimers in the - * documentation and/or other materials provided with the distribution. - * 3. Neither the name of Tlera Corp, nor the names of its contributors - * may be used to endorse or promote products derived from this Software - * without specific prior written permission. - * - * 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 - * CONTRIBUTORS 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 - * WITH THE SOFTWARE. - */ - -#ifndef _I2CDEV_H_ -#define _I2CDEV_H_ - -#include - -class I2Cdev { - public: - I2Cdev(TwoWire*); - ~I2Cdev(); // Class destructor for durable instances - uint8_t readByte(uint8_t address, uint8_t subAddress); - void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest); - void writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data); - void writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t count, uint8_t *dest); - void I2Cscan(); - - private: - TwoWire* _i2c_bus; // Class constructor argument -}; - -#endif //_I2CDEV_H_ diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.cpp b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.cpp deleted file mode 100644 index 1667bd0..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.cpp +++ /dev/null @@ -1,175 +0,0 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LIS2MDL is a low power magnetometer, here used as 3 DoF in a 9 DoF absolute orientation solution. - - Library may be used freely and without limit with attribution. - -*/ - -#include "LIS2MDL.h" - -LIS2MDL::LIS2MDL(uint8_t intPin, I2Cdev* i2c_bus) -{ - _intPin = intPin; - _i2c_bus = i2c_bus; -} - - -uint8_t LIS2MDL::getChipID() -{ - uint8_t c = _i2c_bus->readByte(LIS2MDL_ADDRESS, LIS2MDL_WHO_AM_I); - return c; -} - - -void LIS2MDL::reset() -{ - // reset device - uint8_t temp = _i2c_bus->readByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A); - _i2c_bus->writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, temp | 0x20); // Set bit 5 to 1 to reset LIS2MDL - delay(1); - _i2c_bus->writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, temp | 0x40); // Set bit 6 to 1 to boot LIS2MDL - delay(100); // Wait for all registers to reset -} - -void LIS2MDL::init(uint8_t MODR) -{ - // enable temperature compensation (bit 7 == 1), continuous mode (bits 0:1 == 00) - _i2c_bus->writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, 0x80 | MODR<<2); - - // enable low pass filter (bit 0 == 1), set to ODR/4 - _i2c_bus->writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_B, 0x01); - - // enable data ready on interrupt pin (bit 0 == 1), enable block data read (bit 4 == 1) - _i2c_bus->writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, 0x01 | 0x10); -} - - -uint8_t LIS2MDL::status() -{ - // Read the status register of the altimeter - uint8_t temp = _i2c_bus->readByte(LIS2MDL_ADDRESS, LIS2MDL_STATUS_REG); - return temp; -} - - -void LIS2MDL::readData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z mag register data stored here - _i2c_bus->readBytes(LIS2MDL_ADDRESS, (0x80 | LIS2MDL_OUTX_L_REG), 8, &rawData[0]); // Read the 6 raw data registers into data array - - 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] ; - destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; -} - - -int16_t LIS2MDL::readTemperature() -{ - uint8_t rawData[2]; // x/y/z mag register data stored here - _i2c_bus->readBytes(LIS2MDL_ADDRESS, (0x80 | LIS2MDL_TEMP_OUT_L_REG), 2, &rawData[0]); // Read the 8 raw data registers into data array - int16_t temp = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn the MSB and LSB into a signed 16-bit value - return temp; -} - - -void LIS2MDL::offsetBias(float * dest1, float * dest2) -{ - int32_t mag_bias[3] = {0, 0, 0}, mag_scale[3] = {0, 0, 0}; - int16_t mag_max[3] = {-32767, -32767, -32767}, mag_min[3] = {32767, 32767, 32767}, mag_temp[3] = {0, 0, 0}; - float _mRes = 0.0015f; - - Serial.println("Calculate mag offset bias: move all around to sample the complete response surface!"); - delay(4000); - - for (int ii = 0; ii < 4000; ii++) - { - readData(mag_temp); - 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]; - } - delay(12); - } - - _mRes = 0.0015f; // fixed sensitivity - // 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; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1] * _mRes; - dest1[2] = (float) mag_bias[2] * _mRes; - - // 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.0f; - - 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!"); -} - -void LIS2MDL::selfTest() -{ - int16_t temp[3] = {0, 0, 0}; - float magTest[3] = {0., 0., 0.}; - float magNom[3] = {0., 0., 0.}; - int32_t sum[3] = {0, 0, 0}; - float _mRes = 0.0015f; - - // first, get average response with self test disabled - for (int ii = 0; ii < 50; ii++) - { - readData(temp); - sum[0] += temp[0]; - sum[1] += temp[1]; - sum[2] += temp[2]; - delay(50); - } - - magNom[0] = (float) sum[0] / 50.0f; - magNom[1] = (float) sum[1] / 50.0f; - magNom[2] = (float) sum[2] / 50.0f; - - uint8_t c = _i2c_bus->readByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C); - _i2c_bus->writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, c | 0x02); // enable self test - delay(100); // let mag respond - - sum[0] = 0; - sum[1] = 0; - sum[2] = 0; - for (int ii = 0; ii < 50; ii++) - { - readData(temp); - sum[0] += temp[0]; - sum[1] += temp[1]; - sum[2] += temp[2]; - delay(50); - } - - magTest[0] = (float) sum[0] / 50.0f; - magTest[1] = (float) sum[1] / 50.0f; - magTest[2] = (float) sum[2] / 50.0f; - - _i2c_bus->writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, c); // return to previous settings/normal mode - delay(100); // let mag respond - - Serial.println("Mag Self Test:"); - Serial.print("Mx results:"); Serial.print( (magTest[0] - magNom[0]) * _mRes * 1000.0); Serial.println(" mG"); - Serial.print("My results:"); Serial.println((magTest[0] - magNom[0]) * _mRes * 1000.0); - Serial.print("Mz results:"); Serial.println((magTest[1] - magNom[1]) * _mRes * 1000.0); - Serial.println("Should be between 15 and 500 mG"); - delay(2000); // give some time to read the screen -} - diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.h b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.h deleted file mode 100644 index 434d971..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LIS2MDL.h +++ /dev/null @@ -1,75 +0,0 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LIS2MDL is a low power magnetometer, here used as 3 DoF in a 9 DoF absolute orientation solution. - - Library may be used freely and without limit with attribution. - -*/ - -#ifndef LIS2MDL_h -#define LIS2MDL_h - -#include "Arduino.h" -#include -#include "I2Cdev.h" - -//Register map for LIS2MDL' -// http://www.st.com/content/ccc/resource/technical/document/datasheet/group3/29/13/d1/e0/9a/4d/4f/30/DM00395193/files/DM00395193.pdf/jcr:content/translations/en.DM00395193.pdf -#define LIS2MDL_OFFSET_X_REG_L 0x45 -#define LIS2MDL_OFFSET_X_REG_L 0x46 -#define LIS2MDL_OFFSET_X_REG_L 0x47 -#define LIS2MDL_OFFSET_X_REG_L 0x48 -#define LIS2MDL_OFFSET_X_REG_L 0x49 -#define LIS2MDL_OFFSET_X_REG_L 0x4A -#define LIS2MDL_WHO_AM_I 0x4F -#define LIS2MDL_CFG_REG_A 0x60 -#define LIS2MDL_CFG_REG_B 0x61 -#define LIS2MDL_CFG_REG_C 0x62 -#define LIS2MDL_INT_CTRL_REG 0x63 -#define LIS2MDL_INT_SOURCE_REG 0x64 -#define LIS2MDL_INT_THS_L_REG 0x65 -#define LIS2MDL_INT_THS_H_REG 0x66 -#define LIS2MDL_STATUS_REG 0x67 -#define LIS2MDL_OUTX_L_REG 0x68 -#define LIS2MDL_OUTX_H_REG 0x69 -#define LIS2MDL_OUTY_L_REG 0x6A -#define LIS2MDL_OUTY_H_REG 0x6B -#define LIS2MDL_OUTZ_L_REG 0x6C -#define LIS2MDL_OUTZ_H_REG 0x6D -#define LIS2MDL_TEMP_OUT_L_REG 0x6E -#define LIS2MDL_TEMP_OUT_H_REG 0x6F - -#define LIS2MDL_ADDRESS 0x1E - -#define MODR_10Hz 0x00 -#define MODR_20Hz 0x01 -#define MODR_50Hz 0x02 -#define MODR_100Hz 0x03 - - -class LIS2MDL -{ - public: - LIS2MDL(uint8_t intPin, I2Cdev* i2c_bus); - uint8_t getChipID(); - void init(uint8_t MODR); - void offsetBias(float * dest1, float * dest2); - void reset(); - void selfTest(); - uint8_t status(); - void readData(int16_t * destination); - int16_t readTemperature(); - void I2Cscan(); - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data); - uint8_t readByte(uint8_t address, uint8_t subAddress); - void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest); - private: - uint8_t _intPin; - float _mRes; - I2Cdev* _i2c_bus; -}; - -#endif diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.cpp b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.cpp deleted file mode 100644 index 9402db6..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.cpp +++ /dev/null @@ -1,60 +0,0 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LPS22HB is a low power barometerr. - - Library may be used freely and without limit with attribution. - -*/ - -#include "LPS22HB.h" -#include "Wire.h" - -LPS22H::LPS22H(uint8_t intPin, I2Cdev* i2c_bus) -{ - _intPin = intPin; - _i2c_bus = i2c_bus; -} - -uint8_t LPS22H::getChipID() -{ - // Read the WHO_AM_I register of the altimeter this is a good test of communication - uint8_t temp = _i2c_bus->readByte(LPS22H_ADDRESS, LPS22H_WHOAMI); // Read WHO_AM_I register for LPS22H - return temp; -} - -uint8_t LPS22H::status() -{ - // Read the status register of the altimeter - uint8_t temp = _i2c_bus->readByte(LPS22H_ADDRESS, LPS22H_STATUS); - return temp; -} - -int32_t LPS22H::readAltimeterPressure() -{ - uint8_t rawData[3]; // 24-bit pressure register data stored here - _i2c_bus->readBytes(LPS22H_ADDRESS, (LPS22H_PRESS_OUT_XL | 0x80), 3, &rawData[0]); // bit 7 must be one to read multiple bytes - return (int32_t) ((int32_t) rawData[2] << 16 | (int32_t) rawData[1] << 8 | rawData[0]); -} - -int16_t LPS22H::readAltimeterTemperature() -{ - uint8_t rawData[2]; // 16-bit pressure register data stored here - _i2c_bus->readBytes(LPS22H_ADDRESS, (LPS22H_TEMP_OUT_L | 0x80), 2, &rawData[0]); // bit 7 must be one to read multiple bytes - return (int16_t)((int16_t) rawData[1] << 8 | rawData[0]); -} - - -void LPS22H::Init(uint8_t PODR) -{ - // set sample rate by setting bits 6:4 - // enable low-pass filter by setting bit 3 to one - // bit 2 == 0 means bandwidth is odr/9, bit 2 == 1 means bandwidth is odr/20 - // make sure data not updated during read by setting block data udate (bit 1) to 1 - _i2c_bus->writeByte(LPS22H_ADDRESS, LPS22H_CTRL_REG1, PODR << 4 | 0x08 | 0x02); - _i2c_bus->writeByte(LPS22H_ADDRESS, LPS22H_CTRL_REG3, 0x04); // enable data ready as interrupt source -} - - diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.h b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.h deleted file mode 100644 index 35fbe18..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LPS22HB.h +++ /dev/null @@ -1,73 +0,0 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LPS22HB is a low power barometerr. - - Library may be used freely and without limit with attribution. - -*/ - -#ifndef LPS22HB_h -#define LPS22HB_h - -#include "Arduino.h" -#include "Wire.h" -#include "I2Cdev.h" - -// See LPS22H "MEMS pressure sensor: 260-1260 hPa absolute digital output barometer" Data Sheet -// http://www.st.com/content/ccc/resource/technical/document/datasheet/bf/c1/4f/23/61/17/44/8a/DM00140895.pdf/files/DM00140895.pdf/jcr:content/translations/en.DM00140895.pdf -#define LPS22H_INTERRUPT_CFG 0x0B -#define LPS22H_THS_P_L 0x0C -#define LPS22H_THS_P_H 0x0D -#define LPS22H_WHOAMI 0x0F // should return 0xB1 -#define LPS22H_CTRL_REG1 0x10 -#define LPS22H_CTRL_REG2 0x11 -#define LPS22H_CTRL_REG3 0x12 -#define LPS22H_FIFO_CTRL 0x14 -#define LPS22H_REF_P_XL 0x15 -#define LPS22H_REF_P_L 0x16 -#define LPS22H_REF_P_H 0x17 -#define LPS22H_RPDS_L 0x18 -#define LPS22H_RPDS_H 0x19 -#define LPS22H_RES_CONF 0x1A -#define LPS22H_INT_SOURCE 0x25 -#define LPS22H_FIFO_STATUS 0x26 -#define LPS22H_STATUS 0x27 -#define LPS22H_PRESS_OUT_XL 0x28 -#define LPS22H_PRESS_OUT_L 0x29 -#define LPS22H_PRESS_OUT_H 0x2A -#define LPS22H_TEMP_OUT_L 0x2B -#define LPS22H_TEMP_OUT_H 0x2C -#define LPS22H_LPFP_RES 0x33 - -#define LPS22H_ADDRESS 0x5C // Address of altimeter - -// Altimeter output data rate -#define P_1shot 0x00; -#define P_1Hz 0x01; -#define P_10Hz 0x02; -#define P_25Hz 0x03; // 25 Hz output data rate -#define P_50Hz 0x04; -#define P_75Hz 0x05; - -class LPS22H -{ - public: - LPS22H(uint8_t intPin, I2Cdev* i2c_bus); - void Init(uint8_t PODR); - uint8_t getChipID(); - uint8_t status(); - int32_t readAltimeterPressure(); - int16_t readAltimeterTemperature(); - void I2Cscan(); - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data); - uint8_t readByte(uint8_t address, uint8_t subAddress); - void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest); - private: - uint8_t _intPin; - I2Cdev* _i2c_bus; -}; - -#endif diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.cpp b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.cpp deleted file mode 100644 index 74f0a09..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.cpp +++ /dev/null @@ -1,225 +0,0 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LSM6DSM is a sensor hub with embedded accel and gyro, here used as 6 DoF in a 9 DoF absolute orientation solution. - - Library may be used freely and without limit with attribution. - -*/ - -#include "LSM6DSM.h" - -LSM6DSM::LSM6DSM(uint8_t intPin1, uint8_t intPin2, I2Cdev* i2c_bus) -{ - _intPin1 = intPin1; - _intPin2 = intPin2; - _i2c_bus = i2c_bus; -} - - -uint8_t LSM6DSM::getChipID() -{ - uint8_t c = _i2c_bus->readByte(LSM6DSM_ADDRESS, LSM6DSM_WHO_AM_I); - return c; -} - -float LSM6DSM::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 algorithm to calculate DPS/(ADC tick) based on that 2-bit value: - case AFS_2G: - _aRes = 2.0f/32768.0f; - return _aRes; - break; - case AFS_4G: - _aRes = 4.0f/32768.0f; - return _aRes; - break; - case AFS_8G: - _aRes = 8.0f/32768.0f; - return _aRes; - break; - case AFS_16G: - _aRes = 16.0f/32768.0f; - return _aRes; - break; - } -} - -float LSM6DSM::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). - case GFS_245DPS: - _gRes = 245.0f/32768.0f; - return _gRes; - break; - case GFS_500DPS: - _gRes = 500.0f/32768.0f; - return _gRes; - break; - case GFS_1000DPS: - _gRes = 1000.0f/32768.0f; - return _gRes; - break; - case GFS_2000DPS: - _gRes = 2000.0f/32768.0f; - return _gRes; - break; - } -} - - -void LSM6DSM::reset() -{ - // reset device - uint8_t temp = _i2c_bus->readByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C); - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C, temp | 0x01); // Set bit 0 to 1 to reset LSM6DSM - delay(100); // Wait for all registers to reset -} - - -void LSM6DSM::init(uint8_t Ascale, uint8_t Gscale, uint8_t AODR, uint8_t GODR) -{ - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL1_XL, AODR << 4 | Ascale << 2); - - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL2_G, GODR << 4 | Gscale << 2); - - uint8_t temp = _i2c_bus->readByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C); - // enable block update (bit 6 = 1), auto-increment registers (bit 2 = 1) - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C, temp | 0x40 | 0x04); - // by default, interrupts active HIGH, push pull, little endian data - // (can be changed by writing to bits 5, 4, and 1, resp to above register) - - // enable accel LP2 (bit 7 = 1), set LP2 tp ODR/9 (bit 6 = 1), enable input_composite (bit 3) for low noise - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL8_XL, 0x80 | 0x40 | 0x08 ); - - // interrupt handling - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_DRDY_PULSE_CFG, 0x80); // latch interrupt until data read - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_INT1_CTRL, 0x40); // enable significant motion interrupts on INT1 - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_INT2_CTRL, 0x03); // enable accel/gyro data ready interrupts on INT2 -} - - -void LSM6DSM::selfTest() -{ - int16_t temp[7] = {0, 0, 0, 0, 0, 0, 0}; - int16_t accelPTest[3] = {0, 0, 0}, accelNTest[3] = {0, 0, 0}, gyroPTest[3] = {0, 0, 0}, gyroNTest[3] = {0, 0, 0}; - int16_t accelNom[3] = {0, 0, 0}, gyroNom[3] = {0, 0, 0}; - - readData(temp); - accelNom[0] = temp[4]; - accelNom[1] = temp[5]; - accelNom[2] = temp[6]; - gyroNom[0] = temp[1]; - gyroNom[1] = temp[2]; - gyroNom[2] = temp[3]; - - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x01); // positive accel self test - delay(100); // let accel respond - readData(temp); - accelPTest[0] = temp[4]; - accelPTest[1] = temp[5]; - accelPTest[2] = temp[6]; - - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x03); // negative accel self test - delay(100); // let accel respond - readData(temp); - accelNTest[0] = temp[4]; - accelNTest[1] = temp[5]; - accelNTest[2] = temp[6]; - - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x04); // positive gyro self test - delay(100); // let gyro respond - readData(temp); - gyroPTest[0] = temp[1]; - gyroPTest[1] = temp[2]; - gyroPTest[2] = temp[3]; - - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x0C); // negative gyro self test - delay(100); // let gyro respond - readData(temp); - gyroNTest[0] = temp[1]; - gyroNTest[1] = temp[2]; - gyroNTest[2] = temp[3]; - - _i2c_bus->writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x00); // normal mode - delay(100); // let accel and gyro respond - - Serial.println("Accel Self Test:"); - Serial.print("+Ax results:"); Serial.print( (accelPTest[0] - accelNom[0]) * _aRes * 1000.0); Serial.println(" mg"); - Serial.print("-Ax results:"); Serial.println((accelNTest[0] - accelNom[0]) * _aRes * 1000.0); - Serial.print("+Ay results:"); Serial.println((accelPTest[1] - accelNom[1]) * _aRes * 1000.0); - Serial.print("-Ay results:"); Serial.println((accelNTest[1] - accelNom[1]) * _aRes * 1000.0); - Serial.print("+Az results:"); Serial.println((accelPTest[2] - accelNom[2]) * _aRes * 1000.0); - Serial.print("-Az results:"); Serial.println((accelNTest[2] - accelNom[2]) * _aRes * 1000.0); - Serial.println("Should be between 90 and 1700 mg"); - - Serial.println("Gyro Self Test:"); - Serial.print("+Gx results:"); Serial.print((gyroPTest[0] - gyroNom[0]) * _gRes); Serial.println(" dps"); - Serial.print("-Gx results:"); Serial.println((gyroNTest[0] - gyroNom[0]) * _gRes); - Serial.print("+Gy results:"); Serial.println((gyroPTest[1] - gyroNom[1]) * _gRes); - Serial.print("-Gy results:"); Serial.println((gyroNTest[1] - gyroNom[1]) * _gRes); - Serial.print("+Gz results:"); Serial.println((gyroPTest[2] - gyroNom[2]) * _gRes); - Serial.print("-Gz results:"); Serial.println((gyroNTest[2] - gyroNom[2]) * _gRes); - Serial.println("Should be between 20 and 80 dps"); - delay(2000); - - -} - - -void LSM6DSM::offsetBias(float * dest1, float * dest2) -{ - int16_t temp[7] = {0, 0, 0, 0, 0, 0, 0}; - int32_t sum[7] = {0, 0, 0, 0, 0, 0, 0}; - - Serial.println("Calculate accel and gyro offset biases: keep sensor flat and motionless!"); - delay(4000); - - for (int ii = 0; ii < 128; ii++) - { - readData(temp); - sum[1] += temp[1]; - sum[2] += temp[2]; - sum[3] += temp[3]; - sum[4] += temp[4]; - sum[5] += temp[5]; - sum[6] += temp[6]; - delay(50); - } - - dest1[0] = sum[1]*_gRes/128.0f; - dest1[1] = sum[2]*_gRes/128.0f; - dest1[2] = sum[3]*_gRes/128.0f; - dest2[0] = sum[4]*_aRes/128.0f; - dest2[1] = sum[5]*_aRes/128.0f; - dest2[2] = sum[6]*_aRes/128.0f; - - if(dest2[0] > 0.8f) {dest2[0] -= 1.0f;} // Remove gravity from the x-axis accelerometer bias calculation - if(dest2[0] < -0.8f) {dest2[0] += 1.0f;} // Remove gravity from the x-axis accelerometer bias calculation - if(dest2[1] > 0.8f) {dest2[1] -= 1.0f;} // Remove gravity from the y-axis accelerometer bias calculation - if(dest2[1] < -0.8f) {dest2[1] += 1.0f;} // Remove gravity from the y-axis accelerometer bias calculation - if(dest2[2] > 0.8f) {dest2[2] -= 1.0f;} // Remove gravity from the z-axis accelerometer bias calculation - if(dest2[2] < -0.8f) {dest2[2] += 1.0f;} // Remove gravity from the z-axis accelerometer bias calculation - -} - - -void LSM6DSM::readData(int16_t * destination) -{ - uint8_t rawData[14]; // x/y/z accel register data stored here - _i2c_bus->readBytes(LSM6DSM_ADDRESS, LSM6DSM_OUT_TEMP_L, 14, &rawData[0]); // Read the 14 raw data registers into data array - 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] ; - destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; - destination[3] = ((int16_t)rawData[7] << 8) | rawData[6] ; - destination[4] = ((int16_t)rawData[9] << 8) | rawData[8] ; - destination[5] = ((int16_t)rawData[11] << 8) | rawData[10] ; - destination[6] = ((int16_t)rawData[13] << 8) | rawData[12] ; -} diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.h b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.h deleted file mode 100644 index 675a87f..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/LSM6DSM.h +++ /dev/null @@ -1,180 +0,0 @@ -/* 09/23/2017 Copyright Tlera Corporation - - Created by Kris Winer - - This sketch uses SDA/SCL on pins 21/20 (Butterfly default), respectively, and it uses the Butterfly STM32L433CU Breakout Board. - The LSM6DSM is a sensor hub with embedded accel and gyro, here used as 6 DoF in a 9 DoF absolute orientation solution. - - Library may be used freely and without limit with attribution. - -*/ - -#ifndef LSM6DSM_h -#define LSM6DSM_h - -#include "Arduino.h" -#include -#include "I2Cdev.h" - -/* LSM6DSM registers - http://www.st.com/content/ccc/resource/technical/document/datasheet/76/27/cf/88/c5/03/42/6b/DM00218116.pdf/files/DM00218116.pdf/jcr:content/translations/en.DM00218116.pdf -*/ -#define LSM6DSM_FUNC_CFG_ACCESS 0x01 -#define LSM6DSM_SENSOR_SYNC_TIME_FRAME 0x04 -#define LSM6DSM_SENSOR_SYNC_RES_RATIO 0x05 -#define LSM6DSM_FIFO_CTRL1 0x06 -#define LSM6DSM_FIFO_CTRL2 0x07 -#define LSM6DSM_FIFO_CTRL3 0x08 -#define LSM6DSM_FIFO_CTRL4 0x09 -#define LSM6DSM_FIFO_CTRL5 0x0A -#define LSM6DSM_DRDY_PULSE_CFG 0x0B -#define LSM6DSM_INT1_CTRL 0x0D -#define LSM6DSM_INT2_CTRL 0x0E -#define LSM6DSM_WHO_AM_I 0x0F // should be 0x6A -#define LSM6DSM_CTRL1_XL 0x10 -#define LSM6DSM_CTRL2_G 0x11 -#define LSM6DSM_CTRL3_C 0x12 -#define LSM6DSM_CTRL4_C 0x13 -#define LSM6DSM_CTRL5_C 0x14 -#define LSM6DSM_CTRL6_C 0x15 -#define LSM6DSM_CTRL7_G 0x16 -#define LSM6DSM_CTRL8_XL 0x17 -#define LSM6DSM_CTRL9_XL 0x18 -#define LSM6DSM_CTRL10_C 0x19 -#define LSM6DSM_MASTER_CONFIG 0x1A -#define LSM6DSM_WAKE_UP_SRC 0x1B -#define LSM6DSM_TAP_SRC 0x1C -#define LSM6DSM_D6D_SRC 0x1D -#define LSM6DSM_STATUS_REG 0x1E -#define LSM6DSM_OUT_TEMP_L 0x20 -#define LSM6DSM_OUT_TEMP_H 0x21 -#define LSM6DSM_OUTX_L_G 0x22 -#define LSM6DSM_OUTX_H_G 0x23 -#define LSM6DSM_OUTY_L_G 0x24 -#define LSM6DSM_OUTY_H_G 0x25 -#define LSM6DSM_OUTZ_L_G 0x26 -#define LSM6DSM_OUTZ_H_G 0x27 -#define LSM6DSM_OUTX_L_XL 0x28 -#define LSM6DSM_OUTX_H_XL 0x29 -#define LSM6DSM_OUTY_L_XL 0x2A -#define LSM6DSM_OUTY_H_XL 0x2B -#define LSM6DSM_OUTZ_L_XL 0x2C -#define LSM6DSM_OUTZ_H_XL 0x2D -#define LSM6DSM_SENSORHUB1_REG 0x2E -#define LSM6DSM_SENSORHUB2_REG 0x2F -#define LSM6DSM_SENSORHUB3_REG 0x30 -#define LSM6DSM_SENSORHUB4_REG 0x31 -#define LSM6DSM_SENSORHUB5_REG 0x32 -#define LSM6DSM_SENSORHUB6_REG 0x33 -#define LSM6DSM_SENSORHUB7_REG 0x34 -#define LSM6DSM_SENSORHUB8_REG 0x35 -#define LSM6DSM_SENSORHUB9_REG 0x36 -#define LSM6DSM_SENSORHUB10_REG 0x37 -#define LSM6DSM_SENSORHUB11_REG 0x38 -#define LSM6DSM_SENSORHUB12_REG 0x39 -#define LSM6DSM_FIFO_STATUS1 0x3A -#define LSM6DSM_FIFO_STATUS2 0x3B -#define LSM6DSM_FIFO_STATUS3 0x3C -#define LSM6DSM_FIFO_STATUS4 0x3D -#define LSM6DSM_FIFO_DATA_OUT_L 0x3E -#define LSM6DSM_FIFO_DATA_OUT_H 0x3F -#define LSM6DSM_TIMESTAMP0_REG 0x40 -#define LSM6DSM_TIMESTAMP1_REG 0x41 -#define LSM6DSM_TIMESTAMP2_REG 0x42 -#define LSM6DSM_STEP_TIMESTAMP_L 0x49 -#define LSM6DSM_STEP_TIMESTAMP_H 0x4A -#define LSM6DSM_STEP_COUNTER_L 0x4B -#define LSM6DSM_STEP_COUNTER_H 0x4C -#define LSM6DSM_SENSORHUB13_REG 0x4D -#define LSM6DSM_SENSORHUB14_REG 0x4E -#define LSM6DSM_SENSORHUB15_REG 0x4F -#define LSM6DSM_SENSORHUB16_REG 0x50 -#define LSM6DSM_SENSORHUB17_REG 0x51 -#define LSM6DSM_SENSORHUB18_REG 0x52 -#define LSM6DSM_FUNC_SRC1 0x53 -#define LSM6DSM_FUNC_SRC2 0x54 -#define LSM6DSM_WRIST_TILT_IA 0x55 -#define LSM6DSM_TAP_CFG 0x58 -#define LSM6DSM_TAP_THS_6D 0x59 -#define LSM6DSM_INT_DUR2 0x5A -#define LSM6DSM_WAKE_UP_THS 0x5B -#define LSM6DSM_WAKE_UP_DUR 0x5C -#define LSM6DSM_FREE_FALL 0x5D -#define LSM6DSM_MD1_CFG 0x5E -#define LSM6DSM_MD2_CFG 0x5F -#define LSM6DSM_MASTER_MODE_CODE 0x60 -#define LSM6DSM_SENS_SYNC_SPI_ERROR_CODE 0x61 -#define LSM6DSM_OUT_MAG_RAW_X_L 0x66 -#define LSM6DSM_OUT_MAG_RAW_X_H 0x67 -#define LSM6DSM_OUT_MAG_RAW_Y_L 0x68 -#define LSM6DSM_OUT_MAG_RAW_Y_H 0x69 -#define LSM6DSM_OUT_MAG_RAW_Z_L 0x6A -#define LSM6DSM_OUT_MAG_RAW_Z_H 0x6B -#define LSM6DSM_INT_OIS 0x6F -#define LSM6DSM_CTRL1_OIS 0x70 -#define LSM6DSM_CTRL2_OIS 0x71 -#define LSM6DSM_CTRL3_OIS 0x72 -#define LSM6DSM_X_OFS_USR 0x73 -#define LSM6DSM_Y_OFS_USR 0x74 -#define LSM6DSM_Z_OFS_USR 0x75 - -#define LSM6DSM_ADDRESS 0x6A // Address of LSM6DSM accel/gyro when ADO = 0 - - -#define AFS_2G 0x00 -#define AFS_4G 0x02 -#define AFS_8G 0x03 -#define AFS_16G 0x01 - -#define GFS_245DPS 0x00 -#define GFS_500DPS 0x01 -#define GFS_1000DPS 0x02 -#define GFS_2000DPS 0x03 - -#define AODR_12_5Hz 0x01 // same for accel and gyro in normal mode -#define AODR_26Hz 0x02 -#define AODR_52Hz 0x03 -#define AODR_104Hz 0x04 -#define AODR_208Hz 0x05 -#define AODR_416Hz 0x06 -#define AODR_833Hz 0x07 -#define AODR_1660Hz 0x08 -#define AODR_3330Hz 0x09 -#define AODR_6660Hz 0x0A - -#define GODR_12_5Hz 0x01 -#define GODR_26Hz 0x02 -#define GODR_52Hz 0x03 -#define GODR_104Hz 0x04 -#define GODR_208Hz 0x05 -#define GODR_416Hz 0x06 -#define GODR_833Hz 0x07 -#define GODR_1660Hz 0x08 -#define GODR_3330Hz 0x09 -#define GODR_6660Hz 0x0A - - -class LSM6DSM -{ - public: - LSM6DSM(uint8_t intPin1, uint8_t intPin2, I2Cdev* i2c_bus); - float getAres(uint8_t Ascale); - float getGres(uint8_t Gscale); - uint8_t getChipID(); - void init(uint8_t Ascale, uint8_t Gscale, uint8_t AODR, uint8_t GODR); - void offsetBias(float * dest1, float * dest2); - void reset(); - void selfTest(); - void readData(int16_t * destination); - void I2Cscan(); - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data); - uint8_t readByte(uint8_t address, uint8_t subAddress); - void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest); - private: - uint8_t _intPin1; - uint8_t _intPin2; - float _aRes, _gRes; - I2Cdev* _i2c_bus; -}; - -#endif diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/Readme.md b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/Readme.md deleted file mode 100644 index 738a875..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/Readme.md +++ /dev/null @@ -1 +0,0 @@ -Sample sketch for the EM7180 as mster to LSM6DSM accel/gyro, LIS2MDL magnetometer, and LPS22HB barometer. Should be able to run on any Arduino-compatible platform. Intended for master (normal) mode use, passthrough mode might need some work to get it to function (mostly setting up the interrupts properly). diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.cpp b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.cpp deleted file mode 100644 index 3c7adc9..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.cpp +++ /dev/null @@ -1,670 +0,0 @@ -/* 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, I2Cdev* i2c_bus) -{ - _intPin = intPin; - _passThru = passThru; - _i2c_bus = i2c_bus; -} - -void USFS::getChipID() -{ - // Read SENtral device information - uint16_t ROM1 = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ROMVersion1); - uint16_t ROM2 = _i2c_bus->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 = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_RAMVersion1); - uint16_t RAM2 = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_RAMVersion2); - Serial.print("EM7180 RAM Version: 0x"); Serial.print(RAM1); Serial.println(RAM2); - uint8_t PID = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ProductID); - Serial.print("EM7180 ProductID: 0x"); Serial.print(PID, HEX); Serial.println(" Should be: 0x80"); - uint8_t RID = _i2c_bus->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 = _i2c_bus->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 = (_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x01); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x01) Serial.println("EEPROM detected on the sensor bus!"); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x02) Serial.println("EEPROM uploaded config file!"); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x04) Serial.println("EEPROM CRC incorrect!"); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x08) Serial.println("EM7180 in initialized state!"); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x10) Serial.println("No EEPROM detected!"); - int count = 0; - while(!STAT) { - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ResetRequest, 0x01); - delay(500); - count++; - STAT = (_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x01); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x01) Serial.println("EEPROM detected on the sensor bus!"); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x02) Serial.println("EEPROM uploaded config file!"); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x04) Serial.println("EEPROM CRC incorrect!"); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x08) Serial.println("EM7180 in initialized state!"); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_SentralStatus) & 0x10) Serial.println("No EEPROM detected!"); - if(count > 10) break; - } - - if(!(_i2c_bus->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 = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register and interrupt - return c; - } - - uint8_t USFS::checkEM7180Errors(){ - uint8_t c = _i2c_bus->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 - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x00); // set SENtral in initialized state to configure registers - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x00); // make sure pass through mode is off - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x01); // Force initialize - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x00); // set SENtral in initialized state to configure registers - - //Setup LPF bandwidth (BEFORE setting ODR's) - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ACC_LPF_BW, accBW); // accBW = 3 = 41Hz - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_GYRO_LPF_BW, gyroBW); // gyroBW = 3 = 41Hz - // Set accel/gyro/mag desired ODR rates - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, QRtDiv); // quat rate = gyroRt/(1 QRTDiv) - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_MagRate, magRt); // 0x64 = 100 Hz - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AccelRate, accRt); // 200/10 Hz, 0x14 = 200 Hz - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_GyroRate, gyroRt); // 200/10 Hz, 0x14 = 200 Hz - _i2c_bus->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 - _i2c_bus->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) - _i2c_bus-> writeByte(EM7180_ADDRESS, EM7180_EnableEvents, 0x07); - // Enable EM7180 run mode - _i2c_bus->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 - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x4A); // Request to read parameter 74 - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); // Request parameter transfer process - byte param_xfer = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(param_xfer==0x4A)) { - param_xfer = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - param[0] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); - param[1] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); - param[2] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); - param[3] = _i2c_bus->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"); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x4B); // Request to read parameter 75 - param_xfer = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(param_xfer==0x4B)) { - param_xfer = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - param[0] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); - param[1] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); - param[2] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); - param[3] = _i2c_bus->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"); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //End parameter transfer - _i2c_bus->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 - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x4A); // Request to read parameter 74 - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); // Request parameter transfer process - param_xfer = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(param_xfer==0x4A)) { - param_xfer = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - param[0] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); - param[1] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); - param[2] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); - param[3] = _i2c_bus->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"); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x4B); // Request to read parameter 75 - param_xfer = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(param_xfer==0x4B)) { - param_xfer = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - param[0] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); - param[1] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); - param[2] = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); - param[3] = _i2c_bus->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"); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //End parameter transfer - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // re-enable algorithm - - -// Read EM7180 status -uint8_t runStatus = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_RunStatus); -if(runStatus & 0x01) Serial.println(" EM7180 run status = normal mode"); -uint8_t algoStatus = _i2c_bus->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 = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_PassThruStatus); -if(passthruStatus & 0x01) Serial.print(" EM7180 in passthru mode!"); -uint8_t eventStatus = _i2c_bus->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 = _i2c_bus->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(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_ActualMagRate)); Serial.println(" Hz"); - Serial.print("Actual AccelRate = "); Serial.print(10*(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_ActualAccelRate))); Serial.println(" Hz"); - Serial.print("Actual GyroRate = "); Serial.print(10*(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_ActualGyroRate))); Serial.println(" Hz"); - Serial.print("Actual BaroRate = "); Serial.print(_i2c_bus->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; - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, bytes[0]); //Gyro LSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, bytes[1]); //Gyro MSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, bytes[2]); //Unused - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, bytes[3]); //Unused - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0xCB); //Parameter 75; 0xCB is 75 decimal with the MSB set high to indicate a paramter write processs - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); //Request parameter transfer procedure - STAT = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); //Check the parameter acknowledge register and loop until the result matches parameter request byte - while(!(STAT==0xCB)) { - STAT = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //Parameter request = 0 to end parameter transfer process - _i2c_bus->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); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, bytes[0]); //Mag LSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, bytes[1]); //Mag MSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, bytes[2]); //Acc LSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, bytes[3]); //Acc MSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0xCA); //Parameter 74; 0xCA is 74 decimal with the MSB set high to indicate a paramter write processs - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); //Request parameter transfer procedure - STAT = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); //Check the parameter acknowledge register and loop until the result matches parameter request byte - while(!(STAT==0xCA)) { - STAT = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //Parameter request = 0 to end parameter transfer process - _i2c_bus->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 - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, bytes[0]); //Param LSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, bytes[1]); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, bytes[2]); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, bytes[3]); //Param MSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); //Request parameter transfer procedure - STAT = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); //Check the parameter acknowledge register and loop until the result matches parameter request byte - while(!(STAT==param)) { - STAT = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //Parameter request = 0 to end parameter transfer process - _i2c_bus->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 - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, bytes[0]); //Param LSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, bytes[1]); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, bytes[2]); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, bytes[3]); //Param MSB - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); //Request parameter transfer procedure - STAT = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); //Check the parameter acknowledge register and loop until the result matches parameter request byte - while(!(STAT==param)) { - STAT = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); //Parameter request = 0 to end parameter transfer process - _i2c_bus->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 - _i2c_bus->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 - _i2c_bus->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 - _i2c_bus->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 - _i2c_bus->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]); -} - -int16_t USFS::readSENtralBaroData() -{ - uint8_t rawData[2]; // x/y/z gyro register data stored here - _i2c_bus->readBytes(EM7180_ADDRESS, EM7180_Baro, 2, &rawData[0]); // Read the two raw data registers sequentially into data array - return (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value -} - -int16_t USFS::readSENtralTempData() -{ - uint8_t rawData[2]; // x/y/z gyro register data stored here - _i2c_bus->readBytes(EM7180_ADDRESS, EM7180_Temp, 2, &rawData[0]); // Read the two raw data registers sequentially into data array - return (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value -} - - -void USFS::SENtralPassThroughMode() -{ - // First put SENtral in standby mode - uint8_t c = _i2c_bus->readByte(EM7180_ADDRESS, EM7180_AlgorithmControl); - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, c | 0x01); -// c = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); -// Serial.print("c = "); Serial.println(c); -// Verify standby status -// if(readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus) & 0x01) { - Serial.println("SENtral in standby mode"); - // Place SENtral in pass-through mode - _i2c_bus->writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - if(_i2c_bus->readByte(EM7180_ADDRESS, EM7180_PassThruStatus) & 0x01) { - Serial.println("SENtral in pass-through mode"); - } - else { - Serial.println("ERROR! SENtral not in pass-through mode!"); - } - } - - - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - - void USFS::M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer - } - - - void USFS::M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) - { - if(count > 128) - { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer - } - - - 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.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 - uint8_t i = 0; - Wire.requestFrom(device_address, count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer - } - - - - - - - // 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! -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; - - } diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.h b/EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.h deleted file mode 100644 index 9250971..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB/USFS.h +++ /dev/null @@ -1,126 +0,0 @@ -#ifndef USFS_h -#define USFSh_h - -#include "Arduino.h" -#include "Wire.h" -#include "I2Cdev.h" - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_Baro 0x2A // start of two-byte MS5637 pressure data, 16-bit signed interger -#define EM7180_BaroTIME 0x2C // start of two-byte MS5637 pressure timestamp, 16-bit unsigned -#define EM7180_Temp 0x2E // start of two-byte MS5637 temperature data, 16-bit signed interger -#define EM7180_TempTIME 0x30 // start of two-byte MS5637 temperature timestamp, 16-bit unsigned -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ActualBaroRate 0x48 -#define EM7180_ActualTempRate 0x49 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_BaroRate 0x58 -#define EM7180_TempRate 0x59 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 -#define EM7180_ACC_LPF_BW 0x5B //Register GP36 -#define EM7180_GYRO_LPF_BW 0x5C //Register GP37 -#define EM7180_BARO_LPF_BW 0x5D //Register GP38 - -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page -#define MPU9250_ADDRESS 0x68 // Device address when ADO = 0 -#define AK8963_ADDRESS 0x0C // Address of magnetometer -#define MS5637_ADDRESS 0x76 // Address of altimeter - -class USFS -{ - public: - USFS(uint8_t intPin, bool passThru, I2Cdev* i2c_bus); - float uint32_reg_to_float (uint8_t *buf); - float int32_reg_to_float (uint8_t *buf); - void float_to_bytes (float param_val, uint8_t *buf); - void EM7180_set_gyro_FS (uint16_t gyro_fs); - void EM7180_set_mag_acc_FS (uint16_t mag_fs, uint16_t acc_fs); - void EM7180_set_integer_param (uint8_t param, uint32_t param_val); - void EM7180_set_float_param (uint8_t param, float param_val); - void readSENtralQuatData(float * destination); - void readSENtralAccelData(int16_t * destination); - void readSENtralGyroData(int16_t * destination); - void readSENtralMagData(int16_t * destination); - void 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); - int16_t readSENtralBaroData(); - int16_t readSENtralTempData(); - void SENtralPassThroughMode(); - void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t data); - void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest); - uint8_t M24512DFMreadByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2); - void M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest); - void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz); - void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz); - void getChipID(); - void loadfwfromEEPROM(); - uint8_t checkEM7180Status(); - uint8_t checkEM7180Errors(); - private: - uint8_t _intPin; - bool _passThru; - float _q[4]; - float _beta; - float _deltat; - float _Kp; - float _Ki; - I2Cdev* _i2c_bus; -}; - -#endif diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly.ino b/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly.ino deleted file mode 100644 index 7bf3d5e..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly.ino +++ /dev/null @@ -1,701 +0,0 @@ -#include "LSM6DSM.h" -#include "LIS2MDL.h" -#include "LPS22HB.h" -#include "USFS.h" -#include - -bool SerialDebug = true; // set to true to get Serial output for debugging -bool passThru = false; - -#define myLed 13 - -const char *build_date = __DATE__; // 11 characters MMM DD YYYY -const char *build_time = __TIME__; // 8 characters HH:MM:SS - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float pi = 3.141592653589793238462643383279502884f; -float GyroMeasError = pi * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = pi * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -float beta = sqrtf(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrtf(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -uint32_t delt_t = 0; // used to control display output rate -uint32_t sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float a12, a22, a31, a32, a33; // rotation matrix coefficients for Euler angles and gravity components -float A12, A22, A31, A32, A33; // rotation matrix coefficients for Hardware Euler angles and gravity components -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval -float lin_ax, lin_ay, lin_az; // linear acceleration (acceleration with gravity component subtracted) -float lin_Ax, lin_Ay, lin_Az; // Hardware linear acceleration (acceleration with gravity component subtracted) -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float Q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // hardware quaternion data register -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - - -//LSM6DSM definitions -#define LSM6DSM_intPin1 10 // interrupt1 pin definitions, significant motion -#define LSM6DSM_intPin2 9 // interrupt2 pin definitions, data ready - -/* Specify sensor parameters (sample rate is twice the bandwidth) - * choices are: - AFS_2G, AFS_4G, AFS_8G, AFS_16G - GFS_245DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS - AODR_12_5Hz, AODR_26Hz, AODR_52Hz, AODR_104Hz, AODR_208Hz, AODR_416Hz, AODR_833Hz, AODR_1660Hz, AODR_3330Hz, AODR_6660Hz - GODR_12_5Hz, GODR_26Hz, GODR_52Hz, GODR_104Hz, GODR_208Hz, GODR_416Hz, GODR_833Hz, GODR_1660Hz, GODR_3330Hz, GODR_6660Hz -*/ -uint8_t Ascale = AFS_2G, Gscale = GFS_245DPS, AODR = AODR_208Hz, GODR = GODR_416Hz; - -float aRes, gRes; // scale resolutions per LSB for the accel and gyro sensor2 -float accelBias[3] = {-0.00499, 0.01540, 0.02902}, gyroBias[3] = {-0.50, 0.14, 0.28}; // offset biases for the accel and gyro -int16_t LSM6DSMData[7]; // Stores the 16-bit signed sensor output -float Gtemperature; // Stores the real internal gyro temperature in degrees Celsius -float ax, ay, az, gx, gy, gz; // variables to hold latest accel/gyro data values - -bool newLSM6DSMData = false; -bool newLSM6DSMTap = false; - -LSM6DSM LSM6DSM(LSM6DSM_intPin1, LSM6DSM_intPin2); // instantiate LSM6DSM class - - -//LIS2MDL definitions -#define LIS2MDL_intPin 8 // interrupt for magnetometer data ready - -/* Specify sensor parameters (sample rate is twice the bandwidth) - * choices are: MODR_10Hz, MOIDR_20Hz, MODR_50 Hz and MODR_100Hz -*/ -uint8_t MODR = MODR_100Hz; - -float mRes = 0.0015f; // mag sensitivity -float magBias[3] = {0,0,0}, magScale[3] = {0,0,0}; // Bias corrections for magnetometer -int16_t LIS2MDLData[4]; // Stores the 16-bit signed sensor output -float Mtemperature; // Stores the real internal chip temperature in degrees Celsius -float mx, my, mz; // variables to hold latest mag data values -uint8_t LIS2MDLstatus; - -bool newLIS2MDLData = false; - -LIS2MDL LIS2MDL(LIS2MDL_intPin); // instantiate LIS2MDL class - - -// LPS22H definitions -uint8_t LPS22H_intPin = 5; - -/* Specify sensor parameters (sample rate is twice the bandwidth) - Choices are P_1Hz, P_10Hz P_25 Hz, P_50Hz, and P_75Hz - */ -uint8_t PODR = P_25Hz; // set pressure amd temperature output data rate -uint8_t LPS22Hstatus; -float temperature, pressure, altitude; - -bool newLPS22HData = false; - -LPS22H LPS22H(LPS22H_intPin); - - -// RTC set time using STM32L4 natve RTC class -/* Change these values to set the current initial time */ -uint8_t seconds = 0; -uint8_t minutes = 33; -uint8_t hours = 12; - -/* Change these values to set the current initial date */ -uint8_t day = 2; -uint8_t month = 12; -uint8_t year = 17; - -uint8_t Seconds, Minutes, Hours, Day, Month, Year; - -bool alarmFlag = false; // for RTC alarm interrupt - - -const uint8_t USFS_intPin = 8; -bool newEM7180Data = false; -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output -int16_t tempCount, rawPressure, rawTemperature; // temperature raw count output -float Temperature, Pressure, Altitude; // temperature in degrees Celsius, pressure in mbar -float Ax, Ay, Az, Gx, Gy, Gz, Mx, My, Mz; // variables to hold latest sensor data values - - - -/* Choose EM7180, MPU9250 and MS5637 sample rates and bandwidths - Choices are: - accBW, gyroBW 0x00 = 250 Hz, 0x01 = 184 Hz, 0x02 = 92 Hz, 0x03 = 41 Hz, 0x04 = 20 Hz, 0x05 = 10 Hz, 0x06 = 5 Hz, 0x07 = no filter (3600 Hz) - QRtDiv 0x00, 0x01, 0x02, etc quat rate = gyroRt/(1 + QRtDiv) - magRt 8 Hz = 0x08 or 100 Hz 0x64 - accRt, gyroRt 1000, 500, 250, 200, 125, 100, 50 Hz enter by choosing desired rate - and dividing by 10, so 200 Hz would be 200/10 = 20 = 0x14 - sample rate of barometer is baroRt/2 so for 25 Hz enter 50 = 0x32 -*/ -uint8_t accBW = 0x03, gyroBW = 0x03, QRtDiv = 0x01, magRt = 0x64, accRt = 0x14, gyroRt = 0x14, baroRt = 0x32; -/* - Choose MPU9250 sensor full ranges - Choices are 2, 4, 8, 16 g for accFS, 250, 500, 1000, and 2000 dps for gyro FS and 1000 uT for magFS expressed as HEX values -*/ -uint16_t accFS = 0x08, gyroFS = 0x7D0, magFS = 0x3E8; - -USFS USFS(USFS_intPin, passThru); - - - -void setup() { - // put your setup code here, to run once: - Serial.begin(115200); - delay(4000); - - // Configure led - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); // start with led off - - Wire.begin(TWI_PINS_20_21); // set master mode - Wire.setClock(400000); // I2C frequency at 400 kHz - delay(1000); - - LSM6DSM.I2Cscan(); // which I2C device are on the bus? - - if(!passThru) - { - // Initialize the USFS - USFS.getChipID(); // check ROM/RAM version of EM7180 - USFS.loadfwfromEEPROM(); // load EM7180 firmware from EEPROM - USFS.initEM7180(accBW, gyroBW, accFS, gyroFS, magFS, QRtDiv, magRt, accRt, gyroRt, baroRt); // set MPU and MS5637 sensor parameters - } // end of "if(!passThru)" handling - - if(passThru) - { - // Read the LSM6DSM Chip ID register, this is a good test of communication - Serial.println("LSM6DSM accel/gyro..."); - byte c = LSM6DSM.getChipID(); // Read CHIP_ID register for LSM6DSM - Serial.print("LSM6DSM "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x6A, HEX); - Serial.println(" "); - delay(1000); - - // Read the LIS2MDL Chip ID register, this is a good test of communication - Serial.println("LIS2MDL mag..."); - byte d = LIS2MDL.getChipID(); // Read CHIP_ID register for LSM6DSM - Serial.print("LIS2MDL "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x40, HEX); - Serial.println(" "); - delay(1000); - - Serial.println("LPS22HB barometer..."); - uint8_t e = LPS22H.getChipID(); - Serial.print("LPS25H "); Serial.print("I AM "); Serial.print(e, HEX); Serial.print(" I should be "); Serial.println(0xB1, HEX); - delay(1000); - - - if(c == 0x6A && d == 0x40 && e == 0xB1) // check if all I2C sensors have acknowledged - { - Serial.println("LSM6DSM and LIS2MDL and LPS22HB are online..."); Serial.println(" "); - - digitalWrite(myLed, LOW); - - LSM6DSM.reset(); // software reset LSM6DSM to default registers - - // get sensor resolutions, only need to do this once - aRes = LSM6DSM.getAres(Ascale); - gRes = LSM6DSM.getGres(Gscale); - - LSM6DSM.init(Ascale, Gscale, AODR, GODR); - - LSM6DSM.selfTest(); - - LSM6DSM.offsetBias(gyroBias, accelBias); - Serial.println("accel biases (mg)"); Serial.println(1000.0f * accelBias[0]); Serial.println(1000.0f * accelBias[1]); Serial.println(1000.0f * accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - delay(1000); - - LIS2MDL.reset(); // software reset LIS2MDL to default registers - - mRes = 0.0015f; // fixed sensitivity and full scale (+/- 49.152 Gauss); - - LIS2MDL.init(MODR); - - LIS2MDL.selfTest(); - - LIS2MDL.offsetBias(magBias, magScale); - Serial.println("mag biases (mG)"); Serial.println(1000.0f * magBias[0]); Serial.println(1000.0f * magBias[1]); Serial.println(1000.0f * magBias[2]); - Serial.println("mag scale (mG)"); Serial.println(magScale[0]); Serial.println(magScale[1]); Serial.println(magScale[2]); - delay(2000); // add delay to see results before serial spew of data - - LPS22H.Init(PODR); // Initialize LPS22H altimeter - delay(1000); - - digitalWrite(myLed, HIGH); - - } - else - { - if(c != 0x6A) Serial.println(" LSM6DSM not functioning!"); - if(d != 0x40) Serial.println(" LIS2MDL not functioning!"); - if(e != 0xB1) Serial.println(" LPS22HB not functioning!"); - - while(1){}; - } - } // end of "if(passThru)" handling - - // Set the time - SetDefaultRTC(); - - /* Set up the RTC alarm interrupt */ - RTC.enableAlarm(RTC.MATCH_ANY); // alarm once a second - - RTC.attachInterrupt(alarmMatch); // interrupt every time the alarm sounds - - if(!passThru) - { - attachInterrupt(USFS_intPin, EM7180intHandler, RISING); // define interrupt for INT pin output of EM7180 - - USFS.checkEM7180Status(); - } - - if(passThru) - { - attachInterrupt(LSM6DSM_intPin2, myinthandler1, RISING); // define interrupt for intPin2 output of LSM6DSM - attachInterrupt(LIS2MDL_intPin , myinthandler2, RISING); // define interrupt for intPin output of LIS2MDL - attachInterrupt(LPS22H_intPin , myinthandler3, RISING); // define interrupt for intPin output of LPS22HB - - LIS2MDLstatus = LIS2MDL.status(); // read status register to clear interrupt before main loop - } - -} - -/* End of setup */ - -void loop() { - - if(passThru) - { - // If intPin goes high, either all data registers have new data - if(newLSM6DSMData == true) { // On interrupt, read data - newLSM6DSMData = false; // reset newData flag - - LSM6DSM.readData(LSM6DSMData); // INT2 cleared on any read - - // Now we'll calculate the accleration value into actual g's - ax = (float)LSM6DSMData[4]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)LSM6DSMData[5]*aRes - accelBias[1]; - az = (float)LSM6DSMData[6]*aRes - accelBias[2]; - - // Calculate the gyro value into actual degrees per second - gx = (float)LSM6DSMData[1]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set - gy = (float)LSM6DSMData[2]*gRes - gyroBias[1]; - gz = (float)LSM6DSMData[3]*gRes - gyroBias[2]; - - for(uint8_t i = 0; i < 10; i++) { // iterate a fixed number of times per data read cycle - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - MadgwickQuaternionUpdate(-ax, ay, az, gx*pi/180.0f, -gy*pi/180.0f, -gz*pi/180.0f, mx, my, -mz); - } - - } - - // If intPin goes high, either all data registers have new data - if(newLIS2MDLData == true) { // On interrupt, read data - newLIS2MDLData = false; // reset newData flag - - LIS2MDLstatus = LIS2MDL.status(); - - if(LIS2MDLstatus & 0x08) // if all axes have new data ready - { - LIS2MDL.readData(LIS2MDLData); - - // Now we'll calculate the accleration value into actual G's - mx = (float)LIS2MDLData[0]*mRes - magBias[0]; // get actual G value - my = (float)LIS2MDLData[1]*mRes - magBias[1]; - mz = (float)LIS2MDLData[2]*mRes - magBias[2]; - mx *= magScale[0]; - my *= magScale[1]; - mz *= magScale[2]; - } - } - } // end of "if(passThru)" handling - - if(!passThru) - { - /*EM7180*/ - // If intpin goes high, all data registers have new data - if (newEM7180Data == true) { // On interrupt, read data - newEM7180Data = false; // reset newData flag - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = USFS.checkEM7180Status(); // reading clears the register - - // Check for errors - if (eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = USFS.checkEM7180Errors(); - if (errorStatus != 0x00) { // is there an error? - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if (errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if (errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if (errorStatus == 0x14) Serial.print("Gyro failure!"); - if (errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if (errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if (errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if (errorStatus == 0x30) Serial.print("Math error!"); - if (errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if (eventStatus & 0x10) { // new acceleration data available - USFS.readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - Ax = (float)accelCount[0] * 0.000488f; // get actual g value - Ay = (float)accelCount[1] * 0.000488f; - Az = (float)accelCount[2] * 0.000488f; - } - - if (eventStatus & 0x20) { // new gyro data available - USFS.readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - Gx = (float)gyroCount[0] * 0.153f; // get actual dps value - Gy = (float)gyroCount[1] * 0.153f; - Gz = (float)gyroCount[2] * 0.153f; - } - - if (eventStatus & 0x08) { // new mag data available - USFS.readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - Mx = (float)magCount[0] * 0.305176f; // get actual G value - My = (float)magCount[1] * 0.305176f; - Mz = (float)magCount[2] * 0.305176f; - } - - if (eventStatus & 0x04) { // new quaternion data available - USFS.readSENtralQuatData(Q); - } - - // get MS5637 pressure - if (eventStatus & 0x40) { // new baro data available - rawPressure = USFS.readSENtralBaroData(); - Pressure = (float)rawPressure * 0.01f + 1013.25f; // pressure in mBar - - // get MS5637 temperature - rawTemperature = USFS.readSENtralTempData(); - Temperature = (float) rawTemperature * 0.01f; // temperature in degrees C - } - } - } // end of "if(!passThru)" handling - - // end sensor interrupt handling - - /*RTC*/ - if(alarmFlag) { // update RTC output (serial display) whenever the RTC alarm condition is achieved and the MPU9250 is awake - alarmFlag = false; - - // Read RTC - if(SerialDebug) - { - Serial.println("RTC:"); - Day = RTC.getDay(); - Month = RTC.getMonth(); - Year = RTC.getYear(); - Seconds = RTC.getSeconds(); - Minutes = RTC.getMinutes(); - Hours = RTC.getHours(); - if(Hours < 10) {Serial.print("0"); Serial.print(Hours);} else Serial.print(Hours); - Serial.print(":"); - if(Minutes < 10) {Serial.print("0"); Serial.print(Minutes);} else Serial.print(Minutes); - Serial.print(":"); - if(Seconds < 10) {Serial.print("0"); Serial.println(Seconds);} else Serial.println(Seconds); - - Serial.print(Month); Serial.print("/"); Serial.print(Day); Serial.print("/"); Serial.println(Year); - Serial.println(" "); - } - - if(passThru) - { - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print((int)1000*mx); - Serial.print(" my = "); Serial.print((int)1000*my); - Serial.print(" mz = "); Serial.print((int)1000*mz); Serial.println(" mG"); - - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - } - - // get pressure and temperature from the LPS22HB - LPS22Hstatus = LPS22H.status(); - - if(LPS22Hstatus & 0x01) { // if new pressure data available - pressure = (float) LPS22H.readAltimeterPressure()/4096.0f; - temperature = (float) LPS22H.readAltimeterTemperature()/100.0f; - - altitude = 145366.45f*(1.0f - pow((pressure/1013.25f), 0.190284f)); - - if(SerialDebug) { - Serial.print("Altimeter temperature = "); Serial.print( temperature, 2); Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); Serial.print(9.0f*temperature/5.0f + 32.0f, 2); Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); Serial.print(pressure, 2); Serial.println(" mbar");// pressure in millibar - Serial.print("Altitude = "); Serial.print(altitude, 2); Serial.println(" feet"); - } - } - - Gtemperature = ((float) LSM6DSMData[0]) / 256.0f + 25.0f; // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade - if(SerialDebug) { - Serial.print("Gyro temperature is "); Serial.print(Gtemperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - } - - LIS2MDLData[3] = LIS2MDL.readTemperature(); - Mtemperature = ((float) LIS2MDLData[3]) / 8.0f + 25.0f; // Mag chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade - if(SerialDebug) { - Serial.print("Mag temperature is "); Serial.print(Mtemperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - } - - a12 = 2.0f * (q[1] * q[2] + q[0] * q[3]); - a22 = q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]; - a31 = 2.0f * (q[0] * q[1] + q[2] * q[3]); - a32 = 2.0f * (q[1] * q[3] - q[0] * q[2]); - a33 = q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]; - pitch = -asinf(a32); - roll = atan2f(a31, a33); - yaw = atan2f(a12, a22); - pitch *= 180.0f / pi; - yaw *= 180.0f / pi; - yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(yaw < 0) yaw += 360.0f; // Ensure yaw stays between 0 and 360 - roll *= 180.0f / pi; - lin_ax = ax + a31; - lin_ay = ay + a32; - lin_az = az - a33; - - if(SerialDebug) { - Serial.print("Yaw, Pitch, Roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Grav_x, Grav_y, Grav_z: "); - Serial.print(-a31*1000.0f, 2); - Serial.print(", "); - Serial.print(-a32*1000.0f, 2); - Serial.print(", "); - Serial.print(a33*1000.0f, 2); Serial.println(" mg"); - Serial.print("Lin_ax, Lin_ay, Lin_az: "); - Serial.print(lin_ax*1000.0f, 2); - Serial.print(", "); - Serial.print(lin_ay*1000.0f, 2); - Serial.print(", "); - Serial.print(lin_az*1000.0f, 2); Serial.println(" mg"); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - -// Serial.print(millis()/1000);Serial.print(","); -// Serial.print(yaw, 2); Serial.print(","); Serial.print(pitch, 2); Serial.print(","); Serial.print(roll, 2); Serial.print(","); Serial.println(Pressure, 2); - - sumCount = 0; - sum = 0; - - } // end of "if(passThru)" handling - - if(!passThru) - { - - if (SerialDebug) { - Serial.print("Ax = "); Serial.print((int)1000 * Ax); - Serial.print(" Ay = "); Serial.print((int)1000 * Ay); - Serial.print(" Az = "); Serial.print((int)1000 * Az); Serial.println(" mg"); - Serial.print("Gx = "); Serial.print( Gx, 2); - Serial.print(" Gy = "); Serial.print( Gy, 2); - Serial.print(" Gz = "); Serial.print( Gz, 2); Serial.println(" deg/s"); - Serial.print("Mx = "); Serial.print( (int)Mx); - Serial.print(" My = "); Serial.print( (int)My); - Serial.print(" Mz = "); Serial.print( (int)Mz); Serial.println(" mG"); - - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Q[0]); - Serial.print(" Qx = "); Serial.print(Q[1]); - Serial.print(" Qy = "); Serial.print(Q[2]); - Serial.print(" Qz = "); Serial.println(Q[3]); - } - - //Hardware AHRS: - A12 = 2.0f * (Q[1] * Q[2] + Q[0] * Q[3]); - A22 = Q[0] * Q[0] + Q[1] * Q[1] - Q[2] * Q[2] - Q[3] * Q[3]; - A31 = 2.0f * (Q[0] * Q[1] + Q[2] * Q[3]); - A32 = 2.0f * (Q[1] * Q[3] - Q[0] * Q[2]); - A33 = Q[0] * Q[0] - Q[1] * Q[1] - Q[2] * Q[2] + Q[3] * Q[3]; - Pitch = -asinf(A32); - Roll = atan2f(A31, A33); - Yaw = atan2f(A12, A22); - Pitch *= 180.0f / pi; - Yaw *= 180.0f / pi; - Yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if (Yaw < 0) Yaw += 360.0f ; // Ensure yaw stays between 0 and 360 - Roll *= 180.0f / pi; - lin_Ax = ax + a31; - lin_Ay = ay + a32; - lin_Az = az - a33; - - if (SerialDebug) { - Serial.print("Hardware Yaw, pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.print("Hardware Grav_x, Grav_y, Grav_z: "); - Serial.print(-A31 * 1000, 2); - Serial.print(", "); - Serial.print(-A32 * 1000, 2); - Serial.print(", "); - Serial.print(A33 * 1000, 2); Serial.println(" mg"); - Serial.print("Hardware Lin_ax, Lin_ay, Lin_az: "); - Serial.print(lin_Ax * 1000, 2); - Serial.print(", "); - Serial.print(lin_Ay * 1000, 2); - Serial.print(", "); - Serial.print(lin_Az * 1000, 2); Serial.println(" mg"); - - Serial.println("MS5637:"); - Serial.print("Altimeter temperature = "); - Serial.print(Temperature, 2); - Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); - Serial.print(9.0f * Temperature / 5.0f + 32.0f, 2); - Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); - Serial.print(Pressure, 2); - Serial.println(" mbar");// pressure in millibar - Altitude = 145366.45f * (1.0f - pow(((Pressure) / 1013.25f), 0.190284f)); - Serial.print("Altitude = "); - Serial.print(Altitude, 2); - Serial.println(" feet"); - Serial.println(" "); - } - - } // end of "if(!passThru)" handling - } // end of RTC alarm handling - - digitalWrite(myLed, LOW); delay(10); digitalWrite(myLed, HIGH); // flash led for 10 milliseconds - STM32.sleep(); - -} //end of loop - -/* End of main loop */ - - -void myinthandler1() -{ - newLSM6DSMData = true; -} - -void myinthandler2() -{ - newLIS2MDLData = true; -} - -void myinthandler3() -{ - newLPS22HData = true; -} - -void EM7180intHandler() -{ - newEM7180Data = true; -} - -void alarmMatch() -{ - alarmFlag = true; -} - -void SetDefaultRTC() // Sets the RTC to the FW build date-time... -{ - char Build_mo[3]; - - // Convert month string to integer - - Build_mo[0] = build_date[0]; - Build_mo[1] = build_date[1]; - Build_mo[2] = build_date[2]; - - String build_mo = Build_mo; - - if(build_mo == "Jan") - { - month = 1; - } else if(build_mo == "Feb") - { - month = 2; - } else if(build_mo == "Mar") - { - month = 3; - } else if(build_mo == "Apr") - { - month = 4; - } else if(build_mo == "May") - { - month = 5; - } else if(build_mo == "Jun") - { - month = 6; - } else if(build_mo == "Jul") - { - month = 7; - } else if(build_mo == "Aug") - { - month = 8; - } else if(build_mo == "Sep") - { - month = 9; - } else if(build_mo == "Oct") - { - month = 10; - } else if(build_mo == "Nov") - { - month = 11; - } else if(build_mo == "Dec") - { - month = 12; - } else - { - month = 1; // Default to January if something goes wrong... - } - - // Convert ASCII strings to integers - day = (build_date[4] - 48)*10 + build_date[5] - 48; // ASCII "0" = 48 - year = (build_date[9] - 48)*10 + build_date[10] - 48; - hours = (build_time[0] - 48)*10 + build_time[1] - 48; - minutes = (build_time[3] - 48)*10 + build_time[4] - 48; - seconds = (build_time[6] - 48)*10 + build_time[7] - 48; - - // Set the date/time - - RTC.setDay(day); - RTC.setMonth(month); - RTC.setYear(year); - RTC.setHours(hours); - RTC.setMinutes(minutes); - RTC.setSeconds(seconds); -} - - diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/MadgwickFilter.ino b/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/MadgwickFilter.ino deleted file mode 100644 index 9da178f..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/MadgwickFilter.ino +++ /dev/null @@ -1,97 +0,0 @@ -// 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 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 = sqrtf(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 = sqrtf(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 = sqrtf(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 = sqrtf(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 = sqrtf(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; - - } diff --git a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/Readme.md b/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/Readme.md deleted file mode 100644 index 106ee73..0000000 --- a/EM7180_LSM6DSM_LIS2MDL_LPS22HB_Butterfly/Readme.md +++ /dev/null @@ -1,2 +0,0 @@ -Sketch for the newest Ultimate Sensor Fusion Solution using the latest ST motion sensors: combination accel/gyro LSM6DSM, magnetometer LIS2MDL, and barometer LPS22HB. Now sold on [Tindie](https://www.tindie.com/products/onehorse/ultimate-sensor-fusion-solution-lsm6dsm--lis2md/). -![image](https://user-images.githubusercontent.com/6698410/41677606-a1207402-747d-11e8-9f83-f1c51f899ab4.jpg) diff --git a/EM7180_LSM9DS0_LPS25H.ino b/EM7180_LSM9DS0_LPS25H.ino deleted file mode 100644 index b400730..0000000 --- a/EM7180_LSM9DS0_LPS25H.ino +++ /dev/null @@ -1,1641 +0,0 @@ -/* EM7180_LSM9DS0_MS5637_t3 Basic Example Code - by: Kris Winer - date: January 24, 2014 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the LSM9DS0, and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DFMC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the LSM9DS0 9-axis motion sensor (accel/gyro/mag) as slave, an LPS25H pressure/temperature sensor, and an M24512DFM - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral can use the pressure data in the sensor fusion - and there is currently a driver for the LPS25H in the SENtral firmware. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The LPS25H is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. The LPS25H is connected to the EM7180 I2C master bus and has an interrupt - connected to the EM7180 just like the LSM9DS0. The driver will use the data ready interrupt from the LPS25H to signal - to the EM7180 that it should read and process the pressure/temperature data. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+LSM9DS0+LPS25H+M24512DFM Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: The LSM9DS0 is an I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ -//#include "Wire.h" -#include -#include -#include -#include - -// Using NOKIA 5110 monochrome 84 x 48 pixel display -// pin 7 - Serial clock out (SCLK) -// pin 6 - Serial data out (DIN) -// pin 5 - Data/Command select (D/C) -// pin 3 - LCD chip select (SCE) -// pin 4 - LCD reset (RST) -Adafruit_PCD8544 display = Adafruit_PCD8544(7, 6, 5, 3, 4); - -// See LPS25H "MEMS pressure sensor: 260-1260 hPa absolute digital output barometer" Data Sheet -#define LPS25H_REF_P_XL 0x08 -#define LPS25H_REF_P_L 0x09 -#define LPS25H_REF_P_H 0x0A -#define LPS25H_WHOAMI 0x0F // should return 0xBD -#define LPS25H_RES_CONF 0x10 -#define LPS25H_CTRL_REG1 0x20 -#define LPS25H_CTRL_REG2 0x21 -#define LPS25H_CTRL_REG3 0x22 -#define LPS25H_CTRL_REG4 0x23 -#define LPS25H_INT_CFG 0x24 -#define LPS25H_INT_SOURCE 0x25 -#define LPS25H_STATUS_REG 0x27 -#define LPS25H_PRESS_OUT_XL 0x28 -#define LPS25H_PRESS_OUT_L 0x29 -#define LPS25H_PRESS_OUT_H 0x2A -#define LPS25H_TEMP_OUT_L 0x2B -#define LPS25H_TEMP_OUT_H 0x2C -#define LPS25H_FIFO_CTRL 0x2E -#define LPS25H_FIFO_STATUS 0x2F -#define LPS25H_THS_P_L 0x30 -#define LPS25H_THS_P_H 0x31 -#define LPS25H_RPDS_L 0x39 -#define LPS25H_RPDS_H 0x3A - -// See also LSM9DS0 Register Map and Descriptions,http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00087365.pdf -// -//////////////////////////// -// LSM9DS0 Gyro Registers // -//////////////////////////// -#define LSM9DS0G_WHO_AM_I_G 0x0F -#define LSM9DS0G_CTRL_REG1_G 0x20 -#define LSM9DS0G_CTRL_REG2_G 0x21 -#define LSM9DS0G_CTRL_REG3_G 0x22 -#define LSM9DS0G_CTRL_REG4_G 0x23 -#define LSM9DS0G_CTRL_REG5_G 0x24 -#define LSM9DS0G_REFERENCE_G 0x25 -#define LSM9DS0G_STATUS_REG_G 0x27 -#define LSM9DS0G_OUT_X_L_G 0x28 -#define LSM9DS0G_OUT_X_H_G 0x29 -#define LSM9DS0G_OUT_Y_L_G 0x2A -#define LSM9DS0G_OUT_Y_H_G 0x2B -#define LSM9DS0G_OUT_Z_L_G 0x2C -#define LSM9DS0G_OUT_Z_H_G 0x2D -#define LSM9DS0G_FIFO_CTRL_REG_G 0x2E -#define LSM9DS0G_FIFO_SRC_REG_G 0x2F -#define LSM9DS0G_INT1_CFG_G 0x30 -#define LSM9DS0G_INT1_SRC_G 0x31 -#define LSM9DS0G_INT1_THS_XH_G 0x32 -#define LSM9DS0G_INT1_THS_XL_G 0x33 -#define LSM9DS0G_INT1_THS_YH_G 0x34 -#define LSM9DS0G_INT1_THS_YL_G 0x35 -#define LSM9DS0G_INT1_THS_ZH_G 0x36 -#define LSM9DS0G_INT1_THS_ZL_G 0x37 -#define LSM9DS0G_INT1_DURATION_G 0x38 - -////////////////////////////////////////// -// LSM9DS0XM Accel/Magneto (XM) Registers // -////////////////////////////////////////// -#define LSM9DS0XM_OUT_TEMP_L_XM 0x05 -#define LSM9DS0XM_OUT_TEMP_H_XM 0x06 -#define LSM9DS0XM_STATUS_REG_M 0x07 -#define LSM9DS0XM_OUT_X_L_M 0x08 -#define LSM9DS0XM_OUT_X_H_M 0x09 -#define LSM9DS0XM_OUT_Y_L_M 0x0A -#define LSM9DS0XM_OUT_Y_H_M 0x0B -#define LSM9DS0XM_OUT_Z_L_M 0x0C -#define LSM9DS0XM_OUT_Z_H_M 0x0D -#define LSM9DS0XM_WHO_AM_I_XM 0x0F -#define LSM9DS0XM_INT_CTRL_REG_M 0x12 -#define LSM9DS0XM_INT_SRC_REG_M 0x13 -#define LSM9DS0XM_INT_THS_L_M 0x14 -#define LSM9DS0XM_INT_THS_H_M 0x15 -#define LSM9DS0XM_OFFSET_X_L_M 0x16 -#define LSM9DS0XM_OFFSET_X_H_M 0x17 -#define LSM9DS0XM_OFFSET_Y_L_M 0x18 -#define LSM9DS0XM_OFFSET_Y_H_M 0x19 -#define LSM9DS0XM_OFFSET_Z_L_M 0x1A -#define LSM9DS0XM_OFFSET_Z_H_M 0x1B -#define LSM9DS0XM_REFERENCE_X 0x1C -#define LSM9DS0XM_REFERENCE_Y 0x1D -#define LSM9DS0XM_REFERENCE_Z 0x1E -#define LSM9DS0XM_CTRL_REG0_XM 0x1F -#define LSM9DS0XM_CTRL_REG1_XM 0x20 -#define LSM9DS0XM_CTRL_REG2_XM 0x21 -#define LSM9DS0XM_CTRL_REG3_XM 0x22 -#define LSM9DS0XM_CTRL_REG4_XM 0x23 -#define LSM9DS0XM_CTRL_REG5_XM 0x24 -#define LSM9DS0XM_CTRL_REG6_XM 0x25 -#define LSM9DS0XM_CTRL_REG7_XM 0x26 -#define LSM9DS0XM_STATUS_REG_A 0x27 -#define LSM9DS0XM_OUT_X_L_A 0x28 -#define LSM9DS0XM_OUT_X_H_A 0x29 -#define LSM9DS0XM_OUT_Y_L_A 0x2A -#define LSM9DS0XM_OUT_Y_H_A 0x2B -#define LSM9DS0XM_OUT_Z_L_A 0x2C -#define LSM9DS0XM_OUT_Z_H_A 0x2D -#define LSM9DS0XM_FIFO_CTRL_REG 0x2E -#define LSM9DS0XM_FIFO_SRC_REG 0x2F -#define LSM9DS0XM_INT_GEN_1_REG 0x30 -#define LSM9DS0XM_INT_GEN_1_SRC 0x31 -#define LSM9DS0XM_INT_GEN_1_THS 0x32 -#define LSM9DS0XM_INT_GEN_1_DURATION 0x33 -#define LSM9DS0XM_INT_GEN_2_REG 0x34 -#define LSM9DS0XM_INT_GEN_2_SRC 0x35 -#define LSM9DS0XM_INT_GEN_2_THS 0x36 -#define LSM9DS0XM_INT_GEN_2_DURATION 0x37 -#define LSM9DS0XM_CLICK_CFG 0x38 -#define LSM9DS0XM_CLICK_SRC 0x39 -#define LSM9DS0XM_CLICK_THS 0x3A -#define LSM9DS0XM_TIME_LIMIT 0x3B -#define LSM9DS0XM_TIME_LATENCY 0x3C -#define LSM9DS0XM_TIME_WINDOW 0x3D -#define LSM9DS0XM_ACT_THS 0x3E -#define LSM9DS0XM_ACT_DUR 0x3F - - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_Baro 0x2A // start of two-byte LPS25H pressure data, 16-bit signed interger -#define EM7180_BaroTIME 0x2C // start of two-byte LPS25H pressure timestamp, 16-bit unsigned -#define EM7180_Temp 0x2E // start of two-byte LPS25H temperature data, 16-bit signed interger -#define EM7180_TempTIME 0x30 // start of two-byte LPS25H temperature timestamp, 16-bit unsigned -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ActualBaroRate 0x48 -#define EM7180_ActualTempRate 0x49 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_BaroRate 0x58 -#define EM7180_TempRate 0x59 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 - -// Using the Teensy Mini Add-On board, LSM9DS0 SDOG = SDOXM = GND as designed -// Seven-bit LSM9DS0 device addresses are ACC = 0x1E, GYRO = 0x6A, MAG = 0x1E - -// Using the EM7180+LSM9DS0+LPS25H Teensy 3.1 Add-On shield, ADO is set to 0 -#define ADO 0 -#if ADO -#define LSM9DS0XM_ADDRESS 0x1D // Address of accel/magnetometer when ADO = 1 -#define LSM9DS0G_ADDRESS 0x6B // Address of gyro when ADO = 1 -#else -#define LSM9DS0XM_ADDRESS 0x1E // Address of accel/magnetometer when ADO = 0 -#define LSM9DS0G_ADDRESS 0x6A // Address of gyro when ADO = 0 -#endif -#define LPS25H_ADDRESS 0x5D // Address of altimeter with LPS25H ADO = 1 -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page - -#define SerialDebug true // set to true to get Serial output for debugging - -enum PODR { // Altimeter output data rate - P_1shot = 0, - P_1Hz, - P_7Hz, - P_12Hz, // 12.5 Hz output data rate - P_25Hz -}; - -enum Pavg { // Altimeter pressure internal data averaging - P_avg_8 = 0, // average pressure data 8 times - P_avg_32, // average pressure data 32 times - P_avg_128, // average pressure data 128 times - P_avg_512 // average pressure data 32 times -}; - -enum Tavg { // Altimeter temperature internal data averaging - T_avg_8 = 0, // average temperature data 8 times - T_avg_16, // average temperature data 16 times - T_avg_32, // average temperature data 32 times - T_avg_64 // average temperature data 64 times -}; - -// Set initial input parameters -enum Ascale { // set of allowable accel full scale settings - AFS_2G = 0, - AFS_4G, - AFS_6G, - AFS_8G, - AFS_16G -}; - -enum Aodr { // set of allowable gyro sample rates - AODR_PowerDown = 0, - AODR_3_125Hz, - AODR_6_25Hz, - AODR_12_5Hz, - AODR_25Hz, - AODR_50Hz, - AODR_100Hz, - AODR_200Hz, - AODR_400Hz, - AODR_800Hz, - AODR_1600Hz -}; - -enum Abw { // set of allowable accewl bandwidths - ABW_773Hz = 0, - ABW_194Hz, - ABW_362Hz, - ABW_50Hz -}; - -enum Gscale { // set of allowable gyro full scale settings - GFS_245DPS = 0, - GFS_500DPS, - GFS_NoOp, - GFS_2000DPS -}; - -enum Godr { // set of allowable gyro sample rates - GODR_95Hz = 0, - GODR_190Hz, - GODR_380Hz, - GODR_760Hz -}; - -enum Gbw { // set of allowable gyro data bandwidths - GBW_low = 0, // 12.5 Hz at Godr = 95 Hz, 12.5 Hz at Godr = 190 Hz, 30 Hz at Godr = 760 Hz - GBW_med, // 25 Hz at Godr = 95 Hz, 25 Hz at Godr = 190 Hz, 35 Hz at Godr = 760 Hz - GBW_high, // 25 Hz at Godr = 95 Hz, 50 Hz at Godr = 190 Hz, 50 Hz at Godr = 760 Hz - GBW_highest // 25 Hz at Godr = 95 Hz, 70 Hz at Godr = 190 Hz, 100 Hz at Godr = 760 Hz -}; - -enum Mscale { // set of allowable mag full scale settings - MFS_2G = 0, - MFS_4G, - MFS_8G, - MFS_12G -}; - -enum Mres { - MRES_LowResolution = 0, - MRES_NoOp, - MRES_HighResolution -}; - -enum Modr { // set of allowable mag sample rates - MODR_3_125Hz = 0, - MODR_6_25Hz, - MODR_12_5Hz, - MODR_25Hz, - MODR_50Hz, - MODR_100Hz -}; - -// Specify sensor full scale -uint8_t PODR = P_7Hz, Pavg = P_avg_512, Tavg = T_avg_64; // set LPS25H pressure amd temperature output data rate -uint8_t Gscale = GFS_245DPS; // gyro full scale -uint8_t Godr = GODR_380Hz; // gyro data sample rate -uint8_t Gbw = GBW_low; // gyro data bandwidth -uint8_t Ascale = AFS_2G; // accel full scale -uint8_t Aodr = AODR_400Hz; // accel data sample rate -uint8_t Abw = ABW_50Hz; // accel data bandwidth -uint8_t Mscale = MFS_12G; // mag full scale -uint8_t Modr = MODR_100Hz; // mag data sample rate -uint8_t Mres = MRES_LowResolution; // magnetometer operation mode -float aRes, gRes, mRes; // scale resolutions per LSB for the sensors - -// Pin definitions -int myLed = 13; // LED on the Teensy 3.1 - -// LPS25H variables -float Temperature, Pressure; // stores LPS25H pressures sensor pressure and temperature - -// LSM9DS0 variables -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output -float Quat[4] = {0, 0, 0, 0}; // quaternion data register -float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag -int16_t tempCount, rawPressure, rawTemperature; // pressure, temperature raw count output -float temperature; // Stores the LSM9DS0 internal chip temperature in degrees Celsius -float SelfTest[6]; // holds results of gyro and accelerometer self test - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Ki 0.0f - -uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval -uint8_t param[4]; // used for param transfer -uint16_t EM7180_mag_fs, EM7180_acc_fs, EM7180_gyro_fs; // EM7180 sensor full scale ranges - -float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -bool passThru = false; - -void setup() -{ - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(5000); - Serial.begin(38400); - - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - I2Cscan(); // should detect SENtral at 0x28 - - // 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"); - - delay(2000); // give some time to read the screen - - // 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(2000); // 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!"); - delay(1000); // give some time to read the screen - - // Set up the SENtral as sensor bus in normal operating mode -if(!passThru) { -// 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 -// Set accel/gyro/mage desired ODR rates -writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 95 Hz -writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x1E); // 30 Hz -writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x14); // 200/10 Hz -writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x13); // 190/10 Hz -writeByte(EM7180_ADDRESS, EM7180_BaroRate, 0x80 | 0x19); // set enable bit and set Baro rate to 25 Hz -//writeByte(EM7180_ADDRESS, EM7180_TempRate, 0x19); // set enable bit and set rate to 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, 0x7F); -// 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 - EM7180_set_integer_param (0x49, 0x00); - - //Write desired sensor full scale ranges to the EM7180 - EM7180_set_mag_acc_FS (0x3E8, 0x08); // 1000 uT, 8 g - EM7180_set_gyro_FS (0x7D0); // 2000 dps - - // 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"); -if(eventStatus & 0x40) Serial.println(" EM7180 new baro 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 == 0x00) Serial.println("All sensors OK!"); - if(sensorStatus & 0x01) Serial.println("Magnetometer not acknowledging!"); - if(sensorStatus & 0x02) Serial.println("Accelerometer not acknowledging!"); - if(sensorStatus & 0x04) Serial.println("Gyro not acknowledging!"); - if(sensorStatus & 0x10) Serial.println("Magnetometer ID not recognized!"); - if(sensorStatus & 0x20) Serial.println("Accelerometer ID not recognized!"); - if(sensorStatus & 0x40) Serial.println("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"); - Serial.print("Actual TempRate = "); Serial.print(readByte(EM7180_ADDRESS, EM7180_ActualTempRate)); Serial.println(" Hz"); - - delay(3000); // give some time to read the screen - - } - - // If pass through mode desired, set it up here - if(passThru) { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - -// Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - display.begin(); // Initialize the display - display.setContrast(58); // Set the contrast - -// Start device display with ID of sensor - display.clearDisplay(); - display.setTextSize(2); - display.setCursor(0,0); display.print("LSM9DS0"); - display.setTextSize(1); - display.setCursor(0, 20); display.print("9-DOF 16-bit"); - display.setCursor(0, 30); display.print("motion sensor"); - display.setCursor(20,40); display.print("60 ug LSB"); - display.display(); - delay(1000); - -// Set up for data display - display.setTextSize(1); // Set text size to normal, 2 is twice normal etc. - display.setTextColor(BLACK); // Set pixel color; 1 on the monochrome screen - display.clearDisplay(); // clears the screen and buffer - - // Read the WHO_AM_I registers, this is a good test of communication - Serial.println("LSM9DS0 9-axis motion sensor..."); - byte c = readByte(LSM9DS0G_ADDRESS, LSM9DS0G_WHO_AM_I_G); // Read WHO_AM_I register for LSM9DS0 gyro - Serial.println("LSM9DS0 gyro"); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0xD4, HEX); - byte d = readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_WHO_AM_I_XM); // Read WHO_AM_I register for LSM9DS0 accel/magnetometer - Serial.println("LSM9DS0 accel/magnetometer"); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x49, HEX); - - - if (c == 0xD4 && d == 0x49) // WHO_AM_I should always be 0xD4 for the gyro and 0x49 for the accel/mag - { - Serial.println("LSM9DS0 is online..."); - - initLSM9DS0(); - Serial.println("LSM9DS0 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - getMres(); - Serial.print("accel sensitivity is "); Serial.print(1./(1000.*aRes)); Serial.println(" LSB/mg"); - Serial.print("gyro sensitivity is "); Serial.print(1./(1000.*gRes)); Serial.println(" LSB/mdps"); - Serial.print("mag sensitivity is "); Serial.print(1./(1000.*mRes)); Serial.println(" LSB/mGauss"); - - accelgyrocalLSM9DS0(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - magcalLSM9DS0(magBias); - Serial.println("mag biases (mG)"); Serial.println(1000.*magBias[0]); Serial.println(1000.*magBias[1]); Serial.println(1000.*magBias[2]); - - /* display.clearDisplay(); - - display.setCursor(0, 0); display.print("LSM9DS0bias"); - display.setCursor(0, 8); display.print(" x y z "); - - display.setCursor(0, 16); display.print((int)(1000*accelBias[0])); - display.setCursor(24, 16); display.print((int)(1000*accelBias[1])); - display.setCursor(48, 16); display.print((int)(1000*accelBias[2])); - display.setCursor(72, 16); display.print("mg"); - - display.setCursor(0, 24); display.print(gyroBias[0], 1); - display.setCursor(24, 24); display.print(gyroBias[1], 1); - display.setCursor(48, 24); display.print(gyroBias[2], 1); - display.setCursor(66, 24); display.print("o/s"); - - display.display(); - delay(1000); - */ - } - else - { - Serial.print("Could not connect to LSM9DS0: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } - - - - // Read the WHO_AM_I register of the altimeter this is a good test of communication - byte e = readByte(LPS25H_ADDRESS, LPS25H_WHOAMI); // Read WHO_AM_I register for LPS25H - Serial.print("LPS25H "); Serial.print("I AM "); Serial.print(e, HEX); Serial.print(" I should be "); Serial.println(0xBD, HEX); - display.clearDisplay(); - display.setCursor(20,0); display.print("LPS25H"); - display.setCursor(0,10); display.print("I AM"); - display.setCursor(0,20); display.print(e, HEX); - display.setCursor(0,30); display.print("I Should Be"); - display.setCursor(0,40); display.print(0xBD, HEX); - display.display(); - delay(1000); - - if (e == 0xBD) // WHO_AM_I should always be 0xBD - { - - LPS25HInit(); // Initialize lPS25H altimeter - - display.clearDisplay(); // clears the screen and buffer - display.setCursor(0, 0); display.print("LPS25H"); - display.setCursor(0,10); display.print("ready "); - display.display(); - delay(1000); - } - else - { - Serial.print("Could not connect to LPS25H: 0x"); - Serial.println(e, HEX); - display.clearDisplay(); // clears the screen and buffer - display.setCursor(0, 0); display.print("LPS25H"); - display.setCursor(0,10); display.print("Error! on 0x"); display.print(e, HEX); - display.display(); - - while(1) ; // Loop forever if communication doesn't happen - } - - } -} - - -void loop() -{ - if(!passThru) { - - // Check event status register, way to check data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - if(eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if(errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus == 0x14) Serial.print("Gyro failure!"); - if(errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus == 0x30) Serial.print("Math error!"); - if(errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if(eventStatus & 0x10) { // new acceleration data available - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) { // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus & 0x08) { // new mag data available - readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - mx = (float)magCount[0]*0.305176; // get actual G value - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) { // new quaternion data available - readSENtralQuatData(Quat); - } - - // get LPS25H pressure - if(eventStatus & 0x40) { // new baro data available - // Serial.println("new Baro data!"); - rawPressure = readSENtralBaroData(); - Pressure = (float) rawPressure*3000.; // pressure in mBar - - // get LPS25H temperature - rawTemperature = readSENtralTempData(); - Temperature = (float) rawTemperature*0.01; // temperature in degrees C - // } - - - } - - - - if(passThru) { - if (readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_STATUS_REG_A) & 0x08) { // check if new accel data is ready - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes - accelBias[1]; - az = (float)accelCount[2]*aRes - accelBias[2]; - } - - if (readByte(LSM9DS0G_ADDRESS, LSM9DS0G_STATUS_REG_G) & 0x08) { // check if new gyro data is ready - readGyroData(gyroCount); // Read the x/y/z adc values - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes - gyroBias[1]; - gz = (float)gyroCount[2]*gRes - gyroBias[2]; - } - - if (readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_STATUS_REG_M) & 0x08) { // check if new mag data is ready - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - // Include factory calibration per data sheet and user environmental corrections - mx = (float)magCount[0]*mRes - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes - magBias[1]; - mz = (float)magCount[2]*mRes - magBias[2]; - } - } - - - // keep track of rates - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer is aligned with the -y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ up) is aligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // For the BMX-055, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like - // in the MPU9250 sensor. This rotation can be modified to allow any convenient orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); -// if(passThru)MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - if (delt_t > 1000) { // update LCD once per half-second independent of read rate - - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - if(!passThru) { - Serial.print("mx = "); Serial.print( mx); - Serial.print(" my = "); Serial.print( my); - Serial.print(" mz = "); Serial.print( mz); Serial.println(" mG"); - } - else { - Serial.print("mx = "); Serial.print( (int)1000*mx); - Serial.print(" my = "); Serial.print( (int)1000*my); - Serial.print(" mz = "); Serial.print( (int)1000*mz); Serial.println(" mG"); - } - - - Serial.println("Software quaternions:"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Quat[3]); - Serial.print(" Qx = "); Serial.print(Quat[0]); - Serial.print(" Qy = "); Serial.print(Quat[1]); - Serial.print(" Qz = "); Serial.println(Quat[2]); - - float altitude = 145366.45f*(1.0f - pow((Pressure/1013.25f), 0.190284f)); - - Serial.print("Altimeter temperature = "); Serial.print( Temperature, 2); Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); Serial.print(9.*Temperature/5. + 32., 2); Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); Serial.print(Pressure, 2); Serial.println(" mbar");// pressure in millibar - Serial.print("Altitude = "); Serial.print(altitude, 2); Serial.println(" feet"); - - } - - -// tempCount = readTempData(); // Read the gyro adc values -// temperature = ((float) tempCount/8. + 25.0); // Gyro chip temperature in degrees Centigrade -// Print temperature in degrees Centigrade -// Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - if(passThru) { - // Get altimeter data - if(readByte(LPS25H_ADDRESS, LPS25H_STATUS_REG) & 0x20) { // check if new altimeter data ready - Pressure = (float) readAltimeterPressure()/4096.0f; - Temperature = (float) readAltimeterTemperature()/480.0f + 42.5f; - } - float altitude = 145366.45f*(1.0f - pow((Pressure/1013.25f), 0.190284f)); - - Serial.print("Altimeter temperature = "); Serial.print( Temperature, 2); Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); Serial.print(9.*Temperature/5. + 32., 2); Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); Serial.print(Pressure, 2); Serial.println(" mbar");// pressure in millibar - Serial.print("Altitude = "); Serial.print(altitude, 2); Serial.println(" feet"); - } - - - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - roll *= 180.0f / PI; - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 260) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - // - - if(SerialDebug) { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - - Serial.print(millis()/1000); Serial.print(","); - Serial.print(yaw); Serial.print(","); Serial.print(pitch); Serial.print(","); Serial.print(roll); Serial.print(","); - Serial.print(Yaw); Serial.print(","); Serial.print(Pitch); Serial.print(","); Serial.print(Roll); Serial.println(","); - - /* - display.clearDisplay(); - - display.setCursor(0, 0); display.print(" x y z "); - - display.setCursor(0, 8); display.print((int)(1000*ax)); - display.setCursor(24, 8); display.print((int)(1000*ay)); - display.setCursor(48, 8); display.print((int)(1000*az)); - display.setCursor(72, 8); display.print("mg"); - - // tempCount = readACCTempData(); // Read the gyro adc values - // temperature = ((float) tempCount) / 2.0 + 23.0; // Gyro chip temperature in degrees Centigrade - // display.setCursor(64, 0); display.print(9.*temperature/5. + 32., 0); display.print("F"); - - display.setCursor(0, 16); display.print((int)(gx)); - display.setCursor(24, 16); display.print((int)(gy)); - display.setCursor(48, 16); display.print((int)(gz)); - display.setCursor(66, 16); display.print("o/s"); - - display.setCursor(0, 24); display.print((int)(mx)); - display.setCursor(24, 24); display.print((int)(my)); - display.setCursor(48, 24); display.print((int)(mz)); - display.setCursor(72, 24); display.print("mG"); - - display.setCursor(0, 32); display.print((int)(yaw)); - display.setCursor(24, 32); display.print((int)(pitch)); - display.setCursor(48, 32); display.print((int)(roll)); - display.setCursor(66, 32); display.print("ypr"); - - -// display.setCursor(0, 40); display.print(altitude, 0); display.print("ft"); -// display.setCursor(68, 0); display.print(9.*Temperature/5. + 32., 0); - display.setCursor(42, 40); display.print((float) sumCount / (1000.*sum), 2); display.print("kHz"); - display.display(); -*/ - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } - -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== -void getMres() { - switch (Mscale) - { - // Possible magnetometer scales (and their register bit settings) are: - // 2 Gauss (00), 4 Gauss (01), 8 Gauss (10) and 12 Gauss (11) - case MFS_2G: - mRes = 2.0/32768.0; - break; - case MFS_4G: - mRes = 4.0/32768.0; - break; - case MFS_8G: - mRes = 8.0/32768.0; - break; - case MFS_12G: - mRes = 12.0/32768.0; - break; - } -} - -void getGres() { - switch (Gscale) - { - // Possible gyro scales (and their register bit settings) are: - // 245 DPS (00), 500 DPS (01), and 2000 DPS (11). - case GFS_245DPS: - gRes = 245.0/32768.0; - break; - case GFS_500DPS: - gRes = 500.0/32768.0; - break; - case GFS_2000DPS: - gRes = 2000.0/32768.0; - break; - } -} - -void getAres() { - switch (Ascale) - { - // Possible accelerometer scales (and their register bit settings) are: - // 2 Gs (000), 4 Gs (001), 6 gs (010), 8 Gs (011), and 16 gs (100). - case AFS_2G: - aRes = 2.0/32768.0; - break; - case AFS_4G: - aRes = 4.0/32768.0; - break; - case AFS_6G: - aRes = 6.0/32768.0; - break; - case AFS_8G: - aRes = 8.0/32768.0; - break; - case AFS_16G: - aRes = 16.0/32768.0; - break; - } -} - - -void readAccelData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z accel register data stored here - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_X_L_A, 6, &rawData[0]); // Read the six raw data registers into data array - 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] ; - destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; -} - - -void readGyroData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z gyro register data stored here - readBytes(LSM9DS0G_ADDRESS, 0x80 | LSM9DS0G_OUT_X_L_G, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - 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] ; - destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; -} - -void readMagData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z gyro register data stored here - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_X_L_M, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - 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 readTempData() -{ - uint8_t rawData[2]; // x/y/z gyro register data stored here - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_TEMP_L_XM, 2, &rawData[0]); // Read the two raw data registers sequentially into data array - return (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a 16-bit signed value -} - - -void initLSM9DS0() -{ - // configure the gyroscope, enable normal mode = power on - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG1_G, Godr << 6 | Gbw << 4 | 0x0F); - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG4_G, Gscale << 4 | 0x80); // enable bloack data update - // configure the accelerometer-specify ODR (sample rate) selection with Aodr, enable block data update - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG1_XM, Aodr << 4 | 0x0F); - // configure the accelerometer-specify bandwidth and full-scale selection with Abw, Ascale - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG2_XM, Abw << 6 | Ascale << 3); - // enable temperature sensor, set magnetometer ODR (sample rate) and resolution mode - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG5_XM, 0x80 | Mres << 5 | Modr << 2); - // set magnetometer full scale - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG6_XM, Mscale << 5 & 0x60); - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG7_XM, 0x00); // select continuous conversion mode - } - - -// 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 accelgyrocalLSM9DS0(float * dest1, float * dest2) -{ - uint8_t data[6] = {0, 0, 0, 0, 0, 0}; - int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; - uint16_t samples, ii; - - Serial.println("Calibrating gyro..."); - - // First get gyro bias - byte c = readByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG5_G); - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG5_G, c | 0x40); // Enable gyro FIFO - delay(400); // Wait for change to take effect - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_FIFO_CTRL_REG_G, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples - delay(2000); // delay 1000 milliseconds to collect FIFO samples - - samples = (readByte(LSM9DS0G_ADDRESS, LSM9DS0G_FIFO_SRC_REG_G) & 0x1F); // Read number of stored samples - - for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO - int16_t gyro_temp[3] = {0, 0, 0}; - readBytes(LSM9DS0G_ADDRESS, 0x80 | LSM9DS0G_OUT_X_L_G, 6, &data[0]); - gyro_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO - gyro_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]); - gyro_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]); - - gyro_bias[0] += (int32_t) gyro_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases - gyro_bias[1] += (int32_t) gyro_temp[1]; - gyro_bias[2] += (int32_t) gyro_temp[2]; - } - - gyro_bias[0] /= samples; // average the data - gyro_bias[1] /= samples; - gyro_bias[2] /= samples; - - dest1[0] = (float)gyro_bias[0]*gRes; // Properly scale the data to get deg/s - dest1[1] = (float)gyro_bias[1]*gRes; - dest1[2] = (float)gyro_bias[2]*gRes; - - c = readByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG5_G); - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG5_G, c & ~0x40); //Disable gyro FIFO - delay(200); - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_FIFO_CTRL_REG_G, 0x00); // Enable gyro bypass mode - - Serial.println("Calibrating accel..."); - - // now get the accelerometer bias - c = readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG0_XM); - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG0_XM, c | 0x40); // Enable gyro FIFO - delay(200); // Wait for change to take effect - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_FIFO_CTRL_REG, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples - delay(1000); // delay 1000 milliseconds to collect FIFO samples - - samples = (readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_FIFO_SRC_REG) & 0x1F); // Read number of stored samples - - for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO - int16_t accel_temp[3] = {0, 0, 0}; - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_X_L_A, 6, &data[0]); - accel_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO - accel_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]); - accel_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]); - - 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]; - } - - accel_bias[0] /= samples; // average the data - accel_bias[1] /= samples; - accel_bias[2] /= samples; - - if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) (1.0/aRes);} // Remove gravity from the z-axis accelerometer bias calculation - else {accel_bias[2] += (int32_t) (1.0/aRes);} - - dest2[0] = (float)accel_bias[0]*aRes; // Properly scale the data to get g - dest2[1] = (float)accel_bias[1]*aRes; - dest2[2] = (float)accel_bias[2]*aRes; - - c = readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG0_XM); - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG0_XM, c & ~0x40); //Disable accel FIFO - delay(200); - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_FIFO_CTRL_REG, 0x00); // Enable accel bypass mode -} - -void magcalLSM9DS0(float * dest1) -{ - uint8_t data[6]; // data array to hold mag x, y, z, data - uint16_t ii = 0, sample_count = 0; - int32_t mag_bias[3] = {0, 0, 0}; - int16_t mag_max[3] = {0, 0, 0}, mag_min[3] = {0, 0, 0}; - - Serial.println("Mag Calibration: Wave device in a figure eight until done!"); - delay(4000); - - sample_count = 128; - for(ii = 0; ii < sample_count; ii++) { - int16_t mag_temp[3] = {0, 0, 0}; - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_X_L_M, 6, &data[0]); // Read the six raw data registers into data array - mag_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]) ; // Form signed 16-bit integer for each sample in FIFO - mag_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]) ; - mag_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]) ; - 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]; - } - delay(105); // at 10 Hz ODR, new mag data is available every 100 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]); - - 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; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes; - dest1[2] = (float) mag_bias[2]*mRes; - - /* //write biases to accelerometermagnetometer offset registers as counts); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_X_REG_L_M, (int16_t) mag_bias[0] & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_X_REG_H_M, ((int16_t)mag_bias[0] >> 8) & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_Y_REG_L_M, (int16_t) mag_bias[1] & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_Y_REG_H_M, ((int16_t)mag_bias[1] >> 8) & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_Z_REG_L_M, (int16_t) mag_bias[2] & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_Z_REG_H_M, ((int16_t)mag_bias[2] >> 8) & 0xFF); - */ - Serial.println("Mag Calibration done!"); -} - -int32_t readAltimeterPressure() -{ - uint8_t rawData[3]; // 24-bit pressure register data stored here - readBytes(LPS25H_ADDRESS, (LPS25H_PRESS_OUT_XL | 0x80), 3, &rawData[0]); // bit 7 must be one to read multiple bytes - return (int32_t) ((int32_t) rawData[2] << 16 | (int32_t) rawData[1] << 8 | rawData[0]); -} - -int16_t readAltimeterTemperature() -{ - uint8_t rawData[2]; // 16-bit pressure register data stored here - readBytes(LPS25H_ADDRESS, (LPS25H_TEMP_OUT_L | 0x80), 2, &rawData[0]); // bit 7 must be one to read multiple bytes - return (int16_t)((int16_t) rawData[1] << 8 | rawData[0]); -} - - -void LPS25HInit() -{ - // turn on the altimeter by setting bit 7 to one - // set sample rate by setting bits 6:4 - // enable interrupt circuit by setting bit 3 to one - // make sure data not updated during read by setting block data more (bit 2) to 1 - // writeByte(LPS25H_ADDRESS, LPS25H_CTRL_REG1, 0x80 | PODR << 4 | 0x08 | 0x04); - // writeByte(LPS25H_ADDRESS, LPS25H_CTRL_REG4, 0x01); // set interrupt pin to signal data ready - // writeByte(LPS25H_ADDRESS, LPS25H_RES_CONF, Tavg << 2 | Pavg); // specify temperature and pressure internal averaging - // or use ultra low-power mode - // To reduce power consumption while keeping a low noise figure, reduce the temperature and pressure averaging - // and reduce ODR to the minimum and enable the digital filter (FIFO) - writeByte(LPS25H_ADDRESS, LPS25H_RES_CONF, 0x05); // set Tavg = 16 and Pavg = 32 internal averaging - writeByte(LPS25H_ADDRESS, LPS25H_FIFO_CTRL, 0xDF); // set FIFO mean mode with average on two samples or more - writeByte(LPS25H_ADDRESS, LPS25H_CTRL_REG2, 0x21); // FIFO enabled, decimation disabled - writeByte(LPS25H_ADDRESS, LPS25H_CTRL_REG1, 0x90); // power on device, set to 1 Hz sample rate -} - - -// I2C read/write functions for the LSM9DS0and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - - -static inline float 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; -} - - -void 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 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 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 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 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 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[0] = uint32_reg_to_float (&rawData[0]); - destination[1] = uint32_reg_to_float (&rawData[4]); - destination[2] = uint32_reg_to_float (&rawData[8]); - destination[3] = uint32_reg_to_float (&rawData[12]); - -} - -void 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 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 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]); -} - -int16_t readSENtralBaroData() -{ - uint8_t rawData[2]; // x/y/z gyro register data stored here - readBytes(EM7180_ADDRESS, EM7180_Baro, 2, &rawData[0]); // Read the two raw data registers sequentially into data array - return (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value -} - -int16_t readSENtralTempData() -{ - uint8_t rawData[2]; // x/y/z gyro register data stored here - readBytes(EM7180_ADDRESS, EM7180_Temp, 2, &rawData[0]); // Read the two raw data registers sequentially into data array - return (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value -} - - -void SENtralPassThroughMode() -{ - // First put SENtral in standby mode - uint8_t c = readByte(EM7180_ADDRESS, EM7180_AlgorithmControl); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, c | 0x01); -// c = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); -// Serial.print("c = "); Serial.println(c); -// Verify standby status -// if(readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus) & 0x01) { - Serial.println("SENtral in standby mode"); - // Place SENtral in pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - if(readByte(EM7180_ADDRESS, EM7180_PassThruStatus) & 0x01) { - Serial.println("SENtral in pass-through mode"); - } - else { - Serial.println("ERROR! SENtral not in pass-through mode!"); - } - -// } -// else { Serial.println("ERROR! SENtral not in standby mode!"); -// } - - } - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - - void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - - void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - if(count > 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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"); -} diff --git a/EM7180_LSM9DS0_MS5637_t3.ino b/EM7180_LSM9DS0_MS5637_t3.ino deleted file mode 100644 index f621f27..0000000 --- a/EM7180_LSM9DS0_MS5637_t3.ino +++ /dev/null @@ -1,1455 +0,0 @@ -/* EM7180_LSM9DS0_MS5637_t3 Basic Example Code - by: Kris Winer - date: January 24, 2014 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the LSM9DS0, and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DFMC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the LSM9DS0 9-axis motion sensor (accel/gyro/mag) as slave, an MS5637 pressure/temperature sensor, and an M24512DFM - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral cannot use the pressure data in the sensor fusion - yet and there is currently no driver for the MS5637 in the SENtral firmware. However, like the MAX21100, the SENtral - can be toggled into a bypass mode where the pressure sensor (and EEPROM and BMX055) may be read directly by the - Teensy 3.1 host micrcontroller. If the read rate is infrequent enough (2 Hz is sufficient since pressure and temperature - do not change very fast), then the sensor fusion rate is not significantly affected. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The MS5637 is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+LSM9DS0+MS5637+M24512DFM Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: The LSM9DS0 is an I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ -//#include "Wire.h" -#include -#include -#include -#include - -// Using NOKIA 5110 monochrome 84 x 48 pixel display -// pin 7 - Serial clock out (SCLK) -// pin 6 - Serial data out (DIN) -// pin 5 - Data/Command select (D/C) -// pin 3 - LCD chip select (SCE) -// pin 4 - LCD reset (RST) -Adafruit_PCD8544 display = Adafruit_PCD8544(7, 6, 5, 3, 4); - -// See MS5637-02BA03 Low Voltage Barometric Pressure Sensor Data Sheet http://www.meas-spec.com/downloads/MS5637-02BA03.pdf -#define MS5637_RESET 0x1E -#define MS5637_CONVERT_D1 0x40 -#define MS5637_CONVERT_D2 0x50 -#define MS5637_ADC_READ 0x00 - - -// See also LSM9DS0 Register Map and Descriptions,http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00087365.pdf -// -//////////////////////////// -// LSM9DS0 Gyro Registers // -//////////////////////////// -#define LSM9DS0G_WHO_AM_I_G 0x0F -#define LSM9DS0G_CTRL_REG1_G 0x20 -#define LSM9DS0G_CTRL_REG2_G 0x21 -#define LSM9DS0G_CTRL_REG3_G 0x22 -#define LSM9DS0G_CTRL_REG4_G 0x23 -#define LSM9DS0G_CTRL_REG5_G 0x24 -#define LSM9DS0G_REFERENCE_G 0x25 -#define LSM9DS0G_STATUS_REG_G 0x27 -#define LSM9DS0G_OUT_X_L_G 0x28 -#define LSM9DS0G_OUT_X_H_G 0x29 -#define LSM9DS0G_OUT_Y_L_G 0x2A -#define LSM9DS0G_OUT_Y_H_G 0x2B -#define LSM9DS0G_OUT_Z_L_G 0x2C -#define LSM9DS0G_OUT_Z_H_G 0x2D -#define LSM9DS0G_FIFO_CTRL_REG_G 0x2E -#define LSM9DS0G_FIFO_SRC_REG_G 0x2F -#define LSM9DS0G_INT1_CFG_G 0x30 -#define LSM9DS0G_INT1_SRC_G 0x31 -#define LSM9DS0G_INT1_THS_XH_G 0x32 -#define LSM9DS0G_INT1_THS_XL_G 0x33 -#define LSM9DS0G_INT1_THS_YH_G 0x34 -#define LSM9DS0G_INT1_THS_YL_G 0x35 -#define LSM9DS0G_INT1_THS_ZH_G 0x36 -#define LSM9DS0G_INT1_THS_ZL_G 0x37 -#define LSM9DS0G_INT1_DURATION_G 0x38 - -////////////////////////////////////////// -// LSM9DS0XM Accel/Magneto (XM) Registers // -////////////////////////////////////////// -#define LSM9DS0XM_OUT_TEMP_L_XM 0x05 -#define LSM9DS0XM_OUT_TEMP_H_XM 0x06 -#define LSM9DS0XM_STATUS_REG_M 0x07 -#define LSM9DS0XM_OUT_X_L_M 0x08 -#define LSM9DS0XM_OUT_X_H_M 0x09 -#define LSM9DS0XM_OUT_Y_L_M 0x0A -#define LSM9DS0XM_OUT_Y_H_M 0x0B -#define LSM9DS0XM_OUT_Z_L_M 0x0C -#define LSM9DS0XM_OUT_Z_H_M 0x0D -#define LSM9DS0XM_WHO_AM_I_XM 0x0F -#define LSM9DS0XM_INT_CTRL_REG_M 0x12 -#define LSM9DS0XM_INT_SRC_REG_M 0x13 -#define LSM9DS0XM_INT_THS_L_M 0x14 -#define LSM9DS0XM_INT_THS_H_M 0x15 -#define LSM9DS0XM_OFFSET_X_L_M 0x16 -#define LSM9DS0XM_OFFSET_X_H_M 0x17 -#define LSM9DS0XM_OFFSET_Y_L_M 0x18 -#define LSM9DS0XM_OFFSET_Y_H_M 0x19 -#define LSM9DS0XM_OFFSET_Z_L_M 0x1A -#define LSM9DS0XM_OFFSET_Z_H_M 0x1B -#define LSM9DS0XM_REFERENCE_X 0x1C -#define LSM9DS0XM_REFERENCE_Y 0x1D -#define LSM9DS0XM_REFERENCE_Z 0x1E -#define LSM9DS0XM_CTRL_REG0_XM 0x1F -#define LSM9DS0XM_CTRL_REG1_XM 0x20 -#define LSM9DS0XM_CTRL_REG2_XM 0x21 -#define LSM9DS0XM_CTRL_REG3_XM 0x22 -#define LSM9DS0XM_CTRL_REG4_XM 0x23 -#define LSM9DS0XM_CTRL_REG5_XM 0x24 -#define LSM9DS0XM_CTRL_REG6_XM 0x25 -#define LSM9DS0XM_CTRL_REG7_XM 0x26 -#define LSM9DS0XM_STATUS_REG_A 0x27 -#define LSM9DS0XM_OUT_X_L_A 0x28 -#define LSM9DS0XM_OUT_X_H_A 0x29 -#define LSM9DS0XM_OUT_Y_L_A 0x2A -#define LSM9DS0XM_OUT_Y_H_A 0x2B -#define LSM9DS0XM_OUT_Z_L_A 0x2C -#define LSM9DS0XM_OUT_Z_H_A 0x2D -#define LSM9DS0XM_FIFO_CTRL_REG 0x2E -#define LSM9DS0XM_FIFO_SRC_REG 0x2F -#define LSM9DS0XM_INT_GEN_1_REG 0x30 -#define LSM9DS0XM_INT_GEN_1_SRC 0x31 -#define LSM9DS0XM_INT_GEN_1_THS 0x32 -#define LSM9DS0XM_INT_GEN_1_DURATION 0x33 -#define LSM9DS0XM_INT_GEN_2_REG 0x34 -#define LSM9DS0XM_INT_GEN_2_SRC 0x35 -#define LSM9DS0XM_INT_GEN_2_THS 0x36 -#define LSM9DS0XM_INT_GEN_2_DURATION 0x37 -#define LSM9DS0XM_CLICK_CFG 0x38 -#define LSM9DS0XM_CLICK_SRC 0x39 -#define LSM9DS0XM_CLICK_THS 0x3A -#define LSM9DS0XM_TIME_LIMIT 0x3B -#define LSM9DS0XM_TIME_LATENCY 0x3C -#define LSM9DS0XM_TIME_WINDOW 0x3D -#define LSM9DS0XM_ACT_THS 0x3E -#define LSM9DS0XM_ACT_DUR 0x3F - - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 - -// Using the Teensy Mini Add-On board, LSM9DS0 SDOG = SDOXM = GND as designed -// Seven-bit LSM9DS0 device addresses are ACC = 0x1E, GYRO = 0x6A, MAG = 0x1E - -// Using the EM7180+LSM9DS0+MS5637 Teensy 3.1 Add-On shield, ADO is set to 0 -#define ADO 0 -#if ADO -#define LSM9DS0XM_ADDRESS 0x1D // Address of accel/magnetometer when ADO = 1 -#define LSM9DS0G_ADDRESS 0x6B // Address of gyro when ADO = 1 -#else -#define LSM9DS0XM_ADDRESS 0x1E // Address of accel/magnetometer when ADO = 0 -#define LSM9DS0G_ADDRESS 0x6A // Address of gyro when ADO = 0 -#endif -#define MS5637_ADDRESS 0x76 // Address of MS5637 altimeter -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page - -#define SerialDebug true // set to true to get Serial output for debugging - -// Set initial input parameters -enum Ascale { // set of allowable accel full scale settings - AFS_2G = 0, - AFS_4G, - AFS_6G, - AFS_8G, - AFS_16G -}; - -enum Aodr { // set of allowable gyro sample rates - AODR_PowerDown = 0, - AODR_3_125Hz, - AODR_6_25Hz, - AODR_12_5Hz, - AODR_25Hz, - AODR_50Hz, - AODR_100Hz, - AODR_200Hz, - AODR_400Hz, - AODR_800Hz, - AODR_1600Hz -}; - -enum Abw { // set of allowable accewl bandwidths - ABW_773Hz = 0, - ABW_194Hz, - ABW_362Hz, - ABW_50Hz -}; - -enum Gscale { // set of allowable gyro full scale settings - GFS_245DPS = 0, - GFS_500DPS, - GFS_NoOp, - GFS_2000DPS -}; - -enum Godr { // set of allowable gyro sample rates - GODR_95Hz = 0, - GODR_190Hz, - GODR_380Hz, - GODR_760Hz -}; - -enum Gbw { // set of allowable gyro data bandwidths - GBW_low = 0, // 12.5 Hz at Godr = 95 Hz, 12.5 Hz at Godr = 190 Hz, 30 Hz at Godr = 760 Hz - GBW_med, // 25 Hz at Godr = 95 Hz, 25 Hz at Godr = 190 Hz, 35 Hz at Godr = 760 Hz - GBW_high, // 25 Hz at Godr = 95 Hz, 50 Hz at Godr = 190 Hz, 50 Hz at Godr = 760 Hz - GBW_highest // 25 Hz at Godr = 95 Hz, 70 Hz at Godr = 190 Hz, 100 Hz at Godr = 760 Hz -}; - -enum Mscale { // set of allowable mag full scale settings - MFS_2G = 0, - MFS_4G, - MFS_8G, - MFS_12G -}; - -enum Mres { - MRES_LowResolution = 0, - MRES_NoOp, - MRES_HighResolution -}; - -enum Modr { // set of allowable mag sample rates - MODR_3_125Hz = 0, - MODR_6_25Hz, - MODR_12_5Hz, - MODR_25Hz, - MODR_50Hz, - MODR_100Hz -}; - -// MS5637 pressure sensor sample rates -#define ADC_256 0x00 // define pressure and temperature conversion rates -#define ADC_512 0x02 -#define ADC_1024 0x04 -#define ADC_2048 0x06 -#define ADC_4096 0x08 -#define ADC_8192 0x0A -#define ADC_D1 0x40 -#define ADC_D2 0x50 - -// Specify sensor full scale -uint8_t OSR = ADC_8192; // set pressure amd temperature oversample rate -uint8_t Gscale = GFS_245DPS; // gyro full scale -uint8_t Godr = GODR_190Hz; // gyro data sample rate -uint8_t Gbw = GBW_low; // gyro data bandwidth -uint8_t Ascale = AFS_2G; // accel full scale -uint8_t Aodr = AODR_200Hz; // accel data sample rate -uint8_t Abw = ABW_50Hz; // accel data bandwidth -uint8_t Mscale = MFS_12G; // mag full scale -uint8_t Modr = MODR_6_25Hz; // mag data sample rate -uint8_t Mres = MRES_LowResolution; // magnetometer operation mode -float aRes, gRes, mRes; // scale resolutions per LSB for the sensors - -// Pin definitions -int myLed = 13; // LED on the Teensy 3.1 - -// MS5637 variables -uint16_t Pcal[8]; // calibration constants from MS5637 PROM registers -unsigned char nCRC; // calculated check sum to ensure PROM integrity -uint32_t D1 = 0, D2 = 0; // raw MS5637 pressure and temperature data -double dT, OFFSET, SENS, T2, OFFSET2, SENS2; // First order and second order corrections for raw S5637 temperature and pressure data -double Temperature, Pressure; // stores MS5637 pressures sensor pressure and temperature - -// LSM9DS0 variables -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output -float Quat[4] = {0, 0, 0, 0}; // quaternion data register -float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag -int16_t tempCount; // temperature raw count output -float temperature; // Stores the BMX055 internal chip temperature in degrees Celsius -float SelfTest[6]; // holds results of gyro and accelerometer self test - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Ki 0.0f - -uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval - -float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -bool passThru = true; - -void setup() -{ -// Wire.begin(); -// TWBR = 12; // 400 kbit/sec I2C speed for Pro Mini - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(5000); - Serial.begin(38400); - - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - I2Cscan(); // should detect SENtral at 0x28 - - // 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"); - - 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!"); - delay(1000); // give some time to read the screen - - // Set up the SENtral as sensor bus in normal operating mode -if(!passThru) { -// 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 -// Set accel/gyro/mage desired ODR rates -writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 95 Hz -writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x19); // 25 Hz -writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x0A); // 100/10 Hz -writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x13); // 190/10 Hz -// Configure operating mode -writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // read scale sensor data -// Enable interrupt to host upon certain events -// choose interrupts when 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); - -// 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 == 0x00) Serial.println("All sensors OK!"); - if(sensorStatus & 0x01) Serial.println("Magnetometer not acknowledging!"); - if(sensorStatus & 0x02) Serial.println("Accelerometer not acknowledging!"); - if(sensorStatus & 0x04) Serial.println("Gyro not acknowledging!"); - if(sensorStatus & 0x10) Serial.println("Magnetometer ID not recognized!"); - if(sensorStatus & 0x20) Serial.println("Accelerometer ID not recognized!"); - if(sensorStatus & 0x40) Serial.println("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"); - - delay(1000); // give some time to read the screen - - } - - // If pass through mode desired, set it up here - if(passThru) { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - -// Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - display.begin(); // Initialize the display - display.setContrast(58); // Set the contrast - -// Start device display with ID of sensor - display.clearDisplay(); - display.setTextSize(2); - display.setCursor(0,0); display.print("LSM9DS0"); - display.setTextSize(1); - display.setCursor(0, 20); display.print("9-DOF 16-bit"); - display.setCursor(0, 30); display.print("motion sensor"); - display.setCursor(20,40); display.print("60 ug LSB"); - display.display(); - delay(1000); - -// Set up for data display - display.setTextSize(1); // Set text size to normal, 2 is twice normal etc. - display.setTextColor(BLACK); // Set pixel color; 1 on the monochrome screen - display.clearDisplay(); // clears the screen and buffer - - // Read the WHO_AM_I registers, this is a good test of communication - Serial.println("LSM9DS0 9-axis motion sensor..."); - byte c = readByte(LSM9DS0G_ADDRESS, LSM9DS0G_WHO_AM_I_G); // Read WHO_AM_I register for LSM9DS0 gyro - Serial.println("LSM9DS0 gyro"); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0xD4, HEX); - byte d = readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_WHO_AM_I_XM); // Read WHO_AM_I register for LSM9DS0 accel/magnetometer - Serial.println("LSM9DS0 accel/magnetometer"); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x49, HEX); - - - if (c == 0xD4 && d == 0x49) // WHO_AM_I should always be 0xD4 for the gyro and 0x49 for the accel/mag - { - Serial.println("LSM9DS0 is online..."); - - initLSM9DS0(); - Serial.println("LSM9DS0 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - getMres(); - Serial.print("accel sensitivity is "); Serial.print(1./(1000.*aRes)); Serial.println(" LSB/mg"); - Serial.print("gyro sensitivity is "); Serial.print(1./(1000.*gRes)); Serial.println(" LSB/mdps"); - Serial.print("mag sensitivity is "); Serial.print(1./(1000.*mRes)); Serial.println(" LSB/mGauss"); - - accelgyrocalLSM9DS0(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - magcalLSM9DS0(magBias); - Serial.println("mag biases (mG)"); Serial.println(1000.*magBias[0]); Serial.println(1000.*magBias[1]); Serial.println(1000.*magBias[2]); - - /* display.clearDisplay(); - - display.setCursor(0, 0); display.print("LSM9DS0bias"); - display.setCursor(0, 8); display.print(" x y z "); - - display.setCursor(0, 16); display.print((int)(1000*accelBias[0])); - display.setCursor(24, 16); display.print((int)(1000*accelBias[1])); - display.setCursor(48, 16); display.print((int)(1000*accelBias[2])); - display.setCursor(72, 16); display.print("mg"); - - display.setCursor(0, 24); display.print(gyroBias[0], 1); - display.setCursor(24, 24); display.print(gyroBias[1], 1); - display.setCursor(48, 24); display.print(gyroBias[2], 1); - display.setCursor(66, 24); display.print("o/s"); - - display.display(); - delay(1000); - */ - - - // Reset the MS5637 pressure sensor - MS5637Reset(); - delay(100); - Serial.println("MS5637 pressure sensor reset..."); - // Read PROM data from MS5637 pressure sensor - MS5637PromRead(Pcal); - Serial.println("PROM data read:"); - Serial.print("C0 = "); Serial.println(Pcal[0]); - unsigned char refCRC = Pcal[0] >> 12; - Serial.print("C1 = "); Serial.println(Pcal[1]); - Serial.print("C2 = "); Serial.println(Pcal[2]); - Serial.print("C3 = "); Serial.println(Pcal[3]); - Serial.print("C4 = "); Serial.println(Pcal[4]); - Serial.print("C5 = "); Serial.println(Pcal[5]); - Serial.print("C6 = "); Serial.println(Pcal[6]); - - nCRC = MS5637checkCRC(Pcal); //calculate checksum to ensure integrity of MS5637 calibration data - Serial.print("Checksum = "); Serial.print(nCRC); Serial.print(" , should be "); Serial.println(refCRC); - - display.clearDisplay(); - display.setCursor(20,0); display.print("MS5637"); - display.setCursor(0,10); display.print("CRC is "); display.setCursor(50,10); display.print(nCRC); - display.setCursor(0,20); display.print("Should be "); display.setCursor(50,30); display.print(refCRC); - display.display(); - delay(1000); - } - else - { - Serial.print("Could not connect to BMX055: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } -} -} - - -void loop() -{ - if(!passThru) { - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - if(eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if(errorStatus & 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus & 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus & 0x14) Serial.print("Gyro failure!"); - if(errorStatus & 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus & 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus & 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus & 0x30) Serial.print("Math error!"); - if(errorStatus & 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if(eventStatus & 0x10) { // new acceleration data available - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) { // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus & 0x08) { // new mag data available - readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - mx = (float)magCount[0]*0.305176; // get actual G value - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) { // new quaternion data available - readSENtralQuatData(Quat); - } - } - - - - if(passThru) { - if (readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_STATUS_REG_A) & 0x08) { // check if new accel data is ready - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes - accelBias[1]; - az = (float)accelCount[2]*aRes - accelBias[2]; - } - - if (readByte(LSM9DS0G_ADDRESS, LSM9DS0G_STATUS_REG_G) & 0x08) { // check if new gyro data is ready - readGyroData(gyroCount); // Read the x/y/z adc values - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes - gyroBias[1]; - gz = (float)gyroCount[2]*gRes - gyroBias[2]; - } - - if (readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_STATUS_REG_M) & 0x08) { // check if new mag data is ready - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - // Include factory calibration per data sheet and user environmental corrections - mx = (float)magCount[0]*mRes - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes - magBias[1]; - mz = (float)magCount[2]*mRes - magBias[2]; - } - } - - - // keep track of rates - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer is aligned with the -y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ up) is aligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // For the BMX-055, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like - // in the MPU9250 sensor. This rotation can be modified to allow any convenient orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); -// if(passThru)MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - if (delt_t > 500) { // update LCD once per half-second independent of read rate - - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - if(!passThru) { - Serial.print("mx = "); Serial.print( mx); - Serial.print(" my = "); Serial.print( my); - Serial.print(" mz = "); Serial.print( mz); Serial.println(" mG"); - } - else { - Serial.print("mx = "); Serial.print( (int)1000*mx); - Serial.print(" my = "); Serial.print( (int)1000*my); - Serial.print(" mz = "); Serial.print( (int)1000*mz); Serial.println(" mG"); - } - - - Serial.println("Software quaternions:"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Quat[3]); - Serial.print(" Qx = "); Serial.print(Quat[0]); - Serial.print(" Qy = "); Serial.print(Quat[1]); - Serial.print(" Qz = "); Serial.println(Quat[2]); - } - - -// tempCount = readTempData(); // Read the gyro adc values -// temperature = ((float) tempCount/8. + 25.0); // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade -// Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - if(passThru) { - D1 = MS5637Read(ADC_D1, OSR); // get raw pressure value - D2 = MS5637Read(ADC_D2, OSR); // get raw temperature value - dT = D2 - Pcal[5]*pow(2,8); // calculate temperature difference from reference - OFFSET = Pcal[2]*pow(2, 17) + dT*Pcal[4]/pow(2,6); - SENS = Pcal[1]*pow(2,16) + dT*Pcal[3]/pow(2,7); - - Temperature = (2000 + (dT*Pcal[6])/pow(2, 23))/100; // First-order Temperature in degrees Centigrade -// -// Second order corrections - if(Temperature > 20) - { - T2 = 5*dT*dT/pow(2, 38); // correction for high temperatures - OFFSET2 = 0; - SENS2 = 0; - } - if(Temperature < 20) // correction for low temperature - { - T2 = 3*dT*dT/pow(2, 33); - OFFSET2 = 61*(100*Temperature - 2000)*(100*Temperature - 2000)/16; - SENS2 = 29*(100*Temperature - 2000)*(100*Temperature - 2000)/16; - } - if(Temperature < -15) // correction for very low temperature - { - OFFSET2 = OFFSET2 + 17*(100*Temperature + 1500)*(100*Temperature + 1500); - SENS2 = SENS2 + 9*(100*Temperature + 1500)*(100*Temperature + 1500); - } - // End of second order corrections - // - Temperature = Temperature - T2/100; - OFFSET = OFFSET - OFFSET2; - SENS = SENS - SENS2; - - Pressure = (((D1*SENS)/pow(2, 21) - OFFSET)/pow(2, 15))/100; // Pressure in mbar or kPa - - float altitude = 145366.45*(1. - pow((Pressure/1013.25), 0.190284)); - - if(SerialDebug) { - Serial.print("Digital temperature value = "); Serial.print( (float)Temperature, 2); Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Digital temperature value = "); Serial.print(9.*(float) Temperature/5. + 32., 2); Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Digital pressure value = "); Serial.print((float) Pressure, 2); Serial.println(" mbar");// pressure in millibar - Serial.print("Altitude = "); Serial.print(altitude, 2); Serial.println(" feet"); - } - } - - - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - roll *= 180.0f / PI; - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 260) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - // - - if(SerialDebug) { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - /* - display.clearDisplay(); - - display.setCursor(0, 0); display.print(" x y z "); - - display.setCursor(0, 8); display.print((int)(1000*ax)); - display.setCursor(24, 8); display.print((int)(1000*ay)); - display.setCursor(48, 8); display.print((int)(1000*az)); - display.setCursor(72, 8); display.print("mg"); - - // tempCount = readACCTempData(); // Read the gyro adc values - // temperature = ((float) tempCount) / 2.0 + 23.0; // Gyro chip temperature in degrees Centigrade - // display.setCursor(64, 0); display.print(9.*temperature/5. + 32., 0); display.print("F"); - - display.setCursor(0, 16); display.print((int)(gx)); - display.setCursor(24, 16); display.print((int)(gy)); - display.setCursor(48, 16); display.print((int)(gz)); - display.setCursor(66, 16); display.print("o/s"); - - display.setCursor(0, 24); display.print((int)(mx)); - display.setCursor(24, 24); display.print((int)(my)); - display.setCursor(48, 24); display.print((int)(mz)); - display.setCursor(72, 24); display.print("mG"); - - display.setCursor(0, 32); display.print((int)(yaw)); - display.setCursor(24, 32); display.print((int)(pitch)); - display.setCursor(48, 32); display.print((int)(roll)); - display.setCursor(66, 32); display.print("ypr"); - - -// display.setCursor(0, 40); display.print(altitude, 0); display.print("ft"); -// display.setCursor(68, 0); display.print(9.*Temperature/5. + 32., 0); - display.setCursor(42, 40); display.print((float) sumCount / (1000.*sum), 2); display.print("kHz"); - display.display(); -*/ - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } - -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== -void getMres() { - switch (Mscale) - { - // Possible magnetometer scales (and their register bit settings) are: - // 2 Gauss (00), 4 Gauss (01), 8 Gauss (10) and 12 Gauss (11) - case MFS_2G: - mRes = 2.0/32768.0; - break; - case MFS_4G: - mRes = 4.0/32768.0; - break; - case MFS_8G: - mRes = 8.0/32768.0; - break; - case MFS_12G: - mRes = 12.0/32768.0; - break; - } -} - -void getGres() { - switch (Gscale) - { - // Possible gyro scales (and their register bit settings) are: - // 245 DPS (00), 500 DPS (01), and 2000 DPS (11). - case GFS_245DPS: - gRes = 245.0/32768.0; - break; - case GFS_500DPS: - gRes = 500.0/32768.0; - break; - case GFS_2000DPS: - gRes = 2000.0/32768.0; - break; - } -} - -void getAres() { - switch (Ascale) - { - // Possible accelerometer scales (and their register bit settings) are: - // 2 Gs (000), 4 Gs (001), 6 gs (010), 8 Gs (011), and 16 gs (100). - case AFS_2G: - aRes = 2.0/32768.0; - break; - case AFS_4G: - aRes = 4.0/32768.0; - break; - case AFS_6G: - aRes = 6.0/32768.0; - break; - case AFS_8G: - aRes = 8.0/32768.0; - break; - case AFS_16G: - aRes = 16.0/32768.0; - break; - } -} - - -void readAccelData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z accel register data stored here - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_X_L_A, 6, &rawData[0]); // Read the six raw data registers into data array - 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] ; - destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; -} - - -void readGyroData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z gyro register data stored here - readBytes(LSM9DS0G_ADDRESS, 0x80 | LSM9DS0G_OUT_X_L_G, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - 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] ; - destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; -} - -void readMagData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z gyro register data stored here - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_X_L_M, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - 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 readTempData() -{ - uint8_t rawData[2]; // x/y/z gyro register data stored here - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_TEMP_L_XM, 2, &rawData[0]); // Read the two raw data registers sequentially into data array - return (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a 16-bit signed value -} - - -void initLSM9DS0() -{ - // configure the gyroscope, enable normal mode = power on - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG1_G, Godr << 6 | Gbw << 4 | 0x0F); - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG4_G, Gscale << 4 | 0x80); // enable bloack data update - // configure the accelerometer-specify ODR (sample rate) selection with Aodr, enable block data update - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG1_XM, Aodr << 4 | 0x0F); - // configure the accelerometer-specify bandwidth and full-scale selection with Abw, Ascale - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG2_XM, Abw << 6 | Ascale << 3); - // enable temperature sensor, set magnetometer ODR (sample rate) and resolution mode - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG5_XM, 0x80 | Mres << 5 | Modr << 2); - // set magnetometer full scale - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG6_XM, Mscale << 5 & 0x60); - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG7_XM, 0x00); // select continuous conversion mode - } - - -// 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 accelgyrocalLSM9DS0(float * dest1, float * dest2) -{ - uint8_t data[6] = {0, 0, 0, 0, 0, 0}; - int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; - uint16_t samples, ii; - - Serial.println("Calibrating gyro..."); - - // First get gyro bias - byte c = readByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG5_G); - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG5_G, c | 0x40); // Enable gyro FIFO - delay(400); // Wait for change to take effect - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_FIFO_CTRL_REG_G, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples - delay(2000); // delay 1000 milliseconds to collect FIFO samples - - samples = (readByte(LSM9DS0G_ADDRESS, LSM9DS0G_FIFO_SRC_REG_G) & 0x1F); // Read number of stored samples - - for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO - int16_t gyro_temp[3] = {0, 0, 0}; - readBytes(LSM9DS0G_ADDRESS, 0x80 | LSM9DS0G_OUT_X_L_G, 6, &data[0]); - gyro_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO - gyro_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]); - gyro_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]); - - gyro_bias[0] += (int32_t) gyro_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases - gyro_bias[1] += (int32_t) gyro_temp[1]; - gyro_bias[2] += (int32_t) gyro_temp[2]; - } - - gyro_bias[0] /= samples; // average the data - gyro_bias[1] /= samples; - gyro_bias[2] /= samples; - - dest1[0] = (float)gyro_bias[0]*gRes; // Properly scale the data to get deg/s - dest1[1] = (float)gyro_bias[1]*gRes; - dest1[2] = (float)gyro_bias[2]*gRes; - - c = readByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG5_G); - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_CTRL_REG5_G, c & ~0x40); //Disable gyro FIFO - delay(200); - writeByte(LSM9DS0G_ADDRESS, LSM9DS0G_FIFO_CTRL_REG_G, 0x00); // Enable gyro bypass mode - - Serial.println("Calibrating accel..."); - - // now get the accelerometer bias - c = readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG0_XM); - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG0_XM, c | 0x40); // Enable gyro FIFO - delay(200); // Wait for change to take effect - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_FIFO_CTRL_REG, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples - delay(1000); // delay 1000 milliseconds to collect FIFO samples - - samples = (readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_FIFO_SRC_REG) & 0x1F); // Read number of stored samples - - for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO - int16_t accel_temp[3] = {0, 0, 0}; - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_X_L_A, 6, &data[0]); - accel_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO - accel_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]); - accel_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]); - - 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]; - } - - accel_bias[0] /= samples; // average the data - accel_bias[1] /= samples; - accel_bias[2] /= samples; - - if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) (1.0/aRes);} // Remove gravity from the z-axis accelerometer bias calculation - else {accel_bias[2] += (int32_t) (1.0/aRes);} - - dest2[0] = (float)accel_bias[0]*aRes; // Properly scale the data to get g - dest2[1] = (float)accel_bias[1]*aRes; - dest2[2] = (float)accel_bias[2]*aRes; - - c = readByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG0_XM); - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_CTRL_REG0_XM, c & ~0x40); //Disable accel FIFO - delay(200); - writeByte(LSM9DS0XM_ADDRESS, LSM9DS0XM_FIFO_CTRL_REG, 0x00); // Enable accel bypass mode -} - -void magcalLSM9DS0(float * dest1) -{ - uint8_t data[6]; // data array to hold mag x, y, z, data - uint16_t ii = 0, sample_count = 0; - int32_t mag_bias[3] = {0, 0, 0}; - int16_t mag_max[3] = {0, 0, 0}, mag_min[3] = {0, 0, 0}; - - Serial.println("Mag Calibration: Wave device in a figure eight until done!"); - delay(4000); - - sample_count = 128; - for(ii = 0; ii < sample_count; ii++) { - int16_t mag_temp[3] = {0, 0, 0}; - readBytes(LSM9DS0XM_ADDRESS, 0x80 | LSM9DS0XM_OUT_X_L_M, 6, &data[0]); // Read the six raw data registers into data array - mag_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]) ; // Form signed 16-bit integer for each sample in FIFO - mag_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]) ; - mag_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]) ; - 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]; - } - delay(105); // at 10 Hz ODR, new mag data is available every 100 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]); - - 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; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes; - dest1[2] = (float) mag_bias[2]*mRes; - - /* //write biases to accelerometermagnetometer offset registers as counts); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_X_REG_L_M, (int16_t) mag_bias[0] & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_X_REG_H_M, ((int16_t)mag_bias[0] >> 8) & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_Y_REG_L_M, (int16_t) mag_bias[1] & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_Y_REG_H_M, ((int16_t)mag_bias[1] >> 8) & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_Z_REG_L_M, (int16_t) mag_bias[2] & 0xFF); - writeByte(LSM9DS0M_ADDRESS, LSM9DS0M_OFFSET_Z_REG_H_M, ((int16_t)mag_bias[2] >> 8) & 0xFF); - */ - Serial.println("Mag Calibration done!"); -} - -// I2C communication with the MS5637 is a little different from that with the LSM9DS0and most other sensors -// For the MS5637, we write commands, and the MS5637 sends data in response, rather than directly reading -// MS5637 registers - - void MS5637Reset() - { - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(MS5637_RESET); // Put reset command in Tx buffer - Wire.endTransmission(); // Send the Tx buffer - } - - void MS5637PromRead(uint16_t * destination) - { - uint8_t data[2] = {0,0}; - for (uint8_t ii = 0; ii <8; ii++) { - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(0xA0 | ii << 1); // Put PROM address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(MS5637_ADDRESS, 2); // Read two bytes from slave PROM address - while (Wire.available()) { - data[i++] = Wire.read(); } // Put read results in the Rx buffer - destination[ii] = (uint16_t) (((uint16_t) data[0] << 8) | data[1]); // construct PROM data for return to main program - } - } - - uint32_t MS5637Read(uint8_t CMD, uint8_t OSR) // temperature data read - { - uint8_t data[3] = {0,0,0}; - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(CMD | OSR); // Put pressure conversion command in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - - 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.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(0x00); // Put ADC read command in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(MS5637_ADDRESS, 3); // Read three bytes from slave PROM address - while (Wire.available()) { - data[i++] = Wire.read(); } // Put read results in the Rx buffer - 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 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); -} - - - -// I2C read/write functions for the LSM9DS0and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - - -float 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; -} - -void 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[0] = uint32_reg_to_float (&rawData[0]); - destination[1] = uint32_reg_to_float (&rawData[4]); - destination[2] = uint32_reg_to_float (&rawData[8]); - destination[3] = uint32_reg_to_float (&rawData[12]); - -} - -void 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 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 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]); -} - - -void SENtralPassThroughMode() -{ - // First put SENtral in standby mode - uint8_t c = readByte(EM7180_ADDRESS, EM7180_AlgorithmControl); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, c | 0x01); -// c = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); -// Serial.print("c = "); Serial.println(c); -// Verify standby status -// if(readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus) & 0x01) { - Serial.println("SENtral in standby mode"); - // Place SENtral in pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - if(readByte(EM7180_ADDRESS, EM7180_PassThruStatus) & 0x01) { - Serial.println("SENtral in pass-through mode"); - } - else { - Serial.println("ERROR! SENtral not in pass-through mode!"); - } - -// } -// else { Serial.println("ERROR! SENtral not in standby mode!"); -// } - - } - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - - void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - - void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - if(count > 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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"); -} - - diff --git a/EM7180_MPU6500_AK8963C_BMP280.ino b/EM7180_MPU6500_AK8963C_BMP280.ino deleted file mode 100644 index b8097fe..0000000 --- a/EM7180_MPU6500_AK8963C_BMP280.ino +++ /dev/null @@ -1,1779 +0,0 @@ -/* EM7180_MPU6500_AK8963C_BMP280_t3 Basic Example Code - by: Kris Winer - date: June 12, 2015 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the MPU6500 and AK8963C, and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DFC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the MPU6500+AK8963C 9-axis motion sensor (accel/gyro/mag) as slave, an BMP280 pressure/temperature sensor, and an M24512DFC - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral cannot use the pressure data in the sensor fusion - yet but there is a driver for the BMP280 in the SENtral firmware. However, like the MAX21100, the SENtral - can be toggled into a bypass mode where the pressure sensor (and EEPROM and MPU6500+AK8963C) may be read directly by the - Teensy 3.1 host micrcontroller. If the read rate is infrequent enough (2 Hz is sufficient since pressure and temperature - do not change very fast), then the sensor fusion rate is not significantly affected. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The MS5637 is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+MPU6500+AK8963C+BMP280+M24512DFC Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: All the sensors on this board are I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensors are not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ -//#include "Wire.h" -#include -#include - -// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in -// above document; the MPU6500 and MPU9250 are virtually identical but the latter has a different register map -// -//Magnetometer Registers -#define AK8963_ADDRESS 0x0C -#define WHO_AM_I_AK8963 0x00 // should return 0x48 -#define INFO 0x01 -#define AK8963_ST1 0x02 // data ready status bit 0 -#define AK8963_XOUT_L 0x03 // data -#define AK8963_XOUT_H 0x04 -#define AK8963_YOUT_L 0x05 -#define AK8963_YOUT_H 0x06 -#define AK8963_ZOUT_L 0x07 -#define AK8963_ZOUT_H 0x08 -#define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 -#define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 -#define AK8963_ASTC 0x0C // Self test control -#define AK8963_I2CDIS 0x0F // I2C disable -#define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value -#define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value -#define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value - -#define SELF_TEST_X_GYRO 0x00 -#define SELF_TEST_Y_GYRO 0x01 -#define SELF_TEST_Z_GYRO 0x02 -#define SELF_TEST_X_ACCEL 0x0D -#define SELF_TEST_Y_ACCEL 0x0E -#define SELF_TEST_Z_ACCEL 0x0F -#define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope -#define XG_OFFSET_L 0x14 -#define YG_OFFSET_H 0x15 -#define YG_OFFSET_L 0x16 -#define ZG_OFFSET_H 0x17 -#define ZG_OFFSET_L 0x18 -#define SMPLRT_DIV 0x19 -#define CONFIG 0x1A -#define GYRO_CONFIG 0x1B -#define ACCEL_CONFIG 0x1C -#define ACCEL_CONFIG2 0x1D -#define LP_ACCEL_ODR 0x1E -#define WOM_THR 0x1F -#define FIFO_EN 0x23 -#define I2C_MST_CTRL 0x24 -#define I2C_SLV0_ADDR 0x25 -#define I2C_SLV0_REG 0x26 -#define I2C_SLV0_CTRL 0x27 -#define I2C_SLV1_ADDR 0x28 -#define I2C_SLV1_REG 0x29 -#define I2C_SLV1_CTRL 0x2A -#define I2C_SLV2_ADDR 0x2B -#define I2C_SLV2_REG 0x2C -#define I2C_SLV2_CTRL 0x2D -#define I2C_SLV3_ADDR 0x2E -#define I2C_SLV3_REG 0x2F -#define I2C_SLV3_CTRL 0x30 -#define I2C_SLV4_ADDR 0x31 -#define I2C_SLV4_REG 0x32 -#define I2C_SLV4_DO 0x33 -#define I2C_SLV4_CTRL 0x34 -#define I2C_SLV4_DI 0x35 -#define I2C_MST_STATUS 0x36 -#define INT_PIN_CFG 0x37 -#define INT_ENABLE 0x38 -#define INT_STATUS 0x3A -#define ACCEL_XOUT_H 0x3B -#define ACCEL_XOUT_L 0x3C -#define ACCEL_YOUT_H 0x3D -#define ACCEL_YOUT_L 0x3E -#define ACCEL_ZOUT_H 0x3F -#define ACCEL_ZOUT_L 0x40 -#define TEMP_OUT_H 0x41 -#define TEMP_OUT_L 0x42 -#define GYRO_XOUT_H 0x43 -#define GYRO_XOUT_L 0x44 -#define GYRO_YOUT_H 0x45 -#define GYRO_YOUT_L 0x46 -#define GYRO_ZOUT_H 0x47 -#define GYRO_ZOUT_L 0x48 -#define EXT_SENS_DATA_00 0x49 -#define EXT_SENS_DATA_01 0x4A -#define EXT_SENS_DATA_02 0x4B -#define EXT_SENS_DATA_03 0x4C -#define EXT_SENS_DATA_04 0x4D -#define EXT_SENS_DATA_05 0x4E -#define EXT_SENS_DATA_06 0x4F -#define EXT_SENS_DATA_07 0x50 -#define EXT_SENS_DATA_08 0x51 -#define EXT_SENS_DATA_09 0x52 -#define EXT_SENS_DATA_10 0x53 -#define EXT_SENS_DATA_11 0x54 -#define EXT_SENS_DATA_12 0x55 -#define EXT_SENS_DATA_13 0x56 -#define EXT_SENS_DATA_14 0x57 -#define EXT_SENS_DATA_15 0x58 -#define EXT_SENS_DATA_16 0x59 -#define EXT_SENS_DATA_17 0x5A -#define EXT_SENS_DATA_18 0x5B -#define EXT_SENS_DATA_19 0x5C -#define EXT_SENS_DATA_20 0x5D -#define EXT_SENS_DATA_21 0x5E -#define EXT_SENS_DATA_22 0x5F -#define EXT_SENS_DATA_23 0x60 -#define MOT_DETECT_STATUS 0x61 -#define I2C_SLV0_DO 0x63 -#define I2C_SLV1_DO 0x64 -#define I2C_SLV2_DO 0x65 -#define I2C_SLV3_DO 0x66 -#define I2C_MST_DELAY_CTRL 0x67 -#define SIGNAL_PATH_RESET 0x68 -#define ACCEL_DETECT_CTRL 0x69 -#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP -#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode -#define PWR_MGMT_2 0x6C -#define FIFO_COUNTH 0x72 -#define FIFO_COUNTL 0x73 -#define FIFO_R_W 0x74 -#define WHO_AM_I_MPU6500 0x75 // Should return 0x70 -#define XA_OFFSET_H 0x77 -#define XA_OFFSET_L 0x78 -#define YA_OFFSET_H 0x7A -#define YA_OFFSET_L 0x7B -#define ZA_OFFSET_H 0x7D -#define ZA_OFFSET_L 0x7E - -// BMP280 registers -#define BMP280_TEMP_XLSB 0xFC -#define BMP280_TEMP_LSB 0xFB -#define BMP280_TEMP_MSB 0xFA -#define BMP280_PRESS_XLSB 0xF9 -#define BMP280_PRESS_LSB 0xF8 -#define BMP280_PRESS_MSB 0xF7 -#define BMP280_CONFIG 0xF5 -#define BMP280_CTRL_MEAS 0xF4 -#define BMP280_STATUS 0xF3 -#define BMP280_RESET 0xE0 -#define BMP280_ID 0xD0 // should be 0x58 -#define BMP280_CALIB00 0x88 - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 - -// Using the Teensy Mini Add-On board, BMX055 SDO1 = SDO2 = CSB3 = GND as designed -// Seven-bit BMX055 device addresses are ACC = 0x18, GYRO = 0x68, MAG = 0x10 -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page -#define MPU6500_ADDRESS 0x68 // Device address when ADO = 0 -#define AK8963_ADDRESS 0x0C // Address of magnetometer -#define BMP280_ADDRESS 0x76 // Address of altimeter - -#define SerialDebug true // set to true to get Serial output for debugging - -// Set initial input parameters -enum Ascale { - AFS_2G = 0, - AFS_4G, - AFS_8G, - AFS_16G -}; - -enum Gscale { - GFS_250DPS = 0, - GFS_500DPS, - GFS_1000DPS, - GFS_2000DPS -}; - -enum Mscale { - MFS_14BITS = 0, // 0.6 mG per LSB - MFS_16BITS // 0.15 mG per LSB -}; - -enum Posr { - P_OSR_00 = 0, // no op - P_OSR_01, - P_OSR_02, - P_OSR_04, - P_OSR_08, - P_OSR_16 -}; - -enum Tosr { - T_OSR_00 = 0, // no op - T_OSR_01, - T_OSR_02, - T_OSR_04, - T_OSR_08, - T_OSR_16 -}; - -enum IIRFilter { - full = 0, // bandwidth at full sample rate - BW0_223ODR, - BW0_092ODR, - BW0_042ODR, - BW0_021ODR // bandwidth at 0.021 x sample rate -}; - -enum Mode { - BMP280Sleep = 0, - forced, - forced2, - normal -}; - -enum SBy { - t_00_5ms = 0, - t_62_5ms, - t_125ms, - t_250ms, - t_500ms, - t_1000ms, - t_2000ms, - t_4000ms, -}; - -// Specify BMP280 configuration -uint8_t Posr = P_OSR_16, Tosr = T_OSR_02, Mode = normal, IIRFilter = BW0_042ODR, SBy = t_62_5ms; // set pressure amd temperature output data rate -// t_fine carries fine temperature as global value for BMP280 -int32_t t_fine; -// -// Specify sensor full scale -uint8_t Gscale = GFS_250DPS; -uint8_t Ascale = AFS_2G; -uint8_t Mscale = MFS_16BITS; // Choose either 14-bit or 16-bit magnetometer resolution -uint8_t Mmode = 0x02; // 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read -float aRes, gRes, mRes; // scale resolutions per LSB for the sensors - -// Pin definitions -int myLed = 13; // LED on the Teensy 3.1 - -// BMP280 definitions -double Temperature, Pressure; // stores BMP280 pressures sensor pressure and temperature -int32_t rawPress, rawTemp; // pressure and temperature raw count output for BMP280 - -// BMX055 variables -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output -float Quat[4] = {0, 0, 0, 0}; // quaternion data register -float magCalibration[3] = {0, 0, 0}; // Factory mag calibration and mag bias -float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag -int16_t tempCount; // temperature raw count output -float temperature; // Stores the BMX055 internal chip temperature in degrees Celsius -float SelfTest[6]; // holds results of gyro and accelerometer self test - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Ki 0.0f - -uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval -uint8_t param[4]; // used for param transfer -uint16_t EM7180_mag_fs, EM7180_acc_fs, EM7180_gyro_fs; // EM7180 sensor full scale ranges - -float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -// BMP280 compensation parameters -uint16_t dig_T1, dig_P1; -int16_t dig_T2, dig_T3, dig_P2, dig_P3, dig_P4, dig_P5, dig_P6, dig_P7, dig_P8, dig_P9; - -bool passThru = false; - -; - -void setup() -{ -// Wire.begin(); -// TWBR = 12; // 400 kbit/sec I2C speed for Pro Mini - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(5000); - Serial.begin(38400); - - I2Cscan(); // should detect SENtral at 0x28 - - // 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"); - - 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!"); - delay(1000); // give some time to read the screen - - // Set up the SENtral as sensor bus in normal operating mode -if(!passThru) { -// 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 -// Set accel/gyro/mage desired ODR rates -writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 100 Hz -writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x1E); // 30 Hz -writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x0A); // 100/10 Hz -writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x14); // 200/10 Hz - -// Configure operating mode -writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // read scale sensor data - -// Enable interrupt to host upon certain events -// choose interrupts when 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 - EM7180_set_integer_param (0x49, 0x00); - - //Write desired sensor full scale ranges to the EM7180 - EM7180_set_mag_acc_FS (0x3E8, 0x08); // 1000 uT, 8 g - EM7180_set_gyro_FS (0x7D0); // 2000 dps - - // 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.println("Magnetometer not acknowledging!"); - if(sensorStatus & 0x02) Serial.println("Accelerometer not acknowledging!"); - if(sensorStatus & 0x04) Serial.println("Gyro not acknowledging!"); - if(sensorStatus & 0x10) Serial.println("Magnetometer ID not recognized!"); - if(sensorStatus & 0x20) Serial.println("Accelerometer ID not recognized!"); - if(sensorStatus & 0x40) Serial.println("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"); - - delay(1000); // give some time to read the screen - - } - - // If pass through mode desired, set it up here - if(passThru) { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - -// Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - // Read the WHO_AM_I register, this is a good test of communication - Serial.println("MPU6500 9-axis motion sensor..."); - byte c = readByte(MPU6500_ADDRESS, WHO_AM_I_MPU6500); // Read WHO_AM_I register for MPU-9250 - Serial.print("MPU6500 "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x70, HEX); - writeByte(MPU6500_ADDRESS, INT_PIN_CFG, 0x22); - - delay(1000); - - // Read the WHO_AM_I register of the magnetometer, this is a good test of communication - byte d = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for AK8963 - Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x48, HEX); - - delay(1000); - - // Read the WHO_AM_I register of the BMP280 this is a good test of communication - byte f = readByte(BMP280_ADDRESS, BMP280_ID); // Read WHO_AM_I register for BMP280 - Serial.print("BMP280 "); - Serial.print("I AM "); - Serial.print(f, HEX); - Serial.print(" I should be "); - Serial.println(0x58, HEX); - Serial.println(" "); - - if ((c == 0x70) && (d == 0x48) && f == 0x58 ) // WHO_AM_I should always be ACC/GYRO = 0x68, MAG = 0x48, ALTIMETER = 0x58 - { - Serial.println("MPU6500+AK8963C+BMP280 are online..."); - - delay(1000); - - MPU6500SelfTest(SelfTest); // Start by performing self test and reporting values - Serial.print("x-axis self test: acceleration trim within : "); Serial.print(SelfTest[0],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: acceleration trim within : "); Serial.print(SelfTest[1],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: acceleration trim within : "); Serial.print(SelfTest[2],1); Serial.println("% of factory value"); - Serial.print("x-axis self test: gyration trim within : "); Serial.print(SelfTest[3],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: gyration trim within : "); Serial.print(SelfTest[4],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: gyration trim within : "); Serial.print(SelfTest[5],1); Serial.println("% of factory value"); - delay(1000); - - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - getMres(); - - delay(1000); - - Serial.println(" Calibrate gyro and accel"); - accelgyrocalMPU6500(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - initMPU6500(); - Serial.println("MPU9250 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - - - // Get magnetometer calibration from AK8963 ROM - initAK8963(magCalibration); Serial.println("AK8963 initialized for active data mode...."); // Initialize device for active mode read of magnetometer - if(SerialDebug) { -// Serial.println("Calibration values: "); - Serial.print("X-Axis sensitivity adjustment value "); Serial.println(magCalibration[0], 2); - Serial.print("Y-Axis sensitivity adjustment value "); Serial.println(magCalibration[1], 2); - Serial.print("Z-Axis sensitivity adjustment value "); Serial.println(magCalibration[2], 2); - } - - magcalMPU6500(magBias); - Serial.println("mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]); - delay(2000); // add delay to see results before serial spew of data - - - writeByte(BMP280_ADDRESS, BMP280_RESET, 0xB6); // reset BMP280 before initilization - delay(100); - - BMP280Init(); // Initialize BMP280 altimeter - Serial.println("Calibration coeficients:"); - Serial.print("dig_T1 ="); - Serial.println(dig_T1); - Serial.print("dig_T2 ="); - Serial.println(dig_T2); - Serial.print("dig_T3 ="); - Serial.println(dig_T3); - Serial.print("dig_P1 ="); - Serial.println(dig_P1); - Serial.print("dig_P2 ="); - Serial.println(dig_P2); - Serial.print("dig_P3 ="); - Serial.println(dig_P3); - Serial.print("dig_P4 ="); - Serial.println(dig_P4); - Serial.print("dig_P5 ="); - Serial.println(dig_P5); - Serial.print("dig_P6 ="); - Serial.println(dig_P6); - Serial.print("dig_P7 ="); - Serial.println(dig_P7); - Serial.print("dig_P8 ="); - Serial.println(dig_P8); - Serial.print("dig_P9 ="); - Serial.println(dig_P9); - - - } - else - { - Serial.print("Could not connect to MPU6500: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } -} -} - - -void loop() -{ - if(!passThru) { - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - if(eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); -if(errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus == 0x14) Serial.print("Gyro failure!"); - if(errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus == 0x30) Serial.print("Math error!"); - if(errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if(eventStatus & 0x10) { // new acceleration data available - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) { // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus & 0x08) { // new mag data available - readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - mx = (float)magCount[0]*0.305176; // get actual G value - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) { // new quaternion data available - readSENtralQuatData(Quat); - } - } - - if(passThru) { - // If intPin goes high, all data registers have new data -// if (digitalRead(intACC2)) { // On interrupt, read data - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*aRes; // + accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes; // + accelBias[1]; - az = (float)accelCount[2]*aRes; // + accelBias[2]; - // } -// if (digitalRead(intGYRO2)) { // On interrupt, read data - readGyroData(gyroCount); // Read the x/y/z adc values - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes; - gz = (float)gyroCount[2]*gRes; - // } -// if (digitalRead(intDRDYM)) { // On interrupt, read data - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - // Temperature-compensated magnetic field is in 16 LSB/microTesla - mx = (float)magCount[0]*mRes*magCalibration[0] - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes*magCalibration[1] - magBias[1]; - mz = (float)magCount[2]*mRes*magCalibration[2] - magBias[2]; - // } - } - - - // keep track of rates - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - // Check to make sure the EM7180 is running properly - // 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"); - - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer is aligned with the -y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ up) is aligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // For the BMX-055, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like - // in the MPU6500 sensor. This rotation can be modified to allow any convenient orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); -// if(passThru)MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, mx, mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - if (delt_t > 500) { // update LCD once per half-second independent of read rate - - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print( (int)mx); - Serial.print(" my = "); Serial.print( (int)my); - Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG"); - - Serial.println("Software quaternions:"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Quat[0]); - Serial.print(" Qx = "); Serial.print(Quat[1]); - Serial.print(" Qy = "); Serial.print(Quat[2]); - Serial.print(" Qz = "); Serial.println(Quat[3]); - } - - -// tempCount = readTempData(); // Read the gyro adc values -// temperature = ((float) tempCount) / 333.87 + 21.0; // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade -// Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - if(passThru) { - rawPress = readBMP280Pressure(); - Pressure = (float) bmp280_compensate_P(rawPress)/25600.; // Pressure in mbar - rawTemp = readBMP280Temperature(); - Temperature = (float) bmp280_compensate_T(rawTemp)/100.; - - float altitude = 145366.45f*(1.0f - pow((Pressure/1013.25f), 0.190284f)); - - if(SerialDebug) { - Serial.println("BMP280:"); - Serial.print("Altimeter temperature = "); - Serial.print( Temperature, 2); - Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); - Serial.print(9.*Temperature/5. + 32., 2); - Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); - Serial.print(Pressure, 2); - Serial.println(" mbar");// pressure in millibar - Serial.print("Altitude = "); - Serial.print(altitude, 2); - Serial.println(" feet"); - Serial.println(" "); - } - - } - - - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - roll *= 180.0f / PI; - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[1] * Quat[2] + Quat[0] * Quat[3]), Quat[0] * Quat[0] + Quat[1] * Quat[1] - Quat[2] * Quat[2] - Quat[3] * Quat[3]); - Pitch = -asin(2.0f * (Quat[1] * Quat[3] - Quat[0] * Quat[2])); - Roll = atan2(2.0f * (Quat[0] * Quat[1] + Quat[2] * Quat[3]), Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2] + Quat[3] * Quat[3]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 260) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - // - - if(SerialDebug) { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } - -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== - -float 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; -} - -void 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 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 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 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 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]); -} - -void getMres() { - 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.*4219./8190.; // Proper scale to return milliGauss - break; - case MFS_16BITS: - mRes = 10.*4219./32760.0; // Proper scale to return milliGauss - break; - } -} - -void getGres() { - 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; - break; - case GFS_500DPS: - gRes = 500.0/32768.0; - break; - case GFS_1000DPS: - gRes = 1000.0/32768.0; - break; - case GFS_2000DPS: - gRes = 2000.0/32768.0; - break; - } -} - -void getAres() { - 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; - break; - case AFS_4G: - aRes = 4.0/32768.0; - break; - case AFS_8G: - aRes = 8.0/32768.0; - break; - case AFS_16G: - aRes = 16.0/32768.0; - break; - } -} - - -void readAccelData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z accel register data stored here - readBytes(MPU6500_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 readGyroData(int16_t * destination) -{ - uint8_t rawData[6]; // x/y/z gyro register data stored here - readBytes(MPU6500_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 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 readTempData() -{ - uint8_t rawData[2]; // x/y/z gyro register data stored here - readBytes(MPU6500_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 initAK8963(float * destination) -{ - // 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.; - 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 initMPU6500() -{ - // wake up device - writeByte(MPU6500_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(MPU6500_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 MPU6500, it is possible to get gyro sample rates of 32 kHz (!), 8 kHz, or 1 kHz - writeByte(MPU6500_ADDRESS, CONFIG, 0x03); - - // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) - writeByte(MPU6500_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(MPU6500_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(MPU6500_ADDRESS, GYRO_CONFIG, c ); // Write new GYRO_CONFIG value to register - - // Set accelerometer full-scale range configuration - c = readByte(MPU6500_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(MPU6500_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(MPU6500_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(MPU6500_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(MPU6500_ADDRESS, INT_PIN_CFG, 0x22); - writeByte(MPU6500_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 accelgyrocalMPU6500(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(MPU6500_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(MPU6500_ADDRESS, PWR_MGMT_1, 0x01); - writeByte(MPU6500_ADDRESS, PWR_MGMT_2, 0x00); - delay(200); - -// Configure device for bias calculation - writeByte(MPU6500_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts - writeByte(MPU6500_ADDRESS, FIFO_EN, 0x00); // Disable FIFO - writeByte(MPU6500_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source - writeByte(MPU6500_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master - writeByte(MPU6500_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes - writeByte(MPU6500_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP - delay(15); - -// Configure MPU6050 gyro and accelerometer for bias calculation - writeByte(MPU6500_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz - writeByte(MPU6500_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz - writeByte(MPU6500_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity - writeByte(MPU6500_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(MPU6500_ADDRESS, USER_CTRL, 0x40); // Enable FIFO - writeByte(MPU6500_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(MPU6500_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO - readBytes(MPU6500_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(MPU6500_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(MPU6500_ADDRESS, XG_OFFSET_H, data[0]); - writeByte(MPU6500_ADDRESS, XG_OFFSET_L, data[1]); - writeByte(MPU6500_ADDRESS, YG_OFFSET_H, data[2]); - writeByte(MPU6500_ADDRESS, YG_OFFSET_L, data[3]); - writeByte(MPU6500_ADDRESS, ZG_OFFSET_H, data[4]); - writeByte(MPU6500_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(MPU6500_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(MPU6500_ADDRESS, YA_OFFSET_H, 2, &data[0]); - accel_bias_reg[1] = (int32_t) (((int16_t)data[0] << 8) | data[1]); - readBytes(MPU6500_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) & 0xFF; - data[1] = (accel_bias_reg[0]) & 0xFF; - 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) & 0xFF; - data[3] = (accel_bias_reg[1]) & 0xFF; - 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) & 0xFF; - data[5] = (accel_bias_reg[2]) & 0xFF; - 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(MPU6500_ADDRESS, XA_OFFSET_H, data[0]); - writeByte(MPU6500_ADDRESS, XA_OFFSET_L, data[1]); - writeByte(MPU6500_ADDRESS, YA_OFFSET_H, data[2]); - writeByte(MPU6500_ADDRESS, YA_OFFSET_L, data[3]); - writeByte(MPU6500_ADDRESS, ZA_OFFSET_H, data[4]); - writeByte(MPU6500_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 magcalMPU6500(float * dest1) -{ - uint16_t ii = 0, sample_count = 0; - int32_t mag_bias[3] = {0, 0, 0}; - int16_t mag_max[3] = {0, 0, 0}, mag_min[3] = {0, 0, 0}, mag_temp[3] = {0, 0, 0}; - - Serial.println("Mag Calibration: Wave device in a figure eight until done!"); - delay(4000); - - sample_count = 64; - 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]; - } - delay(135); // at 8 Hz ODR, new mag data is available every 125 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]); - - 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*magCalibration[0]; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1]; - dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2]; - - Serial.println("Mag Calibration done!"); -} - - - -// Accelerometer and gyroscope self test; check calibration wrt factory settings -void MPU6500SelfTest(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(MPU6500_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz - writeByte(MPU6500_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz - writeByte(MPU6500_ADDRESS, GYRO_CONFIG, 1< 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - -int32_t readBMP280Temperature() -{ - uint8_t rawData[3]; // 20-bit pressure register data stored here - readBytes(BMP280_ADDRESS, BMP280_TEMP_MSB, 3, &rawData[0]); - return (int32_t) (((int32_t) rawData[0] << 16 | (int32_t) rawData[1] << 8 | rawData[2]) >> 4); -} - -int32_t readBMP280Pressure() -{ - uint8_t rawData[3]; // 20-bit pressure register data stored here - readBytes(BMP280_ADDRESS, BMP280_PRESS_MSB, 3, &rawData[0]); - return (int32_t) (((int32_t) rawData[0] << 16 | (int32_t) rawData[1] << 8 | rawData[2]) >> 4); -} - -void BMP280Init() -{ - // Configure the BMP280 - // Set T and P oversampling rates and sensor mode - writeByte(BMP280_ADDRESS, BMP280_CTRL_MEAS, Tosr << 5 | Posr << 2 | Mode); - // Set standby time interval in normal mode and bandwidth - writeByte(BMP280_ADDRESS, BMP280_CONFIG, SBy << 5 | IIRFilter << 2); - // Read and store calibration data - uint8_t calib[24]; - readBytes(BMP280_ADDRESS, BMP280_CALIB00, 24, &calib[0]); - dig_T1 = (uint16_t)(((uint16_t) calib[1] << 8) | calib[0]); - dig_T2 = ( int16_t)((( int16_t) calib[3] << 8) | calib[2]); - dig_T3 = ( int16_t)((( int16_t) calib[5] << 8) | calib[4]); - dig_P1 = (uint16_t)(((uint16_t) calib[7] << 8) | calib[6]); - dig_P2 = ( int16_t)((( int16_t) calib[9] << 8) | calib[8]); - dig_P3 = ( int16_t)((( int16_t) calib[11] << 8) | calib[10]); - dig_P4 = ( int16_t)((( int16_t) calib[13] << 8) | calib[12]); - dig_P5 = ( int16_t)((( int16_t) calib[15] << 8) | calib[14]); - dig_P6 = ( int16_t)((( int16_t) calib[17] << 8) | calib[16]); - dig_P7 = ( int16_t)((( int16_t) calib[19] << 8) | calib[18]); - dig_P8 = ( int16_t)((( int16_t) calib[21] << 8) | calib[20]); - dig_P9 = ( int16_t)((( int16_t) calib[23] << 8) | calib[22]); -} - -// Returns temperature in DegC, resolution is 0.01 DegC. Output value of -// “5123” equals 51.23 DegC. -int32_t bmp280_compensate_T(int32_t adc_T) -{ - int32_t var1, var2, T; - var1 = ((((adc_T >> 3) - ((int32_t)dig_T1 << 1))) * ((int32_t)dig_T2)) >> 11; - var2 = (((((adc_T >> 4) - ((int32_t)dig_T1)) * ((adc_T >> 4) - ((int32_t)dig_T1))) >> 12) * ((int32_t)dig_T3)) >> 14; - t_fine = var1 + var2; - T = (t_fine * 5 + 128) >> 8; - return T; -} - -// Returns pressure in Pa as unsigned 32 bit integer in Q24.8 format (24 integer bits and 8 -//fractional bits). -//Output value of “24674867” represents 24674867/256 = 96386.2 Pa = 963.862 hPa -uint32_t bmp280_compensate_P(int32_t adc_P) -{ - long long var1, var2, p; - var1 = ((long long)t_fine) - 128000; - var2 = var1 * var1 * (long long)dig_P6; - var2 = var2 + ((var1*(long long)dig_P5)<<17); - var2 = var2 + (((long long)dig_P4)<<35); - var1 = ((var1 * var1 * (long long)dig_P3)>>8) + ((var1 * (long long)dig_P2)<<12); - var1 = (((((long long)1)<<47)+var1))*((long long)dig_P1)>>33; - if(var1 == 0) - { - return 0; - // avoid exception caused by division by zero - } - p = 1048576 - adc_P; - p = (((p<<31) - var2)*3125)/var1; - var1 = (((long long)dig_P9) * (p>>13) * (p>>13)) >> 25; - var2 = (((long long)dig_P8) * p)>> 19; - p = ((p + var1 + var2) >> 8) + (((long long)dig_P7)<<4); - return (uint32_t)p; -} - - - - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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 MPU6500 and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - -void 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 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 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 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 -} - diff --git a/EM7180_MPU9250_BMP280.ino b/EM7180_MPU9250_BMP280.ino deleted file mode 100644 index e35db5c..0000000 --- a/EM7180_MPU9250_BMP280.ino +++ /dev/null @@ -1,1872 +0,0 @@ -/* EM7180_MPU9250_BMP280_t3 Basic Example Code - by: Kris Winer - date: September 11, 2015 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the MPU9250 (with embedded MPU9250 + AK8963C), and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DRC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the MPU9250 9-axis motion sensor (accel/gyro/mag) as slave, a BMP280 pressure/temperature sensor, and an M24512DRC - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral can use the pressure data in the sensor fusion - yet and there is a driver for the BMP280 in the SENtral firmware. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The BMP280 is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+MPU9250+BMP280+M24512DRC Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: All the sensors n this board are I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensors are not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ -//#include "Wire.h" -#include -#include - -// BMP280 registers -#define BMP280_TEMP_XLSB 0xFC -#define BMP280_TEMP_LSB 0xFB -#define BMP280_TEMP_MSB 0xFA -#define BMP280_PRESS_XLSB 0xF9 -#define BMP280_PRESS_LSB 0xF8 -#define BMP280_PRESS_MSB 0xF7 -#define BMP280_CONFIG 0xF5 -#define BMP280_CTRL_MEAS 0xF4 -#define BMP280_STATUS 0xF3 -#define BMP280_RESET 0xE0 -#define BMP280_ID 0xD0 // should be 0x58 -#define BMP280_CALIB00 0x88 - -// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in -// above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map -// -//Magnetometer Registers -#define AK8963_ADDRESS 0x0C -#define WHO_AM_I_AK8963 0x00 // should return 0x48 -#define INFO 0x01 -#define AK8963_ST1 0x02 // data ready status bit 0 -#define AK8963_XOUT_L 0x03 // data -#define AK8963_XOUT_H 0x04 -#define AK8963_YOUT_L 0x05 -#define AK8963_YOUT_H 0x06 -#define AK8963_ZOUT_L 0x07 -#define AK8963_ZOUT_H 0x08 -#define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 -#define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 -#define AK8963_ASTC 0x0C // Self test control -#define AK8963_I2CDIS 0x0F // I2C disable -#define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value -#define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value -#define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value - -#define SELF_TEST_X_GYRO 0x00 -#define SELF_TEST_Y_GYRO 0x01 -#define SELF_TEST_Z_GYRO 0x02 - -/*#define X_FINE_GAIN 0x03 // [7:0] fine gain -#define Y_FINE_GAIN 0x04 -#define Z_FINE_GAIN 0x05 -#define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer -#define XA_OFFSET_L_TC 0x07 -#define YA_OFFSET_H 0x08 -#define YA_OFFSET_L_TC 0x09 -#define ZA_OFFSET_H 0x0A -#define ZA_OFFSET_L_TC 0x0B */ - -#define SELF_TEST_X_ACCEL 0x0D -#define SELF_TEST_Y_ACCEL 0x0E -#define SELF_TEST_Z_ACCEL 0x0F - -#define SELF_TEST_A 0x10 - -#define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope -#define XG_OFFSET_L 0x14 -#define YG_OFFSET_H 0x15 -#define YG_OFFSET_L 0x16 -#define ZG_OFFSET_H 0x17 -#define ZG_OFFSET_L 0x18 -#define SMPLRT_DIV 0x19 -#define CONFIG 0x1A -#define GYRO_CONFIG 0x1B -#define ACCEL_CONFIG 0x1C -#define ACCEL_CONFIG2 0x1D -#define LP_ACCEL_ODR 0x1E -#define WOM_THR 0x1F - -#define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms -#define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] -#define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms - -#define FIFO_EN 0x23 -#define I2C_MST_CTRL 0x24 -#define I2C_SLV0_ADDR 0x25 -#define I2C_SLV0_REG 0x26 -#define I2C_SLV0_CTRL 0x27 -#define I2C_SLV1_ADDR 0x28 -#define I2C_SLV1_REG 0x29 -#define I2C_SLV1_CTRL 0x2A -#define I2C_SLV2_ADDR 0x2B -#define I2C_SLV2_REG 0x2C -#define I2C_SLV2_CTRL 0x2D -#define I2C_SLV3_ADDR 0x2E -#define I2C_SLV3_REG 0x2F -#define I2C_SLV3_CTRL 0x30 -#define I2C_SLV4_ADDR 0x31 -#define I2C_SLV4_REG 0x32 -#define I2C_SLV4_DO 0x33 -#define I2C_SLV4_CTRL 0x34 -#define I2C_SLV4_DI 0x35 -#define I2C_MST_STATUS 0x36 -#define INT_PIN_CFG 0x37 -#define INT_ENABLE 0x38 -#define DMP_INT_STATUS 0x39 // Check DMP interrupt -#define INT_STATUS 0x3A -#define ACCEL_XOUT_H 0x3B -#define ACCEL_XOUT_L 0x3C -#define ACCEL_YOUT_H 0x3D -#define ACCEL_YOUT_L 0x3E -#define ACCEL_ZOUT_H 0x3F -#define ACCEL_ZOUT_L 0x40 -#define TEMP_OUT_H 0x41 -#define TEMP_OUT_L 0x42 -#define GYRO_XOUT_H 0x43 -#define GYRO_XOUT_L 0x44 -#define GYRO_YOUT_H 0x45 -#define GYRO_YOUT_L 0x46 -#define GYRO_ZOUT_H 0x47 -#define GYRO_ZOUT_L 0x48 -#define EXT_SENS_DATA_00 0x49 -#define EXT_SENS_DATA_01 0x4A -#define EXT_SENS_DATA_02 0x4B -#define EXT_SENS_DATA_03 0x4C -#define EXT_SENS_DATA_04 0x4D -#define EXT_SENS_DATA_05 0x4E -#define EXT_SENS_DATA_06 0x4F -#define EXT_SENS_DATA_07 0x50 -#define EXT_SENS_DATA_08 0x51 -#define EXT_SENS_DATA_09 0x52 -#define EXT_SENS_DATA_10 0x53 -#define EXT_SENS_DATA_11 0x54 -#define EXT_SENS_DATA_12 0x55 -#define EXT_SENS_DATA_13 0x56 -#define EXT_SENS_DATA_14 0x57 -#define EXT_SENS_DATA_15 0x58 -#define EXT_SENS_DATA_16 0x59 -#define EXT_SENS_DATA_17 0x5A -#define EXT_SENS_DATA_18 0x5B -#define EXT_SENS_DATA_19 0x5C -#define EXT_SENS_DATA_20 0x5D -#define EXT_SENS_DATA_21 0x5E -#define EXT_SENS_DATA_22 0x5F -#define EXT_SENS_DATA_23 0x60 -#define MOT_DETECT_STATUS 0x61 -#define I2C_SLV0_DO 0x63 -#define I2C_SLV1_DO 0x64 -#define I2C_SLV2_DO 0x65 -#define I2C_SLV3_DO 0x66 -#define I2C_MST_DELAY_CTRL 0x67 -#define SIGNAL_PATH_RESET 0x68 -#define MOT_DETECT_CTRL 0x69 -#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP -#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode -#define PWR_MGMT_2 0x6C -#define DMP_BANK 0x6D // Activates a specific bank in the DMP -#define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank -#define DMP_REG 0x6F // Register in DMP from which to read or to which to write -#define DMP_REG_1 0x70 -#define DMP_REG_2 0x71 -#define FIFO_COUNTH 0x72 -#define FIFO_COUNTL 0x73 -#define FIFO_R_W 0x74 -#define WHO_AM_I_MPU9250 0x75 // Should return 0x71 -#define XA_OFFSET_H 0x77 -#define XA_OFFSET_L 0x78 -#define YA_OFFSET_H 0x7A -#define YA_OFFSET_L 0x7B -#define ZA_OFFSET_H 0x7D -#define ZA_OFFSET_L 0x7E - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_Baro 0x2A // start of two-byte MS5637 pressure data, 16-bit signed interger -#define EM7180_BaroTIME 0x2C // start of two-byte MS5637 pressure timestamp, 16-bit unsigned -#define EM7180_Temp 0x2E // start of two-byte MS5637 temperature data, 16-bit signed interger -#define EM7180_TempTIME 0x30 // start of two-byte MS5637 temperature timestamp, 16-bit unsigned -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ActualBaroRate 0x48 -#define EM7180_ActualTempRate 0x49 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_BaroRate 0x58 -#define EM7180_TempRate 0x59 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 -#define EM7180_ACC_LPF_BW 0x5B //Register GP36 -#define EM7180_GYRO_LPF_BW 0x5C //Register GP37 -#define EM7180_BARO_LPF_BW 0x5D //Register GP38 - -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DRC EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DRC lockable EEPROM ID page -#define MPU9250_ADDRESS 0x68 // Device address of MPU9250 when ADO = 0 -#define AK8963_ADDRESS 0x0C // Address of magnetometer -#define BMP280_ADDRESS 0x76 // Address of BMP280 altimeter when ADO = 0 - -#define SerialDebug true // set to true to get Serial output for debugging - -// Set initial input parameters -enum Ascale { - AFS_2G = 0, - AFS_4G, - AFS_8G, - AFS_16G -}; - -enum Gscale { - GFS_250DPS = 0, - GFS_500DPS, - GFS_1000DPS, - GFS_2000DPS -}; - -enum Mscale { - MFS_14BITS = 0, // 0.6 mG per LSB - MFS_16BITS // 0.15 mG per LSB -}; - -enum Posr { - P_OSR_00 = 0, // no op - P_OSR_01, - P_OSR_02, - P_OSR_04, - P_OSR_08, - P_OSR_16 -}; - -enum Tosr { - T_OSR_00 = 0, // no op - T_OSR_01, - T_OSR_02, - T_OSR_04, - T_OSR_08, - T_OSR_16 -}; - -enum IIRFilter { - full = 0, // bandwidth at full sample rate - BW0_223ODR, - BW0_092ODR, - BW0_042ODR, - BW0_021ODR // bandwidth at 0.021 x sample rate -}; - -enum Mode { - BMP280Sleep = 0, - forced, - forced2, - normal -}; - -enum SBy { - t_00_5ms = 0, - t_62_5ms, - t_125ms, - t_250ms, - t_500ms, - t_1000ms, - t_2000ms, - t_4000ms, -}; - -// Specify BMP280 configuration -uint8_t Posr = P_OSR_16, Tosr = T_OSR_02, Mode = normal, IIRFilter = BW0_042ODR, SBy = t_62_5ms; // set pressure amd temperature output data rate -// t_fine carries fine temperature as global value for BMP280 -int32_t t_fine; -// -// Specify sensor full scale -uint8_t Gscale = GFS_250DPS; -uint8_t Ascale = AFS_2G; -uint8_t Mscale = MFS_16BITS; // Choose either 14-bit or 16-bit magnetometer resolution -uint8_t Mmode = 0x02; // 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read -float aRes, gRes, mRes; // scale resolutions per LSB for the sensors - -// Pin definitions -int intPin = 8; // These can be changed, 2 and 3 are the Arduinos ext int pins -int myLed = 13; // LED on the Teensy 3.1 - -// BMP280 compensation parameters -uint16_t dig_T1, dig_P1; -int16_t dig_T2, dig_T3, dig_P2, dig_P3, dig_P4, dig_P5, dig_P6, dig_P7, dig_P8, dig_P9; -double Temperature, Pressure; // stores BMP280 pressures sensor pressure and temperature -int32_t rawPress, rawTemp; // pressure and temperature raw count output for BMP280 - -// MPU9250 variables -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output -float Quat[4] = {0, 0, 0, 0}; // quaternion data register -float magCalibration[3] = {0, 0, 0}; // Factory mag calibration and mag bias -float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}, magScale[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag -int16_t tempCount, rawPressure, rawTemperature; // pressure, temperature raw count output -float temperature, pressure, altitude; // Stores the MPU9250 internal chip temperature in degrees Celsius -float SelfTest[6]; // holds results of gyro and accelerometer self test - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Ki 0.0f - -uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval -uint8_t param[4]; // used for param transfer -uint16_t EM7180_mag_fs, EM7180_acc_fs, EM7180_gyro_fs; // EM7180 sensor full scale ranges - -float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -bool passThru = false; - -void setup() -{ -// Wire.begin(); -// TWBR = 12; // 400 kbit/sec I2C speed for Pro Mini - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(5000); - Serial.begin(38400); - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, LOW); - - I2Cscan(); // should detect SENtral at 0x28 - - // 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"); - - delay(1000); // give some time to read the screen - - // 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!"); - delay(1000); // give some time to read the screen - - // Set up the SENtral as sensor bus in normal operating mode - if(!passThru) { - // 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, 0x03); // 41Hz - writeByte(EM7180_ADDRESS, EM7180_GYRO_LPF_BW, 0x03); // 41Hz - // Set accel/gyro/mage desired ODR rates - writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 100 Hz - writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x64); // 100 Hz - writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x14); // 200/10 Hz - writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x14); // 200/10 Hz - writeByte(EM7180_ADDRESS, EM7180_BaroRate, 0x80 | 0x32); // set enable bit and set Baro rate to 25 Hz - // writeByte(EM7180_ADDRESS, EM7180_TempRate, 0x19); // set enable bit and set rate to 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 - EM7180_set_integer_param (0x49, 0x00); - - //Write desired sensor full scale ranges to the EM7180 - EM7180_set_mag_acc_FS (0x3E8, 0x08); // 1000 uT, 8 g - EM7180_set_gyro_FS (0x7D0); // 2000 dps - - // 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"); -// Serial.print("Actual TempRate = "); Serial.print(readByte(EM7180_ADDRESS, EM7180_ActualTempRate)); Serial.println(" Hz"); - - delay(1000); // give some time to read the screen - - } - - // If pass through mode desired, set it up here - if(passThru) { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - -// Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - // Read the WHO_AM_I register, this is a good test of communication - Serial.println("MPU9250 9-axis motion sensor..."); - byte c = readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 - Serial.print("MPU9250 "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x71, HEX); - if (c == 0x71) // WHO_AM_I should always be 0x71 - { - Serial.println("MPU9250 is online..."); - - MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values - Serial.print("x-axis self test: acceleration trim within : "); Serial.print(SelfTest[0],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: acceleration trim within : "); Serial.print(SelfTest[1],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: acceleration trim within : "); Serial.print(SelfTest[2],1); Serial.println("% of factory value"); - Serial.print("x-axis self test: gyration trim within : "); Serial.print(SelfTest[3],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: gyration trim within : "); Serial.print(SelfTest[4],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: gyration trim within : "); Serial.print(SelfTest[5],1); Serial.println("% of factory value"); - delay(1000); - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - getMres(); - - Serial.println(" Calibrate gyro and accel"); - accelgyrocalMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - delay(1000); - - initMPU9250(); - Serial.println("MPU9250 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - - // Read the WHO_AM_I register of the magnetometer, this is a good test of communication - byte d = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for AK8963 - Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x48, HEX); - - delay(1000); - - // Get magnetometer calibration from AK8963 ROM - initAK8963(magCalibration); Serial.println("AK8963 initialized for active data mode...."); // Initialize device for active mode read of magnetometer - - magcalMPU9250(magBias, magScale); - Serial.println("AK8963 mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]); - Serial.println("AK8963 mag scale (mG)"); Serial.println(magScale[0]); Serial.println(magScale[1]); Serial.println(magScale[2]); - delay(2000); // add delay to see results before serial spew of data - - if(SerialDebug) { -// Serial.println("Calibration values: "); - Serial.print("X-Axis sensitivity adjustment value "); Serial.println(magCalibration[0], 2); - Serial.print("Y-Axis sensitivity adjustment value "); Serial.println(magCalibration[1], 2); - Serial.print("Z-Axis sensitivity adjustment value "); Serial.println(magCalibration[2], 2); - } - - delay(1000); - - // Read the WHO_AM_I register of the BMP280 this is a good test of communication - byte f = readByte(BMP280_ADDRESS, BMP280_ID); // Read WHO_AM_I register for BMP280 - Serial.print("BMP280 "); - Serial.print("I AM "); - Serial.print(f, HEX); - Serial.print(" I should be "); - Serial.println(0x58, HEX); - Serial.println(" "); - - delay(1000); - - writeByte(BMP280_ADDRESS, BMP280_RESET, 0xB6); // reset BMP280 before initilization - delay(100); - - BMP280Init(); // Initialize BMP280 altimeter - Serial.println("Calibration coeficients:"); - Serial.print("dig_T1 ="); - Serial.println(dig_T1); - Serial.print("dig_T2 ="); - Serial.println(dig_T2); - Serial.print("dig_T3 ="); - Serial.println(dig_T3); - Serial.print("dig_P1 ="); - Serial.println(dig_P1); - Serial.print("dig_P2 ="); - Serial.println(dig_P2); - Serial.print("dig_P3 ="); - Serial.println(dig_P3); - Serial.print("dig_P4 ="); - Serial.println(dig_P4); - Serial.print("dig_P5 ="); - Serial.println(dig_P5); - Serial.print("dig_P6 ="); - Serial.println(dig_P6); - Serial.print("dig_P7 ="); - Serial.println(dig_P7); - Serial.print("dig_P8 ="); - Serial.println(dig_P8); - Serial.print("dig_P9 ="); - Serial.println(dig_P9); - - delay(1000); - - } - else - { - Serial.print("Could not connect to MPU9250: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } - } -} - - -void loop() -{ - if(!passThru) { - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - if(eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(errorStatus != 0x00) { // non-zero value indicates error, what is it? - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if(errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus == 0x14) Serial.print("Gyro failure!"); - if(errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus == 0x30) Serial.print("Math error!"); - if(errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if(eventStatus & 0x10) { // new acceleration data available - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) { // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus & 0x08) { // new mag data available - readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - mx = (float)magCount[0]*0.305176; // get actual G value - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) { // new quaternion data available - readSENtralQuatData(Quat); - } - - // get BMP280 pressure - if(eventStatus & 0x40) { // new baro data available - // Serial.println("new Baro data!"); - rawPressure = readSENtralBaroData(); - pressure = (float)rawPressure*0.01f +1013.25f; // pressure in mBar - - // get BMP280 temperature - rawTemperature = readSENtralTempData(); - temperature = (float) rawTemperature*0.01; // temperature in degrees C - } - } - - if(passThru) { - // If intPin goes high, all data registers have new data -// if (digitalRead(intACC2)) { // On interrupt, read data - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the acceleration value into actual g's - ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes - accelBias[1]; - az = (float)accelCount[2]*aRes - accelBias[2]; - // } -// if (digitalRead(intGYRO2)) { // On interrupt, read data - readGyroData(gyroCount); // Read the x/y/z adc values - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes; - gz = (float)gyroCount[2]*gRes; - // } -// if (digitalRead(intDRDYM)) { // On interrupt, read data - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - mx = (float)magCount[0]*mRes*magCalibration[0] - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes*magCalibration[1] - magBias[1]; - mz = (float)magCount[2]*mRes*magCalibration[2] - magBias[2]; -// mx *= magScale[0]; -// my *= magScale[1]; -// mz *= magScale[2]; - // } - } - - - // keep track of rates - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer/gyro is aligned with the y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ down) is misaligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // We will assume that +y accel/gyro is North, then x accel/gyro is East. So if we want te quaternions properly aligned - // we need to feed into the madgwick function Ay, Ax, -Az, Gy, Gx, -Gz, Mx, My, and Mz. But because gravity is by convention - // positive down, we need to invert the accel data, so we pass -Ay, -Ax, Az, Gy, Gx, -Gz, Mx, My, and Mz into the Madgwick - // function to get North along the accel +y-axis, East along the accel +x-axis, and Down along the accel -z-axis. - // This orientation choice can be modified to allow any convenient (non-NED) orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(-ay, -ax, az, gy*PI/180.0f, gx*PI/180.0f, -gz*PI/180.0f, mx, my, mz); -// if(passThru)MahonyQuaternionUpdate(-ay, -ax, az, gy*PI/180.0f, gx*PI/180.0f, -gz*PI/180.0f, mx, my, mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - if (delt_t > 500) { // update LCD once per half-second independent of read rate - - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print( (int)mx); - Serial.print(" my = "); Serial.print( (int)my); - Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG"); - - Serial.println("Software quaternions:"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Quat[0]); - Serial.print(" Qx = "); Serial.print(Quat[1]); - Serial.print(" Qy = "); Serial.print(Quat[2]); - Serial.print(" Qz = "); Serial.println(Quat[3]); - } - - -// tempCount = readTempData(); // Read the gyro adc values -// temperature = ((float) tempCount) / 333.87 + 21.0; // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade -// Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - if(passThru) { - rawPress = readBMP280Pressure(); - pressure = (float) bmp280_compensate_P(rawPress)/25600.; // Pressure in mbar - rawTemp = readBMP280Temperature(); - temperature = (float) bmp280_compensate_T(rawTemp)/100.; - - } - - - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(yaw < 0) yaw += 360.0f; // Ensure yaw stays between 0 and 360 - roll *= 180.0f / PI; - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(Yaw < 0) Yaw += 360.0f ; // Ensure yaw stays between 0 and 360 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 360) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - // - - if(SerialDebug) { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - - Serial.println("BMP280:"); - Serial.print("Altimeter temperature = "); - Serial.print( temperature, 2); - Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); - Serial.print(9.*temperature/5. + 32., 2); - Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); - Serial.print(pressure, 2); - Serial.println(" mbar");// pressure in millibar - altitude = 145366.45f*(1.0f - pow((pressure/1013.25f), 0.190284f)); - Serial.print("Altitude = "); - Serial.print(altitude, 2); - Serial.println(" feet"); - Serial.println(" "); - } - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - // Serial.print(millis()/1000.0, 1);Serial.print(","); - // Serial.print(yaw); Serial.print(",");Serial.print(pitch); Serial.print(",");Serial.print(roll); Serial.print(","); - // Serial.print(Yaw); Serial.print(",");Serial.print(Pitch); Serial.print(",");Serial.println(Roll); - - - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } - -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== - -float 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; -} - -void 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 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 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 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 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 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[0] = uint32_reg_to_float (&rawData[0]); - destination[1] = uint32_reg_to_float (&rawData[4]); - destination[2] = uint32_reg_to_float (&rawData[8]); - destination[3] = uint32_reg_to_float (&rawData[12]); // SENtral stores quats as qx, qy, qz, q0! - -} - -void 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 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 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]); -} - -void getMres() { - 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 - break; - case MFS_16BITS: - mRes = 10.*4912./32760.0; // Proper scale to return milliGauss - break; - } -} - -void getGres() { - 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; - break; - case GFS_500DPS: - gRes = 500.0/32768.0; - break; - case GFS_1000DPS: - gRes = 1000.0/32768.0; - break; - case GFS_2000DPS: - gRes = 2000.0/32768.0; - break; - } -} - -void getAres() { - 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; - break; - case AFS_4G: - aRes = 4.0/32768.0; - break; - case AFS_8G: - aRes = 8.0/32768.0; - break; - case AFS_16G: - aRes = 16.0/32768.0; - break; - } -} - - -void 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 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 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 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 initAK8963(float * destination) -{ - // 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.; - 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 initMPU9250() -{ - // 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 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 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] = {0xFF, 0xFF, 0xFF}, mag_min[3] = {0x7F, 0x7F, 0x7F}, 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*magCalibration[0]; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1]; - dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2]; - - // 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 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, FS<<3); // Set full scale range for the gyro to 250 dps - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, FS<<3); // Set full scale range for the accelerometer to 2 g - - for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer - - readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array - aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - - readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - } - - for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings - aAvg[ii] /= 200; - gAvg[ii] /= 200; - } - -// Configure the accelerometer for self-test - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g - writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s - delay(25); // Delay a while to let the device stabilize - - for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer - - readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array - aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - - readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - } - - for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings - aSTAvg[ii] /= 200; - gSTAvg[ii] /= 200; - } - - // Configure the gyro and accelerometer for normal operation - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); - writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); - delay(25); // Delay a while to let the device stabilize - - // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg - selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results - selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results - selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results - selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results - selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results - selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results - - // Retrieve factory self-test value from self-test code reads - factoryTrim[0] = (float)(2620/1< 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - - - - -int32_t readBMP280Temperature() -{ - uint8_t rawData[3]; // 20-bit pressure register data stored here - readBytes(BMP280_ADDRESS, BMP280_TEMP_MSB, 3, &rawData[0]); - return (int32_t) (((int32_t) rawData[0] << 16 | (int32_t) rawData[1] << 8 | rawData[2]) >> 4); -} - -int32_t readBMP280Pressure() -{ - uint8_t rawData[3]; // 20-bit pressure register data stored here - readBytes(BMP280_ADDRESS, BMP280_PRESS_MSB, 3, &rawData[0]); - return (int32_t) (((int32_t) rawData[0] << 16 | (int32_t) rawData[1] << 8 | rawData[2]) >> 4); -} - -void BMP280Init() -{ - // Configure the BMP280 - // Set T and P oversampling rates and sensor mode - writeByte(BMP280_ADDRESS, BMP280_CTRL_MEAS, Tosr << 5 | Posr << 2 | Mode); - // Set standby time interval in normal mode and bandwidth - writeByte(BMP280_ADDRESS, BMP280_CONFIG, SBy << 5 | IIRFilter << 2); - // Read and store calibration data - uint8_t calib[24]; - readBytes(BMP280_ADDRESS, BMP280_CALIB00, 24, &calib[0]); - dig_T1 = (uint16_t)(((uint16_t) calib[1] << 8) | calib[0]); - dig_T2 = ( int16_t)((( int16_t) calib[3] << 8) | calib[2]); - dig_T3 = ( int16_t)((( int16_t) calib[5] << 8) | calib[4]); - dig_P1 = (uint16_t)(((uint16_t) calib[7] << 8) | calib[6]); - dig_P2 = ( int16_t)((( int16_t) calib[9] << 8) | calib[8]); - dig_P3 = ( int16_t)((( int16_t) calib[11] << 8) | calib[10]); - dig_P4 = ( int16_t)((( int16_t) calib[13] << 8) | calib[12]); - dig_P5 = ( int16_t)((( int16_t) calib[15] << 8) | calib[14]); - dig_P6 = ( int16_t)((( int16_t) calib[17] << 8) | calib[16]); - dig_P7 = ( int16_t)((( int16_t) calib[19] << 8) | calib[18]); - dig_P8 = ( int16_t)((( int16_t) calib[21] << 8) | calib[20]); - dig_P9 = ( int16_t)((( int16_t) calib[23] << 8) | calib[22]); -} - -// Returns temperature in DegC, resolution is 0.01 DegC. Output value of -// “5123” equals 51.23 DegC. -int32_t bmp280_compensate_T(int32_t adc_T) -{ - int32_t var1, var2, T; - var1 = ((((adc_T >> 3) - ((int32_t)dig_T1 << 1))) * ((int32_t)dig_T2)) >> 11; - var2 = (((((adc_T >> 4) - ((int32_t)dig_T1)) * ((adc_T >> 4) - ((int32_t)dig_T1))) >> 12) * ((int32_t)dig_T3)) >> 14; - t_fine = var1 + var2; - T = (t_fine * 5 + 128) >> 8; - return T; -} - -// Returns pressure in Pa as unsigned 32 bit integer in Q24.8 format (24 integer bits and 8 -//fractional bits). -//Output value of “24674867” represents 24674867/256 = 96386.2 Pa = 963.862 hPa -uint32_t bmp280_compensate_P(int32_t adc_P) -{ - long long var1, var2, p; - var1 = ((long long)t_fine) - 128000; - var2 = var1 * var1 * (long long)dig_P6; - var2 = var2 + ((var1*(long long)dig_P5)<<17); - var2 = var2 + (((long long)dig_P4)<<35); - var1 = ((var1 * var1 * (long long)dig_P3)>>8) + ((var1 * (long long)dig_P2)<<12); - var1 = (((((long long)1)<<47)+var1))*((long long)dig_P1)>>33; - if(var1 == 0) - { - return 0; - // avoid exception caused by division by zero - } - p = 1048576 - adc_P; - p = (((p<<31) - var2)*3125)/var1; - var1 = (((long long)dig_P9) * (p>>13) * (p>>13)) >> 25; - var2 = (((long long)dig_P8) * p)>> 19; - p = ((p + var1 + var2) >> 8) + (((long long)dig_P7)<<4); - return (uint32_t)p; -} - - - - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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 and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} diff --git a/EM7180_MPU9250_MS5637.ino b/EM7180_MPU9250_MS5637.ino deleted file mode 100644 index 08e94b0..0000000 --- a/EM7180_MPU9250_MS5637.ino +++ /dev/null @@ -1,1906 +0,0 @@ -/* EM7180_MPU9250_MS5637_t3 Basic Example Code - by: Kris Winer - date: September 11, 2015 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the MPU9250 (with embedded MPU9250 + AK8963C), and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DFC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the MPU9250 9-axis motion sensor (accel/gyro/mag) as slave, an MS5637 pressure/temperature sensor as slave, and an M24512DFC - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral can use the pressure data in the sensor fusion - and there is a driver for the MS5637 in the SENtral firmware. Also, like the MAX21100, the SENtral - can be toggled into a bypass mode where the pressure sensor (and EEPROM and MPU9250) may be read directly by the - Teensy 3.1 host microcontroller. If the read rate is infrequent enough (2 Hz is sufficient since pressure and temperature - do not change very fast), then the sensor fusion rate is not significantly affected. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The MS5637 is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+MPU9250+MS5637+M24512DRC Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: All the sensors n this board are I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensors are not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ -//#include "Wire.h" -#include -#include -#include -#include - -// Using NOKIA 5110 monochrome 84 x 48 pixel display -// pin 7 - Serial clock out (SCLK) -// pin 6 - Serial data out (DIN) -// pin 5 - Data/Command select (D/C) -// pin 3 - LCD chip select (SCE) -// pin 4 - LCD reset (RST) -Adafruit_PCD8544 display = Adafruit_PCD8544(7, 6, 5, 3, 4); - -// See MS5637-02BA03 Low Voltage Barometric Pressure Sensor Data Sheet -#define MS5637_RESET 0x1E -#define MS5637_CONVERT_D1 0x40 -#define MS5637_CONVERT_D2 0x50 -#define MS5637_ADC_READ 0x00 - -// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in -// above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map -// -//Magnetometer Registers -#define AK8963_ADDRESS 0x0C -#define WHO_AM_I_AK8963 0x00 // should return 0x48 -#define INFO 0x01 -#define AK8963_ST1 0x02 // data ready status bit 0 -#define AK8963_XOUT_L 0x03 // data -#define AK8963_XOUT_H 0x04 -#define AK8963_YOUT_L 0x05 -#define AK8963_YOUT_H 0x06 -#define AK8963_ZOUT_L 0x07 -#define AK8963_ZOUT_H 0x08 -#define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 -#define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 -#define AK8963_ASTC 0x0C // Self test control -#define AK8963_I2CDIS 0x0F // I2C disable -#define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value -#define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value -#define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value - -#define SELF_TEST_X_GYRO 0x00 -#define SELF_TEST_Y_GYRO 0x01 -#define SELF_TEST_Z_GYRO 0x02 - -/*#define X_FINE_GAIN 0x03 // [7:0] fine gain -#define Y_FINE_GAIN 0x04 -#define Z_FINE_GAIN 0x05 -#define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer -#define XA_OFFSET_L_TC 0x07 -#define YA_OFFSET_H 0x08 -#define YA_OFFSET_L_TC 0x09 -#define ZA_OFFSET_H 0x0A -#define ZA_OFFSET_L_TC 0x0B */ - -#define SELF_TEST_X_ACCEL 0x0D -#define SELF_TEST_Y_ACCEL 0x0E -#define SELF_TEST_Z_ACCEL 0x0F - -#define SELF_TEST_A 0x10 - -#define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope -#define XG_OFFSET_L 0x14 -#define YG_OFFSET_H 0x15 -#define YG_OFFSET_L 0x16 -#define ZG_OFFSET_H 0x17 -#define ZG_OFFSET_L 0x18 -#define SMPLRT_DIV 0x19 -#define CONFIG 0x1A -#define GYRO_CONFIG 0x1B -#define ACCEL_CONFIG 0x1C -#define ACCEL_CONFIG2 0x1D -#define LP_ACCEL_ODR 0x1E -#define WOM_THR 0x1F - -#define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms -#define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] -#define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms - -#define FIFO_EN 0x23 -#define I2C_MST_CTRL 0x24 -#define I2C_SLV0_ADDR 0x25 -#define I2C_SLV0_REG 0x26 -#define I2C_SLV0_CTRL 0x27 -#define I2C_SLV1_ADDR 0x28 -#define I2C_SLV1_REG 0x29 -#define I2C_SLV1_CTRL 0x2A -#define I2C_SLV2_ADDR 0x2B -#define I2C_SLV2_REG 0x2C -#define I2C_SLV2_CTRL 0x2D -#define I2C_SLV3_ADDR 0x2E -#define I2C_SLV3_REG 0x2F -#define I2C_SLV3_CTRL 0x30 -#define I2C_SLV4_ADDR 0x31 -#define I2C_SLV4_REG 0x32 -#define I2C_SLV4_DO 0x33 -#define I2C_SLV4_CTRL 0x34 -#define I2C_SLV4_DI 0x35 -#define I2C_MST_STATUS 0x36 -#define INT_PIN_CFG 0x37 -#define INT_ENABLE 0x38 -#define DMP_INT_STATUS 0x39 // Check DMP interrupt -#define INT_STATUS 0x3A -#define ACCEL_XOUT_H 0x3B -#define ACCEL_XOUT_L 0x3C -#define ACCEL_YOUT_H 0x3D -#define ACCEL_YOUT_L 0x3E -#define ACCEL_ZOUT_H 0x3F -#define ACCEL_ZOUT_L 0x40 -#define TEMP_OUT_H 0x41 -#define TEMP_OUT_L 0x42 -#define GYRO_XOUT_H 0x43 -#define GYRO_XOUT_L 0x44 -#define GYRO_YOUT_H 0x45 -#define GYRO_YOUT_L 0x46 -#define GYRO_ZOUT_H 0x47 -#define GYRO_ZOUT_L 0x48 -#define EXT_SENS_DATA_00 0x49 -#define EXT_SENS_DATA_01 0x4A -#define EXT_SENS_DATA_02 0x4B -#define EXT_SENS_DATA_03 0x4C -#define EXT_SENS_DATA_04 0x4D -#define EXT_SENS_DATA_05 0x4E -#define EXT_SENS_DATA_06 0x4F -#define EXT_SENS_DATA_07 0x50 -#define EXT_SENS_DATA_08 0x51 -#define EXT_SENS_DATA_09 0x52 -#define EXT_SENS_DATA_10 0x53 -#define EXT_SENS_DATA_11 0x54 -#define EXT_SENS_DATA_12 0x55 -#define EXT_SENS_DATA_13 0x56 -#define EXT_SENS_DATA_14 0x57 -#define EXT_SENS_DATA_15 0x58 -#define EXT_SENS_DATA_16 0x59 -#define EXT_SENS_DATA_17 0x5A -#define EXT_SENS_DATA_18 0x5B -#define EXT_SENS_DATA_19 0x5C -#define EXT_SENS_DATA_20 0x5D -#define EXT_SENS_DATA_21 0x5E -#define EXT_SENS_DATA_22 0x5F -#define EXT_SENS_DATA_23 0x60 -#define MOT_DETECT_STATUS 0x61 -#define I2C_SLV0_DO 0x63 -#define I2C_SLV1_DO 0x64 -#define I2C_SLV2_DO 0x65 -#define I2C_SLV3_DO 0x66 -#define I2C_MST_DELAY_CTRL 0x67 -#define SIGNAL_PATH_RESET 0x68 -#define MOT_DETECT_CTRL 0x69 -#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP -#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode -#define PWR_MGMT_2 0x6C -#define DMP_BANK 0x6D // Activates a specific bank in the DMP -#define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank -#define DMP_REG 0x6F // Register in DMP from which to read or to which to write -#define DMP_REG_1 0x70 -#define DMP_REG_2 0x71 -#define FIFO_COUNTH 0x72 -#define FIFO_COUNTL 0x73 -#define FIFO_R_W 0x74 -#define WHO_AM_I_MPU9250 0x75 // Should return 0x71 -#define XA_OFFSET_H 0x77 -#define XA_OFFSET_L 0x78 -#define YA_OFFSET_H 0x7A -#define YA_OFFSET_L 0x7B -#define ZA_OFFSET_H 0x7D -#define ZA_OFFSET_L 0x7E - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_Baro 0x2A // start of two-byte MS5637 pressure data, 16-bit signed interger -#define EM7180_BaroTIME 0x2C // start of two-byte MS5637 pressure timestamp, 16-bit unsigned -#define EM7180_Temp 0x2E // start of two-byte MS5637 temperature data, 16-bit signed interger -#define EM7180_TempTIME 0x30 // start of two-byte MS5637 temperature timestamp, 16-bit unsigned -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ActualBaroRate 0x48 -#define EM7180_ActualTempRate 0x49 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_BaroRate 0x58 -#define EM7180_TempRate 0x59 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 -#define EM7180_ACC_LPF_BW 0x5B //Register GP36 -#define EM7180_GYRO_LPF_BW 0x5C //Register GP37 -#define EM7180_BARO_LPF_BW 0x5D //Register GP38 - -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page -#define MPU9250_ADDRESS 0x68 // Device address when ADO = 0 -#define AK8963_ADDRESS 0x0C // Address of magnetometer -#define MS5637_ADDRESS 0x76 // Address of altimeter - -#define SerialDebug true // set to true to get Serial output for debugging - -// Set initial input parameters -enum Ascale { - AFS_2G = 0, - AFS_4G, - AFS_8G, - AFS_16G -}; - -enum Gscale { - GFS_250DPS = 0, - GFS_500DPS, - GFS_1000DPS, - GFS_2000DPS -}; - -enum Mscale { - MFS_14BITS = 0, // 0.6 mG per LSB - MFS_16BITS // 0.15 mG per LSB -}; - -#define ADC_256 0x00 // define pressure and temperature conversion rates -#define ADC_512 0x02 -#define ADC_1024 0x04 -#define ADC_2048 0x06 -#define ADC_4096 0x08 -#define ADC_8192 0x0A -#define ADC_D1 0x40 -#define ADC_D2 0x50 - -// Specify sensor full scale -uint8_t OSR = ADC_8192; // set pressure amd temperature oversample rate -// -// Specify sensor full scale -uint8_t Gscale = GFS_250DPS; -uint8_t Ascale = AFS_2G; -uint8_t Mscale = MFS_16BITS; // Choose either 14-bit or 16-bit magnetometer resolution -uint8_t Mmode = 0x02; // 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read -float aRes, gRes, mRes; // scale resolutions per LSB for the sensors - -// Pin definitions -int intPin = 8; // These can be changed, 2 and 3 are the Arduinos ext int pins -int myLed = 13; // LED on the Teensy 3.1 - -// MS5637 definitions -uint16_t Pcal[8]; // calibration constants from MS5637 PROM registers -unsigned char nCRC; // calculated check sum to ensure PROM integrity -uint32_t D1 = 0, D2 = 0; // raw MS5637 pressure and temperature data -double dT, OFFSET, SENS, T2, OFFSET2, SENS2; // First order and second order corrections for raw S5637 temperature and pressure data - -// MPU9250 variables -int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output -int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output -int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output -float Quat[4] = {0, 0, 0, 0}; // quaternion data register -float magCalibration[3] = {0, 0, 0}; // Factory mag calibration and mag bias -float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}, magScale[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag -int16_t tempCount, rawPressure, rawTemperature; // temperature raw count output -double Temperature, Pressure; // stores MS5637 pressures sensor pressure and temperature -int32_t rawPress, rawTemp; // pressure and temperature raw count output for MS5637 -float temperature, pressure, altitude; // Stores the MPU9250 internal chip temperature in degrees Celsius -float SelfTest[6]; // holds results of gyro and accelerometer self test - -// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Ki 0.0f - -uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate -float pitch, yaw, roll, Yaw, Pitch, Roll; -float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes -uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval -uint32_t Now = 0; // used to calculate integration interval -uint8_t param[4]; // used for param transfer -uint16_t EM7180_mag_fs, EM7180_acc_fs, EM7180_gyro_fs; // EM7180 sensor full scale ranges - -float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion -float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method - -bool passThru = false; - -; - -void setup() -{ -// Wire.begin(); -// TWBR = 12; // 400 kbit/sec I2C speed for Pro Mini - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(5000); - Serial.begin(38400); - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(intPin, INPUT); - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - display.begin(); // Initialize the display - display.setContrast(40); // Set the contrast - -// Start device display with ID of sensor - display.clearDisplay(); - display.setTextSize(2); - display.setCursor(0,0); display.print("MPU9250"); - display.setTextSize(1); - display.setCursor(0, 20); display.print("9-DOF 16-bit"); - display.setCursor(0, 30); display.print("motion sensor"); - display.setCursor(20,40); display.print("60 ug LSB"); - display.display(); - delay(1000); - -// Set up for data display - display.setTextSize(1); // Set text size to normal, 2 is twice normal etc. - display.setTextColor(BLACK); // Set pixel color; 1 on the monochrome screen - display.clearDisplay(); // clears the screen and buffer - - I2Cscan(); // should detect SENtral at 0x28 - - // 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"); - - delay(1000); // give some time to read the screen - - // 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!"); - delay(1000); // give some time to read the screen - - // Set up the SENtral as sensor bus in normal operating mode - if(!passThru) { - // 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, 0x03); // 41Hz - writeByte(EM7180_ADDRESS, EM7180_GYRO_LPF_BW, 0x03); // 41Hz - // Set accel/gyro/mage desired ODR rates - writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 100 Hz - writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x64); // 100 Hz - writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x14); // 200/10 Hz - writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x14); // 200/10 Hz - writeByte(EM7180_ADDRESS, EM7180_BaroRate, 0x80 | 0x32); // set enable bit and set Baro rate to 25 Hz - // writeByte(EM7180_ADDRESS, EM7180_TempRate, 0x19); // set enable bit and set rate to 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 - EM7180_set_integer_param (0x49, 0x00); - - //Write desired sensor full scale ranges to the EM7180 - EM7180_set_mag_acc_FS (0x3E8, 0x08); // 1000 uT, 8 g - EM7180_set_gyro_FS (0x7D0); // 2000 dps - - // 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"); -// Serial.print("Actual TempRate = "); Serial.print(readByte(EM7180_ADDRESS, EM7180_ActualTempRate)); Serial.println(" Hz"); - - delay(1000); // give some time to read the screen - - } - - // If pass through mode desired, set it up here - if(passThru) { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - -// Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - // Read the WHO_AM_I register, this is a good test of communication - Serial.println("MPU9250 9-axis motion sensor..."); - byte c = readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 - Serial.print("MPU9250 "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x71, HEX); - if (c == 0x71) // WHO_AM_I should always be 0x71 - { - Serial.println("MPU9250 is online..."); - - MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values - Serial.print("x-axis self test: acceleration trim within : "); Serial.print(SelfTest[0],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: acceleration trim within : "); Serial.print(SelfTest[1],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: acceleration trim within : "); Serial.print(SelfTest[2],1); Serial.println("% of factory value"); - Serial.print("x-axis self test: gyration trim within : "); Serial.print(SelfTest[3],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: gyration trim within : "); Serial.print(SelfTest[4],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: gyration trim within : "); Serial.print(SelfTest[5],1); Serial.println("% of factory value"); - delay(1000); - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - getMres(); - - Serial.println(" Calibrate gyro and accel"); - accelgyrocalMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - display.clearDisplay(); - - display.setCursor(0, 0); display.print("MPU9250 bias"); - display.setCursor(0, 8); display.print(" x y z "); - - display.setCursor(0, 16); display.print((int)(1000*accelBias[0])); - display.setCursor(24, 16); display.print((int)(1000*accelBias[1])); - display.setCursor(48, 16); display.print((int)(1000*accelBias[2])); - display.setCursor(72, 16); display.print("mg"); - - display.setCursor(0, 24); display.print(gyroBias[0], 1); - display.setCursor(24, 24); display.print(gyroBias[1], 1); - display.setCursor(48, 24); display.print(gyroBias[2], 1); - display.setCursor(66, 24); display.print("o/s"); - - display.display(); - delay(1000); - - initMPU9250(); - Serial.println("MPU9250 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature -writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - - // Read the WHO_AM_I register of the magnetometer, this is a good test of communication - byte d = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for AK8963 - Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x48, HEX); - display.clearDisplay(); - display.setCursor(20,0); display.print("AK8963"); - display.setCursor(0,10); display.print("I AM"); - display.setCursor(0,20); display.print(d, HEX); - display.setCursor(0,30); display.print("I Should Be"); - display.setCursor(0,40); display.print(0x48, HEX); - display.display(); - delay(1000); - - // Get magnetometer calibration from AK8963 ROM - initAK8963(magCalibration); Serial.println("AK8963 initialized for active data mode...."); // Initialize device for active mode read of magnetometer - - magcalMPU9250(magBias, magScale); - Serial.println("AK8963 mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]); - Serial.println("AK8963 mag scale (mG)"); Serial.println(magScale[0]); Serial.println(magScale[1]); Serial.println(magScale[2]); - delay(2000); // add delay to see results before serial spew of data - - if(SerialDebug) { -// Serial.println("Calibration values: "); - Serial.print("X-Axis sensitivity adjustment value "); Serial.println(magCalibration[0], 2); - Serial.print("Y-Axis sensitivity adjustment value "); Serial.println(magCalibration[1], 2); - Serial.print("Z-Axis sensitivity adjustment value "); Serial.println(magCalibration[2], 2); - } - - display.clearDisplay(); - display.setCursor(20,0); display.print("AK8963"); - display.setCursor(0,10); display.print("ASAX "); display.setCursor(50,10); display.print(magCalibration[0], 2); - display.setCursor(0,20); display.print("ASAY "); display.setCursor(50,20); display.print(magCalibration[1], 2); - display.setCursor(0,30); display.print("ASAZ "); display.setCursor(50,30); display.print(magCalibration[2], 2); - display.display(); - delay(1000); - - // Reset the MS5637 pressure sensor - MS5637Reset(); - delay(100); - Serial.println("MS5637 pressure sensor reset..."); - // Read PROM data from MS5637 pressure sensor - MS5637PromRead(Pcal); - Serial.println("PROM dta read:"); - Serial.print("C0 = "); Serial.println(Pcal[0]); - unsigned char refCRC = Pcal[0] >> 12; - Serial.print("C1 = "); Serial.println(Pcal[1]); - Serial.print("C2 = "); Serial.println(Pcal[2]); - Serial.print("C3 = "); Serial.println(Pcal[3]); - Serial.print("C4 = "); Serial.println(Pcal[4]); - Serial.print("C5 = "); Serial.println(Pcal[5]); - Serial.print("C6 = "); Serial.println(Pcal[6]); - - nCRC = MS5637checkCRC(Pcal); //calculate checksum to ensure integrity of MS5637 calibration data - Serial.print("Checksum = "); Serial.print(nCRC); Serial.print(" , should be "); Serial.println(refCRC); - - display.clearDisplay(); - display.setCursor(20,0); display.print("MS5637"); - display.setCursor(0,10); display.print("CRC is "); display.setCursor(50,10); display.print(nCRC); - display.setCursor(0,20); display.print("Should be "); display.setCursor(50,30); display.print(refCRC); - display.display(); - delay(1000); - - } - else - { - Serial.print("Could not connect to MPU9250: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } - } -} - - -void loop() -{ - if(!passThru) { - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - if(eventStatus & 0x02) { // error detected, what is it? - - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if(errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus == 0x14) Serial.print("Gyro failure!"); - if(errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus == 0x30) Serial.print("Math error!"); - if(errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - - // Handle errors ToDo - - } - - // if no errors, see if new data is ready - if(eventStatus & 0x10) { // new acceleration data available - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) { // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus - - // Now we'll calculate the mag value into actual G's - mx = (float)magCount[0]*0.305176; // get actual G value - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) { // new quaternion data available - readSENtralQuatData(Quat); -// } - -// get MS5637 pressure - if(eventStatus & 0x40) { // new baro data available - // Serial.println("new Baro data!"); - rawPressure = readSENtralBaroData(); - pressure = (float)rawPressure*0.01f + 1013.25f; // pressure in mBar - - // get MS5637 temperature - rawTemperature = readSENtralTempData(); - temperature = (float) rawTemperature*0.01; // temperature in degrees C - } - - } - - if(passThru) { - // If intPin goes high, all data registers have new data -// if (digitalRead(intACC2)) { // On interrupt, read data - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the acceleration value into actual g's - ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes - accelBias[1]; - az = (float)accelCount[2]*aRes - accelBias[2]; - // } -// if (digitalRead(intGYRO2)) { // On interrupt, read data - readGyroData(gyroCount); // Read the x/y/z adc values - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes; - gz = (float)gyroCount[2]*gRes; - // } -// if (digitalRead(intDRDYM)) { // On interrupt, read data - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - mx = (float)magCount[0]*mRes*magCalibration[0] - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes*magCalibration[1] - magBias[1]; - mz = (float)magCount[2]*mRes*magCalibration[2] - magBias[2]; -// mx *= magScale[0]; -// my *= magScale[1]; -// mz *= magScale[2]; - // } - } - - - // keep track of rates - Now = micros(); - deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer/gyro is aligned with the y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ down) is misaligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // We will assume that +y accel/gyro is North, then x accel/gyro is East. So if we want te quaternions properly aligned - // we need to feed into the madgwick function Ay, Ax, -Az, Gy, Gx, -Gz, Mx, My, and Mz. But because gravity is by convention - // positive down, we need to invert the accel data, so we pass -Ay, -Ax, Az, Gy, Gx, -Gz, Mx, My, and Mz into the Madgwick - // function to get North along the accel +y-axis, East along the accel +x-axis, and Down along the accel -z-axis. - // This orientation choice can be modified to allow any convenient (non-NED) orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(-ay, -ax, az, gy*PI/180.0f, gx*PI/180.0f, -gz*PI/180.0f, mx, my, mz); -// if(passThru)MahonyQuaternionUpdate(-ay, -ax, az, gy*PI/180.0f, gx*PI/180.0f, -gz*PI/180.0f, mx, my, mz); - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - if (delt_t > 500) { // update LCD once per half-second independent of read rate - - if(SerialDebug) { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print( (int)mx); - Serial.print(" my = "); Serial.print( (int)my); - Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG"); - - Serial.println("Software quaternions:"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions:"); - Serial.print("Q0 = "); Serial.print(Quat[0]); - Serial.print(" Qx = "); Serial.print(Quat[1]); - Serial.print(" Qy = "); Serial.print(Quat[2]); - Serial.print(" Qz = "); Serial.println(Quat[3]); - } - - - if(passThru) { -// tempCount = readTempData(); // Read the gyro adc values -// temperature = ((float) tempCount) / 333.87 + 21.0; // Gyro chip temperature in degrees Centigrade - // Print temperature in degrees Centigrade -// Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C - - D1 = MS5637Read(ADC_D1, OSR); // get raw pressure value - D2 = MS5637Read(ADC_D2, OSR); // get raw temperature value - dT = D2 - Pcal[5]*pow(2,8); // calculate temperature difference from reference - OFFSET = Pcal[2]*pow(2, 17) + dT*Pcal[4]/pow(2,6); - SENS = Pcal[1]*pow(2,16) + dT*Pcal[3]/pow(2,7); - - Temperature = (2000 + (dT*Pcal[6])/pow(2, 23))/100; // First-order Temperature in degrees Centigrade -// -// Second order corrections - if(Temperature > 20) - { - T2 = 5*dT*dT/pow(2, 38); // correction for high temperatures - OFFSET2 = 0; - SENS2 = 0; - } - if(Temperature < 20) // correction for low temperature - { - T2 = 3*dT*dT/pow(2, 33); - OFFSET2 = 61*(100*Temperature - 2000)*(100*Temperature - 2000)/16; - SENS2 = 29*(100*Temperature - 2000)*(100*Temperature - 2000)/16; - } - if(Temperature < -15) // correction for very low temperature - { - OFFSET2 = OFFSET2 + 17*(100*Temperature + 1500)*(100*Temperature + 1500); - SENS2 = SENS2 + 9*(100*Temperature + 1500)*(100*Temperature + 1500); - } - // End of second order corrections - // - Temperature = Temperature - T2/100; - OFFSET = OFFSET - OFFSET2; - SENS = SENS - SENS2; - - Pressure = (((D1*SENS)/pow(2, 21) - OFFSET)/pow(2, 15))/100; // Pressure in mbar or kPa - - } - - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(yaw < 0) yaw += 360.0f; // Ensure yaw stays between 0 and 360 - roll *= 180.0f / PI; - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(Yaw < 0) Yaw += 360.0f ; // Ensure yaw stays between 0 and 360 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 260) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - // - - if(SerialDebug) { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - - Serial.println("MS5637:"); - Serial.print("Altimeter temperature = "); - if(passThru) Serial.print( (float) Temperature, 2); - if(!passThru) Serial.print( temperature, 2); - Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); - if(passThru) Serial.print(9.*((float)Temperature)/5. + 32., 2); - if(!passThru) Serial.print(9.*temperature/5. + 32., 2); - Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); - if(passThru) Serial.print((float)Pressure, 2); - if(!passThru) Serial.print(pressure, 2); - Serial.println(" mbar");// pressure in millibar - if(passThru) altitude = 145366.45f*(1.0f - pow((((float)Pressure)/1013.25f), 0.190284f)); - if(!passThru) altitude = 145366.45f*(1.0f - pow(((pressure)/1013.25f), 0.190284f)); - Serial.print("Altitude = "); - Serial.print(altitude, 2); - Serial.println(" feet"); - Serial.println(" "); - - Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); - } - - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } - -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== - -float 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; -} - - -void 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 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 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 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 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 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[0] = uint32_reg_to_float (&rawData[0]); - destination[1] = uint32_reg_to_float (&rawData[4]); - destination[2] = uint32_reg_to_float (&rawData[8]); - destination[3] = uint32_reg_to_float (&rawData[12]); // SENtral stores quats as qx, qy, qz, q0! - -} - -void 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 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 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]); -} - -void getMres() { - 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 - break; - case MFS_16BITS: - mRes = 10.*4912./32760.0; // Proper scale to return milliGauss - break; - } -} - -void getGres() { - 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; - break; - case GFS_500DPS: - gRes = 500.0/32768.0; - break; - case GFS_1000DPS: - gRes = 1000.0/32768.0; - break; - case GFS_2000DPS: - gRes = 2000.0/32768.0; - break; - } -} - -void getAres() { - 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; - break; - case AFS_4G: - aRes = 4.0/32768.0; - break; - case AFS_8G: - aRes = 8.0/32768.0; - break; - case AFS_16G: - aRes = 16.0/32768.0; - break; - } -} - - -void 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 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 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 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 initAK8963(float * destination) -{ - // 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.; - 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 initMPU9250() -{ - // 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 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 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] = {0xFF, 0xFF, 0xFF}, mag_min[3] = {0x7F, 0x7F, 0x7F}, 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*magCalibration[0]; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1]; - dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2]; - - // 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 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, FS<<3); // Set full scale range for the gyro to 250 dps - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, FS<<3); // Set full scale range for the accelerometer to 2 g - - for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer - - readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array - aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - - readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - } - - for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings - aAvg[ii] /= 200; - gAvg[ii] /= 200; - } - -// Configure the accelerometer for self-test - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g - writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s - delay(25); // Delay a while to let the device stabilize - - for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer - - readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array - aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - - readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - } - - for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings - aSTAvg[ii] /= 200; - gSTAvg[ii] /= 200; - } - - // Configure the gyro and accelerometer for normal operation - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); - writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); - delay(25); // Delay a while to let the device stabilize - - // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg - selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results - selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results - selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results - selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results - selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results - selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results - - // Retrieve factory self-test value from self-test code reads - factoryTrim[0] = (float)(2620/1< 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - - -// 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 MS5637Reset() - { - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(MS5637_RESET); // Put reset command in Tx buffer - Wire.endTransmission(); // Send the Tx buffer - } - - void MS5637PromRead(uint16_t * destination) - { - uint8_t data[2] = {0,0}; - for (uint8_t ii = 0; ii < 7; ii++) { - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(0xA0 | ii << 1); // Put PROM address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(MS5637_ADDRESS, 2); // Read two bytes from slave PROM address - while (Wire.available()) { - data[i++] = Wire.read(); } // Put read results in the Rx buffer - destination[ii] = (uint16_t) (((uint16_t) data[0] << 8) | data[1]); // construct PROM data for return to main program - } - } - - uint32_t MS5637Read(uint8_t CMD, uint8_t OSR) // temperature data read - { - uint8_t data[3] = {0,0,0}; - Wire.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(CMD | OSR); // Put pressure conversion command in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - - 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.beginTransmission(MS5637_ADDRESS); // Initialize the Tx buffer - Wire.write(0x00); // Put ADC read command in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(MS5637_ADDRESS, 3); // Read three bytes from slave PROM address - while (Wire.available()) { - data[i++] = Wire.read(); } // Put read results in the Rx buffer - 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 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); -} - - - - - - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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 and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} diff --git a/FirmwareUpload.ino b/FirmwareUpload.ino deleted file mode 100644 index cf70ebc..0000000 --- a/FirmwareUpload.ino +++ /dev/null @@ -1,382 +0,0 @@ -#include -#include - -#define SD_CS 10 -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 - -// Using the Teensy Mini Add-On board, BMX055 SDO1 = SDO2 = CSB3 = GND as designed -// Seven-bit BMX055 device addresses are ACC = 0x18, GYRO = 0x68, MAG = 0x10 -#define BMX055_ACC_ADDRESS 0x18 // Address of BMX055 accelerometer -#define BMX055_GYRO_ADDRESS 0x68 // Address of BMX055 gyroscope -#define BMX055_MAG_ADDRESS 0x10 // Address of BMX055 magnetometer -#define MS5637_ADDRESS 0x76 // Address of MS5637 altimeter -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DFM EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DFM lockable EEPROM ID page - -SdFat SD; -SdFile sd_file; - -void setup() { - - // Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - - Serial.begin(9600); - delay(5000); - - while (!SD.begin(SD_CS, SPI_HALF_SPEED)) { - Serial.println("failed to init sd"); - Serial.printf("err: %02x\n", SD.card()->errorCode()); - } - Serial.println("sd init"); - - I2Cscan(); - -// Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - I2Cscan(); - - sd_file.open("/EM6500.fw", O_RDONLY); - Serial.println("File Open!"); - - uint8_t buffer[128]; - uint8_t numbytes= 0, MSadd = 0, totnum = 0; - - Serial.println("erasing EEPROM"); - uint8_t eraseBuffer[128] = { - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; - - for (MSadd = 0; MSadd < 256; MSadd++) { // MS address byte, 0 to 255 - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, MSadd, 0x00, 128, eraseBuffer); // write data starting at first byte of page MSadd - delay(100); - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, MSadd, 0x80, 128, eraseBuffer); // write data starting at 128th byte of page MSadd - delay(100); - - totnum++; - if (MSadd = 255) { break; } - Serial.print("totnum"); Serial.println(totnum); - Serial.print("MSadd 0x"); Serial.println(MSadd, HEX); - } - - // Verify EEPROM ihas been erased - // Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM first page"); - - for (int i = 0; i < 16; i++) { - Serial.println(" "); - - for (int j = 0; j < 8; j++) { - Serial.print(data[i*8 + j], HEX); Serial.print(" "); - } - } - - // Read second page of EEPROM - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x80, 128, data); - Serial.println("");Serial.println("EEPROM second page"); - - for (int i = 0; i < 16; i++) { - Serial.println(" "); - - for (int j = 0; j < 8; j++) { - Serial.print(data[i*8 + j], HEX); Serial.print(" "); - } - } - - // Read third page of EEPROM - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x01, 0x00, 128, data); - Serial.println("");Serial.println("EEPROM third page"); - - for (int i = 0; i < 16; i++) { - Serial.println(" "); - - for (int j = 0; j < 8; j++) { - Serial.print(data[i*8 + j], HEX); Serial.print(" "); - } - } - - // write configuration file to EEPROM - Serial.println("writing data to EEPROM"); - for (MSadd = 0; MSadd < 256; MSadd++) { // MS address byte, 0 to 255 - numbytes = sd_file.read(buffer, 128); // 128 bytes per page, 500 pages - Serial.print("first two bytes: "); Serial.print("0x"); Serial.print(buffer[0], HEX); Serial.print("0x"); Serial.println(buffer[1], HEX); - Serial.print("Number of bytes = "); Serial.println(numbytes); // print number of bytes read - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, MSadd, 0x00, 128, buffer); // write data starting at first byte of page MSadd - delay(100); - numbytes = sd_file.read(buffer, 128); // 128 bytes per page, 500 pages - Serial.print("first two bytes: "); Serial.print("0x"); Serial.print(buffer[0], HEX); Serial.print("0x"); Serial.println(buffer[1], HEX); - Serial.print("Number of bytes = "); Serial.println(numbytes); // print number of bytes read - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, MSadd, 0x80, 128, buffer); // write data starting at 128th byte of page MSadd - delay(100); - - if (numbytes < 128) { break; } - totnum++; - Serial.print("totnum"); Serial.println(totnum); - Serial.print("MSadd 0x"); Serial.println(MSadd, HEX); - } - - - // Read first page of EEPROM - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM first page"); - - for (int i = 0; i < 16; i++) { - Serial.println(" "); - - for (int j = 0; j < 8; j++) { - Serial.print(data[i*8 + j], HEX); Serial.print(" "); - } - } - - // Read second page of EEPROM - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x80, 128, data); - Serial.println("");Serial.println("EEPROM second page"); - - for (int i = 0; i < 16; i++) { - Serial.println(" "); - - for (int j = 0; j < 8; j++) { - Serial.print(data[i*8 + j], HEX); Serial.print(" "); - } - } - - // Read third page of EEPROM - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x01, 0x00, 128, data); - Serial.println("");Serial.println("EEPROM third page"); - - for (int i = 0; i < 16; i++) { - Serial.println(" "); - - for (int j = 0; j < 8; j++) { - Serial.print(data[i*8 + j], HEX); Serial.print(" "); - } - } - - -} - -void loop() { -} - -// I2C read/write functions for the MPU9250 and AK8963 sensors - - void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - - -void SENtralPassThroughMode() -{ - // First put SENtral in standby mode - uint8_t c = readByte(EM7180_ADDRESS, EM7180_AlgorithmControl); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, c | 0x01); -// c = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); -// Serial.print("c = "); Serial.println(c); -// Verify standby status -// if(readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus) & 0x01) { - Serial.println("SENtral in standby mode"); - // Place SENtral in pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - if(readByte(EM7180_ADDRESS, EM7180_PassThruStatus) & 0x01) { - Serial.println("SENtral in pass-through mode"); - } - else { - Serial.println("ERROR! SENtral not in pass-through mode!"); - } -} - - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - - void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - - - void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - if(count > 128) { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - - 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 - for(uint8_t i=0; i < count; i++) { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - - - uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.requestFrom(address, 1); // Read one byte from slave register address - Wire.requestFrom(device_address, (size_t) 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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive -// Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; -// Wire.requestFrom(address, count); // Read bytes from slave register address - Wire.requestFrom(device_address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) { - dest[i++] = Wire.read(); } // Put read results in the Rx buffer -} - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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"); -} diff --git a/README.md b/README.md index b3e4a56..afd9508 100644 --- a/README.md +++ b/README.md @@ -1,20 +1,2 @@ -EM7180_SENtral_sensor_hub -========================= - -![](https://cloud.githubusercontent.com/assets/6698410/11551753/019db928-9931-11e5-99bf-5ede3555a8d8.jpg) - -*EM7180 sensor hub with Invensense's MPU9250 gyro/accelerometer with embedded Asahi Kasei AK8963C magnetometer, Measurement Specialties' MS5637 Barometer, and ST's M24512DFC I2C EEPROM on a board directly mountable onto the Teensy Cortex ARM M4 microcontroller.* - -There are two kinds of files in this repository. - -The FirmwareUpload.ino file is a sketch that takes the firmware file xxx.fw (~22 kbyte) generated by the EM7180 [SENtral Tool Kit Configuration](http://www.emdeveloper.com/?page_id=105) tool and writes it to an ST Microelectronics M24512DFM/C EEPROM from an SD card. Both the SD card and the [SENtral breakout board](https://www.tindie.com/products/onehorse/em7180-sentral-sensor-hub-with-bmx055-motion-sensor/) need to be connected to a microcontroller; I use the Teensy 3.1. The SENtral breakout board is connected to the Teensy 3.1 I2C port on pins 16 and 17 and the SD card reader is connected to the SPI port on pins 10-13. Once the firmware is loaded onto the EEPROM it doesn't have to be done again unless the firmware changes or is updated; the SENtral reads the firmware upon power on and gets the information it needs about the particular sensors on the board. - -The other files are sketches that further configure the SENtral for either normal mode, where it manages the BMX055 or LSM9DS0 or MPU6500+AK8963C sensors as slaves providing scaled sensor output and quaternions,or pass-through mode, where the Teensy microcontroller can directly communicate with the BMX055 or LSM9DS0 or MPU6500+AK8963C motion sensors and the MS5637/BMP280 pressure sensor. - -These are the three major motion sensor inputs I am planning to implement in the short term. These will allow me to test the dependence of the quality of the motion sensor input data on the resulting sensor fusion solution using the same fusion algorithms and fusion engine. - -The SENtral is configurable and the firmware, including the sensor fusion algorithms, can be programmed by the (sophisticated) user. It's just not easy. - -Later, I will add altimetry to the sensor fusion algorithm as well as some other refinements. This is a great platform for testing sensor fusion algorithms and new motion sensors. - -This project is a work in progress... +STM32 Driver for the newest Ultimate Sensor Fusion Solution using the latest ST motion sensors: combination accel/gyro LSM6DSM, magnetometer LIS2MDL, and barometer LPS22HB. Now sold on [Tindie](https://www.tindie.com/products/onehorse/ultimate-sensor-fusion-solution-lsm6dsm--lis2md/). +![image](https://user-images.githubusercontent.com/6698410/41677606-a1207402-747d-11e8-9f83-f1c51f899ab4.jpg) diff --git a/WarmStart/EM7180_MPU9250_BMP280_M24512DFC_WS b/WarmStart/EM7180_MPU9250_BMP280_M24512DFC_WS deleted file mode 100644 index 411a3f7..0000000 --- a/WarmStart/EM7180_MPU9250_BMP280_M24512DFC_WS +++ /dev/null @@ -1,1774 +0,0 @@ -/* EM7180_MPU9250_BMP280_M24512DFC Basic Example Code - by: Kris Winer - date: September 11, 2015 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the MPU9250 (with embedded MPU9250 + AK8963C), and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DRC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the MPU9250 9-axis motion sensor (accel/gyro/mag) as slave, a BMP280 pressure/temperature sensor, and an M24512DRC - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral can use the pressure data in the sensor fusion - yet and there is a driver for the BMP280 in the SENtral firmware. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The BMP280 is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+MPU9250+BMP280+M24512DRC Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: All the sensors n this board are I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensors are not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ - -#include "Arduino.h" -#include "Globals.h" -#include -#include - -#define SerialDebug true -//#define SerialDebug false - -bool passThru = false; - -void setup() -{ - // Setup for Master mode, pins 16/17, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(100); - - // Read Acc offset info - //eeprom->readGlobalSet(); - delay(100); - Serial.begin(115200); - delay(5000); - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, LOW); - - // should detect SENtral at 0x28 - I2Cscan(); - - // 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"); - - // Give some time to read the screen - delay(1000); - - // 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"); - - // Give some time to read the screen - delay(1000); - - // 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!"); - - // Take user input to choose Warm Start or not... - // "1" from the keboard is ASCII "1" which gives integer value 49 - // "0" from the keboard is ASCII "0" which gives integer value 48 - Serial.println("Send '1' for Warm Start, '0' for no Warm Start"); - serial_input = Serial.read(); - while(!(serial_input == 49) && !(serial_input == 48)) - { - serial_input = Serial.read(); - delay(500); - } - if(serial_input == 49) - { - warm_start = 1; - } else - { - warm_start = 0; - } - if(warm_start) - { - Serial.println("!!!Warm Start active!!!"); - - // Put the Sentral in pass-thru mode - WS_PassThroughMode(); - - // Fetch the WarmStart data from the M24512DFM I2C EEPROM - readSenParams(); - - // Take Sentral out of pass-thru mode and re-start algorithm - WS_Resume(); - } else - { - Serial.println("***No Warm Start***"); - } - - // Reset Sentral after - - // Give some time to read the screen - delay(1000); - - // Set up the SENtral as sensor bus in normal operating mode - if(!passThru) - { - // Set SENtral in initialized state to configure registers - writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x00); - - // Insert Acc Cal upload here when the time comes... - - // Force initialize - writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x01); - - // Load Warm Start parameters - if(warm_start) - { - EM7180_set_WS_params(); - } - - // Set SENtral in initialized state to configure registers - writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x00); - - //Setup LPF bandwidth (BEFORE setting ODR's) - writeByte(EM7180_ADDRESS, EM7180_ACC_LPF_BW, 0x03); // 41 Hz - writeByte(EM7180_ADDRESS, EM7180_GYRO_LPF_BW, 0x03); // 42 Hz - - // Set accel/gyro/mage desired ODR rates - writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 100 Hz - writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x64); // 100 Hz - writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x14); // 200/10 Hz - writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x14); // 200/10 Hz - writeByte(EM7180_ADDRESS, EM7180_BaroRate, 0x80 | 0x32); // set enable bit and set Baro rate to 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 - EM7180_set_integer_param (0x49, 0x00); - - //Write desired sensor full scale ranges to the EM7180 - EM7180_set_mag_acc_FS (0x3E8, 0x08); // 1000 uT, 8 g - EM7180_set_gyro_FS (0x7D0); // 2000 dps - - // 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"); - - // Give some time to read the screen - delay(1000); - - // 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"); - Serial.println(""); Serial.println("*******************************************"); - Serial.println("Send '1' to store Warm Start configuration"); - Serial.println("*******************************************"); Serial.println(""); - - // Give some time to read the screen - delay(1000); - } - - // If pass through mode desired, set it up here - if(passThru) - { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - I2Cscan(); - - // Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) - { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - // Read the WHO_AM_I register, this is a good test of communication - Serial.println("MPU9250 9-axis motion sensor..."); - byte c = readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 - Serial.print("MPU9250 "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x71, HEX); - if (c == 0x71) // WHO_AM_I should always be 0x71 - { - Serial.println("MPU9250 is online..."); - MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values - Serial.print("x-axis self test: acceleration trim within : "); Serial.print(SelfTest[0],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: acceleration trim within : "); Serial.print(SelfTest[1],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: acceleration trim within : "); Serial.print(SelfTest[2],1); Serial.println("% of factory value"); - Serial.print("x-axis self test: gyration trim within : "); Serial.print(SelfTest[3],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: gyration trim within : "); Serial.print(SelfTest[4],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: gyration trim within : "); Serial.print(SelfTest[5],1); Serial.println("% of factory value"); - - delay(1000); - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - getMres(); - - Serial.println(" Calibrate gyro and accel"); - accelgyrocalMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - delay(1000); - - initMPU9250(); - Serial.println("MPU9250 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - - // Read the WHO_AM_I register of the magnetometer, this is a good test of communication - byte d = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for AK8963 - Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x48, HEX); - - delay(1000); - - // Get magnetometer calibration from AK8963 ROM - // Initialize device for active mode read of magnetometer - initAK8963(magCalibration); Serial.println("AK8963 initialized for active data mode...."); - - magcalMPU9250(magBias, magScale); - Serial.println("AK8963 mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]); - Serial.println("AK8963 mag scale (mG)"); Serial.println(magScale[0]); Serial.println(magScale[1]); Serial.println(magScale[2]); - delay(2000); // add delay to see results before serial spew of data - - if(SerialDebug) - { - Serial.print("X-Axis sensitivity adjustment value "); Serial.println(magCalibration[0], 2); - Serial.print("Y-Axis sensitivity adjustment value "); Serial.println(magCalibration[1], 2); - Serial.print("Z-Axis sensitivity adjustment value "); Serial.println(magCalibration[2], 2); - } - - delay(1000); - - // Read the WHO_AM_I register of the BMP280 this is a good test of communication - // Read WHO_AM_I register for BMP280 - byte f = readByte(BMP280_ADDRESS, BMP280_ID); - Serial.print("BMP280 "); - Serial.print("I AM "); - Serial.print(f, HEX); - Serial.print(" I should be "); - Serial.println(0x58, HEX); - Serial.println(" "); - - delay(1000); - - // reset BMP280 before initilization - writeByte(BMP280_ADDRESS, BMP280_RESET, 0xB6); - - delay(100); - - // Initialize BMP280 altimeter - BMP280Init(); - Serial.println("Calibration coeficients:"); - Serial.print("dig_T1 ="); - Serial.println(dig_T1); - Serial.print("dig_T2 ="); - Serial.println(dig_T2); - Serial.print("dig_T3 ="); - Serial.println(dig_T3); - Serial.print("dig_P1 ="); - Serial.println(dig_P1); - Serial.print("dig_P2 ="); - Serial.println(dig_P2); - Serial.print("dig_P3 ="); - Serial.println(dig_P3); - Serial.print("dig_P4 ="); - Serial.println(dig_P4); - Serial.print("dig_P5 ="); - Serial.println(dig_P5); - Serial.print("dig_P6 ="); - Serial.println(dig_P6); - Serial.print("dig_P7 ="); - Serial.println(dig_P7); - Serial.print("dig_P8 ="); - Serial.println(dig_P8); - Serial.print("dig_P9 ="); - Serial.println(dig_P9); - - delay(1000); - } - else - { - Serial.print("Could not connect to MPU9250: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } - } -} - -void loop() -{ - if(!passThru) - { - serial_input = Serial.read(); - if (serial_input == 49) - { - delay(100); - EM7180_get_WS_params(); - - // Put the Sentral in pass-thru mode - WS_PassThroughMode(); - - // Store WarmStart data to the M24512DFM I2C EEPROM - writeSenParams(); - - // Take Sentral out of pass-thru mode and re-start algorithm - WS_Resume(); - warm_start_saved = 1; - } - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - // Error detected, what is it? - if(eventStatus & 0x02) - { - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) - { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if(errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus == 0x14) Serial.print("Gyro failure!"); - if(errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus == 0x30) Serial.print("Math error!"); - if(errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - // Handle errors ToDo - } - // if no errors, see if new data is ready - // new acceleration data available - if(eventStatus & 0x10) - { - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - } - - if(eventStatus & 0x20) - { - // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - - if(eventStatus & 0x08) - { - // new mag data available - readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - // get actual G value - mx = (float)magCount[0]*0.305176; - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) // new quaternions available - { - readSENtralQuatData(Quat); - } - - // get BMP280 pressure - // new baro data available - - if(eventStatus & 0x40) - { - rawPressure = readSENtralBaroData(); - pressure = (float)rawPressure*0.01f +1013.25f; // pressure in mBar - - // get BMP280 temperature - rawTemperature = readSENtralTempData(); - temperature = (float) rawTemperature*0.01; // temperature in degrees C - } - } - - if(passThru) - { - // If intPin goes high, all data registers have new data - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the acceleration value into actual g's - ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes - accelBias[1]; - az = (float)accelCount[2]*aRes - accelBias[2]; - - // Read the x/y/z adc values - readGyroData(gyroCount); - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes; - gz = (float)gyroCount[2]*gRes; - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - mx = (float)magCount[0]*mRes*magCalibration[0] - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes*magCalibration[1] - magBias[1]; - mz = (float)magCount[2]*mRes*magCalibration[2] - magBias[2]; - } - - // keep track of rates - Now = micros(); - - // set integration time by time elapsed since last filter update - deltat = ((Now - lastUpdate)/1000000.0f); - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer is aligned with the -y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ up) is aligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // For the BMX-055, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like - // in the MPU9250 sensor. This rotation can be modified to allow any convenient orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); -// if(passThru)MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, mx, mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - - // update LCD once per half-second independent of read rate - if (delt_t > 500) - { - - if(SerialDebug) - { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print( (int)mx); - Serial.print(" my = "); Serial.print( (int)my); - Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG"); - Serial.println("Software quaternions (ENU):"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions (NED):"); - Serial.print("Q0 = "); Serial.print(Quat[0]); - Serial.print(" Qx = "); Serial.print(Quat[1]); - Serial.print(" Qy = "); Serial.print(Quat[2]); - Serial.print(" Qz = "); Serial.println(Quat[3]); - } - if(passThru) - { - rawPress = readBMP280Pressure(); - pressure = (float) bmp280_compensate_P(rawPress)/25600.; // Pressure in mbar - rawTemp = readBMP280Temperature(); - temperature = (float) bmp280_compensate_T(rawTemp)/100.; - } - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(yaw < 0) yaw += 360.0f; // Ensure yaw stays between 0 and 360 - roll *= 180.0f / PI; - - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(Yaw < 0) Yaw += 360.0f ; // Ensure yaw stays between 0 and 360 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 360) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - - if(SerialDebug) - { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - Serial.println("BMP280:"); - Serial.print("Altimeter temperature = "); - Serial.print( temperature, 2); - Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); - Serial.print(9.*temperature/5. + 32., 2); - Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); - Serial.print(pressure, 2); - Serial.println(" mbar");// pressure in millibar - altitude = 145366.45f*(1.0f - pow((pressure/1013.25f), 0.190284f)); - Serial.print("Altitude = "); - Serial.print(altitude, 2); - Serial.println(" feet"); - Serial.println(" "); - if(warm_start_saved) - { - Serial.println("Warm Start configuration saved!"); - } else - { - Serial.println("Send '1' to store Warm Start configuration"); - } - } - Serial.print(millis()/1000.0, 1);Serial.print(","); - Serial.print(yaw); Serial.print(",");Serial.print(pitch); Serial.print(",");Serial.print(roll); Serial.print(","); - Serial.print(Yaw); Serial.print(",");Serial.print(Pitch); Serial.print(",");Serial.println(Roll); - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } -} - -//=================================================================================================================== -//====== Sentral parameter management functions -//=================================================================================================================== - -void 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 - - // Parameter 75; 0xCB is 75 decimal with the MSB set high to indicate a paramter write processs - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0xCB); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - 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 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 - - // Parameter 74; 0xCA is 74 decimal with the MSB set high to indicate a paramter write processs - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0xCA); - - //Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==0xCA)) { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm -} - -void 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); - - // Parameter is the decimal value with the MSB set high to indicate a paramter write processs - param = param | 0x80; - 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); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm -} - -void EM7180_set_float_param (uint8_t param, float param_val) { - uint8_t bytes[4], STAT; - float_to_bytes (param_val, &bytes[0]); - - // Parameter is the decimal value with the MSB set high to indicate a paramter write processs - param = param | 0x80; - 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); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm -} - -void EM7180_set_WS_params() -{ - uint8_t param = 1; - uint8_t STAT; - - // Parameter is the decimal value with the MSB set high to indicate a paramter write processs - param = param | 0x80; - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, WS_params.Sen_param[0][0]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, WS_params.Sen_param[0][1]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, WS_params.Sen_param[0][2]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, WS_params.Sen_param[0][3]); - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) - { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - for(uint8_t i=1; i<35; i++) - { - param = (i+1) | 0x80; - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, WS_params.Sen_param[i][0]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, WS_params.Sen_param[i][1]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, WS_params.Sen_param[i][2]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, WS_params.Sen_param[i][3]); - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) - { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); -} - -void EM7180_get_WS_params() -{ - uint8_t param = 1; - uint8_t STAT; - - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - delay(10); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - delay(10); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) - { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - - // Parameter is the decimal value with the MSB set low (default) to indicate a paramter read processs - WS_params.Sen_param[0][0] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); - WS_params.Sen_param[0][1] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); - WS_params.Sen_param[0][2] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); - WS_params.Sen_param[0][3] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte3); - - for(uint8_t i=1; i<35; i++) - { - param = (i+1); - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - delay(10); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) - { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - WS_params.Sen_param[i][0] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); - WS_params.Sen_param[i][1] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); - WS_params.Sen_param[i][2] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); - WS_params.Sen_param[i][3] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte3); - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); - - // Re-start algorithm - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); -} - -void WS_PassThroughMode() -{ - uint8_t stat = 0; - - // First put SENtral in standby mode - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x01); - delay(5); - - // Place SENtral in pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - delay(5); - stat = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); - while(!(stat & 0x01)) - { - stat = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); - delay(5); - } -} - -void WS_Resume() -{ - uint8_t stat = 0; - - // Cancel pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x00); - delay(5); - stat = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); - while((stat & 0x01)) - { - stat = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); - delay(5); - } - - // Re-start algorithm - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); - delay(5); - stat = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); - while((stat & 0x01)) - { - stat = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); - delay(5); - } -} - -void readSenParams() -{ - uint8_t data[140]; - uint8_t paramnum; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x80, 12, &data[128]); // Page 255 - delay(100); - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x00, 128, &data[0]); // Page 254 - for (paramnum = 0; paramnum < 35; paramnum++) // 35 parameters - { - for (uint8_t i= 0; i < 4; i++) - { - WS_params.Sen_param[paramnum][i] = data[(paramnum*4 + i)]; - } - } -} - -void writeSenParams() -{ - uint8_t data[140]; - uint8_t paramnum; - for (paramnum = 0; paramnum < 35; paramnum++) // 35 parameters - { - for (uint8_t i= 0; i < 4; i++) - { - data[(paramnum*4 + i)] = WS_params.Sen_param[paramnum][i]; - } - } - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x80, 12, &data[128]); // Page 255 - delay(100); - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x00, 128, &data[0]); // Page 254 -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== - -float 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; -} - -void 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 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[0] = uint32_reg_to_float (&rawData[0]); - destination[1] = uint32_reg_to_float (&rawData[4]); - destination[2] = uint32_reg_to_float (&rawData[8]); - destination[3] = uint32_reg_to_float (&rawData[12]); // SENtral stores quats as qx, qy, qz, q0! - -} - -void 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 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 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]); -} - -void getMres() { - 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 - break; - case MFS_16BITS: - mRes = 10.*4912./32760.0; // Proper scale to return milliGauss - break; - } -} - -void getGres() { - 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; - break; - case GFS_500DPS: - gRes = 500.0/32768.0; - break; - case GFS_1000DPS: - gRes = 1000.0/32768.0; - break; - case GFS_2000DPS: - gRes = 2000.0/32768.0; - break; - } -} - -void getAres() { - 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; - break; - case AFS_4G: - aRes = 4.0/32768.0; - break; - case AFS_8G: - aRes = 8.0/32768.0; - break; - case AFS_16G: - aRes = 16.0/32768.0; - break; - } -} - - -void 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 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 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 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 initAK8963(float * destination) -{ - // 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.; - 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 initMPU9250() -{ - // 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 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 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] = {0xFF, 0xFF, 0xFF}, mag_min[3] = {0x7F, 0x7F, 0x7F}, 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*magCalibration[0]; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1]; - dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2]; - - // 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 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, FS<<3); // Set full scale range for the gyro to 250 dps - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, FS<<3); // Set full scale range for the accelerometer to 2 g - - for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer - - readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array - aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - - readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - } - - for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings - aAvg[ii] /= 200; - gAvg[ii] /= 200; - } - -// Configure the accelerometer for self-test - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g - writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s - delay(25); // Delay a while to let the device stabilize - - for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer - - readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array - aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - - readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - } - - for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings - aSTAvg[ii] /= 200; - gSTAvg[ii] /= 200; - } - - // Configure the gyro and accelerometer for normal operation - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); - writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); - delay(25); // Delay a while to let the device stabilize - - // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg - selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results - selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results - selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results - selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results - selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results - selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results - - // Retrieve factory self-test value from self-test code reads - factoryTrim[0] = (float)(2620/1<> 4); -} - -int32_t readBMP280Pressure() -{ - uint8_t rawData[3]; // 20-bit pressure register data stored here - readBytes(BMP280_ADDRESS, BMP280_PRESS_MSB, 3, &rawData[0]); - return (int32_t) (((int32_t) rawData[0] << 16 | (int32_t) rawData[1] << 8 | rawData[2]) >> 4); -} - -void BMP280Init() -{ - // Configure the BMP280 - // Set T and P oversampling rates and sensor mode - writeByte(BMP280_ADDRESS, BMP280_CTRL_MEAS, Tosr << 5 | Posr << 2 | Mode); - // Set standby time interval in normal mode and bandwidth - writeByte(BMP280_ADDRESS, BMP280_CONFIG, SBy << 5 | IIRFilter << 2); - // Read and store calibration data - uint8_t calib[24]; - readBytes(BMP280_ADDRESS, BMP280_CALIB00, 24, &calib[0]); - dig_T1 = (uint16_t)(((uint16_t) calib[1] << 8) | calib[0]); - dig_T2 = ( int16_t)((( int16_t) calib[3] << 8) | calib[2]); - dig_T3 = ( int16_t)((( int16_t) calib[5] << 8) | calib[4]); - dig_P1 = (uint16_t)(((uint16_t) calib[7] << 8) | calib[6]); - dig_P2 = ( int16_t)((( int16_t) calib[9] << 8) | calib[8]); - dig_P3 = ( int16_t)((( int16_t) calib[11] << 8) | calib[10]); - dig_P4 = ( int16_t)((( int16_t) calib[13] << 8) | calib[12]); - dig_P5 = ( int16_t)((( int16_t) calib[15] << 8) | calib[14]); - dig_P6 = ( int16_t)((( int16_t) calib[17] << 8) | calib[16]); - dig_P7 = ( int16_t)((( int16_t) calib[19] << 8) | calib[18]); - dig_P8 = ( int16_t)((( int16_t) calib[21] << 8) | calib[20]); - dig_P9 = ( int16_t)((( int16_t) calib[23] << 8) | calib[22]); -} - -// Returns temperature in DegC, resolution is 0.01 DegC. Output value of -// “5123” equals 51.23 DegC. -int32_t bmp280_compensate_T(int32_t adc_T) -{ - int32_t var1, var2, T; - var1 = ((((adc_T >> 3) - ((int32_t)dig_T1 << 1))) * ((int32_t)dig_T2)) >> 11; - var2 = (((((adc_T >> 4) - ((int32_t)dig_T1)) * ((adc_T >> 4) - ((int32_t)dig_T1))) >> 12) * ((int32_t)dig_T3)) >> 14; - t_fine = var1 + var2; - T = (t_fine * 5 + 128) >> 8; - return T; -} - -// Returns pressure in Pa as unsigned 32 bit integer in Q24.8 format (24 integer bits and 8 -//fractional bits). -//Output value of “24674867” represents 24674867/256 = 96386.2 Pa = 963.862 hPa -uint32_t bmp280_compensate_P(int32_t adc_P) -{ - long long var1, var2, p; - var1 = ((long long)t_fine) - 128000; - var2 = var1 * var1 * (long long)dig_P6; - var2 = var2 + ((var1*(long long)dig_P5)<<17); - var2 = var2 + (((long long)dig_P4)<<35); - var1 = ((var1 * var1 * (long long)dig_P3)>>8) + ((var1 * (long long)dig_P2)<<12); - var1 = (((((long long)1)<<47)+var1))*((long long)dig_P1)>>33; - if(var1 == 0) - { - return 0; - // avoid exception caused by division by zero - } - p = 1048576 - adc_P; - p = (((p<<31) - var2)*3125)/var1; - var1 = (((long long)dig_P9) * (p>>13) * (p>>13)) >> 25; - var2 = (((long long)dig_P8) * p)>> 19; - p = ((p + var1 + var2) >> 8) + (((long long)dig_P7)<<4); - return (uint32_t)p; -} - -//=================================================================================================================== -//====== I2C Communication Support Functions -//=================================================================================================================== - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - -void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - -void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - if(count > 128) - { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - 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 - for(uint8_t i=0; i < count; i++) - { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - -uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - Wire.requestFrom(device_address, (size_t)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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(device_address, (size_t)count); // Read bytes from slave register address - while (Wire.available()) - { - dest[i++] = Wire.read(); - } // Put read results in the Rx buffer -} - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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 and AK8963 sensors - -void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - -uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) - { - dest[i++] = Wire.read(); - } // Put read results in the Rx buffer -} diff --git a/WarmStart/Globals.h b/WarmStart/Globals.h deleted file mode 100644 index 8d23f95..0000000 --- a/WarmStart/Globals.h +++ /dev/null @@ -1,524 +0,0 @@ -#ifndef Globals_h -#define Globals_h - -/*************************************************************************************************/ -/************* ***************/ -/************* Parameter Definitions ***************/ -/************* ***************/ -/*************************************************************************************************/ - -// These are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Kp 2.0f * 5.0f -#define Ki 0.0f - -// BMP280 registers -#define BMP280_TEMP_XLSB 0xFC -#define BMP280_TEMP_LSB 0xFB -#define BMP280_TEMP_MSB 0xFA -#define BMP280_PRESS_XLSB 0xF9 -#define BMP280_PRESS_LSB 0xF8 -#define BMP280_PRESS_MSB 0xF7 -#define BMP280_CONFIG 0xF5 -#define BMP280_CTRL_MEAS 0xF4 -#define BMP280_STATUS 0xF3 -#define BMP280_RESET 0xE0 -#define BMP280_ID 0xD0 // should be 0x58 -#define BMP280_CALIB00 0x88 - -// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in -// above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map -// -//Magnetometer Registers -#define AK8963_ADDRESS 0x0C -#define WHO_AM_I_AK8963 0x00 // should return 0x48 -#define INFO 0x01 -#define AK8963_ST1 0x02 // data ready status bit 0 -#define AK8963_XOUT_L 0x03 // data -#define AK8963_XOUT_H 0x04 -#define AK8963_YOUT_L 0x05 -#define AK8963_YOUT_H 0x06 -#define AK8963_ZOUT_L 0x07 -#define AK8963_ZOUT_H 0x08 -#define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 -#define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 -#define AK8963_ASTC 0x0C // Self test control -#define AK8963_I2CDIS 0x0F // I2C disable -#define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value -#define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value -#define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value - -#define SELF_TEST_X_GYRO 0x00 -#define SELF_TEST_Y_GYRO 0x01 -#define SELF_TEST_Z_GYRO 0x02 - -/*#define X_FINE_GAIN 0x03 // [7:0] fine gain -#define Y_FINE_GAIN 0x04 -#define Z_FINE_GAIN 0x05 -#define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer -#define XA_OFFSET_L_TC 0x07 -#define YA_OFFSET_H 0x08 -#define YA_OFFSET_L_TC 0x09 -#define ZA_OFFSET_H 0x0A -#define ZA_OFFSET_L_TC 0x0B */ - -#define SELF_TEST_X_ACCEL 0x0D -#define SELF_TEST_Y_ACCEL 0x0E -#define SELF_TEST_Z_ACCEL 0x0F - -#define SELF_TEST_A 0x10 - -#define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope -#define XG_OFFSET_L 0x14 -#define YG_OFFSET_H 0x15 -#define YG_OFFSET_L 0x16 -#define ZG_OFFSET_H 0x17 -#define ZG_OFFSET_L 0x18 -#define SMPLRT_DIV 0x19 -#define CONFIG 0x1A -#define GYRO_CONFIG 0x1B -#define ACCEL_CONFIG 0x1C -#define ACCEL_CONFIG2 0x1D -#define LP_ACCEL_ODR 0x1E -#define WOM_THR 0x1F - -#define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms -#define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] -#define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms - -#define FIFO_EN 0x23 -#define I2C_MST_CTRL 0x24 -#define I2C_SLV0_ADDR 0x25 -#define I2C_SLV0_REG 0x26 -#define I2C_SLV0_CTRL 0x27 -#define I2C_SLV1_ADDR 0x28 -#define I2C_SLV1_REG 0x29 -#define I2C_SLV1_CTRL 0x2A -#define I2C_SLV2_ADDR 0x2B -#define I2C_SLV2_REG 0x2C -#define I2C_SLV2_CTRL 0x2D -#define I2C_SLV3_ADDR 0x2E -#define I2C_SLV3_REG 0x2F -#define I2C_SLV3_CTRL 0x30 -#define I2C_SLV4_ADDR 0x31 -#define I2C_SLV4_REG 0x32 -#define I2C_SLV4_DO 0x33 -#define I2C_SLV4_CTRL 0x34 -#define I2C_SLV4_DI 0x35 -#define I2C_MST_STATUS 0x36 -#define INT_PIN_CFG 0x37 -#define INT_ENABLE 0x38 -#define DMP_INT_STATUS 0x39 // Check DMP interrupt -#define INT_STATUS 0x3A -#define ACCEL_XOUT_H 0x3B -#define ACCEL_XOUT_L 0x3C -#define ACCEL_YOUT_H 0x3D -#define ACCEL_YOUT_L 0x3E -#define ACCEL_ZOUT_H 0x3F -#define ACCEL_ZOUT_L 0x40 -#define TEMP_OUT_H 0x41 -#define TEMP_OUT_L 0x42 -#define GYRO_XOUT_H 0x43 -#define GYRO_XOUT_L 0x44 -#define GYRO_YOUT_H 0x45 -#define GYRO_YOUT_L 0x46 -#define GYRO_ZOUT_H 0x47 -#define GYRO_ZOUT_L 0x48 -#define EXT_SENS_DATA_00 0x49 -#define EXT_SENS_DATA_01 0x4A -#define EXT_SENS_DATA_02 0x4B -#define EXT_SENS_DATA_03 0x4C -#define EXT_SENS_DATA_04 0x4D -#define EXT_SENS_DATA_05 0x4E -#define EXT_SENS_DATA_06 0x4F -#define EXT_SENS_DATA_07 0x50 -#define EXT_SENS_DATA_08 0x51 -#define EXT_SENS_DATA_09 0x52 -#define EXT_SENS_DATA_10 0x53 -#define EXT_SENS_DATA_11 0x54 -#define EXT_SENS_DATA_12 0x55 -#define EXT_SENS_DATA_13 0x56 -#define EXT_SENS_DATA_14 0x57 -#define EXT_SENS_DATA_15 0x58 -#define EXT_SENS_DATA_16 0x59 -#define EXT_SENS_DATA_17 0x5A -#define EXT_SENS_DATA_18 0x5B -#define EXT_SENS_DATA_19 0x5C -#define EXT_SENS_DATA_20 0x5D -#define EXT_SENS_DATA_21 0x5E -#define EXT_SENS_DATA_22 0x5F -#define EXT_SENS_DATA_23 0x60 -#define MOT_DETECT_STATUS 0x61 -#define I2C_SLV0_DO 0x63 -#define I2C_SLV1_DO 0x64 -#define I2C_SLV2_DO 0x65 -#define I2C_SLV3_DO 0x66 -#define I2C_MST_DELAY_CTRL 0x67 -#define SIGNAL_PATH_RESET 0x68 -#define MOT_DETECT_CTRL 0x69 -#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP -#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode -#define PWR_MGMT_2 0x6C -#define DMP_BANK 0x6D // Activates a specific bank in the DMP -#define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank -#define DMP_REG 0x6F // Register in DMP from which to read or to which to write -#define DMP_REG_1 0x70 -#define DMP_REG_2 0x71 -#define FIFO_COUNTH 0x72 -#define FIFO_COUNTL 0x73 -#define FIFO_R_W 0x74 -#define WHO_AM_I_MPU9250 0x75 // Should return 0x71 -#define XA_OFFSET_H 0x77 -#define XA_OFFSET_L 0x78 -#define YA_OFFSET_H 0x7A -#define YA_OFFSET_L 0x7B -#define ZA_OFFSET_H 0x7D -#define ZA_OFFSET_L 0x7E - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_Baro 0x2A // start of two-byte MS5637 pressure data, 16-bit signed interger -#define EM7180_BaroTIME 0x2C // start of two-byte MS5637 pressure timestamp, 16-bit unsigned -#define EM7180_Temp 0x2E // start of two-byte MS5637 temperature data, 16-bit signed interger -#define EM7180_TempTIME 0x30 // start of two-byte MS5637 temperature timestamp, 16-bit unsigned -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ActualBaroRate 0x48 -#define EM7180_ActualTempRate 0x49 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_BaroRate 0x58 -#define EM7180_TempRate 0x59 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 -#define EM7180_ACC_LPF_BW 0x5B //Register GP36 -#define EM7180_GYRO_LPF_BW 0x5C //Register GP37 -#define EM7180_BARO_LPF_BW 0x5D //Register GP38 -#define EM7180_GP36 0x5B -#define EM7180_GP37 0x5C -#define EM7180_GP38 0x5D -#define EM7180_GP39 0x5E -#define EM7180_GP40 0x5F -#define EM7180_GP50 0x69 -#define EM7180_GP51 0x6A -#define EM7180_GP52 0x6B -#define EM7180_GP53 0x6C -#define EM7180_GP54 0x6D -#define EM7180_GP55 0x6E -#define EM7180_GP56 0x6F - -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DRC EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DRC lockable EEPROM ID page -#define MPU9250_ADDRESS 0x68 // Device address of MPU9250 when ADO = 0 -#define AK8963_ADDRESS 0x0C // Address of magnetometer -#define BMP280_ADDRESS 0x76 // Address of BMP280 altimeter when ADO = 0 - -/*************************************************************************************************/ -/************* ***************/ -/************* Enumerators and Structure Variables ***************/ -/************* ***************/ -/*************************************************************************************************/ - -// Set initial input parameters -enum Ascale { - AFS_2G = 0, - AFS_4G, - AFS_8G, - AFS_16G -}; - -enum Gscale { - GFS_250DPS = 0, - GFS_500DPS, - GFS_1000DPS, - GFS_2000DPS -}; - -enum Mscale { - MFS_14BITS = 0, // 0.6 mG per LSB - MFS_16BITS // 0.15 mG per LSB -}; - -enum Posr { - P_OSR_00 = 0, // no op - P_OSR_01, - P_OSR_02, - P_OSR_04, - P_OSR_08, - P_OSR_16 -}; - -enum Tosr { - T_OSR_00 = 0, // no op - T_OSR_01, - T_OSR_02, - T_OSR_04, - T_OSR_08, - T_OSR_16 -}; - -enum IIRFilter { - full = 0, // bandwidth at full sample rate - BW0_223ODR, - BW0_092ODR, - BW0_042ODR, - BW0_021ODR // bandwidth at 0.021 x sample rate -}; - -enum Mode { - BMP280Sleep = 0, - forced, - forced2, - normal -}; - -enum SBy { - t_00_5ms = 0, - t_62_5ms, - t_125ms, - t_250ms, - t_500ms, - t_1000ms, - t_2000ms, - t_4000ms, -}; - -struct global_conf_t -{ - uint8_t currentSet; - int16_t accZero_max[3]; - int16_t accZero_min[3]; - int16_t magZero[3]; - int16_t grav; - uint8_t checksum; // Last position in structure -}; - -struct Sentral_WS_params -{ - uint8_t Sen_param[35][4]; -}; - -/*************************************************************************************************/ -/************* ***************/ -/************* Global Scope Variables ***************/ -/************* ***************/ -/*************************************************************************************************/ - -// General purpose variables -int16_t serial_input; -static int16_t warm_start = 0; -static int16_t warm_start_saved = 0; - -// Specify BMP280 configuration -uint8_t Posr = P_OSR_16; -uint8_t Tosr = T_OSR_02; -uint8_t Mode = normal; -uint8_t IIRFilter = BW0_042ODR; -uint8_t SBy = t_62_5ms; - -// t_fine carries fine temperature as global value for BMP280 -int32_t t_fine; - -// Specify sensor full scale -uint8_t Gscale = GFS_250DPS; -uint8_t Ascale = AFS_2G; - -// Choose either 14-bit or 16-bit magnetometer resolution -uint8_t Mscale = MFS_16BITS; - -// 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read -uint8_t Mmode = 0x02; - -// scale resolutions per LSB for the sensors -float aRes; -float gRes; -float mRes; - -// Pin definitions -// These can be changed, 2 and 3 are the Arduinos ext int pins -int intPin = 8; - -// LED on the Teensy 3.1 -int myLed = 13; - -// BMP280 compensation parameters -uint16_t dig_T1; -uint16_t dig_P1; -int16_t dig_T2; -int16_t dig_T3; -int16_t dig_P2; -int16_t dig_P3; -int16_t dig_P4; -int16_t dig_P5; -int16_t dig_P6; -int16_t dig_P7; -int16_t dig_P8; -int16_t dig_P9; - -// stores BMP280 pressures sensor pressure and temperature -double Temperature; -double Pressure; - -// pressure and temperature raw count output for BMP280 -int32_t rawPress; -int32_t rawTemp; - -// MPU9250 variables -// Stores the 16-bit signed accelerometer sensor output -int16_t accelCount[3]; - -// Stores the 16-bit signed gyro sensor output -int16_t gyroCount[3]; - -// Stores the 16-bit signed magnetometer sensor output -int16_t magCount[3]; - -// quaternion data register -float Quat[4] = {0, 0, 0, 0}; - -// Factory mag calibration and mag bias -float magCalibration[3] = {0, 0, 0}; - -// Bias corrections for gyro, accelerometer, mag -float gyroBias[3] = {0, 0, 0}; -float accelBias[3] = {0, 0, 0}; -float magBias[3] = {0, 0, 0}; -float magScale[3] = {0, 0, 0}; - -// Pressure, temperature raw count output -int16_t tempCount; -int16_t rawPressure; -int16_t rawTemperature; - -// Stores the MPU9250 internal chip temperature in degrees Celsius -float temperature; -float pressure; -float altitude; - -// holds results of gyro and accelerometer self test -float SelfTest[6]; - -// Global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -// Gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasError = PI * (40.0f / 180.0f); - -// Gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); - -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. - -// Compute beta -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; - -// Compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; - -// Used to control display output rate -uint32_t delt_t = 0; -uint32_t count = 0; -uint32_t sumCount = 0; -float pitch; -float yaw; -float roll; -float Yaw; -float Pitch; -float Roll; - -// Integration interval for both filter schemes -float deltat = 0.0f; -float sum = 0.0f; - -// used to calculate integration interval -uint32_t lastUpdate = 0; -uint32_t firstUpdate = 0; - -// used to calculate integration interval -uint32_t Now = 0; - -// used for param transfer -uint8_t param[4]; - -// EM7180 sensor full scale ranges -uint16_t EM7180_mag_fs; -uint16_t EM7180_acc_fs; -uint16_t EM7180_gyro_fs; - -// variables to hold latest sensor data values -float ax; -float ay; -float az; -float gx; -float gy; -float gz; -float mx; -float my; -float mz; - -// Vector to hold quaternion -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; - -// Vector to hold integral error for Mahony method -float eInt[3] = {0.0f, 0.0f, 0.0f}; - -global_conf_t global_conf; -Sentral_WS_params WS_params; - -#endif // Globals_h diff --git a/WarmStart/Readme.md b/WarmStart/Readme.md deleted file mode 100644 index da30c02..0000000 --- a/WarmStart/Readme.md +++ /dev/null @@ -1 +0,0 @@ -These are the most recent host-side programs for the EM7180 reference board AKA Ultimate Sensor Fusion Solution available at [Tindie](https://www.tindie.com/products/onehorse/ultimate-sensor-fusion-solution/) and updated with the warm-start function which stores the dynamic calibration parameters on the on-board EEPROM so the device starts well-calibrated (given similar environmental conditions) upon subsequent power on. The code is designed to be used with the Teensy 3.Xmicrcontroller but with few changes any I2C-compatible micrcontroller will do. diff --git a/WarmStart/quaternionFilters b/WarmStart/quaternionFilters deleted file mode 100644 index 465dd61..0000000 --- a/WarmStart/quaternionFilters +++ /dev/null @@ -1,195 +0,0 @@ -#include "Arduino.h" - -// 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! - void 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 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 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; - - } diff --git a/WarmStartandAccelCal/EM71280_MPU9250_BMP280_M24512DFC_WS_Acc_Cal.ino b/WarmStartandAccelCal/EM71280_MPU9250_BMP280_M24512DFC_WS_Acc_Cal.ino deleted file mode 100644 index d71c525..0000000 --- a/WarmStartandAccelCal/EM71280_MPU9250_BMP280_M24512DFC_WS_Acc_Cal.ino +++ /dev/null @@ -1,1997 +0,0 @@ -/* EM7180_MPU9250_BMP280_t3 Basic Example Code - by: Kris Winer - date: September 11, 2015 - license: Beerware - Use this code however you'd like. If you - find it useful you can buy me a beer some time. - - The EM7180 SENtral sensor hub is not a motion sensor, but rather takes raw sensor data from a variety of motion sensors, - in this case the MPU9250 (with embedded MPU9250 + AK8963C), and does sensor fusion with quaternions as its output. The SENtral loads firmware from the - on-board M24512DRC 512 kbit EEPROM upon startup, configures and manages the sensors on its dedicated master I2C bus, - and outputs scaled sensor data (accelerations, rotation rates, and magnetic fields) as well as quaternions and - heading/pitch/roll, if selected. - - This sketch demonstrates basic EM7180 SENtral functionality including parameterizing the register addresses, initializing the sensor, - getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to - allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and - Mahony filter algorithms to compare with the hardware sensor fusion results. - Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. - - This sketch is specifically for the Teensy 3.1 Mini Add-On shield with the EM7180 SENtral sensor hub as master, - the MPU9250 9-axis motion sensor (accel/gyro/mag) as slave, a BMP280 pressure/temperature sensor, and an M24512DRC - 512kbit (64 kByte) EEPROM as slave all connected via I2C. The SENtral can use the pressure data in the sensor fusion - yet and there is a driver for the BMP280 in the SENtral firmware. - - This sketch uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. - The BMP280 is a simple but high resolution pressure sensor, which can be used in its high resolution - mode but with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of - only 1 microAmp. The choice will depend on the application. - - SDA and SCL should have external pull-up resistors (to 3.3V). - 4k7 resistors are on the EM7180+MPU9250+BMP280+M24512DRC Mini Add-On board for Teensy 3.1. - - Hardware setup: - EM7180 Mini Add-On ------- Teensy 3.1 - VDD ---------------------- 3.3V - SDA ----------------------- 17 - SCL ----------------------- 16 - GND ---------------------- GND - INT------------------------ 8 - - Note: All the sensors n this board are I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library. - Because the sensors are not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. - */ - -#include "Arduino.h" -#include "Globals.h" -#include -#include - -#define SerialDebug true -//#define SerialDebug false - -bool passThru = false; -//bool passThru = true; - -void setup() -{ - // Setup for Master mode, pins 16/17, external pullups, 400kHz for Teensy 3.1 - Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400); - delay(100); - - delay(100); - Serial.begin(115200); - delay(5000); - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, LOW); - - // should detect SENtral at 0x28 - I2Cscan(); - - // 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"); - - // Give some time to read the screen - delay(1000); - - // 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"); - - // Give some time to read the screen - delay(1000); - - // 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!"); - if(!passThru) - { - // Take user input to choose Warm Start or not... - // "1" from the keboard is ASCII "1" which gives integer value 49 - // "0" from the keboard is ASCII "0" which gives integer value 48 - Serial.println("Send '1' for Warm Start, '0' for no Warm Start"); - serial_input = Serial.read(); - while(!(serial_input == 49) && !(serial_input == 48)) - { - serial_input = Serial.read(); - delay(500); - } - if(serial_input == 49) - { - warm_start = 1; - } else - { - warm_start = 0; - } - if(warm_start) - { - Serial.println("!!!Warm Start active!!!"); - - // Put the Sentral in pass-thru mode - WS_PassThroughMode(); - - // Fetch the WarmStart data from the M24512DFM I2C EEPROM - readSenParams(); - - // Take Sentral out of pass-thru mode and re-start algorithm - WS_Resume(); - } else - { - Serial.println("***No Warm Start***"); - } - // Take user input to choose Warm Start or not... - // "2" from the keboard is ASCII "1" which gives integer value 50 - // "0" from the keboard is ASCII "0" which gives integer value 48 - Serial.println("Send '2' to apply Accelerometer Cal, '0' to not apply Accelerometer Cal"); - serial_input = Serial.read(); - while(!(serial_input == 50) && !(serial_input == 48)) - { - serial_input = Serial.read(); - delay(500); - } - if(serial_input == 50) - { - accel_cal = 1; - } else - { - accel_cal = 0; - } - if(accel_cal) - { - Serial.println("!!!Accel Cal Active!!!"); - - // Put the Sentral in pass-thru mode - WS_PassThroughMode(); - - // Fetch the WarmStart data from the M24512DFM I2C EEPROM - readAccelCal(); - Serial.print("X-acc max: "); Serial.println(global_conf.accZero_max[0]); - Serial.print("Y-acc max: "); Serial.println(global_conf.accZero_max[1]); - Serial.print("Z-acc max: "); Serial.println(global_conf.accZero_max[2]); - Serial.print("X-acc min: "); Serial.println(global_conf.accZero_min[0]); - Serial.print("Y-acc min: "); Serial.println(global_conf.accZero_min[1]); - Serial.print("Z-acc min: "); Serial.println(global_conf.accZero_min[2]); - - // Take Sentral out of pass-thru mode and re-start algorithm - WS_Resume(); - } else - { - Serial.println("***No Accel Cal***"); - } - } - - // Give some time to read the screen - delay(1000); - - // Set up the SENtral as sensor bus in normal operating mode - if(!passThru) - { - // Set SENtral in initialized state to configure registers - writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x00); - - // Load Accel Cal - if(accel_cal) - { - EM7180_acc_cal_upload(); - } - - // Force initialize - writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x01); - - // Load Warm Start parameters - if(warm_start) - { - EM7180_set_WS_params(); - } - - // Set SENtral in initialized state to configure registers - writeByte(EM7180_ADDRESS, EM7180_HostControl, 0x00); - - //Setup LPF bandwidth (BEFORE setting ODR's) - writeByte(EM7180_ADDRESS, EM7180_ACC_LPF_BW, 0x03); // 41Hz - writeByte(EM7180_ADDRESS, EM7180_GYRO_LPF_BW, 0x01); // 184Hz - - // Set accel/gyro/mage desired ODR rates - writeByte(EM7180_ADDRESS, EM7180_QRateDivisor, 0x02); // 100 Hz - writeByte(EM7180_ADDRESS, EM7180_MagRate, 0x64); // 100 Hz - writeByte(EM7180_ADDRESS, EM7180_AccelRate, 0x14); // 200/10 Hz - writeByte(EM7180_ADDRESS, EM7180_GyroRate, 0x14); // 200/10 Hz - writeByte(EM7180_ADDRESS, EM7180_BaroRate, 0x80 | 0x32); // set enable bit and set Baro rate to 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 - EM7180_set_integer_param (0x49, 0x00); - - //Write desired sensor full scale ranges to the EM7180 - EM7180_set_mag_acc_FS (0x3E8, 0x08); // 1000 uT, 8 g - EM7180_set_gyro_FS (0x7D0); // 2000 dps - - // 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"); - - // Give some time to read the screen - delay(1000); - - // 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"); - Serial.println(""); Serial.println("*******************************************"); - Serial.println("Send '1' to store Warm Start configuration"); - Serial.println("*******************************************"); Serial.println(""); - - // Give some time to read the screen - delay(1000); - } - - // If pass through mode desired, set it up here - if(passThru) - { - // Put EM7180 SENtral into pass-through mode - SENtralPassThroughMode(); - delay(1000); - - // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - I2Cscan(); - - // Read first page of EEPROM - uint8_t data[128]; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x00, 0x00, 128, data); - Serial.println("EEPROM Signature Byte"); - Serial.print(data[0], HEX); Serial.println(" Should be 0x2A"); - Serial.print(data[1], HEX); Serial.println(" Should be 0x65"); - for (int i = 0; i < 128; i++) - { - Serial.print(data[i], HEX); Serial.print(" "); - } - - // Set up the interrupt pin, its set as active high, push-pull - pinMode(myLed, OUTPUT); - digitalWrite(myLed, HIGH); - - // Read the WHO_AM_I register, this is a good test of communication - Serial.println("MPU9250 9-axis motion sensor..."); - byte c = readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 - Serial.print("MPU9250 "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x71, HEX); - if (c == 0x71) // WHO_AM_I should always be 0x71 - { - Serial.println("MPU9250 is online..."); - MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values - Serial.print("x-axis self test: acceleration trim within : "); Serial.print(SelfTest[0],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: acceleration trim within : "); Serial.print(SelfTest[1],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: acceleration trim within : "); Serial.print(SelfTest[2],1); Serial.println("% of factory value"); - Serial.print("x-axis self test: gyration trim within : "); Serial.print(SelfTest[3],1); Serial.println("% of factory value"); - Serial.print("y-axis self test: gyration trim within : "); Serial.print(SelfTest[4],1); Serial.println("% of factory value"); - Serial.print("z-axis self test: gyration trim within : "); Serial.print(SelfTest[5],1); Serial.println("% of factory value"); - - delay(1000); - - // get sensor resolutions, only need to do this once - getAres(); - getGres(); - getMres(); - - Serial.println(" Calibrate gyro and accel"); - accelgyrocalMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers - Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]); - Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]); - - delay(1000); - - initMPU9250(); - Serial.println("MPU9250 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature - writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); - I2Cscan(); // should see all the devices on the I2C bus including two from the EEPROM (ID page and data pages) - - // Read the WHO_AM_I register of the magnetometer, this is a good test of communication - byte d = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for AK8963 - Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x48, HEX); - - delay(1000); - - // Get magnetometer calibration from AK8963 ROM - // Initialize device for active mode read of magnetometer - initAK8963(magCalibration); Serial.println("AK8963 initialized for active data mode...."); - - magcalMPU9250(magBias, magScale); - Serial.println("AK8963 mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]); - Serial.println("AK8963 mag scale (mG)"); Serial.println(magScale[0]); Serial.println(magScale[1]); Serial.println(magScale[2]); - delay(2000); // add delay to see results before serial spew of data - - if(SerialDebug) - { - Serial.print("X-Axis sensitivity adjustment value "); Serial.println(magCalibration[0], 2); - Serial.print("Y-Axis sensitivity adjustment value "); Serial.println(magCalibration[1], 2); - Serial.print("Z-Axis sensitivity adjustment value "); Serial.println(magCalibration[2], 2); - } - - delay(1000); - - // Read the WHO_AM_I register of the BMP280 this is a good test of communication - // Read WHO_AM_I register for BMP280 - byte f = readByte(BMP280_ADDRESS, BMP280_ID); - Serial.print("BMP280 "); - Serial.print("I AM "); - Serial.print(f, HEX); - Serial.print(" I should be "); - Serial.println(0x58, HEX); - Serial.println(" "); - - delay(1000); - - // reset BMP280 before initilization - writeByte(BMP280_ADDRESS, BMP280_RESET, 0xB6); - - delay(100); - - // Initialize BMP280 altimeter - BMP280Init(); - Serial.println("Calibration coeficients:"); - Serial.print("dig_T1 ="); - Serial.println(dig_T1); - Serial.print("dig_T2 ="); - Serial.println(dig_T2); - Serial.print("dig_T3 ="); - Serial.println(dig_T3); - Serial.print("dig_P1 ="); - Serial.println(dig_P1); - Serial.print("dig_P2 ="); - Serial.println(dig_P2); - Serial.print("dig_P3 ="); - Serial.println(dig_P3); - Serial.print("dig_P4 ="); - Serial.println(dig_P4); - Serial.print("dig_P5 ="); - Serial.println(dig_P5); - Serial.print("dig_P6 ="); - Serial.println(dig_P6); - Serial.print("dig_P7 ="); - Serial.println(dig_P7); - Serial.print("dig_P8 ="); - Serial.println(dig_P8); - Serial.print("dig_P9 ="); - Serial.println(dig_P9); - - delay(1000); - } - else - { - Serial.print("Could not connect to MPU9250: 0x"); - Serial.println(c, HEX); - while(1) ; // Loop forever if communication doesn't happen - } - } -} - -void loop() -{ - if(!passThru) - { - serial_input = Serial.read(); - if (serial_input == 49) - { - delay(100); - EM7180_get_WS_params(); - - // Put the Sentral in pass-thru mode - WS_PassThroughMode(); - - // Store WarmStart data to the M24512DFM I2C EEPROM - writeSenParams(); - - // Take Sentral out of pass-thru mode and re-start algorithm - WS_Resume(); - warm_start_saved = 1; - } - if (serial_input == 50) - { - calibratingA = 512; - } - - // Check event status register, way to chech data ready by polling rather than interrupt - uint8_t eventStatus = readByte(EM7180_ADDRESS, EM7180_EventStatus); // reading clears the register - - // Check for errors - // Error detected, what is it? - if(eventStatus & 0x02) - { - uint8_t errorStatus = readByte(EM7180_ADDRESS, EM7180_ErrorRegister); - if(!errorStatus) - { - Serial.print(" EM7180 sensor status = "); Serial.println(errorStatus); - if(errorStatus == 0x11) Serial.print("Magnetometer failure!"); - if(errorStatus == 0x12) Serial.print("Accelerometer failure!"); - if(errorStatus == 0x14) Serial.print("Gyro failure!"); - if(errorStatus == 0x21) Serial.print("Magnetometer initialization failure!"); - if(errorStatus == 0x22) Serial.print("Accelerometer initialization failure!"); - if(errorStatus == 0x24) Serial.print("Gyro initialization failure!"); - if(errorStatus == 0x30) Serial.print("Math error!"); - if(errorStatus == 0x80) Serial.print("Invalid sample rate!"); - } - // Handle errors ToDo - } - // if no errors, see if new data is ready - // new acceleration data available - if(eventStatus & 0x10) - { - readSENtralAccelData(accelCount); - - // Now we'll calculate the accleration value into actual g's - ax = (float)accelCount[0]*0.000488; // get actual g value - ay = (float)accelCount[1]*0.000488; - az = (float)accelCount[2]*0.000488; - - // Manages accelerometer calibration; is active when calibratingA > 0 - Accel_cal_check(); - } - - if(eventStatus & 0x20) - { - // new gyro data available - readSENtralGyroData(gyroCount); - - // Now we'll calculate the gyro value into actual dps's - gx = (float)gyroCount[0]*0.153; // get actual dps value - gy = (float)gyroCount[1]*0.153; - gz = (float)gyroCount[2]*0.153; - } - if(eventStatus & 0x08) - { - // new mag data available - readSENtralMagData(magCount); - - // Now we'll calculate the mag value into actual G's - // get actual G value - mx = (float)magCount[0]*0.305176; - my = (float)magCount[1]*0.305176; - mz = (float)magCount[2]*0.305176; - } - - if(eventStatus & 0x04) - { - readSENtralQuatData(Quat); - } - - // get BMP280 pressure - // new baro data available - if(eventStatus & 0x40) - { - rawPressure = readSENtralBaroData(); - pressure = (float)rawPressure*0.01f +1013.25f; // pressure in mBar - - // get BMP280 temperature - rawTemperature = readSENtralTempData(); - temperature = (float) rawTemperature*0.01; // temperature in degrees C - } - } - - if(passThru) - { - // If intPin goes high, all data registers have new data - readAccelData(accelCount); // Read the x/y/z adc values - - // Now we'll calculate the acceleration value into actual g's - ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set - ay = (float)accelCount[1]*aRes - accelBias[1]; - az = (float)accelCount[2]*aRes - accelBias[2]; - - // Read the x/y/z adc values - readGyroData(gyroCount); - - // Calculate the gyro value into actual degrees per second - gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set - gy = (float)gyroCount[1]*gRes; - gz = (float)gyroCount[2]*gRes; - readMagData(magCount); // Read the x/y/z adc values - - // Calculate the magnetometer values in milliGauss - mx = (float)magCount[0]*mRes*magCalibration[0] - magBias[0]; // get actual magnetometer value, this depends on scale being set - my = (float)magCount[1]*mRes*magCalibration[1] - magBias[1]; - mz = (float)magCount[2]*mRes*magCalibration[2] - magBias[2]; - } - - // keep track of rates - Now = micros(); - - // set integration time by time elapsed since last filter update - deltat = ((Now - lastUpdate)/1000000.0f); - lastUpdate = Now; - - sum += deltat; // sum for averaging filter update rate - sumCount++; - - // Sensors x (y)-axis of the accelerometer is aligned with the -y (x)-axis of the magnetometer; - // the magnetometer z-axis (+ up) is aligned with z-axis (+ up) of accelerometer and gyro! - // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. - // For the BMX-055, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like - // in the MPU9250 sensor. This rotation can be modified to allow any convenient orientation convention. - // This is ok by aircraft orientation standards! - // Pass gyro rate as rad/s - MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); -// if(passThru)MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, mx, mz); - - // Serial print and/or display at 0.5 s rate independent of data rates - delt_t = millis() - count; - - // update LCD once per half-second independent of read rate - if (delt_t > 500) - { - - if(SerialDebug) - { - Serial.print("ax = "); Serial.print((int)1000*ax); - Serial.print(" ay = "); Serial.print((int)1000*ay); - Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); - Serial.print("gx = "); Serial.print( gx, 2); - Serial.print(" gy = "); Serial.print( gy, 2); - Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); - Serial.print("mx = "); Serial.print( (int)mx); - Serial.print(" my = "); Serial.print( (int)my); - Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG"); - Serial.println("Software quaternions (ENU):"); - Serial.print("q0 = "); Serial.print(q[0]); - Serial.print(" qx = "); Serial.print(q[1]); - Serial.print(" qy = "); Serial.print(q[2]); - Serial.print(" qz = "); Serial.println(q[3]); - Serial.println("Hardware quaternions (NED):"); - Serial.print("Q0 = "); Serial.print(Quat[0]); - Serial.print(" Qx = "); Serial.print(Quat[1]); - Serial.print(" Qy = "); Serial.print(Quat[2]); - Serial.print(" Qz = "); Serial.println(Quat[3]); - } - if(passThru) - { - rawPress = readBMP280Pressure(); - pressure = (float) bmp280_compensate_P(rawPress)/25600.; // Pressure in mbar - rawTemp = readBMP280Temperature(); - temperature = (float) bmp280_compensate_T(rawTemp)/100.; - } - // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. - // In this coordinate system, the positive z-axis is down toward Earth. - // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. - // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. - // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. - // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. - // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be - // applied in the correct order which for this configuration is yaw, pitch, and then roll. - // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. - - //Software AHRS: - yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); - pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); - roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); - pitch *= 180.0f / PI; - yaw *= 180.0f / PI; - yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(yaw < 0) yaw += 360.0f; // Ensure yaw stays between 0 and 360 - roll *= 180.0f / PI; - - //Hardware AHRS: - Yaw = atan2(2.0f * (Quat[0] * Quat[1] + Quat[3] * Quat[2]), Quat[3] * Quat[3] + Quat[0] * Quat[0] - Quat[1] * Quat[1] - Quat[2] * Quat[2]); - Pitch = -asin(2.0f * (Quat[0] * Quat[2] - Quat[3] * Quat[1])); - Roll = atan2(2.0f * (Quat[3] * Quat[0] + Quat[1] * Quat[2]), Quat[3] * Quat[3] - Quat[0] * Quat[0] - Quat[1] * Quat[1] + Quat[2] * Quat[2]); - Pitch *= 180.0f / PI; - Yaw *= 180.0f / PI; - Yaw += 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 - if(Yaw < 0) Yaw += 360.0f ; // Ensure yaw stays between 0 and 360 - Roll *= 180.0f / PI; - - // Or define output variable according to the Android system, where heading (0 to 360) is defined by the angle between the y-axis - // and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90) - // In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis - // points toward the right of the device. - - if(SerialDebug) - { - Serial.print("Software yaw, pitch, roll: "); - Serial.print(yaw, 2); - Serial.print(", "); - Serial.print(pitch, 2); - Serial.print(", "); - Serial.println(roll, 2); - Serial.print("Hardware Yaw, Pitch, Roll: "); - Serial.print(Yaw, 2); - Serial.print(", "); - Serial.print(Pitch, 2); - Serial.print(", "); - Serial.println(Roll, 2); - Serial.println("BMP280:"); - Serial.print("Altimeter temperature = "); - Serial.print( temperature, 2); - Serial.println(" C"); // temperature in degrees Celsius - Serial.print("Altimeter temperature = "); - Serial.print(9.*temperature/5. + 32., 2); - Serial.println(" F"); // temperature in degrees Fahrenheit - Serial.print("Altimeter pressure = "); - Serial.print(pressure, 2); - Serial.println(" mbar");// pressure in millibar - altitude = 145366.45f*(1.0f - pow((pressure/1013.25f), 0.190284f)); - Serial.print("Altitude = "); - Serial.print(altitude, 2); - Serial.println(" feet"); - Serial.println(" "); - if(!passThru) - { - if(warm_start_saved) - { - Serial.println("Warm Start configuration saved!"); - } else - { - Serial.println("Send '1' to store Warm Start configuration"); - } - if(accel_cal_saved > 0) - { - Serial.print("Accel Cals Complete:"); Serial.println(accel_cal_saved); - } else - { - Serial.println("Send '2' to store Accel Cal"); - } - } - } - Serial.print(millis()/1000.0, 1);Serial.print(","); - Serial.print(yaw); Serial.print(",");Serial.print(pitch); Serial.print(",");Serial.print(roll); Serial.print(","); - Serial.print(Yaw); Serial.print(",");Serial.print(Pitch); Serial.print(",");Serial.println(Roll); - digitalWrite(myLed, !digitalRead(myLed)); - count = millis(); - sumCount = 0; - sum = 0; - } -} - -//=================================================================================================================== -//====== Sentral parameter management functions -//=================================================================================================================== - -void 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 - - // Parameter 75; 0xCB is 75 decimal with the MSB set high to indicate a paramter write processs - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0xCB); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - 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 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 - - // Parameter 74; 0xCA is 74 decimal with the MSB set high to indicate a paramter write processs - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0xCA); - - //Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==0xCA)) { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm -} - -void 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); - - // Parameter is the decimal value with the MSB set high to indicate a paramter write processs - param = param | 0x80; - 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); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm -} - -void EM7180_set_float_param (uint8_t param, float param_val) { - uint8_t bytes[4], STAT; - float_to_bytes (param_val, &bytes[0]); - - // Parameter is the decimal value with the MSB set high to indicate a paramter write processs - param = param | 0x80; - 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); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); // Re-start algorithm -} - -void EM7180_set_WS_params() -{ - uint8_t param = 1; - uint8_t STAT; - - // Parameter is the decimal value with the MSB set high to indicate a paramter write processs - param = param | 0x80; - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, WS_params.Sen_param[0][0]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, WS_params.Sen_param[0][1]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, WS_params.Sen_param[0][2]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, WS_params.Sen_param[0][3]); - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) - { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - for(uint8_t i=1; i<35; i++) - { - param = (i+1) | 0x80; - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte0, WS_params.Sen_param[i][0]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte1, WS_params.Sen_param[i][1]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte2, WS_params.Sen_param[i][2]); - writeByte(EM7180_ADDRESS, EM7180_LoadParamByte3, WS_params.Sen_param[i][3]); - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) - { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); -} - -void EM7180_get_WS_params() -{ - uint8_t param = 1; - uint8_t STAT; - - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - delay(10); - - // Request parameter transfer procedure - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x80); - delay(10); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) - { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - - // Parameter is the decimal value with the MSB set low (default) to indicate a paramter read processs - WS_params.Sen_param[0][0] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); - WS_params.Sen_param[0][1] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); - WS_params.Sen_param[0][2] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); - WS_params.Sen_param[0][3] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte3); - - for(uint8_t i=1; i<35; i++) - { - param = (i+1); - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, param); - delay(10); - - // Check the parameter acknowledge register and loop until the result matches parameter request byte - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - while(!(STAT==param)) - { - STAT = readByte(EM7180_ADDRESS, EM7180_ParamAcknowledge); - } - WS_params.Sen_param[i][0] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte0); - WS_params.Sen_param[i][1] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte1); - WS_params.Sen_param[i][2] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte2); - WS_params.Sen_param[i][3] = readByte(EM7180_ADDRESS, EM7180_SavedParamByte3); - } - // Parameter request = 0 to end parameter transfer process - writeByte(EM7180_ADDRESS, EM7180_ParamRequest, 0x00); - - // Re-start algorithm - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); -} - -void EM7180_acc_cal_upload() -{ - int64_t big_cal_num; - union - { - int16_t cal_num; - unsigned char cal_num_byte[2]; - }; - - if(!accel_cal) - { - cal_num_byte[0] = 0; - cal_num_byte[1] = 0; - } else - { - big_cal_num = (4096000000/(global_conf.accZero_max[0] - global_conf.accZero_min[0])) - 1000000; - cal_num = (int16_t)big_cal_num; - } - writeByte(EM7180_ADDRESS, EM7180_GP36, cal_num_byte[0]); - writeByte(EM7180_ADDRESS, EM7180_GP37, cal_num_byte[1]); - - if(!accel_cal) - { - cal_num_byte[0] = 0; - cal_num_byte[1] = 0; - } else - { - big_cal_num = (4096000000/(global_conf.accZero_max[1] - global_conf.accZero_min[1])) - 1000000; - cal_num = (int16_t)big_cal_num; - } - writeByte(EM7180_ADDRESS, EM7180_GP38, cal_num_byte[0]); - writeByte(EM7180_ADDRESS, EM7180_GP39, cal_num_byte[1]); - - if(!accel_cal) - { - cal_num_byte[0] = 0; - cal_num_byte[1] = 0; - } else - { - big_cal_num = (4096000000/(global_conf.accZero_max[2] - global_conf.accZero_min[2])) - 1000000; - cal_num = (int16_t)big_cal_num; - } - writeByte(EM7180_ADDRESS, EM7180_GP40, cal_num_byte[0]); - writeByte(EM7180_ADDRESS, EM7180_GP50, cal_num_byte[1]); - - if(!accel_cal) - { - cal_num_byte[0] = 0; - cal_num_byte[1] = 0; - } else - { - big_cal_num = (((2048 - global_conf.accZero_max[0]) + (-2048 - global_conf.accZero_min[0]))*100000)/4096; - cal_num = (int16_t)big_cal_num; - } - writeByte(EM7180_ADDRESS, EM7180_GP51, cal_num_byte[0]); - writeByte(EM7180_ADDRESS, EM7180_GP52, cal_num_byte[1]); - - if(!accel_cal) - { - cal_num_byte[0] = 0; - cal_num_byte[1] = 0; - } else - { - big_cal_num = (((2048 - global_conf.accZero_max[1]) + (-2048 - global_conf.accZero_min[1]))*100000)/4096; - cal_num = (int16_t)big_cal_num; - } - writeByte(EM7180_ADDRESS, EM7180_GP53, cal_num_byte[0]); - writeByte(EM7180_ADDRESS, EM7180_GP54, cal_num_byte[1]); - - if(!accel_cal) - { - cal_num_byte[0] = 0; - cal_num_byte[1] = 0; - } else - { - big_cal_num = (((2048 - global_conf.accZero_max[2]) + (-2048 - global_conf.accZero_min[2]))*100000)/4096; - cal_num = -(int16_t)big_cal_num; - } - writeByte(EM7180_ADDRESS, EM7180_GP55, cal_num_byte[0]); - writeByte(EM7180_ADDRESS, EM7180_GP56, cal_num_byte[1]); -} - -void WS_PassThroughMode() -{ - uint8_t stat = 0; - - // First put SENtral in standby mode - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x01); - delay(5); - - // Place SENtral in pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x01); - delay(5); - stat = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); - while(!(stat & 0x01)) - { - stat = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); - delay(5); - } -} - -void WS_Resume() -{ - uint8_t stat = 0; - - // Cancel pass-through mode - writeByte(EM7180_ADDRESS, EM7180_PassThruControl, 0x00); - delay(5); - stat = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); - while((stat & 0x01)) - { - stat = readByte(EM7180_ADDRESS, EM7180_PassThruStatus); - delay(5); - } - - // Re-start algorithm - writeByte(EM7180_ADDRESS, EM7180_AlgorithmControl, 0x00); - delay(5); - stat = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); - while((stat & 0x01)) - { - stat = readByte(EM7180_ADDRESS, EM7180_AlgorithmStatus); - delay(5); - } -} - -void readSenParams() -{ - uint8_t data[140]; - uint8_t paramnum; - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x80, 12, &data[128]); // Page 255 - delay(100); - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x00, 128, &data[0]); // Page 254 - for (paramnum = 0; paramnum < 35; paramnum++) // 35 parameters - { - for (uint8_t i= 0; i < 4; i++) - { - WS_params.Sen_param[paramnum][i] = data[(paramnum*4 + i)]; - } - } -} - -void writeSenParams() -{ - uint8_t data[140]; - uint8_t paramnum; - for (paramnum = 0; paramnum < 35; paramnum++) // 35 parameters - { - for (uint8_t i= 0; i < 4; i++) - { - data[(paramnum*4 + i)] = WS_params.Sen_param[paramnum][i]; - } - } - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x80, 12, &data[128]); // Page 255 - delay(100); - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x00, 128, &data[0]); // Page 254 -} - -void Accel_cal_check() -{ - static int64_t a[3] = {0, 0, 0}, b[3] = {0, 0, 0}; - - if (calibratingA > 0) - { - for (uint8_t axis = 0; axis < 3; axis++) - { - if (accelCount[axis] > 1024) - { - // Sum up 512 readings - a[axis] += accelCount[axis]; - } - if (accelCount[axis] < -1024) - { - b[axis] += accelCount[axis]; - } - // Clear global variables for next reading - accelCount[axis] = 0; - } - - // Calculate averages, and store values in EEPROM at end of calibration - if (calibratingA == 1) - { - for (uint8_t axis = 0; axis < 3; axis++) - { - if (a[axis]>>9 > 1024) - { - global_conf.accZero_max[axis] = a[axis]>>9; - } - if (b[axis]>>9 < -1024) - { - global_conf.accZero_min[axis] = b[axis]>>9; - } - a[axis] = 0; - b[axis] = 0; - } - - //Write accZero to EEPROM - delay(100); - - // Put the Sentral in pass-thru mode - WS_PassThroughMode(); - - // Store accelerometer calibration data to the M24512DFM I2C EEPROM - writeAccCal(); - - - // Take Sentral out of pass-thru mode and re-start algorithm - WS_Resume(); - accel_cal_saved++; - if(accel_cal_saved > 6) accel_cal_saved = 0; - } - calibratingA--; - } -} - -void readAccelCal() -{ - uint8_t data[12]; - uint8_t axis; - - M24512DFMreadBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x8c, 12, data); // Page 255 - for (axis = 0; axis < 3; axis++) - { - global_conf.accZero_max[axis] = ((int16_t)(data[(2*axis + 1)]<<8) | data[2*axis]); - global_conf.accZero_min[axis] = ((int16_t)(data[(2*axis + 7)]<<8) | data[(2*axis + 6)]); - } -} - -void writeAccCal() -{ - uint8_t data[12]; - uint8_t axis; - for (axis = 0; axis < 3; axis++) - { - data[2*axis] = (global_conf.accZero_max[axis] & 0xff); - data[(2*axis + 1)] = (global_conf.accZero_max[axis] >> 8); - data[(2*axis + 6)] = (global_conf.accZero_min[axis] & 0xff); - data[(2*axis + 7)] = (global_conf.accZero_min[axis] >> 8); - } - M24512DFMwriteBytes(M24512DFM_DATA_ADDRESS, 0x7f, 0x8c, 12, data); // Page 255 -} - -//=================================================================================================================== -//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data -//=================================================================================================================== - -float 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; -} - -void 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 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[0] = uint32_reg_to_float (&rawData[0]); - destination[1] = uint32_reg_to_float (&rawData[4]); - destination[2] = uint32_reg_to_float (&rawData[8]); - destination[3] = uint32_reg_to_float (&rawData[12]); // SENtral stores quats as qx, qy, qz, q0! - -} - -void 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 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 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]); -} - -void getMres() { - 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 - break; - case MFS_16BITS: - mRes = 10.*4912./32760.0; // Proper scale to return milliGauss - break; - } -} - -void getGres() { - 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; - break; - case GFS_500DPS: - gRes = 500.0/32768.0; - break; - case GFS_1000DPS: - gRes = 1000.0/32768.0; - break; - case GFS_2000DPS: - gRes = 2000.0/32768.0; - break; - } -} - -void getAres() { - 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; - break; - case AFS_4G: - aRes = 4.0/32768.0; - break; - case AFS_8G: - aRes = 8.0/32768.0; - break; - case AFS_16G: - aRes = 16.0/32768.0; - break; - } -} - - -void 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 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 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 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 initAK8963(float * destination) -{ - // 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.; - 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 initMPU9250() -{ - // 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 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 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] = {0xFF, 0xFF, 0xFF}, mag_min[3] = {0x7F, 0x7F, 0x7F}, 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*magCalibration[0]; // save mag biases in G for main program - dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1]; - dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2]; - - // 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 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, FS<<3); // Set full scale range for the gyro to 250 dps - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, FS<<3); // Set full scale range for the accelerometer to 2 g - - for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer - - readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array - aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - - readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - } - - for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings - aAvg[ii] /= 200; - gAvg[ii] /= 200; - } - -// Configure the accelerometer for self-test - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g - writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s - delay(25); // Delay a while to let the device stabilize - - for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer - - readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array - aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - - readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array - gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value - gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; - gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; - } - - for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings - aSTAvg[ii] /= 200; - gSTAvg[ii] /= 200; - } - - // Configure the gyro and accelerometer for normal operation - writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); - writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); - delay(25); // Delay a while to let the device stabilize - - // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg - selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results - selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results - selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results - selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results - selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results - selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results - - // Retrieve factory self-test value from self-test code reads - factoryTrim[0] = (float)(2620/1<> 4); -} - -int32_t readBMP280Pressure() -{ - uint8_t rawData[3]; // 20-bit pressure register data stored here - readBytes(BMP280_ADDRESS, BMP280_PRESS_MSB, 3, &rawData[0]); - return (int32_t) (((int32_t) rawData[0] << 16 | (int32_t) rawData[1] << 8 | rawData[2]) >> 4); -} - -void BMP280Init() -{ - // Configure the BMP280 - // Set T and P oversampling rates and sensor mode - writeByte(BMP280_ADDRESS, BMP280_CTRL_MEAS, Tosr << 5 | Posr << 2 | Mode); - // Set standby time interval in normal mode and bandwidth - writeByte(BMP280_ADDRESS, BMP280_CONFIG, SBy << 5 | IIRFilter << 2); - // Read and store calibration data - uint8_t calib[24]; - readBytes(BMP280_ADDRESS, BMP280_CALIB00, 24, &calib[0]); - dig_T1 = (uint16_t)(((uint16_t) calib[1] << 8) | calib[0]); - dig_T2 = ( int16_t)((( int16_t) calib[3] << 8) | calib[2]); - dig_T3 = ( int16_t)((( int16_t) calib[5] << 8) | calib[4]); - dig_P1 = (uint16_t)(((uint16_t) calib[7] << 8) | calib[6]); - dig_P2 = ( int16_t)((( int16_t) calib[9] << 8) | calib[8]); - dig_P3 = ( int16_t)((( int16_t) calib[11] << 8) | calib[10]); - dig_P4 = ( int16_t)((( int16_t) calib[13] << 8) | calib[12]); - dig_P5 = ( int16_t)((( int16_t) calib[15] << 8) | calib[14]); - dig_P6 = ( int16_t)((( int16_t) calib[17] << 8) | calib[16]); - dig_P7 = ( int16_t)((( int16_t) calib[19] << 8) | calib[18]); - dig_P8 = ( int16_t)((( int16_t) calib[21] << 8) | calib[20]); - dig_P9 = ( int16_t)((( int16_t) calib[23] << 8) | calib[22]); -} - -// Returns temperature in DegC, resolution is 0.01 DegC. Output value of -// “5123” equals 51.23 DegC. -int32_t bmp280_compensate_T(int32_t adc_T) -{ - int32_t var1, var2, T; - var1 = ((((adc_T >> 3) - ((int32_t)dig_T1 << 1))) * ((int32_t)dig_T2)) >> 11; - var2 = (((((adc_T >> 4) - ((int32_t)dig_T1)) * ((adc_T >> 4) - ((int32_t)dig_T1))) >> 12) * ((int32_t)dig_T3)) >> 14; - t_fine = var1 + var2; - T = (t_fine * 5 + 128) >> 8; - return T; -} - -// Returns pressure in Pa as unsigned 32 bit integer in Q24.8 format (24 integer bits and 8 -//fractional bits). -//Output value of “24674867” represents 24674867/256 = 96386.2 Pa = 963.862 hPa -uint32_t bmp280_compensate_P(int32_t adc_P) -{ - long long var1, var2, p; - var1 = ((long long)t_fine) - 128000; - var2 = var1 * var1 * (long long)dig_P6; - var2 = var2 + ((var1*(long long)dig_P5)<<17); - var2 = var2 + (((long long)dig_P4)<<35); - var1 = ((var1 * var1 * (long long)dig_P3)>>8) + ((var1 * (long long)dig_P2)<<12); - var1 = (((((long long)1)<<47)+var1))*((long long)dig_P1)>>33; - if(var1 == 0) - { - return 0; - // avoid exception caused by division by zero - } - p = 1048576 - adc_P; - p = (((p<<31) - var2)*3125)/var1; - var1 = (((long long)dig_P9) * (p>>13) * (p>>13)) >> 25; - var2 = (((long long)dig_P8) * p)>> 19; - p = ((p + var1 + var2) >> 8) + (((long long)dig_P7)<<4); - return (uint32_t)p; -} - -//=================================================================================================================== -//====== I2C Communication Support Functions -//=================================================================================================================== - -// I2C communication with the M24512DFM EEPROM is a little different from I2C communication with the usual motion sensor -// since the address is defined by two bytes - -void M24512DFMwriteByte(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t 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.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - -void M24512DFMwriteBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - if(count > 128) - { - count = 128; - Serial.print("Page count cannot be more than 128 bytes!"); - } - 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 - for(uint8_t i=0; i < count; i++) - { - Wire.write(dest[i]); // Put data in Tx buffer - } - Wire.endTransmission(); // Send the Tx buffer -} - -uint8_t 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - Wire.requestFrom(device_address, (size_t)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 M24512DFMreadBytes(uint8_t device_address, uint8_t data_address1, uint8_t data_address2, uint8_t count, uint8_t * dest) -{ - 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(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(device_address, (size_t)count); // Read bytes from slave register address - while (Wire.available()) - { - dest[i++] = Wire.read(); - } // Put read results in the Rx buffer -} - -// simple function to scan for I2C devices on the bus -void 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. - Wire.beginTransmission(address); - error = Wire.endTransmission(); - - 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("Unknow 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 and AK8963 sensors - -void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.write(data); // Put data in Tx buffer - Wire.endTransmission(); // Send the Tx buffer -} - -uint8_t readByte(uint8_t address, uint8_t subAddress) -{ - uint8_t data; // `data` will store the register data - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - Wire.requestFrom(address, (size_t) 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 readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) -{ - Wire.beginTransmission(address); // Initialize the Tx buffer - Wire.write(subAddress); // Put slave register address in Tx buffer - Wire.endTransmission(I2C_NOSTOP); // Send the Tx buffer, but send a restart to keep connection alive - uint8_t i = 0; - Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address - while (Wire.available()) - { - dest[i++] = Wire.read(); - } // Put read results in the Rx buffer -} diff --git a/WarmStartandAccelCal/Global.h b/WarmStartandAccelCal/Global.h deleted file mode 100644 index 99e9a87..0000000 --- a/WarmStartandAccelCal/Global.h +++ /dev/null @@ -1,523 +0,0 @@ -#ifndef Globals_h -#define Globals_h - -/*************************************************************************************************/ -/************* ***************/ -/************* Parameter Definitions ***************/ -/************* ***************/ -/*************************************************************************************************/ - -// These are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral -#define Kp 2.0f * 5.0f -#define Ki 0.0f - -// BMP280 registers -#define BMP280_TEMP_XLSB 0xFC -#define BMP280_TEMP_LSB 0xFB -#define BMP280_TEMP_MSB 0xFA -#define BMP280_PRESS_XLSB 0xF9 -#define BMP280_PRESS_LSB 0xF8 -#define BMP280_PRESS_MSB 0xF7 -#define BMP280_CONFIG 0xF5 -#define BMP280_CTRL_MEAS 0xF4 -#define BMP280_STATUS 0xF3 -#define BMP280_RESET 0xE0 -#define BMP280_ID 0xD0 // should be 0x58 -#define BMP280_CALIB00 0x88 - -// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in -// above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map -// -//Magnetometer Registers -#define AK8963_ADDRESS 0x0C -#define WHO_AM_I_AK8963 0x00 // should return 0x48 -#define INFO 0x01 -#define AK8963_ST1 0x02 // data ready status bit 0 -#define AK8963_XOUT_L 0x03 // data -#define AK8963_XOUT_H 0x04 -#define AK8963_YOUT_L 0x05 -#define AK8963_YOUT_H 0x06 -#define AK8963_ZOUT_L 0x07 -#define AK8963_ZOUT_H 0x08 -#define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 -#define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 -#define AK8963_ASTC 0x0C // Self test control -#define AK8963_I2CDIS 0x0F // I2C disable -#define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value -#define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value -#define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value - -#define SELF_TEST_X_GYRO 0x00 -#define SELF_TEST_Y_GYRO 0x01 -#define SELF_TEST_Z_GYRO 0x02 - -/*#define X_FINE_GAIN 0x03 // [7:0] fine gain -#define Y_FINE_GAIN 0x04 -#define Z_FINE_GAIN 0x05 -#define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer -#define XA_OFFSET_L_TC 0x07 -#define YA_OFFSET_H 0x08 -#define YA_OFFSET_L_TC 0x09 -#define ZA_OFFSET_H 0x0A -#define ZA_OFFSET_L_TC 0x0B */ - -#define SELF_TEST_X_ACCEL 0x0D -#define SELF_TEST_Y_ACCEL 0x0E -#define SELF_TEST_Z_ACCEL 0x0F - -#define SELF_TEST_A 0x10 - -#define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope -#define XG_OFFSET_L 0x14 -#define YG_OFFSET_H 0x15 -#define YG_OFFSET_L 0x16 -#define ZG_OFFSET_H 0x17 -#define ZG_OFFSET_L 0x18 -#define SMPLRT_DIV 0x19 -#define CONFIG 0x1A -#define GYRO_CONFIG 0x1B -#define ACCEL_CONFIG 0x1C -#define ACCEL_CONFIG2 0x1D -#define LP_ACCEL_ODR 0x1E -#define WOM_THR 0x1F - -#define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms -#define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] -#define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms - -#define FIFO_EN 0x23 -#define I2C_MST_CTRL 0x24 -#define I2C_SLV0_ADDR 0x25 -#define I2C_SLV0_REG 0x26 -#define I2C_SLV0_CTRL 0x27 -#define I2C_SLV1_ADDR 0x28 -#define I2C_SLV1_REG 0x29 -#define I2C_SLV1_CTRL 0x2A -#define I2C_SLV2_ADDR 0x2B -#define I2C_SLV2_REG 0x2C -#define I2C_SLV2_CTRL 0x2D -#define I2C_SLV3_ADDR 0x2E -#define I2C_SLV3_REG 0x2F -#define I2C_SLV3_CTRL 0x30 -#define I2C_SLV4_ADDR 0x31 -#define I2C_SLV4_REG 0x32 -#define I2C_SLV4_DO 0x33 -#define I2C_SLV4_CTRL 0x34 -#define I2C_SLV4_DI 0x35 -#define I2C_MST_STATUS 0x36 -#define INT_PIN_CFG 0x37 -#define INT_ENABLE 0x38 -#define DMP_INT_STATUS 0x39 // Check DMP interrupt -#define INT_STATUS 0x3A -#define ACCEL_XOUT_H 0x3B -#define ACCEL_XOUT_L 0x3C -#define ACCEL_YOUT_H 0x3D -#define ACCEL_YOUT_L 0x3E -#define ACCEL_ZOUT_H 0x3F -#define ACCEL_ZOUT_L 0x40 -#define TEMP_OUT_H 0x41 -#define TEMP_OUT_L 0x42 -#define GYRO_XOUT_H 0x43 -#define GYRO_XOUT_L 0x44 -#define GYRO_YOUT_H 0x45 -#define GYRO_YOUT_L 0x46 -#define GYRO_ZOUT_H 0x47 -#define GYRO_ZOUT_L 0x48 -#define EXT_SENS_DATA_00 0x49 -#define EXT_SENS_DATA_01 0x4A -#define EXT_SENS_DATA_02 0x4B -#define EXT_SENS_DATA_03 0x4C -#define EXT_SENS_DATA_04 0x4D -#define EXT_SENS_DATA_05 0x4E -#define EXT_SENS_DATA_06 0x4F -#define EXT_SENS_DATA_07 0x50 -#define EXT_SENS_DATA_08 0x51 -#define EXT_SENS_DATA_09 0x52 -#define EXT_SENS_DATA_10 0x53 -#define EXT_SENS_DATA_11 0x54 -#define EXT_SENS_DATA_12 0x55 -#define EXT_SENS_DATA_13 0x56 -#define EXT_SENS_DATA_14 0x57 -#define EXT_SENS_DATA_15 0x58 -#define EXT_SENS_DATA_16 0x59 -#define EXT_SENS_DATA_17 0x5A -#define EXT_SENS_DATA_18 0x5B -#define EXT_SENS_DATA_19 0x5C -#define EXT_SENS_DATA_20 0x5D -#define EXT_SENS_DATA_21 0x5E -#define EXT_SENS_DATA_22 0x5F -#define EXT_SENS_DATA_23 0x60 -#define MOT_DETECT_STATUS 0x61 -#define I2C_SLV0_DO 0x63 -#define I2C_SLV1_DO 0x64 -#define I2C_SLV2_DO 0x65 -#define I2C_SLV3_DO 0x66 -#define I2C_MST_DELAY_CTRL 0x67 -#define SIGNAL_PATH_RESET 0x68 -#define MOT_DETECT_CTRL 0x69 -#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP -#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode -#define PWR_MGMT_2 0x6C -#define DMP_BANK 0x6D // Activates a specific bank in the DMP -#define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank -#define DMP_REG 0x6F // Register in DMP from which to read or to which to write -#define DMP_REG_1 0x70 -#define DMP_REG_2 0x71 -#define FIFO_COUNTH 0x72 -#define FIFO_COUNTL 0x73 -#define FIFO_R_W 0x74 -#define WHO_AM_I_MPU9250 0x75 // Should return 0x71 -#define XA_OFFSET_H 0x77 -#define XA_OFFSET_L 0x78 -#define YA_OFFSET_H 0x7A -#define YA_OFFSET_L 0x7B -#define ZA_OFFSET_H 0x7D -#define ZA_OFFSET_L 0x7E - -// EM7180 SENtral register map -// see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf -// -#define EM7180_QX 0x00 // this is a 32-bit normalized floating point number read from registers 0x00-03 -#define EM7180_QY 0x04 // this is a 32-bit normalized floating point number read from registers 0x04-07 -#define EM7180_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B -#define EM7180_QW 0x0C // this is a 32-bit normalized floating point number read from registers 0x0C-0F -#define EM7180_QTIME 0x10 // this is a 16-bit unsigned integer read from registers 0x10-11 -#define EM7180_MX 0x12 // int16_t from registers 0x12-13 -#define EM7180_MY 0x14 // int16_t from registers 0x14-15 -#define EM7180_MZ 0x16 // int16_t from registers 0x16-17 -#define EM7180_MTIME 0x18 // uint16_t from registers 0x18-19 -#define EM7180_AX 0x1A // int16_t from registers 0x1A-1B -#define EM7180_AY 0x1C // int16_t from registers 0x1C-1D -#define EM7180_AZ 0x1E // int16_t from registers 0x1E-1F -#define EM7180_ATIME 0x20 // uint16_t from registers 0x20-21 -#define EM7180_GX 0x22 // int16_t from registers 0x22-23 -#define EM7180_GY 0x24 // int16_t from registers 0x24-25 -#define EM7180_GZ 0x26 // int16_t from registers 0x26-27 -#define EM7180_GTIME 0x28 // uint16_t from registers 0x28-29 -#define EM7180_Baro 0x2A // start of two-byte MS5637 pressure data, 16-bit signed interger -#define EM7180_BaroTIME 0x2C // start of two-byte MS5637 pressure timestamp, 16-bit unsigned -#define EM7180_Temp 0x2E // start of two-byte MS5637 temperature data, 16-bit signed interger -#define EM7180_TempTIME 0x30 // start of two-byte MS5637 temperature timestamp, 16-bit unsigned -#define EM7180_QRateDivisor 0x32 // uint8_t -#define EM7180_EnableEvents 0x33 -#define EM7180_HostControl 0x34 -#define EM7180_EventStatus 0x35 -#define EM7180_SensorStatus 0x36 -#define EM7180_SentralStatus 0x37 -#define EM7180_AlgorithmStatus 0x38 -#define EM7180_FeatureFlags 0x39 -#define EM7180_ParamAcknowledge 0x3A -#define EM7180_SavedParamByte0 0x3B -#define EM7180_SavedParamByte1 0x3C -#define EM7180_SavedParamByte2 0x3D -#define EM7180_SavedParamByte3 0x3E -#define EM7180_ActualMagRate 0x45 -#define EM7180_ActualAccelRate 0x46 -#define EM7180_ActualGyroRate 0x47 -#define EM7180_ActualBaroRate 0x48 -#define EM7180_ActualTempRate 0x49 -#define EM7180_ErrorRegister 0x50 -#define EM7180_AlgorithmControl 0x54 -#define EM7180_MagRate 0x55 -#define EM7180_AccelRate 0x56 -#define EM7180_GyroRate 0x57 -#define EM7180_BaroRate 0x58 -#define EM7180_TempRate 0x59 -#define EM7180_LoadParamByte0 0x60 -#define EM7180_LoadParamByte1 0x61 -#define EM7180_LoadParamByte2 0x62 -#define EM7180_LoadParamByte3 0x63 -#define EM7180_ParamRequest 0x64 -#define EM7180_ROMVersion1 0x70 -#define EM7180_ROMVersion2 0x71 -#define EM7180_RAMVersion1 0x72 -#define EM7180_RAMVersion2 0x73 -#define EM7180_ProductID 0x90 -#define EM7180_RevisionID 0x91 -#define EM7180_RunStatus 0x92 -#define EM7180_UploadAddress 0x94 // uint16_t registers 0x94 (MSB)-5(LSB) -#define EM7180_UploadData 0x96 -#define EM7180_CRCHost 0x97 // uint32_t from registers 0x97-9A -#define EM7180_ResetRequest 0x9B -#define EM7180_PassThruStatus 0x9E -#define EM7180_PassThruControl 0xA0 -#define EM7180_ACC_LPF_BW 0x5B //Register GP36 -#define EM7180_GYRO_LPF_BW 0x5C //Register GP37 -#define EM7180_BARO_LPF_BW 0x5D //Register GP38 -#define EM7180_GP36 0x5B -#define EM7180_GP37 0x5C -#define EM7180_GP38 0x5D -#define EM7180_GP39 0x5E -#define EM7180_GP40 0x5F -#define EM7180_GP50 0x69 -#define EM7180_GP51 0x6A -#define EM7180_GP52 0x6B -#define EM7180_GP53 0x6C -#define EM7180_GP54 0x6D -#define EM7180_GP55 0x6E -#define EM7180_GP56 0x6F - -#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub -#define M24512DFM_DATA_ADDRESS 0x50 // Address of the 500 page M24512DRC EEPROM data buffer, 1024 bits (128 8-bit bytes) per page -#define M24512DFM_IDPAGE_ADDRESS 0x58 // Address of the single M24512DRC lockable EEPROM ID page -#define MPU9250_ADDRESS 0x68 // Device address of MPU9250 when ADO = 0 -#define AK8963_ADDRESS 0x0C // Address of magnetometer -#define BMP280_ADDRESS 0x76 // Address of BMP280 altimeter when ADO = 0 - -/*************************************************************************************************/ -/************* ***************/ -/************* Enumerators and Structure Variables ***************/ -/************* ***************/ -/*************************************************************************************************/ - -// Set initial input parameters -enum Ascale { - AFS_2G = 0, - AFS_4G, - AFS_8G, - AFS_16G -}; - -enum Gscale { - GFS_250DPS = 0, - GFS_500DPS, - GFS_1000DPS, - GFS_2000DPS -}; - -enum Mscale { - MFS_14BITS = 0, // 0.6 mG per LSB - MFS_16BITS // 0.15 mG per LSB -}; - -enum Posr { - P_OSR_00 = 0, // no op - P_OSR_01, - P_OSR_02, - P_OSR_04, - P_OSR_08, - P_OSR_16 -}; - -enum Tosr { - T_OSR_00 = 0, // no op - T_OSR_01, - T_OSR_02, - T_OSR_04, - T_OSR_08, - T_OSR_16 -}; - -enum IIRFilter { - full = 0, // bandwidth at full sample rate - BW0_223ODR, - BW0_092ODR, - BW0_042ODR, - BW0_021ODR // bandwidth at 0.021 x sample rate -}; - -enum Mode { - BMP280Sleep = 0, - forced, - forced2, - normal -}; - -enum SBy { - t_00_5ms = 0, - t_62_5ms, - t_125ms, - t_250ms, - t_500ms, - t_1000ms, - t_2000ms, - t_4000ms, -}; - -struct acc_cal -{ - int16_t accZero_max[3]; - int16_t accZero_min[3]; -}; - -struct Sentral_WS_params -{ - uint8_t Sen_param[35][4]; -}; - -/*************************************************************************************************/ -/************* ***************/ -/************* Global Scope Variables ***************/ -/************* ***************/ -/*************************************************************************************************/ - -// General purpose variables -int16_t serial_input; -static int16_t warm_start = 0; -static int16_t accel_cal = 0; -static int16_t warm_start_saved = 0; -static int16_t accel_cal_saved = 0; -static uint16_t calibratingA = 0; - -// Specify BMP280 configuration -uint8_t Posr = P_OSR_16; -uint8_t Tosr = T_OSR_02; -uint8_t Mode = normal; -uint8_t IIRFilter = BW0_042ODR; -uint8_t SBy = t_62_5ms; - -// t_fine carries fine temperature as global value for BMP280 -int32_t t_fine; - -// Specify sensor full scale -uint8_t Gscale = GFS_250DPS; -uint8_t Ascale = AFS_2G; - -// Choose either 14-bit or 16-bit magnetometer resolution -uint8_t Mscale = MFS_16BITS; - -// 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read -uint8_t Mmode = 0x02; - -// scale resolutions per LSB for the sensors -float aRes; -float gRes; -float mRes; - -// Pin definitions -// These can be changed, 2 and 3 are the Arduinos ext int pins -int intPin = 8; - -// LED on the Teensy 3.1 -int myLed = 13; - -// BMP280 compensation parameters -uint16_t dig_T1; -uint16_t dig_P1; -int16_t dig_T2; -int16_t dig_T3; -int16_t dig_P2; -int16_t dig_P3; -int16_t dig_P4; -int16_t dig_P5; -int16_t dig_P6; -int16_t dig_P7; -int16_t dig_P8; -int16_t dig_P9; - -// stores BMP280 pressures sensor pressure and temperature -double Temperature; -double Pressure; - -// pressure and temperature raw count output for BMP280 -int32_t rawPress; -int32_t rawTemp; - -// MPU9250 variables -// Stores the 16-bit signed accelerometer sensor output -int16_t accelCount[3]; - -// Stores the 16-bit signed gyro sensor output -int16_t gyroCount[3]; - -// Stores the 16-bit signed magnetometer sensor output -int16_t magCount[3]; - -// quaternion data register -float Quat[4] = {0, 0, 0, 0}; - -// Factory mag calibration and mag bias -float magCalibration[3] = {0, 0, 0}; - -// Bias corrections for gyro, accelerometer, mag -float gyroBias[3] = {0, 0, 0}; -float accelBias[3] = {0, 0, 0}; -float magBias[3] = {0, 0, 0}; -float magScale[3] = {0, 0, 0}; - -// Pressure, temperature raw count output -int16_t tempCount; -int16_t rawPressure; -int16_t rawTemperature; - -// Stores the MPU9250 internal chip temperature in degrees Celsius -float temperature; -float pressure; -float altitude; - -// holds results of gyro and accelerometer self test -float SelfTest[6]; - -// Global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) -// Gyroscope measurement error in rads/s (start at 40 deg/s) -float GyroMeasError = PI * (40.0f / 180.0f); - -// Gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) -float GyroMeasDrift = PI * (0.0f / 180.0f); - -// There is a tradeoff in the beta parameter between accuracy and response speed. -// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. -// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. -// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! -// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec -// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; -// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. -// In any case, this is the free parameter in the Madgwick filtering and fusion scheme. - -// Compute beta -float beta = sqrt(3.0f / 4.0f) * GyroMeasError; - -// Compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value -float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; - -// Used to control display output rate -uint32_t delt_t = 0; -uint32_t count = 0; -uint32_t sumCount = 0; -float pitch; -float yaw; -float roll; -float Yaw; -float Pitch; -float Roll; - -// Integration interval for both filter schemes -float deltat = 0.0f; -float sum = 0.0f; - -// used to calculate integration interval -uint32_t lastUpdate = 0; -uint32_t firstUpdate = 0; - -// used to calculate integration interval -uint32_t Now = 0; - -// used for param transfer -uint8_t param[4]; - -// EM7180 sensor full scale ranges -uint16_t EM7180_mag_fs; -uint16_t EM7180_acc_fs; -uint16_t EM7180_gyro_fs; - -// variables to hold latest sensor data values -float ax; -float ay; -float az; -float gx; -float gy; -float gz; -float mx; -float my; -float mz; - -// Vector to hold quaternion -float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; - -// Vector to hold integral error for Mahony method -float eInt[3] = {0.0f, 0.0f, 0.0f}; - -acc_cal global_conf; -Sentral_WS_params WS_params; - -#endif // Globals_h diff --git a/WarmStartandAccelCal/quaternionFilters b/WarmStartandAccelCal/quaternionFilters deleted file mode 100644 index 465dd61..0000000 --- a/WarmStartandAccelCal/quaternionFilters +++ /dev/null @@ -1,195 +0,0 @@ -#include "Arduino.h" - -// 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! - void 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 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 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; - - } diff --git a/quaternionFilters.ino b/quaternionFilters.ino deleted file mode 100644 index b347c43..0000000 --- a/quaternionFilters.ino +++ /dev/null @@ -1,194 +0,0 @@ - -// 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! - void 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 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 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; - - }