Browse Source

C-ify original Arduino C++ code; on the road to a clean compile

master
Daniel Peter Chokola 4 years ago
parent
commit
4ac2f8860f
  1. 244
      Drivers/EM7180/Inc/em7180.h
  2. 28
      Drivers/EM7180/Inc/lis2mdl.h
  3. 21
      Drivers/EM7180/Inc/lps22hb.h
  4. 35
      Drivers/EM7180/Inc/lsm6dsm.h
  5. 1393
      Drivers/EM7180/Src/em7180.c
  6. 208
      Drivers/EM7180/Src/lis2mdl.c
  7. 119
      Drivers/EM7180/Src/lps22hb.c
  8. 281
      Drivers/EM7180/Src/lsm6dsm.c

244
Drivers/EM7180/Inc/em7180.h

@ -18,164 +18,11 @@
/* Includes */ /* Includes */
#include <stdint.h> #include <stdint.h>
// See MS5637-02BA03 Low Voltage Barometric Pressure Sensor Data Sheet /* Definitions */
#define MS5637_RESET 0x1E /*
#define MS5637_CONVERT_D1 0x40 * EM7180 SENtral register map
#define MS5637_CONVERT_D2 0x50 * see http://www.emdeveloper.com/downloads/7180/EMSentral_EM7180_Register_Map_v1_3.pdf
#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_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_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_QZ 0x08 // this is a 32-bit normalized floating point number read from registers 0x08-0B
@ -247,9 +94,6 @@
#define EM7180_ADDRESS 0x28 // Address of the EM7180 SENtral sensor hub #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 #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 AFS_2G 0 #define AFS_2G 0
#define AFS_4G 1 #define AFS_4G 1
@ -264,79 +108,9 @@
#define MFS_14BITS 0 // 0.6 mG per LSB #define MFS_14BITS 0 // 0.6 mG per LSB
#define MFS_16BITS 1 // 0.15 mG per LSB #define MFS_16BITS 1 // 0.15 mG per LSB
#define ADC_256 0x00 // define pressure and temperature conversion rates /* Function Prototypes */
#define ADC_512 0x02 void em7180_gyro_set_fs(uint16_t gyro_fs);
#define ADC_1024 0x04 void em7180_mag_acc_set_fs(uint16_t mag_fs, uint16_t acc_fs);
#define ADC_2048 0x06 void em7180_set_integer_param(uint8_t param, uint32_t param_val);
#define ADC_4096 0x08
#define ADC_8192 0x0A
#define ADC_D1 0x40
#define ADC_D2 0x50
class USFS
{
public:
USFS(uint8_t intPin, bool passThru);
float getAres(uint8_t Ascale);
float getGres(uint8_t Gscale);
float getMres(uint8_t Mscale);
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 readAccelData(int16_t * destination);
void readGyroData(int16_t * destination);
void readMagData(int16_t * destination);
int16_t readTempData();
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);
void initAK8963(uint8_t Mscale, uint8_t Mmode, float * destination);
void initMPU9250(uint8_t Ascale, uint8_t Gscale);
void accelgyrocalMPU9250(float * dest1, float * dest2);
void magcalMPU9250(float * dest1, float * dest2);
void MPU9250SelfTest(float * destination);
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 MS5637Reset();
void MS5637PromRead(uint16_t * destination);
uint32_t MS5637Read(uint8_t CMD, uint8_t OSR);
unsigned char MS5637checkCRC(uint16_t * n_prom);
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();
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;
bool _passThru;
float _aRes;
float _gRes;
float _mRes;
uint8_t _Mmode;
float _fuseROMx;
float _fuseROMy;
float _fuseROMz;
float _q[4];
float _beta;
float _deltat;
float _Kp;
float _Ki;
};
#endif /* EM7180_H_ */ #endif /* EM7180_H_ */

28
Drivers/EM7180/Inc/lis2mdl.h

@ -17,9 +17,10 @@
#ifndef LIS2MDL_h #ifndef LIS2MDL_h
#define LIS2MDL_h #define LIS2MDL_h
#include "Arduino.h" /* Includes */
#include <Wire.h> #include <stdint.h>
/* Definitions */
//Register map for LIS2MDL' //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 // 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 0x45
@ -53,27 +54,4 @@
#define MODR_50Hz 0x02 #define MODR_50Hz 0x02
#define MODR_100Hz 0x03 #define MODR_100Hz 0x03
class LIS2MDL
{
public:
LIS2MDL(uint8_t intPin);
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;
};
#endif #endif

21
Drivers/EM7180/Inc/lps22hb.h

@ -17,8 +17,8 @@
#ifndef LPS22HB_h #ifndef LPS22HB_h
#define LPS22HB_h #define LPS22HB_h
#include "Arduino.h" /* Includes */
#include "Wire.h" #include <stdint.h>
// See LPS22H "MEMS pressure sensor: 260-1260 hPa absolute digital output barometer" Data Sheet // 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 // 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
@ -56,21 +56,4 @@
#define P_50Hz 0x04; #define P_50Hz 0x04;
#define P_75Hz 0x05; #define P_75Hz 0x05;
class LPS22H
{
public:
LPS22H(uint8_t intPin);
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;
};
#endif #endif

35
Drivers/EM7180/Inc/lsm6dsm.h

@ -17,12 +17,13 @@
#ifndef LSM6DSM_h #ifndef LSM6DSM_h
#define LSM6DSM_h #define LSM6DSM_h
#include "Arduino.h" /* Includes */
#include <Wire.h> #include <stdint.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 * 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_FUNC_CFG_ACCESS 0x01
#define LSM6DSM_SENSOR_SYNC_TIME_FRAME 0x04 #define LSM6DSM_SENSOR_SYNC_TIME_FRAME 0x04
#define LSM6DSM_SENSOR_SYNC_RES_RATIO 0x05 #define LSM6DSM_SENSOR_SYNC_RES_RATIO 0x05
@ -157,28 +158,4 @@
#define GODR_3330Hz 0x09 #define GODR_3330Hz 0x09
#define GODR_6660Hz 0x0A #define GODR_6660Hz 0x0A
class LSM6DSM
{
public:
LSM6DSM(uint8_t intPin1, uint8_t intPin2);
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;
};
#endif #endif

1393
Drivers/EM7180/Src/em7180.c

File diff suppressed because it is too large Load Diff

208
Drivers/EM7180/Src/lis2mdl.c

@ -14,132 +14,147 @@
* Library may be used freely and without limit with attribution. * Library may be used freely and without limit with attribution.
*/ */
/* Includes */
#include <stdint.h>
#include "lis2mdl.h" #include "lis2mdl.h"
LIS2MDL::LIS2MDL(uint8_t intPin) /* Private Global Variables */
static uint8_t _intPin;
static float _mRes;
/* Function Prototypes */
static void lis2mdl_write_byte(uint8_t address, uint8_t subAddress,
uint8_t data);
static uint8_t lis2mdl_read_byte(uint8_t address, uint8_t subAddress);
static void lis2mdl_read(uint8_t address, uint8_t subAddress, uint8_t count,
uint8_t *dest);
/* Function Definitions */
lis2mdl_new(uint8_t pin)
{ {
pinMode(intPin, INPUT); pinMode(pin, INPUT);
_intPin = intPin; _intPin = pin;
} }
uint8_t lis2mdl_chip_id_get()
uint8_t LIS2MDL::getChipID()
{ {
uint8_t c = readByte(LIS2MDL_ADDRESS, LIS2MDL_WHO_AM_I); uint8_t c = lis2mdl_read_byte(LIS2MDL_ADDRESS, LIS2MDL_WHO_AM_I);
return c; return c;
} }
void lis2mdl_reset()
void LIS2MDL::reset()
{ {
// reset device // reset device
uint8_t temp = readByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A); uint8_t temp = lis2mdl_read_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A);
writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, temp | 0x20); // Set bit 5 to 1 to reset LIS2MDL lis2mdl_write_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, temp | 0x20); // Set bit 5 to 1 to reset LIS2MDL
delay(1); delay(1);
writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, temp | 0x40); // Set bit 6 to 1 to boot LIS2MDL lis2mdl_write_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, temp | 0x40); // Set bit 6 to 1 to boot LIS2MDL
delay(100); // Wait for all registers to reset delay(100); // Wait for all registers to reset
} }
void LIS2MDL::init(uint8_t MODR) void lis2mdl_init(uint8_t MODR)
{ {
// enable temperature compensation (bit 7 == 1), continuous mode (bits 0:1 == 00) // enable temperature compensation (bit 7 == 1), continuous mode (bits 0:1 == 00)
writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, 0x80 | MODR<<2); lis2mdl_write_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_A, 0x80 | MODR << 2);
// enable low pass filter (bit 0 == 1), set to ODR/4 // enable low pass filter (bit 0 == 1), set to ODR/4
writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_B, 0x01); lis2mdl_write_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_B, 0x01);
// enable data ready on interrupt pin (bit 0 == 1), enable block data read (bit 4 == 1) // enable data ready on interrupt pin (bit 0 == 1), enable block data read (bit 4 == 1)
writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, 0x01 | 0x10); lis2mdl_write_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, 0x01 | 0x10);
} }
uint8_t lis2mdl_status()
uint8_t LIS2MDL::status()
{ {
// Read the status register of the altimeter // Read the status register of the altimeter
uint8_t temp = readByte(LIS2MDL_ADDRESS, LIS2MDL_STATUS_REG); uint8_t temp = lis2mdl_read_byte(LIS2MDL_ADDRESS, LIS2MDL_STATUS_REG);
return temp; return temp;
} }
void lis2mdl_data_get(int16_t *destination)
void LIS2MDL::readData(int16_t * destination)
{ {
uint8_t rawData[6]; // x/y/z mag register data stored here uint8_t rawData[6]; // x/y/z mag register data stored here
readBytes(LIS2MDL_ADDRESS, (0x80 | LIS2MDL_OUTX_L_REG), 8, &rawData[0]); // Read the 6 raw data registers into data array lis2mdl_read_bytes(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[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[1] = ((int16_t) rawData[3] << 8) | rawData[2];
destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; destination[2] = ((int16_t) rawData[5] << 8) | rawData[4];
} }
int16_t lis2mdl_temp_get()
int16_t LIS2MDL::readTemperature()
{ {
uint8_t rawData[2]; // x/y/z mag register data stored here uint8_t rawData[2]; // x/y/z mag register data stored here
readBytes(LIS2MDL_ADDRESS, (0x80 | LIS2MDL_TEMP_OUT_L_REG), 2, &rawData[0]); // Read the 8 raw data registers into data array lis2mdl_read_bytes(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 int16_t temp = ((int16_t) rawData[1] << 8) | rawData[0]; // Turn the MSB and LSB into a signed 16-bit value
return temp; return temp;
} }
void lis2mdl_offset_bias(float *dest1, float *dest2)
void LIS2MDL::offsetBias(float * dest1, float * dest2)
{ {
int32_t mag_bias[3] = {0, 0, 0}, mag_scale[3] = {0, 0, 0}; 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}; int16_t mag_max[3] = { -32767, -32767, -32767 }, mag_min[3] =
{ 32767, 32767, 32767 }, mag_temp[3] = { 0, 0, 0 };
float _mRes = 0.0015f; float _mRes = 0.0015f;
Serial.println("Calculate mag offset bias: move all around to sample the complete response surface!"); Serial.println(
"Calculate mag offset bias: move all around to sample the complete response surface!");
delay(4000); delay(4000);
for (int ii = 0; ii < 4000; ii++) for(int ii = 0; ii < 4000; ii++)
{
lis2mdl_data_get(mag_temp);
for(int jj = 0; jj < 3; jj++)
{ {
readData(mag_temp); if(mag_temp[jj] > mag_max[jj])
for (int jj = 0; jj < 3; jj++) { mag_max[jj] = mag_temp[jj];
if(mag_temp[jj] > mag_max[jj]) mag_max[jj] = mag_temp[jj]; if(mag_temp[jj] < mag_min[jj])
if(mag_temp[jj] < mag_min[jj]) mag_min[jj] = mag_temp[jj]; mag_min[jj] = mag_temp[jj];
} }
delay(12); delay(12);
} }
_mRes = 0.0015f; // fixed sensitivity _mRes = 0.0015f; // fixed sensitivity
// Get hard iron correction // Get hard iron correction
mag_bias[0] = (mag_max[0] + mag_min[0])/2; // get average x mag bias in counts 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[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 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[0] = (float) mag_bias[0] * _mRes; // save mag biases in G for main program
dest1[1] = (float) mag_bias[1] * _mRes; dest1[1] = (float) mag_bias[1] * _mRes;
dest1[2] = (float) mag_bias[2] * _mRes; dest1[2] = (float) mag_bias[2] * _mRes;
// Get soft iron correction estimate // 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[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[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 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]; float avg_rad = mag_scale[0] + mag_scale[1] + mag_scale[2];
avg_rad /= 3.0f; avg_rad /= 3.0f;
dest2[0] = avg_rad/((float)mag_scale[0]); dest2[0] = avg_rad / ((float) mag_scale[0]);
dest2[1] = avg_rad/((float)mag_scale[1]); dest2[1] = avg_rad / ((float) mag_scale[1]);
dest2[2] = avg_rad/((float)mag_scale[2]); dest2[2] = avg_rad / ((float) mag_scale[2]);
Serial.println("Mag Calibration done!"); Serial.println("Mag Calibration done!");
} }
void LIS2MDL::selfTest() void lis2mdl_self_test()
{ {
int16_t temp[3] = {0, 0, 0}; int16_t temp[3] = { 0, 0, 0 };
float magTest[3] = {0., 0., 0.}; float magTest[3] = { 0., 0., 0. };
float magNom[3] = {0., 0., 0.}; float magNom[3] = { 0., 0., 0. };
int32_t sum[3] = {0, 0, 0}; int32_t sum[3] = { 0, 0, 0 };
float _mRes = 0.0015f; float _mRes = 0.0015f;
// first, get average response with self test disabled // first, get average response with self test disabled
for (int ii = 0; ii < 50; ii++) for(int ii = 0; ii < 50; ii++)
{ {
readData(temp); lis2mdl_data_get(temp);
sum[0] += temp[0]; sum[0] += temp[0];
sum[1] += temp[1]; sum[1] += temp[1];
sum[2] += temp[2]; sum[2] += temp[2];
@ -150,16 +165,16 @@ void LIS2MDL::selfTest()
magNom[1] = (float) sum[1] / 50.0f; magNom[1] = (float) sum[1] / 50.0f;
magNom[2] = (float) sum[2] / 50.0f; magNom[2] = (float) sum[2] / 50.0f;
uint8_t c = readByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C); uint8_t c = lis2mdl_read_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C);
writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, c | 0x02); // enable self test lis2mdl_write_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, c | 0x02); // enable self test
delay(100); // let mag respond delay(100); // let mag respond
sum[0] = 0; sum[0] = 0;
sum[1] = 0; sum[1] = 0;
sum[2] = 0; sum[2] = 0;
for (int ii = 0; ii < 50; ii++) for(int ii = 0; ii < 50; ii++)
{ {
readData(temp); lis2mdl_data_get(temp);
sum[0] += temp[0]; sum[0] += temp[0];
sum[1] += temp[1]; sum[1] += temp[1];
sum[2] += temp[2]; sum[2] += temp[2];
@ -170,80 +185,41 @@ void LIS2MDL::selfTest()
magTest[1] = (float) sum[1] / 50.0f; magTest[1] = (float) sum[1] / 50.0f;
magTest[2] = (float) sum[2] / 50.0f; magTest[2] = (float) sum[2] / 50.0f;
writeByte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, c); // return to previous settings/normal mode lis2mdl_write_byte(LIS2MDL_ADDRESS, LIS2MDL_CFG_REG_C, c); // return to previous settings/normal mode
delay(100); // let mag respond delay(100); // let mag respond
Serial.println("Mag Self Test:"); Serial.println("Mag Self Test:");
Serial.print("Mx results:"); Serial.print( (magTest[0] - magNom[0]) * _mRes * 1000.0); Serial.println(" mG"); Serial.print("Mx results:");
Serial.print("My results:"); Serial.println((magTest[0] - magNom[0]) * _mRes * 1000.0); Serial.print((magTest[0] - magNom[0]) * _mRes * 1000.0);
Serial.print("Mz results:"); Serial.println((magTest[1] - magNom[1]) * _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"); Serial.println("Should be between 15 and 500 mG");
delay(2000); // give some time to read the screen delay(2000); // give some time to read the screen
} }
// I2C scan function
void LIS2MDL::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.endTransmission to see if
// a device did acknowledge to the address.
// Wire.beginTransmission(address);
// error = Wire.endTransmission();
error = Wire.transfer(address, NULL, 0, NULL, 0);
if (error == 0)
{
Serial.print("I2C device found at address 0x");
if (address<16)
Serial.print("0");
Serial.print(address,HEX);
Serial.println(" !");
nDevices++;
}
else if (error==4)
{
Serial.print("Unknown error at address 0x");
if (address<16)
Serial.print("0");
Serial.println(address,HEX);
}
}
if (nDevices == 0)
Serial.println("No I2C devices found\n");
else
Serial.println("done\n");
}
// I2C read/write functions for the LIS2MDL // I2C read/write functions for the LIS2MDL
void LIS2MDL::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) { static void lis2mdl_write_byte(uint8_t address, uint8_t subAddress,
uint8_t data)
{
uint8_t temp[2]; uint8_t temp[2];
temp[0] = subAddress; temp[0] = subAddress;
temp[1] = data; temp[1] = data;
Wire.transfer(address, &temp[0], 2, NULL, 0); Wire.transfer(address, &temp[0], 2, NULL, 0);
} }
uint8_t LIS2MDL::readByte(uint8_t address, uint8_t subAddress) { static uint8_t lis2mdl_read_byte(uint8_t address, uint8_t subAddress)
{
uint8_t temp[1]; uint8_t temp[1];
Wire.transfer(address, &subAddress, 1, &temp[0], 1); Wire.transfer(address, &subAddress, 1, &temp[0], 1);
return temp[0]; return temp[0];
} }
void LIS2MDL::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) { static void lis2mdl_read(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);
} }

119
Drivers/EM7180/Src/lps22hb.c

@ -14,124 +14,95 @@
* Library may be used freely and without limit with attribution. * Library may be used freely and without limit with attribution.
*/ */
/* Includes */
#include <stdint.h>
#include "lps22hb.h" #include "lps22hb.h"
#include "Wire.h"
LPS22H::LPS22H(uint8_t intPin) /* Private Global Variables */
static uint8_t _intPin;
/* Function Prototypes */
static void lps22h_write_byte(uint8_t address, uint8_t subAddress, uint8_t data);
static uint8_t lps22h_read_byte(uint8_t address, uint8_t subAddress);
static void lps22h_read(uint8_t address, uint8_t subAddress, uint8_t count,
uint8_t *dest);
/* Function Definitions */
lps22h_new(uint8_t pin)
{ {
pinMode(intPin, INPUT); pinMode(pin, INPUT);
_intPin = intPin; _intPin = pin;
} }
uint8_t LPS22H::getChipID() uint8_t lps22h_getChipID()
{ {
// Read the WHO_AM_I register of the altimeter this is a good test of communication // Read the WHO_AM_I register of the altimeter this is a good test of communication
uint8_t temp = readByte(LPS22H_ADDRESS, LPS22H_WHOAMI); // Read WHO_AM_I register for LPS22H uint8_t temp = lps22h_read_byte(LPS22H_ADDRESS, LPS22H_WHOAMI); // Read WHO_AM_I register for LPS22H
return temp; return temp;
} }
uint8_t LPS22H::status() uint8_t lps22h_status()
{ {
// Read the status register of the altimeter // Read the status register of the altimeter
uint8_t temp = readByte(LPS22H_ADDRESS, LPS22H_STATUS); uint8_t temp = lps22h_read_byte(LPS22H_ADDRESS, LPS22H_STATUS);
return temp; return temp;
} }
int32_t LPS22H::readAltimeterPressure() int32_t lps22h_pressure_get()
{ {
uint8_t rawData[3]; // 24-bit pressure register data stored here uint8_t rawData[3]; // 24-bit pressure register data stored here
readBytes(LPS22H_ADDRESS, (LPS22H_PRESS_OUT_XL | 0x80), 3, &rawData[0]); // bit 7 must be one to read multiple bytes lps22h_read(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]); return (int32_t) ((int32_t) rawData[2] << 16 | (int32_t) rawData[1] << 8
| rawData[0]);
} }
int16_t LPS22H::readAltimeterTemperature() int16_t lps22h_temp_get()
{ {
uint8_t rawData[2]; // 16-bit pressure register data stored here uint8_t rawData[2]; // 16-bit pressure register data stored here
readBytes(LPS22H_ADDRESS, (LPS22H_TEMP_OUT_L | 0x80), 2, &rawData[0]); // bit 7 must be one to read multiple bytes lps22h_read(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]); return (int16_t) ((int16_t) rawData[1] << 8 | rawData[0]);
} }
void lps22h_init(uint8_t PODR)
void LPS22H::Init(uint8_t PODR)
{ {
// set sample rate by setting bits 6:4 // set sample rate by setting bits 6:4
// enable low-pass filter by setting bit 3 to one // 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 // 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 // make sure data not updated during read by setting block data udate (bit 1) to 1
writeByte(LPS22H_ADDRESS, LPS22H_CTRL_REG1, PODR << 4 | 0x08 | 0x02); lps22h_write_byte(LPS22H_ADDRESS, LPS22H_CTRL_REG1,
writeByte(LPS22H_ADDRESS, LPS22H_CTRL_REG3, 0x04); // enable data ready as interrupt source PODR << 4 | 0x08 | 0x02);
lps22h_write_byte(LPS22H_ADDRESS, LPS22H_CTRL_REG3, 0x04); // enable data ready as interrupt source
} }
// I2C scan function static void lps22h_write_byte(uint8_t address, uint8_t subAddress, uint8_t data)
void LPS22H::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.endTransmission 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("Unknown error at address 0x");
if (address<16)
Serial.print("0");
Serial.println(address,HEX);
}
}
if (nDevices == 0)
Serial.println("No I2C devices found\n");
else
Serial.println("done\n");
}
void LPS22H::writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
{
Wire.beginTransmission(address); // Initialize the Tx buffer Wire.beginTransmission(address); // Initialize the Tx buffer
Wire.write(subAddress); // Put slave register address in Tx buffer Wire.write(subAddress); // Put slave register address in Tx buffer
Wire.write(data); // Put data in Tx buffer Wire.write(data); // Put data in Tx buffer
Wire.endTransmission(); // Send the Tx buffer Wire.endTransmission(); // Send the Tx buffer
} }
uint8_t LPS22H::readByte(uint8_t address, uint8_t subAddress) static uint8_t lps22h_read_byte(uint8_t address, uint8_t subAddress)
{ {
uint8_t data; // `data` will store the register data uint8_t data; // `data` will store the register data
Wire.beginTransmission(address); // Initialize the Tx buffer Wire.beginTransmission(address); // Initialize the Tx buffer
Wire.write(subAddress); // Put slave register address in Tx buffer Wire.write(subAddress); // Put slave register address in Tx buffer
Wire.endTransmission(false); // 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, (size_t) 1); // Read one uint8_t from slave register address Wire.requestFrom(address, (size_t) 1); // Read one uint8_t from slave register address
data = Wire.read(); // Fill Rx buffer with result data = Wire.read(); // Fill Rx buffer with result
return data; // Return data read from slave register return data; // Return data lps22h_read from slave register
} }
void LPS22H::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) static void lps22h_read(uint8_t address, uint8_t subAddress, uint8_t count,
{ uint8_t *dest)
{
Wire.beginTransmission(address); // Initialize the Tx buffer Wire.beginTransmission(address); // Initialize the Tx buffer
Wire.write(subAddress); // Put slave register address in Tx buffer Wire.write(subAddress); // Put slave register address in Tx buffer
Wire.endTransmission(false); // 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; uint8_t i = 0;
Wire.requestFrom(address, (size_t)count); // Read bytes from slave register address Wire.requestFrom(address, (size_t) count); // Read bytes from slave register address
while (Wire.available()) { while(Wire.available())
dest[i++] = Wire.read(); } // Put read results in the Rx buffer {
} dest[i++] = Wire.lps22h_read();
} // Put lps22h_read results in the Rx buffer
}

281
Drivers/EM7180/Src/lsm6dsm.c

@ -14,109 +14,126 @@
* Library may be used freely and without limit with attribution. * Library may be used freely and without limit with attribution.
*/ */
/* Includes */
#include <stdint.h>
#include "lsm6dsm.h" #include "lsm6dsm.h"
LSM6DSM::LSM6DSM(uint8_t intPin1, uint8_t intPin2) /* Private Global Variables */
static uint8_t _intPin1;
static uint8_t _intPin2;
static float _aRes;
static float _gRes;
/* Function Prototypes */
static void lsm6dsm_write_byte(uint8_t address, uint8_t subAddress,
uint8_t data);
static uint8_t lsm6dsm_read_byte(uint8_t address, uint8_t subAddress);
static void lsm6dsm_read(uint8_t address, uint8_t subAddress, uint8_t count,
uint8_t *dest);
/* Function Definitions */
lsm6dsm_new(uint8_t pin1, uint8_t pin2)
{ {
pinMode(intPin1, INPUT); pinMode(pin1, INPUT);
_intPin1 = intPin1; _intPin1 = pin1;
pinMode(intPin2, INPUT); pinMode(pin2, INPUT);
_intPin2 = intPin2; _intPin2 = pin2;
} }
uint8_t lsm6dsm_chip_id_get()
uint8_t LSM6DSM::getChipID()
{ {
uint8_t c = readByte(LSM6DSM_ADDRESS, LSM6DSM_WHO_AM_I); uint8_t c = lsm6dsm_read_byte(LSM6DSM_ADDRESS, LSM6DSM_WHO_AM_I);
return c; return c;
} }
float LSM6DSM::getAres(uint8_t Ascale) { float lsm6dsm_ares_get(uint8_t ascale)
switch (Ascale) {
switch(ascale)
{ {
// Possible accelerometer scales (and their register bit settings) are: // 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 algorithm to calculate DPS/(ADC tick) based on that 2-bit value: // Here's a bit of an algorithm to calculate DPS/(ADC tick) based on that 2-bit value:
case AFS_2G: case AFS_2G:
_aRes = 2.0f/32768.0f; _aRes = 2.0f / 32768.0f;
return _aRes; return _aRes;
break; break;
case AFS_4G: case AFS_4G:
_aRes = 4.0f/32768.0f; _aRes = 4.0f / 32768.0f;
return _aRes; return _aRes;
break; break;
case AFS_8G: case AFS_8G:
_aRes = 8.0f/32768.0f; _aRes = 8.0f / 32768.0f;
return _aRes; return _aRes;
break; break;
case AFS_16G: case AFS_16G:
_aRes = 16.0f/32768.0f; _aRes = 16.0f / 32768.0f;
return _aRes; return _aRes;
break; break;
} }
} }
float LSM6DSM::getGres(uint8_t Gscale) { float lsm6dsm_gres_get(uint8_t gscale)
switch (Gscale) {
switch(gscale)
{ {
// Possible gyro scales (and their register bit settings) are: // 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).
case GFS_245DPS: case GFS_245DPS:
_gRes = 245.0f/32768.0f; _gRes = 245.0f / 32768.0f;
return _gRes; return _gRes;
break; break;
case GFS_500DPS: case GFS_500DPS:
_gRes = 500.0f/32768.0f; _gRes = 500.0f / 32768.0f;
return _gRes; return _gRes;
break; break;
case GFS_1000DPS: case GFS_1000DPS:
_gRes = 1000.0f/32768.0f; _gRes = 1000.0f / 32768.0f;
return _gRes; return _gRes;
break; break;
case GFS_2000DPS: case GFS_2000DPS:
_gRes = 2000.0f/32768.0f; _gRes = 2000.0f / 32768.0f;
return _gRes; return _gRes;
break; break;
} }
} }
void lsm6dsm_reset()
void LSM6DSM::reset()
{ {
// reset device // reset device
uint8_t temp = readByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C); uint8_t temp = lsm6dsm_read_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C);
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C, temp | 0x01); // Set bit 0 to 1 to reset LSM6DSM lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C, temp | 0x01); // Set bit 0 to 1 to reset LSM6DSM
delay(100); // Wait for all registers to reset delay(100); // Wait for all registers to reset
} }
void lsm6dsm_init(uint8_t ascale, uint8_t gscale, uint8_t AODR, uint8_t GODR)
void LSM6DSM::init(uint8_t Ascale, uint8_t Gscale, uint8_t AODR, uint8_t GODR)
{ {
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL1_XL, AODR << 4 | Ascale << 2); lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL1_XL,
AODR << 4 | ascale << 2);
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL2_G, GODR << 4 | Gscale << 2); lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL2_G,
GODR << 4 | gscale << 2);
uint8_t temp = readByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C); uint8_t temp = lsm6dsm_read_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C);
// enable block update (bit 6 = 1), auto-increment registers (bit 2 = 1) // enable block update (bit 6 = 1), auto-increment registers (bit 2 = 1)
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C, temp | 0x40 | 0x04); lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL3_C, temp | 0x40 | 0x04);
// by default, interrupts active HIGH, push pull, little endian data // 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) // (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 // enable accel LP2 (bit 7 = 1), set LP2 tp ODR/9 (bit 6 = 1), enable input_composite (bit 3) for low noise
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL8_XL, 0x80 | 0x40 | 0x08 ); lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL8_XL, 0x80 | 0x40 | 0x08);
// interrupt handling // interrupt handling
writeByte(LSM6DSM_ADDRESS, LSM6DSM_DRDY_PULSE_CFG, 0x80); // latch interrupt until data read lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_DRDY_PULSE_CFG, 0x80); // latch interrupt until data read
writeByte(LSM6DSM_ADDRESS, LSM6DSM_INT1_CTRL, 0x40); // enable significant motion interrupts on INT1 lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_INT1_CTRL, 0x40); // enable significant motion interrupts on INT1
writeByte(LSM6DSM_ADDRESS, LSM6DSM_INT2_CTRL, 0x03); // enable accel/gyro data ready interrupts on INT2 lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_INT2_CTRL, 0x03); // enable accel/gyro data ready interrupts on INT2
} }
void lsm6dsm_selfTest()
void LSM6DSM::selfTest()
{ {
int16_t temp[7] = {0, 0, 0, 0, 0, 0, 0}; 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 accelPTest[3] = { 0, 0, 0 }, accelNTest[3] = { 0, 0, 0 },
int16_t accelNom[3] = {0, 0, 0}, gyroNom[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); readData(temp);
accelNom[0] = temp[4]; accelNom[0] = temp[4];
@ -126,69 +143,82 @@ void LSM6DSM::selfTest()
gyroNom[1] = temp[2]; gyroNom[1] = temp[2];
gyroNom[2] = temp[3]; gyroNom[2] = temp[3];
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x01); // positive accel self test lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x01); // positive accel self test
delay(100); // let accel respond delay(100); // let accel respond
readData(temp); readData(temp);
accelPTest[0] = temp[4]; accelPTest[0] = temp[4];
accelPTest[1] = temp[5]; accelPTest[1] = temp[5];
accelPTest[2] = temp[6]; accelPTest[2] = temp[6];
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x03); // negative accel self test lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x03); // negative accel self test
delay(100); // let accel respond delay(100); // let accel respond
readData(temp); readData(temp);
accelNTest[0] = temp[4]; accelNTest[0] = temp[4];
accelNTest[1] = temp[5]; accelNTest[1] = temp[5];
accelNTest[2] = temp[6]; accelNTest[2] = temp[6];
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x04); // positive gyro self test lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x04); // positive gyro self test
delay(100); // let gyro respond delay(100); // let gyro respond
readData(temp); readData(temp);
gyroPTest[0] = temp[1]; gyroPTest[0] = temp[1];
gyroPTest[1] = temp[2]; gyroPTest[1] = temp[2];
gyroPTest[2] = temp[3]; gyroPTest[2] = temp[3];
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x0C); // negative gyro self test lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x0C); // negative gyro self test
delay(100); // let gyro respond delay(100); // let gyro respond
readData(temp); readData(temp);
gyroNTest[0] = temp[1]; gyroNTest[0] = temp[1];
gyroNTest[1] = temp[2]; gyroNTest[1] = temp[2];
gyroNTest[2] = temp[3]; gyroNTest[2] = temp[3];
writeByte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x00); // normal mode lsm6dsm_write_byte(LSM6DSM_ADDRESS, LSM6DSM_CTRL5_C, 0x00); // normal mode
delay(100); // let accel and gyro respond delay(100); // let accel and gyro respond
Serial.println("Accel Self Test:"); 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.print("-Ax results:"); Serial.println((accelNTest[0] - accelNom[0]) * _aRes * 1000.0); Serial.print((accelPTest[0] - accelNom[0]) * _aRes * 1000.0);
Serial.print("+Ay results:"); Serial.println((accelPTest[1] - accelNom[1]) * _aRes * 1000.0); Serial.println(" mg");
Serial.print("-Ay results:"); Serial.println((accelNTest[1] - accelNom[1]) * _aRes * 1000.0); Serial.print("-Ax results:");
Serial.print("+Az results:"); Serial.println((accelPTest[2] - accelNom[2]) * _aRes * 1000.0); Serial.println((accelNTest[0] - accelNom[0]) * _aRes * 1000.0);
Serial.print("-Az results:"); Serial.println((accelNTest[2] - accelNom[2]) * _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("Should be between 90 and 1700 mg");
Serial.println("Gyro Self Test:"); Serial.println("Gyro Self Test:");
Serial.print("+Gx results:"); Serial.print((gyroPTest[0] - gyroNom[0]) * _gRes); Serial.println(" dps"); Serial.print("+Gx results:");
Serial.print("-Gx results:"); Serial.println((gyroNTest[0] - gyroNom[0]) * _gRes); Serial.print((gyroPTest[0] - gyroNom[0]) * _gRes);
Serial.print("+Gy results:"); Serial.println((gyroPTest[1] - gyroNom[1]) * _gRes); Serial.println(" dps");
Serial.print("-Gy results:"); Serial.println((gyroNTest[1] - gyroNom[1]) * _gRes); Serial.print("-Gx results:");
Serial.print("+Gz results:"); Serial.println((gyroPTest[2] - gyroNom[2]) * _gRes); Serial.println((gyroNTest[0] - gyroNom[0]) * _gRes);
Serial.print("-Gz results:"); Serial.println((gyroNTest[2] - gyroNom[2]) * _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"); Serial.println("Should be between 20 and 80 dps");
delay(2000); delay(2000);
} }
void lsm6dsm_offsetBias(float *dest1, float *dest2)
void LSM6DSM::offsetBias(float * dest1, float * dest2)
{ {
int16_t temp[7] = {0, 0, 0, 0, 0, 0, 0}; int16_t temp[7] = { 0, 0, 0, 0, 0, 0, 0 };
int32_t sum[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!"); Serial.println(
"Calculate accel and gyro offset biases: keep sensor flat and motionless!");
delay(4000); delay(4000);
for (int ii = 0; ii < 128; ii++) for(int ii = 0; ii < 128; ii++)
{ {
readData(temp); readData(temp);
sum[1] += temp[1]; sum[1] += temp[1];
@ -200,95 +230,72 @@ void LSM6DSM::offsetBias(float * dest1, float * dest2)
delay(50); delay(50);
} }
dest1[0] = sum[1]*_gRes/128.0f; dest1[0] = sum[1] * _gRes / 128.0f;
dest1[1] = sum[2]*_gRes/128.0f; dest1[1] = sum[2] * _gRes / 128.0f;
dest1[2] = sum[3]*_gRes/128.0f; dest1[2] = sum[3] * _gRes / 128.0f;
dest2[0] = sum[4]*_aRes/128.0f; dest2[0] = sum[4] * _aRes / 128.0f;
dest2[1] = sum[5]*_aRes/128.0f; dest2[1] = sum[5] * _aRes / 128.0f;
dest2[2] = sum[6]*_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)
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
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] ;
}
// I2C scan function
void LSM6DSM::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 dest2[0] -= 1.0f;
// the Write.endTransmission to see if } // Remove gravity from the x-axis accelerometer bias calculation
// a device did acknowledge to the address. if(dest2[0] < -0.8f)
// Wire.beginTransmission(address);
// error = Wire.endTransmission();
error = Wire.transfer(address, NULL, 0, NULL, 0);
if (error == 0)
{ {
Serial.print("I2C device found at address 0x"); dest2[0] += 1.0f;
if (address<16) } // Remove gravity from the x-axis accelerometer bias calculation
Serial.print("0"); if(dest2[1] > 0.8f)
Serial.print(address,HEX);
Serial.println(" !");
nDevices++;
}
else if (error==4)
{ {
Serial.print("Unknown error at address 0x"); dest2[1] -= 1.0f;
if (address<16) } // Remove gravity from the y-axis accelerometer bias calculation
Serial.print("0"); if(dest2[1] < -0.8f)
Serial.println(address,HEX); {
} dest2[1] += 1.0f;
} } // Remove gravity from the y-axis accelerometer bias calculation
if (nDevices == 0) if(dest2[2] > 0.8f)
Serial.println("No I2C devices found\n"); {
else dest2[2] -= 1.0f;
Serial.println("done\n"); } // 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
} }
// I2C read/write functions for the LSM6DSM void lsm6dsm_read_data(int16_t *destination)
{
uint8_t rawdata[14]; // x/y/z accel register data stored here
lsm6dsm_read(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];
}
void LSM6DSM::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) { // I2C read/write functions for the LSM6DSM
static void lsm6dsm_write_byte(uint8_t address, uint8_t subAddress,
uint8_t data)
{
uint8_t temp[2]; uint8_t temp[2];
temp[0] = subAddress; temp[0] = subAddress;
temp[1] = data; temp[1] = data;
Wire.transfer(address, &temp[0], 2, NULL, 0); Wire.transfer(address, &temp[0], 2, NULL, 0);
} }
uint8_t LSM6DSM::readByte(uint8_t address, uint8_t subAddress) { static uint8_t lsm6dsm_read_byte(uint8_t address, uint8_t subAddress)
{
uint8_t temp[1]; uint8_t temp[1];
Wire.transfer(address, &subAddress, 1, &temp[0], 1); Wire.transfer(address, &subAddress, 1, &temp[0], 1);
return temp[0]; return temp[0];
} }
void LSM6DSM::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) { static void lsm6dsm_read(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);
} }

Loading…
Cancel
Save