Skip to content

Issue #149: Provide scaled IMU data #243

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Closed
wants to merge 1 commit into from
Closed
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
22 changes: 3 additions & 19 deletions libraries/CurieIMU/examples/Accelerometer/Accelerometer.ino
Original file line number Diff line number Diff line change
Expand Up @@ -23,16 +23,10 @@ void setup() {
}

void loop() {
int axRaw, ayRaw, azRaw; // raw accelerometer values
float ax, ay, az;
float ax, ay, az; //scaled accelerometer values

// read raw accelerometer measurements from device
CurieIMU.readAccelerometer(axRaw, ayRaw, azRaw);

// convert the raw accelerometer data to G's
ax = convertRawAcceleration(axRaw);
ay = convertRawAcceleration(ayRaw);
az = convertRawAcceleration(azRaw);
// read accelerometer measurements from device, scaled to the configured range
CurieIMU.readAccelerometerScaled(ax, ay, az);

// display tab-separated accelerometer x/y/z values
Serial.print("a:\t");
Expand All @@ -44,16 +38,6 @@ void loop() {
Serial.println();
}

float convertRawAcceleration(int aRaw) {
// since we are using 2G range
// -2g maps to a raw value of -32768
// +2g maps to a raw value of 32767

float a = (aRaw * 2.0) / 32768.0;

return a;
}

/*
Copyright (c) 2016 Intel Corporation. All rights reserved.

Expand Down
22 changes: 3 additions & 19 deletions libraries/CurieIMU/examples/Gyro/Gyro.ino
Original file line number Diff line number Diff line change
Expand Up @@ -23,16 +23,10 @@ void setup() {
}

void loop() {
int gxRaw, gyRaw, gzRaw; // raw gyro values
float gx, gy, gz;
float gx, gy, gz; //scaled Gyro values

// read raw gyro measurements from device
CurieIMU.readGyro(gxRaw, gyRaw, gzRaw);

// convert the raw gyro data to degrees/second
gx = convertRawGyro(gxRaw);
gy = convertRawGyro(gyRaw);
gz = convertRawGyro(gzRaw);
// read gyro measurements from device, scaled to the configured range
CurieIMU.readGyroScaled(gx, gy, gz);

// display tab-separated gyro x/y/z values
Serial.print("g:\t");
Expand All @@ -44,16 +38,6 @@ void loop() {
Serial.println();
}

float convertRawGyro(int gRaw) {
// since we are using 250 degrees/seconds range
// -250 maps to a raw value of -32768
// +250 maps to a raw value of 32767

float g = (gRaw * 250.0) / 32768.0;

return g;
}

/*
Copyright (c) 2016 Intel Corporation. All rights reserved.

Expand Down
3 changes: 3 additions & 0 deletions libraries/CurieIMU/keywords.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,11 +59,14 @@ setStepCountEnabled KEYWORD1
resetStepCount KEYWORD1

readMotionSensor KEYWORD1
readMotionSensorScaled KEYWORD1
readAcceleration KEYWORD1
readRotation KEYWORD1

readAccelerometer KEYWORD1
readAccelerometerScaled KEYWORD1
readGyro KEYWORD1
readGyroScaled KEYWORD1
readTemperature KEYWORD1

shockDetected KEYWORD1
Expand Down
3 changes: 3 additions & 0 deletions libraries/CurieIMU/src/BMI160.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,9 @@ THE SOFTWARE.

#include "Arduino.h"

#define BMI160_SENSOR_RANGE 65535.0f
#define BMI160_SENSOR_LOW 32768.0f

#define BMI160_SPI_READ_BIT 7

#define BMI160_RA_CHIP_ID 0x00
Expand Down
92 changes: 92 additions & 0 deletions libraries/CurieIMU/src/CurieIMU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,14 +232,19 @@ void CurieIMUClass::setGyroRange(int range)

if (range >= 2000) {
bmiRange = BMI160_GYRO_RANGE_2000;
gyro_range = 2000.0f;
} else if (range >= 1000) {
bmiRange = BMI160_GYRO_RANGE_1000;
gyro_range = 1000.0f;
} else if (range >= 500) {
bmiRange = BMI160_GYRO_RANGE_500;
gyro_range = 500.0f;
} else if (range >= 250) {
bmiRange = BMI160_GYRO_RANGE_250;
gyro_range = 250.0f;
} else {
bmiRange = BMI160_GYRO_RANGE_125;
gyro_range = 125.0f;
}

setFullScaleGyroRange(bmiRange);
Expand Down Expand Up @@ -277,12 +282,16 @@ void CurieIMUClass::setAccelerometerRange(int range)

if (range <= 2) {
bmiRange = BMI160_ACCEL_RANGE_2G;
accel_range = 2.0f;
} else if (range <= 4) {
bmiRange = BMI160_ACCEL_RANGE_4G;
accel_range = 4.0f;
} else if (range <= 8) {
bmiRange = BMI160_ACCEL_RANGE_8G;
accel_range = 8.0f;
} else {
bmiRange = BMI160_ACCEL_RANGE_16G;
accel_range = 16.0f;
}

setFullScaleAccelRange(bmiRange);
Expand Down Expand Up @@ -1556,6 +1565,18 @@ void CurieIMUClass::setStepDetectionMode(int mode)
BMI160Class::setStepDetectionMode((BMI160StepMode)mode);
}

float CurieIMUClass::convertRaw(int16_t raw, float range_abs)
{
float slope;
float val;

/* Input range will be -32768 to 32767
* Output range must be -range_abs to range_abs */
val = (float) raw;
slope = (range_abs * 2.0f) / BMI160_SENSOR_RANGE;
return -(range_abs) + slope * (val + BMI160_SENSOR_LOW);
}

void CurieIMUClass::readMotionSensor(int& ax, int& ay, int& az, int& gx, int& gy, int& gz)
{
short sax, say, saz, sgx, sgy, sgz;
Expand All @@ -1570,6 +1591,21 @@ void CurieIMUClass::readMotionSensor(int& ax, int& ay, int& az, int& gx, int& gy
gz = sgz;
}

void CurieIMUClass::readMotionSensorScaled(float& ax, float& ay, float& az,
float& gx, float& gy, float& gz)
{
int16_t sax, say, saz, sgx, sgy, sgz;

getMotion6(&sax, &say, &saz, &sgx, &sgy, &sgz);

ax = convertRaw(sax, accel_range);
ay = convertRaw(say, accel_range);
az = convertRaw(saz, accel_range);
gx = convertRaw(sgx, gyro_range);
gy = convertRaw(sgy, gyro_range);
gz = convertRaw(sgz, gyro_range);
}

void CurieIMUClass::readAccelerometer(int& x, int& y, int& z)
{
short sx, sy, sz;
Expand All @@ -1581,6 +1617,17 @@ void CurieIMUClass::readAccelerometer(int& x, int& y, int& z)
z = sz;
}

void CurieIMUClass::readAccelerometerScaled(float& x, float& y, float& z)
{
int16_t sx, sy, sz;

getAcceleration(&sx, &sy, &sz);

x = convertRaw(sx, accel_range);
y = convertRaw(sy, accel_range);
z = convertRaw(sz, accel_range);
}

void CurieIMUClass::readGyro(int& x, int& y, int& z)
{
short sx, sy, sz;
Expand All @@ -1592,6 +1639,17 @@ void CurieIMUClass::readGyro(int& x, int& y, int& z)
z = sz;
}

void CurieIMUClass::readGyroScaled(float& x, float& y, float& z)
{
int16_t sx, sy, sz;

getRotation(&sx, &sy, &sz);

x = convertRaw(sx, gyro_range);
y = convertRaw(sy, gyro_range);
z = convertRaw(sz, gyro_range);
}

int CurieIMUClass::readAccelerometer(int axis)
{
if (axis == X_AXIS) {
Expand All @@ -1605,6 +1663,23 @@ int CurieIMUClass::readAccelerometer(int axis)
return 0;
}

float CurieIMUClass::readAccelerometerScaled(int axis)
{
int16_t raw;

if (axis == X_AXIS) {
raw = getAccelerationX();
} else if (axis == Y_AXIS) {
raw = getAccelerationY();
} else if (axis == Z_AXIS) {
raw = getAccelerationZ();
} else {
return 0;
}

return convertRaw(raw, accel_range);
}

int CurieIMUClass::readGyro(int axis)
{
if (axis == X_AXIS) {
Expand All @@ -1618,6 +1693,23 @@ int CurieIMUClass::readGyro(int axis)
return 0;
}

float CurieIMUClass::readGyroScaled(int axis)
{
int16_t raw;

if (axis == X_AXIS) {
raw = getRotationX();
} else if (axis == Y_AXIS) {
raw = getRotationY();
} else if (axis == Z_AXIS) {
raw = getRotationZ();
} else {
return 0;
}

return convertRaw(raw, gyro_range);
}

int CurieIMUClass::readTemperature()
{
return getTemperature();
Expand Down
11 changes: 10 additions & 1 deletion libraries/CurieIMU/src/CurieIMU.h
Original file line number Diff line number Diff line change
Expand Up @@ -187,11 +187,15 @@ class CurieIMUClass : public BMI160Class {
void setStepDetectionMode(int mode);

void readMotionSensor(int& ax, int& ay, int& az, int& gx, int& gy, int& gz);
void readMotionSensorScaled(float& ax, float& ay, float& az, float& gx, float& gy, float& gz);
void readAccelerometer(int& x, int& y, int& z);
void readAccelerometerScaled(float& x, float& y, float& z);
void readGyro(int& x, int& y, int& z);

void readGyroScaled(float& x, float& y, float& z);
int readAccelerometer(int axis);
float readAccelerometerScaled(int axis);
int readGyro(int axis);
float readGyroScaled(int axis);
int readTemperature();

bool shockDetected(int axis, int direction);
Expand All @@ -205,6 +209,9 @@ class CurieIMUClass : public BMI160Class {
private:
int serial_buffer_transfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt);

float accel_range;
float gyro_range;

float getFreefallDetectionThreshold();
void setFreefallDetectionThreshold(float threshold);
float getShockDetectionThreshold();
Expand All @@ -231,6 +238,8 @@ class CurieIMUClass : public BMI160Class {
int getDoubleTapDetectionDuration();
void setDoubleTapDetectionDuration(int duration);

float convertRaw(int16_t raw, float range_abs);

void enableInterrupt(int feature, bool enabled);

void (*_user_callback)(void);
Expand Down