Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
361 changes: 352 additions & 9 deletions BMI160.cpp

Large diffs are not rendered by default.

238 changes: 229 additions & 9 deletions BMI160.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,130 @@ THE SOFTWARE.

#include "Arduino.h"

/********** Define for magnetometer *************/
#define BMI160_MAG_PMU_STATUS_BIT 0 //Added for BMM150 Support
#define BMI160_MAG_PMU_STATUS_LEN 2 //Added for BMM150 Support

#define BMI160_STATUS_DRDY_MAG 5 //Added for BMM150 Support
#define BMI160_STATUS_MAG_MAN_OP 2 //Added for BMM150 Support
#define BMI160_MAG_RATE_SEL_BIT 0 //Added for BMM150 Support
#define BMI160_MAG_RATE_SEL_LEN 4 //Added for BMM150 Support
#define BMI160_FIFO_MAG_EN_BIT 5 //Added for BMM150 Support

#define BMI160_MAG_IF_0 0x4B //Added for BMM150 Support
#define BMI160_MAG_IF_1 0x4C //Added for BMM150 Support
#define BMI160_MAG_IF_2 0x4D //Added for BMM150 Support
#define BMI160_MAG_IF_3 0x4E //Added for BMM150 Support
#define BMI160_MAG_IF_4 0x4F //Added for BMM150 Support

#define BMM150_OK 0x00 //Added for BMM150 Support

#define BMM150_EN_SLEEP_MODE 0x01 //Added for BMM150 Support
//#define BMM150_XY_REPETITIONS 0x04 //Added for BMM150 Support
//#define BMM150_Z_REPETITIONS 0x0E //Added for BMM150 Support

/**\name POWER MODE DEFINTIONS */
#define BMM150_NORMAL_MODE UINT8_C(0x00)
#define BMM150_FORCED_MODE UINT8_C(0x01)
#define BMM150_SLEEP_MODE UINT8_C(0x03)
#define BMM150_SUSPEND_MODE UINT8_C(0x04)

#define BMM150_OP_MODE_BIT 1
#define BMM150_OP_MODE_LEN 2

//**\name PRESET MODES - REPETITIONS-XY RATES */
#define BMM150_LOWPOWER_REPXY UINT8_C(1)
#define BMM150_REGULAR_REPXY UINT8_C(4)
#define BMM150_ENHANCED_REPXY UINT8_C(7)
#define BMM150_HIGHACCURACY_REPXY UINT8_C(23)

/**\name PRESET MODES - REPETITIONS-Z RATES */
#define BMM150_LOWPOWER_REPZ UINT8_C(2)
#define BMM150_REGULAR_REPZ UINT8_C(14)
#define BMM150_ENHANCED_REPZ UINT8_C(26)
#define BMM150_HIGHACCURACY_REPZ UINT8_C(82)

#define BMM150_DATA_REG 0x42 //Added for BMM150 Support
#define BMM150_POWER_REG 0x4B //Added for BMM150 Support
#define BMM150_OPMODE_REG 0x4C //Added for BMM150 Support
#define BMM150_XY_REP_REG 0x51 //Added for BMM150 Support
#define BMM150_Z_REP_REG 0x52 //Added for BMM150 Support

//Based I2C addr is 0x20 caused it is 0x10 plus one 0 at the end.
#define BMM150_BASED_I2C_ADDR 0x20 //Added for BMM150 Support
#define BMI160_MAG_MAN_EN 0x83 //Added for BMM150 Support
#define BMI160_MAG_MAN_DIS 0x03 //Added for BMM150 Support
#define BMI160_MAG_CONF_25Hz 0x06 //Added for BMM150 Support
#define BMM150_BASED_I2C_MASK 0xFE

#define BMM150_POWER_REG_DEFAULT 0x01 //Added for BMM150 Support
#define BMM150_OPMODE_REG_DEFAULT 0x02 //Added for BMM150 Support
#define BMM150_OPMODE_REG_P 0x06 //Added for BMM150 Support
#define BMM150_R_DATA_ADDR 0x42 //Added for BMM150 Support

//**\name Register Address */
#define BMM150_CHIP_ID_ADDR UINT8_C(0x40)
#define BMM150_DATA_X_LSB UINT8_C(0x42)
#define BMM150_DATA_READY_STATUS UINT8_C(0x48)
#define BMM150_INTERRUPT_STATUS UINT8_C(0x4A)
#define BMM150_POWER_CONTROL_ADDR UINT8_C(0x4B)
#define BMM150_OP_MODE_ADDR UINT8_C(0x4C)
#define BMM150_INT_CONFIG_ADDR UINT8_C(0x4D)
#define BMM150_AXES_ENABLE_ADDR UINT8_C(0x4E)
#define BMM150_LOW_THRESHOLD_ADDR UINT8_C(0x4F)
#define BMM150_HIGH_THRESHOLD_ADDR UINT8_C(0x50)
#define BMM150_REP_XY_ADDR UINT8_C(0x51)
#define BMM150_REP_Z_ADDR UINT8_C(0x52)

//**\name PRESET MODE DEFINITIONS */
#define BMM150_PRESETMODE_LOWPOWER UINT8_C(0x01)
#define BMM150_PRESETMODE_REGULAR UINT8_C(0x02)
#define BMM150_PRESETMODE_HIGHACCURACY UINT8_C(0x03)
#define BMM150_PRESETMODE_ENHANCED UINT8_C(0x04)

//**\name DATA RATE DEFINITIONS */
#define BMM150_DATA_RATE_10HZ UINT8_C(0x00)
#define BMM150_DATA_RATE_02HZ UINT8_C(0x01)
#define BMM150_DATA_RATE_06HZ UINT8_C(0x02)
#define BMM150_DATA_RATE_08HZ UINT8_C(0x03)
#define BMM150_DATA_RATE_15HZ UINT8_C(0x04)
#define BMM150_DATA_RATE_20HZ UINT8_C(0x05)
#define BMM150_DATA_RATE_25HZ UINT8_C(0x06)
#define BMM150_DATA_RATE_30HZ UINT8_C(0x07)

#define BMM150_DATA_RATE_BIT 3
#define BMM150_DATA_RATE_LEN 3

#define BMI160_FOC_CONF_DEFAULT 0x40 //Added for BMM150 Support

#define BMI160_IF_CONF 0x6B //Added for BMM150 Support

#define BMI160_2ND_INT_MAG 0x20 //Added for BMM150 Support

#define BMI160_EN_PULL_UP_REG_1 0x37 //Added for BMM150 Support
#define BMI160_EN_PULL_UP_REG_2 0x9A //Added for BMM150 Support
#define BMI160_EN_PULL_UP_REG_3 0xC0 //Added for BMM150 Support
#define BMI160_EN_PULL_UP_REG_4 0x90 //Added for BMM150 Support
#define BMI160_EN_PULL_UP_REG_5 0x80 //Added for BMM150 Support

#define BMI160_7F 0x7F //Added for BMM150 Support

#define BMI160_CMD_MAG_MODE_NORMAL 0x19 //Added for BMM150 Support

#define BMI160_RA_MAG_X_L 0x04 //Added for BMM150 Support
#define BMI160_RA_MAG_X_H 0x05 //Added for BMM150 Support
#define BMI160_RA_MAG_Y_L 0x06 //Added for BMM150 Support
#define BMI160_RA_MAG_Y_H 0x07 //Added for BMM150 Support
#define BMI160_RA_MAG_Z_L 0x08 //Added for BMM150 Support
#define BMI160_RA_MAG_Z_H 0x09 //Added for BMM150 Support
#define BMI160_RA_MAG_R_L 0x0A //Added for BMM150 Support
#define BMI160_RA_MAG_R_H 0x0B //Added for BMM150 Support

//#define BMI160_RA_MAG_CONF 0X44 //Added for BMM150 Support
#define BMI160_AUX_ODR_ADDR UINT8_C(0x44) //Added for BMM150 Support

/**************************/

#define BMI160_SPI_READ_BIT 7

#define BMI160_RA_CHIP_ID 0x00
Expand Down Expand Up @@ -124,6 +248,8 @@ THE SOFTWARE.
#define BMI160_RA_FIFO_CONFIG_0 0x46
#define BMI160_RA_FIFO_CONFIG_1 0x47

#define MAX_FIFO_BYTES 1024

#define BMI160_ANYMOTION_EN_BIT 0
#define BMI160_ANYMOTION_EN_LEN 3
#define BMI160_D_TAP_EN_BIT 4
Expand Down Expand Up @@ -264,6 +390,61 @@ THE SOFTWARE.

#define BMI160_RA_CMD 0x7E

//** Enable/disable bit value */
#define BMI160_ENABLE UINT8_C(0x01)
#define BMI160_DISABLE UINT8_C(0x00)

//Added for getMotion9() and convertMagneto[X-Z]() support

//Define Overflow Constants for MagnetoConversion on BMM150
#define BMM150_XYAXES_FLIP_OVERFLOW_ADCVAL INT16_C(-4096)
#define BMM150_ZAXIS_HALL_OVERFLOW_ADCVAL INT16_C(-16384)
#define BMM150_OVERFLOW_OUTPUT_FLOAT 0.0f

//Important BMM150 Registers
#define BMM150_DIG_X1 UINT8_C(0x5D)
#define BMM150_DIG_Z4_LSB UINT8_C(0x62)
#define BMM150_DIG_Z2_LSB UINT8_C(0x68)

//Delays, in milliseconds
#define BMI160_AUX_COM_DELAY UINT8_C(10)
#define BMI160_READ_WRITE_DELAY UINT8_C(1)

//Bit Masks for MAG_IF[1]
#define BMI160_MANUAL_MODE_EN_MSK UINT8_C(0x80)
#define BMI160_AUX_READ_BURST_MSK UINT8_C(0x03)

//Bit Masks and POS for LSB registers
#define BMM150_DATA_X_MSK UINT8_C(0xF8)
#define BMM150_DATA_X_POS UINT8_C(0x03)

#define BMM150_DATA_Y_MSK UINT8_C(0xF8)
#define BMM150_DATA_Y_POS UINT8_C(0x03)

#define BMM150_DATA_Z_MSK UINT8_C(0xFE)
#define BMM150_DATA_Z_POS UINT8_C(0x01)

#define BMM150_DATA_RHALL_MSK UINT8_C(0xFC)
#define BMM150_DATA_RHALL_POS UINT8_C(0x02)

#define BMM150_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> (bitname##_POS))


/** Bandwidth settings */
/* Accel Bandwidth */
#define BMI160_ACCEL_BW_OSR4_AVG1 UINT8_C(0x00)
#define BMI160_ACCEL_BW_OSR2_AVG2 UINT8_C(0x01)
#define BMI160_ACCEL_BW_NORMAL_AVG4 UINT8_C(0x02)
#define BMI160_ACCEL_BW_RES_AVG8 UINT8_C(0x03)
#define BMI160_ACCEL_BW_RES_AVG16 UINT8_C(0x04)
#define BMI160_ACCEL_BW_RES_AVG32 UINT8_C(0x05)
#define BMI160_ACCEL_BW_RES_AVG64 UINT8_C(0x06)
#define BMI160_ACCEL_BW_RES_AVG128 UINT8_C(0x07)

#define BMI160_GYRO_BW_OSR4_MODE UINT8_C(0x00)
#define BMI160_GYRO_BW_OSR2_MODE UINT8_C(0x01)
#define BMI160_GYRO_BW_NORMAL_MODE UINT8_C(0x02)

/**
* Interrupt Latch Mode options
* @see setInterruptLatch()
Expand Down Expand Up @@ -351,6 +532,24 @@ typedef enum {
BMI160_GYRO_RATE_3200HZ, /**< 3200 Hz */
} BMI160GyroRate;

/**
* Magnetometer Output Data Rate options
* @see setMagRate()
*/
typedef enum { //Added for BMM150 Support
BMI160_MAG_RATE_25_32HZ = 1, /**< 25/32 Hz */
BMI160_MAG_RATE_25_16HZ, /**< 25/16 Hz */
BMI160_MAG_RATE_25_8HZ, /**< 25/8 Hz */
BMI160_MAG_RATE_25_4HZ, /**< 25/4 Hz */
BMI160_MAG_RATE_25_2HZ, /**< 25/2 Hz */
BMI160_MAG_RATE_25HZ, /**< 25 Hz */
BMI160_MAG_RATE_50HZ, /**< 50 Hz */
BMI160_MAG_RATE_100HZ, /**< 100 Hz */
BMI160_MAG_RATE_200HZ, /**< 200 Hz */
BMI160_MAG_RATE_400HZ, /**< 400 Hz */
BMI160_MAG_RATE_800HZ, /**< 800 Hz */
} BMI160MagRate;

/**
* Step Detection Mode options
* @see setStepDetectionMode()
Expand Down Expand Up @@ -470,6 +669,9 @@ class BMI160Class {
public:
void initialize();
bool testConnection();

uint8_t getMagRate(); //Added for BMM150 Support
void setMagRate(uint8_t rate); //Added for BMM150 Support

uint8_t getGyroRate();
void setGyroRate(uint8_t rate);
Expand Down Expand Up @@ -524,11 +726,11 @@ class BMI160Class {
uint8_t getShockDetectionDuration();
void setShockDetectionDuration(uint8_t duration);

uint8_t getMotionDetectionThreshold();
void setMotionDetectionThreshold(uint8_t threshold);
uint8_t getMotionDetectionThreshold();
void setMotionDetectionThreshold(uint8_t threshold);

uint8_t getMotionDetectionDuration();
void setMotionDetectionDuration(uint8_t duration);
uint8_t getMotionDetectionDuration();
void setMotionDetectionDuration(uint8_t duration);
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you please eliminate these unintentional changes?


uint8_t getZeroMotionDetectionThreshold();
void setZeroMotionDetectionThreshold(uint8_t threshold);
Expand Down Expand Up @@ -574,12 +776,14 @@ class BMI160Class {
void setGyroFIFOEnabled(bool enabled);
bool getAccelFIFOEnabled();
void setAccelFIFOEnabled(bool enabled);

bool getIntFIFOBufferFullEnabled();
bool getMagFIFOEnabled(); //Added for BMM150 Support
void setMagFIFOEnabled(bool enabled); //Added for BMM150 Support

bool getIntFIFOBufferFullEnabled();
void setIntFIFOBufferFullEnabled(bool enabled);
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Indent looks strange here.

bool getIntDataReadyEnabled();
void setIntDataReadyEnabled(bool enabled);

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you please eliminate these unintentional changes?

uint8_t getIntStatus0();
uint8_t getIntStatus1();
uint8_t getIntStatus2();
Expand All @@ -595,7 +799,9 @@ class BMI160Class {
bool getIntDataReadyStatus();

void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz, uint16_t* rh); //Added for BMM150 Support
void extractMotion9(uint8_t* buffer, int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz, uint16_t* rh); //Added for BMM150 Support
void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you please eliminate these unintentional changes?
Please fix indentation here.

int16_t getAccelerationX();
int16_t getAccelerationY();
int16_t getAccelerationZ();
Expand All @@ -607,6 +813,13 @@ class BMI160Class {
int16_t getRotationY();
int16_t getRotationZ();

//DO NOT USE: UNTESTED, but changed to match getMotion9()
// void getMagneto(int16_t* mx, int16_t* my, int16_t* mz, uint16_t* rh); //Added for BMM150 Support
// int16_t getMagnetoX(); //Added for BMM150 Support
// int16_t getMagnetoY(); //Added for BMM150 Support
// int16_t getMagnetoZ(); //Added for BMM150 Support
// uint16_t getRHall();

bool getXNegShockDetected();
bool getXPosShockDetected();
bool getYNegShockDetected();
Expand Down Expand Up @@ -639,6 +852,7 @@ class BMI160Class {

uint8_t getRegister(uint8_t reg);
void setRegister(uint8_t reg, uint8_t data);
void setRegister(uint8_t reg, uint8_t data, uint8_t bitMask);
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please correct the indentation.


bool getIntEnabled();
void setIntEnabled(bool enabled);
Expand All @@ -650,14 +864,20 @@ class BMI160Class {
void setInterruptLatch(uint8_t latch);
void resetInterrupt();

void reg_write_bits(uint8_t reg, uint8_t data, unsigned pos, unsigned len);
//Added for a better hibernate function
//Puts Accel, Gyro, and Mag into suspend mode, for low power consumption
//Time to exectute function is untested; while() is present
void suspendIMU();

protected:
virtual int serial_buffer_transfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt);

private:
uint8_t reg_read (uint8_t reg);
void reg_write(uint8_t reg, uint8_t data);
void reg_write_bits(uint8_t reg, uint8_t data, unsigned pos, unsigned len);
uint8_t reg_read_bits(uint8_t reg, unsigned pos, unsigned len);
bool get_bit(uint8_t num, uint8_t bit); //some cases this may be useful for when the register is already read
};

#endif /* _BMI160_H_ */
29 changes: 15 additions & 14 deletions BMI160Gen.cpp
Original file line number Diff line number Diff line change
@@ -1,17 +1,18 @@
#include "BMI160Gen.h"
#include "SPI.h"
#include "Wire.h"


//#define DEBUG

bool BMI160GenClass::begin(const int spi_cs_pin, const int intr_pin)
{
return begin(SPI_MODE, spi_cs_pin, intr_pin);
{
return begin(SPI_MODE, Wire, spi_cs_pin, intr_pin);
}

bool BMI160GenClass::begin(Mode mode, const int arg1, const int arg2)
bool BMI160GenClass::begin(Mode mode, TwoWire &wirePort,const int arg1, const int arg2)
{
this->mode = mode;
_i2cPort = &wirePort;
switch (this->mode) {
case INVALID_MODE:
return false;
Expand Down Expand Up @@ -80,9 +81,9 @@ void BMI160GenClass::i2c_init()
Serial.println("BMI160GenClass::i2c_init()...");
#endif // DEBUG

Wire.begin();
Wire.beginTransmission(i2c_addr);
if( Wire.endTransmission() != 0 )
//_i2cPort->begin();
_i2cPort->beginTransmission(i2c_addr);
if( _i2cPort->endTransmission() != 0 )
Serial.println("BMI160GenClass::i2c_init(): I2C failed.");

#ifdef DEBUG
Expand All @@ -107,26 +108,26 @@ int BMI160GenClass::i2c_xfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt)
Serial.print("):");
#endif // DEBUG

Wire.beginTransmission(i2c_addr);
_i2cPort->beginTransmission(i2c_addr);
p = buf;
while (0 < tx_cnt) {
tx_cnt--;
Wire.write(*p++);
_i2cPort->write(*p++);
}
if( Wire.endTransmission() != 0 ) {
if( _i2cPort->endTransmission() != 0 ) {
Serial.println("Wire.endTransmission() failed.");
}
if (0 < rx_cnt) {
Wire.requestFrom(i2c_addr, rx_cnt);
_i2cPort->requestFrom(i2c_addr, rx_cnt);
p = buf;
while ( Wire.available() && 0 < rx_cnt) {
while ( _i2cPort->available() && 0 < rx_cnt) {
rx_cnt--;
#ifdef DEBUG
int t = *p++ = Wire.read();
int t = *p++ = _i2cPort->read();
Serial.print(" ");
Serial.print(t, HEX);
#else
*p++ = Wire.read();;
*p++ = _i2cPort->read();;
#endif // DEBUG
}
}
Expand Down
Loading