This is a port from the library for Arduino provided by Sparkfun with their breakout board of the LSM9DS0. The original library can be found here: https://github.com/sparkfun/SparkFun_LSM9DS0_Arduino_Library/tree/V_1.0.1 It is also provided an AHRS example based on Madgwick, also a port from an Arduino example. All of this was tested on a Nucleo F411RE and a Sparkfun breakout board.
Revision 0:32b177f0030e, committed 2015-12-05
- Comitter:
- olimexsmart
- Date:
- Sat Dec 05 16:23:36 2015 +0000
- Commit message:
- What in this world I am supposed to type here?
Changed in this revision
diff -r 000000000000 -r 32b177f0030e AHRS_example.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/AHRS_example.cpp Sat Dec 05 16:23:36 2015 +0000 @@ -0,0 +1,448 @@ +#include "LSM9DS0_mbed.h" +#include "mbed.h" + +#define INT1 PB_3 +#define INT2 PA_10 +#define DR_DYG PB_5 + +#define SDA PB_9 +#define SCL PB_8 + +/////////////////////// +// Example I2C Setup // +/////////////////////// +// SDO_XM and SDO_G are both grounded, so our addresses are: +#define LSM9DS0_XM 0x1D // Would be 0x1E if SDO_XM is LOW +#define LSM9DS0_G 0x6B // Would be 0x6A if SDO_G is LOW + +// Create an instance of the LSM9DS0 library called `dof` the +// parameters for this constructor are: +// [I2C SDA], [I2C SCL],[gyro I2C address],[xm I2C add.] +LSM9DS0 dof(SDA, SCL, LSM9DS0_G, LSM9DS0_XM); + +/////////////////////////////////// +// Interrupt Handler Definitions // +/////////////////////////////////// +DigitalIn INT1XM(INT1); +DigitalIn INT2XM(INT2); +DigitalIn DRDYG(DR_DYG); + +// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) +#define GyroMeasError PI * (40.0f / 180.0f) // gyroscope measurement error in rads/s (shown as 3 deg/s) +#define GyroMeasDrift PI * (0.0f / 180.0f) // gyroscope measurement drift in rad/s/s (shown as 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. +#define beta sqrt(3.0f / 4.0f) * GyroMeasError // compute beta +#define 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 +const float PI = 3.14159265358979f; + +Timer t1; //Integration timer +Timer t2; //Print timer +Serial pc(SERIAL_TX, SERIAL_RX); +DigitalOut myled(LED1); +float pitch, yaw, roll, heading; +float deltat = 0.0f; // integration interval for both filter schemes + + +float abias[3] = {0, 0, 0}, gbias[3] = {0, 0, 0}; +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 +float temperature; + +////////////////////////////////// +// FUNCTION DECLARATION // +////////////////////////////////// +void setup(); +void loop(); +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 dataGyro(); +void dataAccel(); +void dataMag(); + +////////////////////////////////// +// MAIN // +////////////////////////////////// +int main() +{ + setup(); //Setup sensor and Serial + pc.printf("Setup Done\n\r"); + + + while (true) + loop(); +} + + +////////////////////////////////// +// FUNCTION BODY // +////////////////////////////////// +void dataGyro() +{ + dof.readGyro(); // Read raw gyro data + gx = dof.calcGyro(dof.gx) - gbias[0]; // Convert to degrees per seconds, remove gyro biases + gy = dof.calcGyro(dof.gy) - gbias[1]; + gz = dof.calcGyro(dof.gz) - gbias[2]; +} +void dataAccel() +{ + dof.readAccel(); // Read raw accelerometer data + ax = dof.calcAccel(dof.ax) - abias[0]; // Convert to g's, remove accelerometer biases + ay = dof.calcAccel(dof.ay) - abias[1]; + az = dof.calcAccel(dof.az) - abias[2]; +} +void dataMag() +{ + dof.readMag(); // Read raw magnetometer data + mx = dof.calcMag(dof.mx); // Convert to Gauss and correct for calibration + my = dof.calcMag(dof.my); + mz = dof.calcMag(dof.mz); +} +void setup() +{ + pc.baud(115200); // Start serial at 115200 bps + myled = true; + /*//Interrupt + INT1XM.rise(&dataAccel); + INT2XM.rise(&dataMag); + DRDYG.rise(&dataGyro); + */ + // begin() returns a 16-bit value which includes both the gyro + // and accelerometers WHO_AM_I response. You can check this to + // make sure communication was successful. + uint16_t status = dof.begin(); + + pc.printf("LSM9DS0 WHO_AM_I's returned: "); + pc.printf("0x%X\t", status); + pc.printf("Should be 0x49D4"); + pc.printf("\n\r"); + + +// Set data output ranges; choose lowest ranges for maximum resolution +// Accelerometer scale can be: A_SCALE_2G, A_SCALE_4G, A_SCALE_6G, A_SCALE_8G, or A_SCALE_16G + dof.setAccelScale(dof.A_SCALE_2G); +// Gyro scale can be: G_SCALE__245, G_SCALE__500, or G_SCALE__2000DPS + dof.setGyroScale(dof.G_SCALE_245DPS); +// Magnetometer scale can be: M_SCALE_2GS, M_SCALE_4GS, M_SCALE_8GS, M_SCALE_12GS + dof.setMagScale(dof.M_SCALE_2GS); + +// Set output data rates +// Accelerometer output data rate (ODR) can be: A_ODR_3125 (3.225 Hz), A_ODR_625 (6.25 Hz), A_ODR_125 (12.5 Hz), A_ODR_25, A_ODR_50, +// A_ODR_100, A_ODR_200, A_ODR_400, A_ODR_800, A_ODR_1600 (1600 Hz) + dof.setAccelODR(dof.A_ODR_200); // Set accelerometer update rate at 100 Hz +// Accelerometer anti-aliasing filter rate can be 50, 194, 362, or 763 Hz +// Anti-aliasing acts like a low-pass filter allowing oversampling of accelerometer and rejection of high-frequency spurious noise. +// Strategy here is to effectively oversample accelerometer at 100 Hz and use a 50 Hz anti-aliasing (low-pass) filter frequency +// to get a smooth ~150 Hz filter update rate + dof.setAccelABW(dof.A_ABW_50); // Choose lowest filter setting for low noise + +// Gyro output data rates can be: 95 Hz (bandwidth 12.5 or 25 Hz), 190 Hz (bandwidth 12.5, 25, 50, or 70 Hz) +// 380 Hz (bandwidth 20, 25, 50, 100 Hz), or 760 Hz (bandwidth 30, 35, 50, 100 Hz) + dof.setGyroODR(dof.G_ODR_190_BW_125); // Set gyro update rate to 190 Hz with the smallest bandwidth for low noise + +// Magnetometer output data rate can be: 3.125 (ODR_3125), 6.25 (ODR_625), 12.5 (ODR_125), 25, 50, or 100 Hz + dof.setMagODR(dof.M_ODR_125); // Set magnetometer to update every 80 ms + +// Use the FIFO mode to average accelerometer and gyro readings to calculate the biases, which can then be removed from +// all subsequent measurements. + dof.calLSM9DS0(gbias, abias); + +// Start timers to get integration time and print time + t2.start(); + t1.start(); + dataGyro(); + dataAccel(); + dataMag(); +} + +void loop() +{ + //Couldn't manage to get these in interrupt, the interrupt won't fire. It isn't so nececesary indeed. + if(INT1XM.read()) + dataAccel(); + if(INT2XM.read()) + { + dataMag(); + // dof.readTemp(); Can't get temp reading from a Sparkfun breakout board, the problem is not just mine. + //temperature = 21.0 + (float) dof.temperature/8.0f; // slope is 8 LSB per degree C, just guessing at the intercept + } + if(DRDYG.read()) + dataGyro(); + + deltat = t1.read(); // set integration time by time elapsed since last filter update + t1.reset(); + + // Sensors x- and y-axes are aligned but magnetometer z-axis (+ down) is opposite to z-axis (+ up) of accelerometer and gyro! + // 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); +//MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); + + + // Serial print at 0.5 s rate independent of data rates + if (t2.read() > 1.0f) { + t2.reset(); + + myled = !myled; + + pc.printf("%f\t%f\t%f\n\r", ax, ay, az); + pc.printf("%f\t%f\t%f\n\r", gx, gy, gz); + pc.printf("%f\t%f\t%f\n\r", mx, my, mz); + /* + // 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, to 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. + */ + 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; + roll *= 180.0f / PI; + //yaw -= 13.8; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 + +/* + pc.printf("Temperature = "); + pc.printf("%d\n\r", dof.temperature); +*/ + //Angles print + pc.printf("Yaw, Pitch, Roll: "); + pc.printf("%f", yaw); + pc.printf(", "); + pc.printf("%f", pitch); + pc.printf(", "); + pc.printf("%f\n\r", roll); + + //Update rate print + pc.printf("Filter rate = "); + pc.printf("%f\n\r", 1.0f/deltat); + + /* + // The filter update rate can be increased by reducing the rate of data reading. The optimal implementation is + // one which balances the competing rates so they are about the same; that is, the filter updates the sensor orientation + // at about the same rate the data is changing. Of course, other implementations are possible. One might consider + // updating the filter at twice the average new data rate to allow for finite filter convergence times. + // The filter update rate is determined mostly by the mathematical steps in the respective algorithms, + // the processor speed (8 MHz for the 3.3V Pro Mini), and the sensor ODRs, especially the magnetometer ODR: + // smaller ODRs for the magnetometer produce the above rates, maximum magnetometer ODR of 100 Hz produces + // filter update rates of ~110 and ~135 Hz for the Madgwick and Mahony schemes, respectively. + // This is presumably because the magnetometer read takes longer than the gyro or accelerometer reads. + // With low ODR settings of 100 Hz, 95 Hz, and 6.25 Hz for the accelerometer, gyro, and magnetometer, respectively, + // the filter is updating at a ~150 Hz rate using the Madgwick scheme and ~200 Hz using the Mahony scheme. + // These filter update rates should be fast enough to maintain accurate platform orientation for + // stabilization control of a fast-moving robot or quadcopter. Compare to the update rate of 200 Hz + // produced by the on-board Digital Motion Processor of Invensense's MPU6050 6 DoF and MPU9150 9DoF sensors. + // The 3.3 V 8 MHz Pro Mini is doing pretty well! + */ + } +} + + + + +// 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 -r 000000000000 -r 32b177f0030e LSM9DS0_mbed.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/LSM9DS0_mbed.cpp Sat Dec 05 16:23:36 2015 +0000 @@ -0,0 +1,427 @@ +/* +Code by @OlimexSmart - Luca Olivieri +This is a port from the Sparkfun library provided +with the breakout board of the LSM9DS0. +Visit their github for full comments: +https://github.com/sparkfun/SparkFun_LSM9DS0_Arduino_Library/tree/V_1.0.1 +*/ + +#include "LSM9DS0_mbed.h" + +LSM9DS0::LSM9DS0(PinName sdaP, PinName sclP, uint8_t gAddr, uint8_t xmAddr) +{ + // xmAddress and gAddress will store the 7-bit I2C address. + xmAddress = xmAddr; + gAddress = gAddr; + + i2c_ = new I2C(sdaP, sclP); //This is initI2C(); in the original library + i2c_->frequency(400000); + +} + +uint16_t LSM9DS0::begin(gyro_scale gScl, accel_scale aScl, mag_scale mScl, + gyro_odr gODR, accel_odr aODR, mag_odr mODR) +{ + // Store the given scales in class variables. These scale variables + // are used throughout to calculate the actual g's, DPS,and Gs's. + gScale = gScl; + aScale = aScl; + mScale = mScl; + + // Once we have the scale values, we can calculate the resolution + // of each sensor. That's what these functions are for. One for each sensor + calcgRes(); // Calculate DPS / ADC tick, stored in gRes variable + calcmRes(); // Calculate Gs / ADC tick, stored in mRes variable + calcaRes(); // Calculate g / ADC tick, stored in aRes variable + + + // To verify communication, we can read from the WHO_AM_I register of + // each device. Store those in a variable so we can return them. + uint8_t gTest = gReadByte(WHO_AM_I_G); // Read the gyro WHO_AM_I + uint8_t xmTest = xmReadByte(WHO_AM_I_XM); // Read the accel/mag WHO_AM_I + + // Gyro initialization stuff: + initGyro(); // This will "turn on" the gyro. Setting up interrupts, etc. + setGyroODR(gODR); // Set the gyro output data rate and bandwidth. + setGyroScale(gScale); // Set the gyro range + + // Accelerometer initialization stuff: + initAccel(); // "Turn on" all axes of the accel. Set up interrupts, etc. + setAccelODR(aODR); // Set the accel data rate. + setAccelScale(aScale); // Set the accel range. + + // Magnetometer initialization stuff: + initMag(); // "Turn on" all axes of the mag. Set up interrupts, etc. + setMagODR(mODR); // Set the magnetometer output data rate. + setMagScale(mScale); // Set the magnetometer's range. + + // Once everything is initialized, return the WHO_AM_I registers we read: + return (xmTest << 8) | gTest; +} + +void LSM9DS0::initGyro() +{ + + gWriteByte(CTRL_REG1_G, 0x0F); // Normal mode, enable all axes + gWriteByte(CTRL_REG2_G, 0x00); // Normal mode, high cutoff frequency + gWriteByte(CTRL_REG3_G, 0x88); //Interrupt enabled on both INT_G and I2_DRDY + gWriteByte(CTRL_REG4_G, 0x00); // Set scale to 245 dps + gWriteByte(CTRL_REG5_G, 0x00); //Init default values + +} + +void LSM9DS0::initAccel() +{ + xmWriteByte(CTRL_REG0_XM, 0x00); + xmWriteByte(CTRL_REG1_XM, 0x57); // 50Hz data rate, x/y/z all enabled + xmWriteByte(CTRL_REG2_XM, 0x00); // Set scale to 2g + xmWriteByte(CTRL_REG3_XM, 0x04); // Accelerometer data ready on INT1_XM (0x04) + +} + +void LSM9DS0::initMag() +{ + xmWriteByte(CTRL_REG5_XM, 0x94); // Mag data rate - 100 Hz, enable temperature sensor + xmWriteByte(CTRL_REG6_XM, 0x00); // Mag scale to +/- 2GS + xmWriteByte(CTRL_REG7_XM, 0x00); // Continuous conversion mode + xmWriteByte(CTRL_REG4_XM, 0x04); // Magnetometer data ready on INT2_XM (0x08) + xmWriteByte(INT_CTRL_REG_M, 0x09); // Enable interrupts for mag, active-low, push-pull +} + +// This is a function that uses the FIFO to accumulate sample of accelerometer and gyro data, average +// them, scales them to gs and deg/s, respectively, and then passes the biases to the main sketch +// for subtraction from all subsequent data. There are no gyro and accelerometer bias registers to store +// the data as there are in the ADXL345, a precursor to the LSM9DS0, or the MPU-9150, so we have to +// subtract the biases ourselves. This results in a more accurate measurement in general and can +// remove errors due to imprecise or varying initial placement. Calibration of sensor data in this manner +// is good practice. +void LSM9DS0::calLSM9DS0(float * gbias, float * abias) +{ + uint8_t data[6] = {0, 0, 0, 0, 0, 0}; + int16_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; + int samples, ii; + + // First get gyro bias + uint8_t c = gReadByte(CTRL_REG5_G); + gWriteByte(CTRL_REG5_G, c | 0x40); // Enable gyro FIFO + wait_ms(20); // Wait for change to take effect + gWriteByte(FIFO_CTRL_REG_G, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples + wait_ms(1000); // delay 1000 milliseconds to collect FIFO samples + + samples = (gReadByte(FIFO_SRC_REG_G) & 0x1F); // Read number of stored samples + + for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO + gReadBytes(OUT_X_L_G, &data[0], 6); + gyro_bias[0] += (((int16_t)data[1] << 8) | data[0]); + gyro_bias[1] += (((int16_t)data[3] << 8) | data[2]); + gyro_bias[2] += (((int16_t)data[5] << 8) | data[4]); + } + + gyro_bias[0] /= samples; // average the data + gyro_bias[1] /= samples; + gyro_bias[2] /= samples; + + gbias[0] = (float)gyro_bias[0]*gRes; // Properly scale the data to get deg/s + gbias[1] = (float)gyro_bias[1]*gRes; + gbias[2] = (float)gyro_bias[2]*gRes; + + c = gReadByte(CTRL_REG5_G); + gWriteByte(CTRL_REG5_G, c & ~0x40); // Disable gyro FIFO + wait_ms(20); + gWriteByte(FIFO_CTRL_REG_G, 0x00); // Enable gyro bypass mode + + // Now get the accelerometer biases + c = xmReadByte(CTRL_REG0_XM); + xmWriteByte(CTRL_REG0_XM, c | 0x40); // Enable accelerometer FIFO + wait_ms(20); // Wait for change to take effect + xmWriteByte(FIFO_CTRL_REG, 0x20 | 0x1F); // Enable accelerometer FIFO stream mode and set watermark at 32 samples + wait_ms(1000); // delay 1000 milliseconds to collect FIFO samples + + samples = (xmReadByte(FIFO_SRC_REG) & 0x1F); // Read number of stored accelerometer samples + + for(ii = 0; ii < samples ; ii++) { // Read the accelerometer data stored in the FIFO + xmReadBytes(OUT_X_L_A, &data[0], 6); + accel_bias[0] += (((int16_t)data[1] << 8) | data[0]); + accel_bias[1] += (((int16_t)data[3] << 8) | data[2]); + accel_bias[2] += (((int16_t)data[5] << 8) | data[4]) - (int16_t)(1./aRes); // Assumes sensor facing up! + } + + accel_bias[0] /= samples; // average the data + accel_bias[1] /= samples; + accel_bias[2] /= samples; + + abias[0] = (float)accel_bias[0]*aRes; // Properly scale data to get gs + abias[1] = (float)accel_bias[1]*aRes; + abias[2] = (float)accel_bias[2]*aRes; + + c = xmReadByte(CTRL_REG0_XM); + xmWriteByte(CTRL_REG0_XM, c & ~0x40); // Disable accelerometer FIFO + wait_ms(20); + xmWriteByte(FIFO_CTRL_REG, 0x00); // Enable accelerometer bypass mode + +} +void LSM9DS0::readAccel() +{ + uint8_t temp[6]; // We'll read six bytes from the accelerometer into temp + xmReadBytes(OUT_X_L_A, temp, 6); // Read 6 bytes, beginning at OUT_X_L_A + ax = (temp[1] << 8) | temp[0]; // Store x-axis values into ax + ay = (temp[3] << 8) | temp[2]; // Store y-axis values into ay + az = (temp[5] << 8) | temp[4]; // Store z-axis values into az + +} + +void LSM9DS0::readMag() +{ + uint8_t temp[6]; // We'll read six bytes from the mag into temp + xmReadBytes(OUT_X_L_M, temp, 6); // Read 6 bytes, beginning at OUT_X_L_M + mx = (temp[1] << 8) | temp[0]; // Store x-axis values into mx + my = (temp[3] << 8) | temp[2]; // Store y-axis values into my + mz = (temp[5] << 8) | temp[4]; // Store z-axis values into mz +} + +void LSM9DS0::readTemp() +{ + uint8_t temp[2]; // We'll read two bytes from the temperature sensor into temp + xmReadBytes(OUT_TEMP_L_XM, temp, 2); // Read 2 bytes, beginning at OUT_TEMP_L_XM + //temperature = (((int16_t) temp[1] << 12) | temp[0] << 4 ) >> 4; // Temperature is a 12-bit signed integer + + uint8_t xlo = temp[0]; + int16_t xhi = temp[1]; + xhi <<= 8; + xhi |= xlo; + temperature = xhi; +} + + +void LSM9DS0::readGyro() +{ + uint8_t temp[6]; // We'll read six bytes from the gyro into temp + gReadBytes(OUT_X_L_G, temp, 6); // Read 6 bytes, beginning at OUT_X_L_G + gx = (temp[1] << 8) | temp[0]; // Store x-axis values into gx + gy = (temp[3] << 8) | temp[2]; // Store y-axis values into gy + gz = (temp[5] << 8) | temp[4]; // Store z-axis values into gz +} + +float LSM9DS0::calcGyro(int16_t gyro) +{ + // Return the gyro raw reading times our pre-calculated DPS / (ADC tick): + return gRes * gyro; +} + +float LSM9DS0::calcAccel(int16_t accel) +{ + // Return the accel raw reading times our pre-calculated g's / (ADC tick): + return aRes * accel; +} + +float LSM9DS0::calcMag(int16_t mag) +{ + // Return the mag raw reading times our pre-calculated Gs / (ADC tick): + return mRes * mag; +} + +void LSM9DS0::setGyroScale(gyro_scale gScl) +{ + // We need to preserve the other bytes in CTRL_REG4_G. So, first read it: + uint8_t temp = gReadByte(CTRL_REG4_G); + // Then mask out the gyro scale bits: + temp &= 0xFF^(0x3 << 4); + // Then shift in our new scale bits: + temp |= gScl << 4; + // And write the new register value back into CTRL_REG4_G: + gWriteByte(CTRL_REG4_G, temp); + + // We've updated the sensor, but we also need to update our class variables + // First update gScale: + gScale = gScl; + // Then calculate a new gRes, which relies on gScale being set correctly: + calcgRes(); +} + +void LSM9DS0::setAccelScale(accel_scale aScl) +{ + // We need to preserve the other bytes in CTRL_REG2_XM. So, first read it: + uint8_t temp = xmReadByte(CTRL_REG2_XM); + // Then mask out the accel scale bits: + temp &= 0xFF^(0x3 << 3); + // Then shift in our new scale bits: + temp |= aScl << 3; + // And write the new register value back into CTRL_REG2_XM: + xmWriteByte(CTRL_REG2_XM, temp); + + // We've updated the sensor, but we also need to update our class variables + // First update aScale: + aScale = aScl; + // Then calculate a new aRes, which relies on aScale being set correctly: + calcaRes(); +} + +void LSM9DS0::setMagScale(mag_scale mScl) +{ + // We need to preserve the other bytes in CTRL_REG6_XM. So, first read it: + uint8_t temp = xmReadByte(CTRL_REG6_XM); + // Then mask out the mag scale bits: + temp &= 0xFF^(0x3 << 5); + // Then shift in our new scale bits: + temp |= mScl << 5; + // And write the new register value back into CTRL_REG6_XM: + xmWriteByte(CTRL_REG6_XM, temp); + + // We've updated the sensor, but we also need to update our class variables + // First update mScale: + mScale = mScl; + // Then calculate a new mRes, which relies on mScale being set correctly: + calcmRes(); +} + +void LSM9DS0::setGyroODR(gyro_odr gRate) +{ + // We need to preserve the other bytes in CTRL_REG1_G. So, first read it: + uint8_t temp = gReadByte(CTRL_REG1_G); + // Then mask out the gyro ODR bits: + temp &= 0xFF^(0xF << 4); + // Then shift in our new ODR bits: + temp |= (gRate << 4); + // And write the new register value back into CTRL_REG1_G: + gWriteByte(CTRL_REG1_G, temp); +} + +void LSM9DS0::setAccelODR(accel_odr aRate) +{ + // We need to preserve the other bytes in CTRL_REG1_XM. So, first read it: + uint8_t temp = xmReadByte(CTRL_REG1_XM); + // Then mask out the accel ODR bits: + temp &= 0xFF^(0xF << 4); + // Then shift in our new ODR bits: + temp |= (aRate << 4); + // And write the new register value back into CTRL_REG1_XM: + xmWriteByte(CTRL_REG1_XM, temp); +} + +void LSM9DS0::setMagODR(mag_odr mRate) +{ + // We need to preserve the other bytes in CTRL_REG5_XM. So, first read it: + uint8_t temp = xmReadByte(CTRL_REG5_XM); + // Then mask out the mag ODR bits: + temp &= 0xFF^(0x7 << 2); + // Then shift in our new ODR bits: + temp |= (mRate << 2); + // And write the new register value back into CTRL_REG5_XM: + xmWriteByte(CTRL_REG5_XM, temp); +} + +void LSM9DS0::setAccelABW(accel_abw abwRate) +{ + // We need to preserve the other bytes in CTRL_REG2_XM. So, first read it: + uint8_t temp = xmReadByte(CTRL_REG2_XM); + // Then mask out the accel ABW bits: + temp &= 0xFF^(0x3 << 7); + // Then shift in our new ODR bits: + temp |= (abwRate << 7); + // And write the new register value back into CTRL_REG2_XM: + xmWriteByte(CTRL_REG2_XM, temp); +} + +void LSM9DS0::calcgRes() +{ + // Possible gyro scales (and their register bit settings) are: + // 245 DPS (00), 500 DPS (01), 2000 DPS (10). Here's a bit of an algorithm + // to calculate DPS/(ADC tick) based on that 2-bit value: + switch (gScale) { + case G_SCALE_245DPS: + gRes = 245.0 / 32768.0; + break; + case G_SCALE_500DPS: + gRes = 500.0 / 32768.0; + break; + case G_SCALE_2000DPS: + gRes = 2000.0 / 32768.0; + break; + } +} + +void LSM9DS0::calcaRes() +{ + // Possible accelerometer scales (and their register bit settings) are: + // 2 g (000), 4g (001), 6g (010) 8g (011), 16g (100). Here's a bit of an + // algorithm to calculate g/(ADC tick) based on that 3-bit value: + aRes = aScale == A_SCALE_16G ? 16.0 / 32768.0 : + (((float) aScale + 1.0) * 2.0) / 32768.0; +} + +void LSM9DS0::calcmRes() +{ + // Possible magnetometer scales (and their register bit settings) are: + // 2 Gs (00), 4 Gs (01), 8 Gs (10) 12 Gs (11). Here's a bit of an algorithm + // to calculate Gs/(ADC tick) based on that 2-bit value: + mRes = mScale == M_SCALE_2GS ? 2.0 / 32768.0 : + (float) (mScale << 2) / 32768.0; +} + +void LSM9DS0::gWriteByte(uint8_t subAddress, uint8_t data) +{ + // Whether we're using I2C or SPI, write a byte using the + // gyro-specific I2C address or SPI CS pin. + I2CwriteByte(gAddress, subAddress, data); +} + +void LSM9DS0::xmWriteByte(uint8_t subAddress, uint8_t data) +{ + // Whether we're using I2C or SPI, write a byte using the + // accelerometer-specific I2C address or SPI CS pin. + return I2CwriteByte(xmAddress, subAddress, data); +} + +uint8_t LSM9DS0::gReadByte(uint8_t subAddress) +{ + return I2CreadByte(gAddress, subAddress); +} + +void LSM9DS0::gReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count) +{ + // Whether we're using I2C or SPI, read multiple bytes using the + // gyro-specific I2C address. + I2CreadBytes(gAddress, subAddress, dest, count); +} + +uint8_t LSM9DS0::xmReadByte(uint8_t subAddress) +{ + // Whether we're using I2C or SPI, read a byte using the + // accelerometer-specific I2C address. + return I2CreadByte(xmAddress, subAddress); +} + +void LSM9DS0::xmReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count) +{ + // read multiple bytes using the + // accelerometer-specific I2C address. + I2CreadBytes(xmAddress, subAddress, dest, count); +} + + +//I2C rewritten to accomodate i2cdev instead of Wire (Arduino) +void LSM9DS0::I2CwriteByte(uint8_t address, uint8_t subAddress, uint8_t data) +{ + char dt[2]; // Initialize the Tx buffer + dt[0] = subAddress; // Put slave register address in Tx buffer + dt[1] = data; // Put data in Tx buffer + i2c_->write(address << 1, dt, 2); // Send the Tx buffer +} + +uint8_t LSM9DS0::I2CreadByte(uint8_t address, uint8_t subAddress) +{ + i2c_->write(address << 1, (char*)&subAddress, 1, true); // Send request, but keep connection alive + char dt = 0; + i2c_->read(address << 1, &dt, 1); // Fill Rx buffer with result + + return dt; // Return data read from slave register + +} + +void LSM9DS0::I2CreadBytes(uint8_t address, uint8_t subAddress, uint8_t * dest, + uint8_t count) +{ + char sA = subAddress | 0x80; // Send the register to be read. OR with 0x80 to indicate multi-read. + i2c_->write(address << 1, &sA, 1, true); // Send the Tx buffer, but keep connection alive + i2c_->read(address << 1, (char*)dest, count); // Read bytes from slave register address +}
diff -r 000000000000 -r 32b177f0030e LSM9DS0_mbed.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/LSM9DS0_mbed.h Sat Dec 05 16:23:36 2015 +0000 @@ -0,0 +1,493 @@ +/* +Code by @OlimexSmart - Luca Olivieri +This is a port from the Sparkfun library provided +with the breakout board of the LSM9DS0. +Visit their github for full comments: +https://github.com/sparkfun/SparkFun_LSM9DS0_Arduino_Library/tree/V_1.0.1 +*/ + +#ifndef _LSM9DS0_H__ +#define _LSM9DS0_H__ + +#include "mbed.h" + +//////////////////////////// +// LSM9DS0 Gyro Registers // +//////////////////////////// +#define WHO_AM_I_G 0x0F +#define CTRL_REG1_G 0x20 +#define CTRL_REG2_G 0x21 +#define CTRL_REG3_G 0x22 +#define CTRL_REG4_G 0x23 +#define CTRL_REG5_G 0x24 +#define REFERENCE_G 0x25 +#define STATUS_REG_G 0x27 +#define OUT_X_L_G 0x28 +#define OUT_X_H_G 0x29 +#define OUT_Y_L_G 0x2A +#define OUT_Y_H_G 0x2B +#define OUT_Z_L_G 0x2C +#define OUT_Z_H_G 0x2D +#define FIFO_CTRL_REG_G 0x2E +#define FIFO_SRC_REG_G 0x2F +#define INT1_CFG_G 0x30 +#define INT1_SRC_G 0x31 +#define INT1_THS_XH_G 0x32 +#define INT1_THS_XL_G 0x33 +#define INT1_THS_YH_G 0x34 +#define INT1_THS_YL_G 0x35 +#define INT1_THS_ZH_G 0x36 +#define INT1_THS_ZL_G 0x37 +#define INT1_DURATION_G 0x38 + +////////////////////////////////////////// +// LSM9DS0 Accel/Magneto (XM) Registers // +////////////////////////////////////////// +#define OUT_TEMP_L_XM 0x05 +#define OUT_TEMP_H_XM 0x06 +#define STATUS_REG_M 0x07 +#define OUT_X_L_M 0x08 +#define OUT_X_H_M 0x09 +#define OUT_Y_L_M 0x0A +#define OUT_Y_H_M 0x0B +#define OUT_Z_L_M 0x0C +#define OUT_Z_H_M 0x0D +#define WHO_AM_I_XM 0x0F +#define INT_CTRL_REG_M 0x12 +#define INT_SRC_REG_M 0x13 +#define INT_THS_L_M 0x14 +#define INT_THS_H_M 0x15 +#define OFFSET_X_L_M 0x16 +#define OFFSET_X_H_M 0x17 +#define OFFSET_Y_L_M 0x18 +#define OFFSET_Y_H_M 0x19 +#define OFFSET_Z_L_M 0x1A +#define OFFSET_Z_H_M 0x1B +#define REFERENCE_X 0x1C +#define REFERENCE_Y 0x1D +#define REFERENCE_Z 0x1E +#define CTRL_REG0_XM 0x1F +#define CTRL_REG1_XM 0x20 +#define CTRL_REG2_XM 0x21 +#define CTRL_REG3_XM 0x22 +#define CTRL_REG4_XM 0x23 +#define CTRL_REG5_XM 0x24 +#define CTRL_REG6_XM 0x25 +#define CTRL_REG7_XM 0x26 +#define STATUS_REG_A 0x27 +#define OUT_X_L_A 0x28 +#define OUT_X_H_A 0x29 +#define OUT_Y_L_A 0x2A +#define OUT_Y_H_A 0x2B +#define OUT_Z_L_A 0x2C +#define OUT_Z_H_A 0x2D +#define FIFO_CTRL_REG 0x2E +#define FIFO_SRC_REG 0x2F +#define INT_GEN_1_REG 0x30 +#define INT_GEN_1_SRC 0x31 +#define INT_GEN_1_THS 0x32 +#define INT_GEN_1_DURATION 0x33 +#define INT_GEN_2_REG 0x34 +#define INT_GEN_2_SRC 0x35 +#define INT_GEN_2_THS 0x36 +#define INT_GEN_2_DURATION 0x37 +#define CLICK_CFG 0x38 +#define CLICK_SRC 0x39 +#define CLICK_THS 0x3A +#define TIME_LIMIT 0x3B +#define TIME_LATENCY 0x3C +#define TIME_WINDOW 0x3D +#define ACT_THS 0x3E +#define ACT_DUR 0x3F + + +class LSM9DS0 +{ +public: + // gyro_scale defines the possible full-scale ranges of the gyroscope: + enum gyro_scale { + G_SCALE_245DPS, // 00: +/- 245 degrees per second + G_SCALE_500DPS, // 01: +/- 500 dps + G_SCALE_2000DPS, // 10: +/- 2000 dps + }; + + // accel_scale defines all possible FSR's of the accelerometer: + enum accel_scale { + A_SCALE_2G, // 000: +/- 2g + A_SCALE_4G, // 001: +/- 4g + A_SCALE_6G, // 010: +/- 6g + A_SCALE_8G, // 011: +/- 8g + A_SCALE_16G // 100: +/- 16g + }; + + // mag_scale defines all possible FSR's of the magnetometer: + enum mag_scale { + M_SCALE_2GS, // 00: +/- 2Gs + M_SCALE_4GS, // 01: +/- 4Gs + M_SCALE_8GS, // 10: +/- 8Gs + M_SCALE_12GS, // 11: +/- 12Gs + }; + + // gyro_odr defines all possible data rate/bandwidth combos of the gyro: + enum gyro_odr { + // ODR (Hz) --- Cutoff + G_ODR_95_BW_125 = 0x0, // 95 12.5 + G_ODR_95_BW_25 = 0x1, // 95 25 + // 0x2 and 0x3 define the same data rate and bandwidth + G_ODR_190_BW_125 = 0x4, // 190 12.5 + G_ODR_190_BW_25 = 0x5, // 190 25 + G_ODR_190_BW_50 = 0x6, // 190 50 + G_ODR_190_BW_70 = 0x7, // 190 70 + G_ODR_380_BW_20 = 0x8, // 380 20 + G_ODR_380_BW_25 = 0x9, // 380 25 + G_ODR_380_BW_50 = 0xA, // 380 50 + G_ODR_380_BW_100 = 0xB, // 380 100 + G_ODR_760_BW_30 = 0xC, // 760 30 + G_ODR_760_BW_35 = 0xD, // 760 35 + G_ODR_760_BW_50 = 0xE, // 760 50 + G_ODR_760_BW_100 = 0xF, // 760 100 + }; + + // accel_oder defines all possible output data rates of the accelerometer: + enum accel_odr { + A_POWER_DOWN, // Power-down mode (0x0) + A_ODR_3125, // 3.125 Hz (0x1) + A_ODR_625, // 6.25 Hz (0x2) + A_ODR_125, // 12.5 Hz (0x3) + A_ODR_25, // 25 Hz (0x4) + A_ODR_50, // 50 Hz (0x5) + A_ODR_100, // 100 Hz (0x6) + A_ODR_200, // 200 Hz (0x7) + A_ODR_400, // 400 Hz (0x8) + A_ODR_800, // 800 Hz (9) + A_ODR_1600 // 1600 Hz (0xA) + }; + + // accel_abw defines all possible anti-aliasing filter rates of the accelerometer: + enum accel_abw { + A_ABW_773, // 773 Hz (0x0) + A_ABW_194, // 194 Hz (0x1) + A_ABW_362, // 362 Hz (0x2) + A_ABW_50, // 50 Hz (0x3) + }; + + // accel_oder defines all possible output data rates of the magnetometer: + enum mag_odr { + M_ODR_3125, // 3.125 Hz (0x00) + M_ODR_625, // 6.25 Hz (0x01) + M_ODR_125, // 12.5 Hz (0x02) + M_ODR_25, // 25 Hz (0x03) + M_ODR_50, // 50 (0x04) + M_ODR_100, // 100 Hz (0x05) + }; + + // We'll store the gyro, accel, and magnetometer readings in a series of + // public class variables. Each sensor gets three variables -- one for each + // axis. Call readGyro(), readAccel(), and readMag() first, before using + // these variables! + // These values are the RAW signed 16-bit readings from the sensors. + int16_t gx, gy, gz; // x, y, and z axis readings of the gyroscope + int16_t ax, ay, az; // x, y, and z axis readings of the accelerometer + int16_t mx, my, mz; // x, y, and z axis readings of the magnetometer + int16_t temperature; + float abias[3]; + float gbias[3]; + + + // LSM9DS0 -- LSM9DS0 class constructor + // The constructor will set up a handful of private variables, and set the + // communication mode as well. + // Input: + // - interface = Either MODE_SPI or MODE_I2C, whichever you're using + // to talk to the IC. + // - gAddr = If MODE_I2C, this is the I2C address of the gyroscope. + // If MODE_SPI, this is the chip select pin of the gyro (CSG) + // - xmAddr = If MODE_I2C, this is the I2C address of the accel/mag. + // If MODE_SPI, this is the cs pin of the accel/mag (CSXM) + LSM9DS0(PinName sda, PinName scl, uint8_t gAddr, uint8_t xmAddr); + + // begin() -- Initialize the gyro, accelerometer, and magnetometer. + // This will set up the scale and output rate of each sensor. It'll also + // "turn on" every sensor and every axis of every sensor. + // Input: + // - gScl = The scale of the gyroscope. This should be a gyro_scale value. + // - aScl = The scale of the accelerometer. Should be a accel_scale value. + // - mScl = The scale of the magnetometer. Should be a mag_scale value. + // - gODR = Output data rate of the gyroscope. gyro_odr value. + // - aODR = Output data rate of the accelerometer. accel_odr value. + // - mODR = Output data rate of the magnetometer. mag_odr value. + // Output: The function will return an unsigned 16-bit value. The most-sig + // bytes of the output are the WHO_AM_I reading of the accel. The + // least significant two bytes are the WHO_AM_I reading of the gyro. + // All parameters have a defaulted value, so you can call just "begin()". + // Default values are FSR's of: +/- 245DPS, 2g, 2Gs; ODRs of 95 Hz for + // gyro, 100 Hz for accelerometer, 100 Hz for magnetometer. + // Use the return value of this function to verify communication. + uint16_t begin(gyro_scale gScl = G_SCALE_245DPS, + accel_scale aScl = A_SCALE_2G, mag_scale mScl = M_SCALE_2GS, + gyro_odr gODR = G_ODR_95_BW_125, accel_odr aODR = A_ODR_50, + mag_odr mODR = M_ODR_50); + + // readGyro() -- Read the gyroscope output registers. + // This function will read all six gyroscope output registers. + // The readings are stored in the class' gx, gy, and gz variables. Read + // those _after_ calling readGyro(). + void readGyro(); + + // readAccel() -- Read the accelerometer output registers. + // This function will read all six accelerometer output registers. + // The readings are stored in the class' ax, ay, and az variables. Read + // those _after_ calling readAccel(). + void readAccel(); + + // readMag() -- Read the magnetometer output registers. + // This function will read all six magnetometer output registers. + // The readings are stored in the class' mx, my, and mz variables. Read + // those _after_ calling readMag(). + void readMag(); + + // readTemp() -- Read the temperature output register. + // This function will read two temperature output registers. + // The combined readings are stored in the class' temperature variables. Read + // those _after_ calling readTemp(). + void readTemp(); + + // calcGyro() -- Convert from RAW signed 16-bit value to degrees per second + // This function reads in a signed 16-bit value and returns the scaled + // DPS. This function relies on gScale and gRes being correct. + // Input: + // - gyro = A signed 16-bit raw reading from the gyroscope. + float calcGyro(int16_t gyro); + + // calcAccel() -- Convert from RAW signed 16-bit value to gravity (g's). + // This function reads in a signed 16-bit value and returns the scaled + // g's. This function relies on aScale and aRes being correct. + // Input: + // - accel = A signed 16-bit raw reading from the accelerometer. + float calcAccel(int16_t accel); + + // calcMag() -- Convert from RAW signed 16-bit value to Gauss (Gs) + // This function reads in a signed 16-bit value and returns the scaled + // Gs. This function relies on mScale and mRes being correct. + // Input: + // - mag = A signed 16-bit raw reading from the magnetometer. + float calcMag(int16_t mag); + + // setGyroScale() -- Set the full-scale range of the gyroscope. + // This function can be called to set the scale of the gyroscope to + // 245, 500, or 200 degrees per second. + // Input: + // - gScl = The desired gyroscope scale. Must be one of three possible + // values from the gyro_scale enum. + void setGyroScale(gyro_scale gScl); + + // setAccelScale() -- Set the full-scale range of the accelerometer. + // This function can be called to set the scale of the accelerometer to + // 2, 4, 6, 8, or 16 g's. + // Input: + // - aScl = The desired accelerometer scale. Must be one of five possible + // values from the accel_scale enum. + void setAccelScale(accel_scale aScl); + + // setMagScale() -- Set the full-scale range of the magnetometer. + // This function can be called to set the scale of the magnetometer to + // 2, 4, 8, or 12 Gs. + // Input: + // - mScl = The desired magnetometer scale. Must be one of four possible + // values from the mag_scale enum. + void setMagScale(mag_scale mScl); + + // setGyroODR() -- Set the output data rate and bandwidth of the gyroscope + // Input: + // - gRate = The desired output rate and cutoff frequency of the gyro. + // Must be a value from the gyro_odr enum (check above, there're 14). + void setGyroODR(gyro_odr gRate); + + // setAccelODR() -- Set the output data rate of the accelerometer + // Input: + // - aRate = The desired output rate of the accel. + // Must be a value from the accel_odr enum (check above, there're 11). + void setAccelODR(accel_odr aRate); + + // setMagODR() -- Set the output data rate of the magnetometer + // Input: + // - mRate = The desired output rate of the mag. + // Must be a value from the mag_odr enum (check above, there're 6). + void setMagODR(mag_odr mRate); + + // setAccelABW() -- Set the anti-aliasing filter rate of the accelerometer + // Input: + // - abwRate = The desired anti-aliasing filter rate of the accel. + // Must be a value from the accel_abw enum (check above, there're 4). + void setAccelABW(accel_abw abwRate); + + + // configGyroInt() -- Configure the gyro interrupt output. + // Triggers can be set to either rising above or falling below a specified + // threshold. This function helps setup the interrupt configuration and + // threshold values for all axes. + // Input: + // - int1Cfg = A 8-bit value that is sent directly to the INT1_CFG_G + // register. This sets AND/OR and high/low interrupt gen for each axis + // - int1ThsX = 16-bit interrupt threshold value for x-axis + // - int1ThsY = 16-bit interrupt threshold value for y-axis + // - int1ThsZ = 16-bit interrupt threshold value for z-axis + // - duration = Duration an interrupt holds after triggered. This value + // is copied directly into the INT1_DURATION_G register. + // Before using this function, read about the INT1_CFG_G register and + // the related INT1* registers in the LMS9DS0 datasheet. + void configGyroInt(uint8_t int1Cfg, uint16_t int1ThsX = 0, + uint16_t int1ThsY = 0, uint16_t int1ThsZ = 0, + uint8_t duration = 0); + + void calLSM9DS0(float gbias[3], float abias[3]); + + +private: + // xmAddress and gAddress store the I2C address + // for each sensor. + uint8_t xmAddress, gAddress; + + // gScale, aScale, and mScale store the current scale range for each + // sensor. Should be updated whenever that value changes. + gyro_scale gScale; + accel_scale aScale; + mag_scale mScale; + + // gRes, aRes, and mRes store the current resolution for each sensor. + // Units of these values would be DPS (or g's or Gs's) per ADC tick. + // This value is calculated as (sensor scale) / (2^15). + float gRes, aRes, mRes; + + // initGyro() -- Sets up the gyroscope to begin reading. + // This function steps through all five gyroscope control registers. + // Upon exit, the following parameters will be set: + // - CTRL_REG1_G = 0x0F: Normal operation mode, all axes enabled. + // 95 Hz ODR, 12.5 Hz cutoff frequency. + // - CTRL_REG2_G = 0x00: HPF set to normal mode, cutoff frequency + // set to 7.2 Hz (depends on ODR). + // - CTRL_REG3_G = 0x88: Interrupt enabled on INT_G (set to push-pull and + // active high). Data-ready output enabled on DRDY_G. + // - CTRL_REG4_G = 0x00: Continuous update mode. Data LSB stored in lower + // address. Scale set to 245 DPS. SPI mode set to 4-wire. + // - CTRL_REG5_G = 0x00: FIFO disabled. HPF disabled. + void initGyro(); + + // initAccel() -- Sets up the accelerometer to begin reading. + // This function steps through all accelerometer related control registers. + // Upon exit these registers will be set as: + // - CTRL_REG0_XM = 0x00: FIFO disabled. HPF bypassed. Normal mode. + // - CTRL_REG1_XM = 0x57: 100 Hz data rate. Continuous update. + // all axes enabled. + // - CTRL_REG2_XM = 0x00: +/- 2g scale. 773 Hz anti-alias filter BW. + // - CTRL_REG3_XM = 0x04: Accel data ready signal on INT1_XM pin. + void initAccel(); + + // initMag() -- Sets up the magnetometer to begin reading. + // This function steps through all magnetometer-related control registers. + // Upon exit these registers will be set as: + // - CTRL_REG4_XM = 0x04: Mag data ready signal on INT2_XM pin. + // - CTRL_REG5_XM = 0x14: 100 Hz update rate. Low resolution. Interrupt + // requests don't latch. Temperature sensor disabled. + // - CTRL_REG6_XM = 0x00: +/- 2 Gs scale. + // - CTRL_REG7_XM = 0x00: Continuous conversion mode. Normal HPF mode. + // - INT_CTRL_REG_M = 0x09: Interrupt active-high. Enable interrupts. + void initMag(); + + // gReadByte() -- Reads a byte from a specified gyroscope register. + // Input: + // - subAddress = Register to be read from. + // Output: + // - An 8-bit value read from the requested address. + uint8_t gReadByte(uint8_t subAddress); + + // gReadBytes() -- Reads a number of bytes -- beginning at an address + // and incrementing from there -- from the gyroscope. + // Input: + // - subAddress = Register to be read from. + // - * dest = A pointer to an array of uint8_t's. Values read will be + // stored in here on return. + // - count = The number of bytes to be read. + // Output: No value is returned, but the `dest` array will store + // the data read upon exit. + void gReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count); + + // gWriteByte() -- Write a byte to a register in the gyroscope. + // Input: + // - subAddress = Register to be written to. + // - data = data to be written to the register. + void gWriteByte(uint8_t subAddress, uint8_t data); + + // xmReadByte() -- Read a byte from a register in the accel/mag sensor + // Input: + // - subAddress = Register to be read from. + // Output: + // - An 8-bit value read from the requested register. + uint8_t xmReadByte(uint8_t subAddress); + + // xmReadBytes() -- Reads a number of bytes -- beginning at an address + // and incrementing from there -- from the accelerometer/magnetometer. + // Input: + // - subAddress = Register to be read from. + // - * dest = A pointer to an array of uint8_t's. Values read will be + // stored in here on return. + // - count = The number of bytes to be read. + // Output: No value is returned, but the `dest` array will store + // the data read upon exit. + void xmReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count); + + // xmWriteByte() -- Write a byte to a register in the accel/mag sensor. + // Input: + // - subAddress = Register to be written to. + // - data = data to be written to the register. + void xmWriteByte(uint8_t subAddress, uint8_t data); + + // calcgRes() -- Calculate the resolution of the gyroscope. + // This function will set the value of the gRes variable. gScale must + // be set prior to calling this function. + void calcgRes(); + + // calcmRes() -- Calculate the resolution of the magnetometer. + // This function will set the value of the mRes variable. mScale must + // be set prior to calling this function. + void calcmRes(); + + // calcaRes() -- Calculate the resolution of the accelerometer. + // This function will set the value of the aRes variable. aScale must + // be set prior to calling this function. + void calcaRes(); + + + /////////////////// + // I2C Functions // + /////////////////// + I2C* i2c_; + + + // I2CwriteByte() -- Write a byte out of I2C to a register in the device + // Input: + // - address = The 7-bit I2C address of the slave device. + // - subAddress = The register to be written to. + // - data = Byte to be written to the register. + void I2CwriteByte(uint8_t address, uint8_t subAddress, uint8_t data); + + // I2CreadByte() -- Read a single byte from a register over I2C. + // Input: + // - address = The 7-bit I2C address of the slave device. + // - subAddress = The register to be read from. + // Output: + // - The byte read from the requested address. + uint8_t I2CreadByte(uint8_t address, uint8_t subAddress); + + // I2CreadBytes() -- Read a series of bytes, starting at a register via SPI + // Input: + // - address = The 7-bit I2C address of the slave device. + // - subAddress = The register to begin reading. + // - * dest = Pointer to an array where we'll store the readings. + // - count = Number of registers to be read. + // Output: No value is returned by the function, but the registers read are + // all stored in the *dest array given. + void I2CreadBytes(uint8_t address, uint8_t subAddress, uint8_t * dest, uint8_t count); +}; + +#endif // _LSM9DS0_H //
diff -r 000000000000 -r 32b177f0030e mbed.bld --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Sat Dec 05 16:23:36 2015 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/mbed_official/code/mbed/builds/165afa46840b \ No newline at end of file