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.
AHRS_example.cpp@0:32b177f0030e, 2015-12-05 (annotated)
- Committer:
- olimexsmart
- Date:
- Sat Dec 05 16:23:36 2015 +0000
- Revision:
- 0:32b177f0030e
What in this world I am supposed to type here?
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
olimexsmart | 0:32b177f0030e | 1 | #include "LSM9DS0_mbed.h" |
olimexsmart | 0:32b177f0030e | 2 | #include "mbed.h" |
olimexsmart | 0:32b177f0030e | 3 | |
olimexsmart | 0:32b177f0030e | 4 | #define INT1 PB_3 |
olimexsmart | 0:32b177f0030e | 5 | #define INT2 PA_10 |
olimexsmart | 0:32b177f0030e | 6 | #define DR_DYG PB_5 |
olimexsmart | 0:32b177f0030e | 7 | |
olimexsmart | 0:32b177f0030e | 8 | #define SDA PB_9 |
olimexsmart | 0:32b177f0030e | 9 | #define SCL PB_8 |
olimexsmart | 0:32b177f0030e | 10 | |
olimexsmart | 0:32b177f0030e | 11 | /////////////////////// |
olimexsmart | 0:32b177f0030e | 12 | // Example I2C Setup // |
olimexsmart | 0:32b177f0030e | 13 | /////////////////////// |
olimexsmart | 0:32b177f0030e | 14 | // SDO_XM and SDO_G are both grounded, so our addresses are: |
olimexsmart | 0:32b177f0030e | 15 | #define LSM9DS0_XM 0x1D // Would be 0x1E if SDO_XM is LOW |
olimexsmart | 0:32b177f0030e | 16 | #define LSM9DS0_G 0x6B // Would be 0x6A if SDO_G is LOW |
olimexsmart | 0:32b177f0030e | 17 | |
olimexsmart | 0:32b177f0030e | 18 | // Create an instance of the LSM9DS0 library called `dof` the |
olimexsmart | 0:32b177f0030e | 19 | // parameters for this constructor are: |
olimexsmart | 0:32b177f0030e | 20 | // [I2C SDA], [I2C SCL],[gyro I2C address],[xm I2C add.] |
olimexsmart | 0:32b177f0030e | 21 | LSM9DS0 dof(SDA, SCL, LSM9DS0_G, LSM9DS0_XM); |
olimexsmart | 0:32b177f0030e | 22 | |
olimexsmart | 0:32b177f0030e | 23 | /////////////////////////////////// |
olimexsmart | 0:32b177f0030e | 24 | // Interrupt Handler Definitions // |
olimexsmart | 0:32b177f0030e | 25 | /////////////////////////////////// |
olimexsmart | 0:32b177f0030e | 26 | DigitalIn INT1XM(INT1); |
olimexsmart | 0:32b177f0030e | 27 | DigitalIn INT2XM(INT2); |
olimexsmart | 0:32b177f0030e | 28 | DigitalIn DRDYG(DR_DYG); |
olimexsmart | 0:32b177f0030e | 29 | |
olimexsmart | 0:32b177f0030e | 30 | // global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) |
olimexsmart | 0:32b177f0030e | 31 | #define GyroMeasError PI * (40.0f / 180.0f) // gyroscope measurement error in rads/s (shown as 3 deg/s) |
olimexsmart | 0:32b177f0030e | 32 | #define GyroMeasDrift PI * (0.0f / 180.0f) // gyroscope measurement drift in rad/s/s (shown as 0.0 deg/s/s) |
olimexsmart | 0:32b177f0030e | 33 | // There is a tradeoff in the beta parameter between accuracy and response speed. |
olimexsmart | 0:32b177f0030e | 34 | // In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. |
olimexsmart | 0:32b177f0030e | 35 | // However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. |
olimexsmart | 0:32b177f0030e | 36 | // Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! |
olimexsmart | 0:32b177f0030e | 37 | // By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec |
olimexsmart | 0:32b177f0030e | 38 | // I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; |
olimexsmart | 0:32b177f0030e | 39 | // the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. |
olimexsmart | 0:32b177f0030e | 40 | // In any case, this is the free parameter in the Madgwick filtering and fusion scheme. |
olimexsmart | 0:32b177f0030e | 41 | #define beta sqrt(3.0f / 4.0f) * GyroMeasError // compute beta |
olimexsmart | 0:32b177f0030e | 42 | #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 |
olimexsmart | 0:32b177f0030e | 43 | #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 |
olimexsmart | 0:32b177f0030e | 44 | #define Ki 0.0f |
olimexsmart | 0:32b177f0030e | 45 | const float PI = 3.14159265358979f; |
olimexsmart | 0:32b177f0030e | 46 | |
olimexsmart | 0:32b177f0030e | 47 | Timer t1; //Integration timer |
olimexsmart | 0:32b177f0030e | 48 | Timer t2; //Print timer |
olimexsmart | 0:32b177f0030e | 49 | Serial pc(SERIAL_TX, SERIAL_RX); |
olimexsmart | 0:32b177f0030e | 50 | DigitalOut myled(LED1); |
olimexsmart | 0:32b177f0030e | 51 | float pitch, yaw, roll, heading; |
olimexsmart | 0:32b177f0030e | 52 | float deltat = 0.0f; // integration interval for both filter schemes |
olimexsmart | 0:32b177f0030e | 53 | |
olimexsmart | 0:32b177f0030e | 54 | |
olimexsmart | 0:32b177f0030e | 55 | float abias[3] = {0, 0, 0}, gbias[3] = {0, 0, 0}; |
olimexsmart | 0:32b177f0030e | 56 | float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values |
olimexsmart | 0:32b177f0030e | 57 | float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion |
olimexsmart | 0:32b177f0030e | 58 | float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method |
olimexsmart | 0:32b177f0030e | 59 | float temperature; |
olimexsmart | 0:32b177f0030e | 60 | |
olimexsmart | 0:32b177f0030e | 61 | ////////////////////////////////// |
olimexsmart | 0:32b177f0030e | 62 | // FUNCTION DECLARATION // |
olimexsmart | 0:32b177f0030e | 63 | ////////////////////////////////// |
olimexsmart | 0:32b177f0030e | 64 | void setup(); |
olimexsmart | 0:32b177f0030e | 65 | void loop(); |
olimexsmart | 0:32b177f0030e | 66 | void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz); |
olimexsmart | 0:32b177f0030e | 67 | void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz); |
olimexsmart | 0:32b177f0030e | 68 | void dataGyro(); |
olimexsmart | 0:32b177f0030e | 69 | void dataAccel(); |
olimexsmart | 0:32b177f0030e | 70 | void dataMag(); |
olimexsmart | 0:32b177f0030e | 71 | |
olimexsmart | 0:32b177f0030e | 72 | ////////////////////////////////// |
olimexsmart | 0:32b177f0030e | 73 | // MAIN // |
olimexsmart | 0:32b177f0030e | 74 | ////////////////////////////////// |
olimexsmart | 0:32b177f0030e | 75 | int main() |
olimexsmart | 0:32b177f0030e | 76 | { |
olimexsmart | 0:32b177f0030e | 77 | setup(); //Setup sensor and Serial |
olimexsmart | 0:32b177f0030e | 78 | pc.printf("Setup Done\n\r"); |
olimexsmart | 0:32b177f0030e | 79 | |
olimexsmart | 0:32b177f0030e | 80 | |
olimexsmart | 0:32b177f0030e | 81 | while (true) |
olimexsmart | 0:32b177f0030e | 82 | loop(); |
olimexsmart | 0:32b177f0030e | 83 | } |
olimexsmart | 0:32b177f0030e | 84 | |
olimexsmart | 0:32b177f0030e | 85 | |
olimexsmart | 0:32b177f0030e | 86 | ////////////////////////////////// |
olimexsmart | 0:32b177f0030e | 87 | // FUNCTION BODY // |
olimexsmart | 0:32b177f0030e | 88 | ////////////////////////////////// |
olimexsmart | 0:32b177f0030e | 89 | void dataGyro() |
olimexsmart | 0:32b177f0030e | 90 | { |
olimexsmart | 0:32b177f0030e | 91 | dof.readGyro(); // Read raw gyro data |
olimexsmart | 0:32b177f0030e | 92 | gx = dof.calcGyro(dof.gx) - gbias[0]; // Convert to degrees per seconds, remove gyro biases |
olimexsmart | 0:32b177f0030e | 93 | gy = dof.calcGyro(dof.gy) - gbias[1]; |
olimexsmart | 0:32b177f0030e | 94 | gz = dof.calcGyro(dof.gz) - gbias[2]; |
olimexsmart | 0:32b177f0030e | 95 | } |
olimexsmart | 0:32b177f0030e | 96 | void dataAccel() |
olimexsmart | 0:32b177f0030e | 97 | { |
olimexsmart | 0:32b177f0030e | 98 | dof.readAccel(); // Read raw accelerometer data |
olimexsmart | 0:32b177f0030e | 99 | ax = dof.calcAccel(dof.ax) - abias[0]; // Convert to g's, remove accelerometer biases |
olimexsmart | 0:32b177f0030e | 100 | ay = dof.calcAccel(dof.ay) - abias[1]; |
olimexsmart | 0:32b177f0030e | 101 | az = dof.calcAccel(dof.az) - abias[2]; |
olimexsmart | 0:32b177f0030e | 102 | } |
olimexsmart | 0:32b177f0030e | 103 | void dataMag() |
olimexsmart | 0:32b177f0030e | 104 | { |
olimexsmart | 0:32b177f0030e | 105 | dof.readMag(); // Read raw magnetometer data |
olimexsmart | 0:32b177f0030e | 106 | mx = dof.calcMag(dof.mx); // Convert to Gauss and correct for calibration |
olimexsmart | 0:32b177f0030e | 107 | my = dof.calcMag(dof.my); |
olimexsmart | 0:32b177f0030e | 108 | mz = dof.calcMag(dof.mz); |
olimexsmart | 0:32b177f0030e | 109 | } |
olimexsmart | 0:32b177f0030e | 110 | void setup() |
olimexsmart | 0:32b177f0030e | 111 | { |
olimexsmart | 0:32b177f0030e | 112 | pc.baud(115200); // Start serial at 115200 bps |
olimexsmart | 0:32b177f0030e | 113 | myled = true; |
olimexsmart | 0:32b177f0030e | 114 | /*//Interrupt |
olimexsmart | 0:32b177f0030e | 115 | INT1XM.rise(&dataAccel); |
olimexsmart | 0:32b177f0030e | 116 | INT2XM.rise(&dataMag); |
olimexsmart | 0:32b177f0030e | 117 | DRDYG.rise(&dataGyro); |
olimexsmart | 0:32b177f0030e | 118 | */ |
olimexsmart | 0:32b177f0030e | 119 | // begin() returns a 16-bit value which includes both the gyro |
olimexsmart | 0:32b177f0030e | 120 | // and accelerometers WHO_AM_I response. You can check this to |
olimexsmart | 0:32b177f0030e | 121 | // make sure communication was successful. |
olimexsmart | 0:32b177f0030e | 122 | uint16_t status = dof.begin(); |
olimexsmart | 0:32b177f0030e | 123 | |
olimexsmart | 0:32b177f0030e | 124 | pc.printf("LSM9DS0 WHO_AM_I's returned: "); |
olimexsmart | 0:32b177f0030e | 125 | pc.printf("0x%X\t", status); |
olimexsmart | 0:32b177f0030e | 126 | pc.printf("Should be 0x49D4"); |
olimexsmart | 0:32b177f0030e | 127 | pc.printf("\n\r"); |
olimexsmart | 0:32b177f0030e | 128 | |
olimexsmart | 0:32b177f0030e | 129 | |
olimexsmart | 0:32b177f0030e | 130 | // Set data output ranges; choose lowest ranges for maximum resolution |
olimexsmart | 0:32b177f0030e | 131 | // Accelerometer scale can be: A_SCALE_2G, A_SCALE_4G, A_SCALE_6G, A_SCALE_8G, or A_SCALE_16G |
olimexsmart | 0:32b177f0030e | 132 | dof.setAccelScale(dof.A_SCALE_2G); |
olimexsmart | 0:32b177f0030e | 133 | // Gyro scale can be: G_SCALE__245, G_SCALE__500, or G_SCALE__2000DPS |
olimexsmart | 0:32b177f0030e | 134 | dof.setGyroScale(dof.G_SCALE_245DPS); |
olimexsmart | 0:32b177f0030e | 135 | // Magnetometer scale can be: M_SCALE_2GS, M_SCALE_4GS, M_SCALE_8GS, M_SCALE_12GS |
olimexsmart | 0:32b177f0030e | 136 | dof.setMagScale(dof.M_SCALE_2GS); |
olimexsmart | 0:32b177f0030e | 137 | |
olimexsmart | 0:32b177f0030e | 138 | // Set output data rates |
olimexsmart | 0:32b177f0030e | 139 | // 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, |
olimexsmart | 0:32b177f0030e | 140 | // A_ODR_100, A_ODR_200, A_ODR_400, A_ODR_800, A_ODR_1600 (1600 Hz) |
olimexsmart | 0:32b177f0030e | 141 | dof.setAccelODR(dof.A_ODR_200); // Set accelerometer update rate at 100 Hz |
olimexsmart | 0:32b177f0030e | 142 | // Accelerometer anti-aliasing filter rate can be 50, 194, 362, or 763 Hz |
olimexsmart | 0:32b177f0030e | 143 | // Anti-aliasing acts like a low-pass filter allowing oversampling of accelerometer and rejection of high-frequency spurious noise. |
olimexsmart | 0:32b177f0030e | 144 | // Strategy here is to effectively oversample accelerometer at 100 Hz and use a 50 Hz anti-aliasing (low-pass) filter frequency |
olimexsmart | 0:32b177f0030e | 145 | // to get a smooth ~150 Hz filter update rate |
olimexsmart | 0:32b177f0030e | 146 | dof.setAccelABW(dof.A_ABW_50); // Choose lowest filter setting for low noise |
olimexsmart | 0:32b177f0030e | 147 | |
olimexsmart | 0:32b177f0030e | 148 | // Gyro output data rates can be: 95 Hz (bandwidth 12.5 or 25 Hz), 190 Hz (bandwidth 12.5, 25, 50, or 70 Hz) |
olimexsmart | 0:32b177f0030e | 149 | // 380 Hz (bandwidth 20, 25, 50, 100 Hz), or 760 Hz (bandwidth 30, 35, 50, 100 Hz) |
olimexsmart | 0:32b177f0030e | 150 | dof.setGyroODR(dof.G_ODR_190_BW_125); // Set gyro update rate to 190 Hz with the smallest bandwidth for low noise |
olimexsmart | 0:32b177f0030e | 151 | |
olimexsmart | 0:32b177f0030e | 152 | // Magnetometer output data rate can be: 3.125 (ODR_3125), 6.25 (ODR_625), 12.5 (ODR_125), 25, 50, or 100 Hz |
olimexsmart | 0:32b177f0030e | 153 | dof.setMagODR(dof.M_ODR_125); // Set magnetometer to update every 80 ms |
olimexsmart | 0:32b177f0030e | 154 | |
olimexsmart | 0:32b177f0030e | 155 | // Use the FIFO mode to average accelerometer and gyro readings to calculate the biases, which can then be removed from |
olimexsmart | 0:32b177f0030e | 156 | // all subsequent measurements. |
olimexsmart | 0:32b177f0030e | 157 | dof.calLSM9DS0(gbias, abias); |
olimexsmart | 0:32b177f0030e | 158 | |
olimexsmart | 0:32b177f0030e | 159 | // Start timers to get integration time and print time |
olimexsmart | 0:32b177f0030e | 160 | t2.start(); |
olimexsmart | 0:32b177f0030e | 161 | t1.start(); |
olimexsmart | 0:32b177f0030e | 162 | dataGyro(); |
olimexsmart | 0:32b177f0030e | 163 | dataAccel(); |
olimexsmart | 0:32b177f0030e | 164 | dataMag(); |
olimexsmart | 0:32b177f0030e | 165 | } |
olimexsmart | 0:32b177f0030e | 166 | |
olimexsmart | 0:32b177f0030e | 167 | void loop() |
olimexsmart | 0:32b177f0030e | 168 | { |
olimexsmart | 0:32b177f0030e | 169 | //Couldn't manage to get these in interrupt, the interrupt won't fire. It isn't so nececesary indeed. |
olimexsmart | 0:32b177f0030e | 170 | if(INT1XM.read()) |
olimexsmart | 0:32b177f0030e | 171 | dataAccel(); |
olimexsmart | 0:32b177f0030e | 172 | if(INT2XM.read()) |
olimexsmart | 0:32b177f0030e | 173 | { |
olimexsmart | 0:32b177f0030e | 174 | dataMag(); |
olimexsmart | 0:32b177f0030e | 175 | // dof.readTemp(); Can't get temp reading from a Sparkfun breakout board, the problem is not just mine. |
olimexsmart | 0:32b177f0030e | 176 | //temperature = 21.0 + (float) dof.temperature/8.0f; // slope is 8 LSB per degree C, just guessing at the intercept |
olimexsmart | 0:32b177f0030e | 177 | } |
olimexsmart | 0:32b177f0030e | 178 | if(DRDYG.read()) |
olimexsmart | 0:32b177f0030e | 179 | dataGyro(); |
olimexsmart | 0:32b177f0030e | 180 | |
olimexsmart | 0:32b177f0030e | 181 | deltat = t1.read(); // set integration time by time elapsed since last filter update |
olimexsmart | 0:32b177f0030e | 182 | t1.reset(); |
olimexsmart | 0:32b177f0030e | 183 | |
olimexsmart | 0:32b177f0030e | 184 | // Sensors x- and y-axes are aligned but magnetometer z-axis (+ down) is opposite to z-axis (+ up) of accelerometer and gyro! |
olimexsmart | 0:32b177f0030e | 185 | // This is ok by aircraft orientation standards! |
olimexsmart | 0:32b177f0030e | 186 | // Pass gyro rate as rad/s |
olimexsmart | 0:32b177f0030e | 187 | MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); |
olimexsmart | 0:32b177f0030e | 188 | //MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz); |
olimexsmart | 0:32b177f0030e | 189 | |
olimexsmart | 0:32b177f0030e | 190 | |
olimexsmart | 0:32b177f0030e | 191 | // Serial print at 0.5 s rate independent of data rates |
olimexsmart | 0:32b177f0030e | 192 | if (t2.read() > 1.0f) { |
olimexsmart | 0:32b177f0030e | 193 | t2.reset(); |
olimexsmart | 0:32b177f0030e | 194 | |
olimexsmart | 0:32b177f0030e | 195 | myled = !myled; |
olimexsmart | 0:32b177f0030e | 196 | |
olimexsmart | 0:32b177f0030e | 197 | pc.printf("%f\t%f\t%f\n\r", ax, ay, az); |
olimexsmart | 0:32b177f0030e | 198 | pc.printf("%f\t%f\t%f\n\r", gx, gy, gz); |
olimexsmart | 0:32b177f0030e | 199 | pc.printf("%f\t%f\t%f\n\r", mx, my, mz); |
olimexsmart | 0:32b177f0030e | 200 | /* |
olimexsmart | 0:32b177f0030e | 201 | // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. |
olimexsmart | 0:32b177f0030e | 202 | // In this coordinate system, the positive z-axis is down toward Earth. |
olimexsmart | 0:32b177f0030e | 203 | // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination), |
olimexsmart | 0:32b177f0030e | 204 | // looking down on the sensor positive yaw is counterclockwise. |
olimexsmart | 0:32b177f0030e | 205 | // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. |
olimexsmart | 0:32b177f0030e | 206 | // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. |
olimexsmart | 0:32b177f0030e | 207 | // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. |
olimexsmart | 0:32b177f0030e | 208 | // Tait-Bryan angles as well as Euler angles are non-commutative; that is, to get the correct orientation the rotations must be |
olimexsmart | 0:32b177f0030e | 209 | // applied in the correct order which for this configuration is yaw, pitch, and then roll. |
olimexsmart | 0:32b177f0030e | 210 | // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. |
olimexsmart | 0:32b177f0030e | 211 | */ |
olimexsmart | 0:32b177f0030e | 212 | 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]); |
olimexsmart | 0:32b177f0030e | 213 | pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); |
olimexsmart | 0:32b177f0030e | 214 | 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]); |
olimexsmart | 0:32b177f0030e | 215 | pitch *= 180.0f / PI; |
olimexsmart | 0:32b177f0030e | 216 | yaw *= 180.0f / PI; |
olimexsmart | 0:32b177f0030e | 217 | roll *= 180.0f / PI; |
olimexsmart | 0:32b177f0030e | 218 | //yaw -= 13.8; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 |
olimexsmart | 0:32b177f0030e | 219 | |
olimexsmart | 0:32b177f0030e | 220 | /* |
olimexsmart | 0:32b177f0030e | 221 | pc.printf("Temperature = "); |
olimexsmart | 0:32b177f0030e | 222 | pc.printf("%d\n\r", dof.temperature); |
olimexsmart | 0:32b177f0030e | 223 | */ |
olimexsmart | 0:32b177f0030e | 224 | //Angles print |
olimexsmart | 0:32b177f0030e | 225 | pc.printf("Yaw, Pitch, Roll: "); |
olimexsmart | 0:32b177f0030e | 226 | pc.printf("%f", yaw); |
olimexsmart | 0:32b177f0030e | 227 | pc.printf(", "); |
olimexsmart | 0:32b177f0030e | 228 | pc.printf("%f", pitch); |
olimexsmart | 0:32b177f0030e | 229 | pc.printf(", "); |
olimexsmart | 0:32b177f0030e | 230 | pc.printf("%f\n\r", roll); |
olimexsmart | 0:32b177f0030e | 231 | |
olimexsmart | 0:32b177f0030e | 232 | //Update rate print |
olimexsmart | 0:32b177f0030e | 233 | pc.printf("Filter rate = "); |
olimexsmart | 0:32b177f0030e | 234 | pc.printf("%f\n\r", 1.0f/deltat); |
olimexsmart | 0:32b177f0030e | 235 | |
olimexsmart | 0:32b177f0030e | 236 | /* |
olimexsmart | 0:32b177f0030e | 237 | // The filter update rate can be increased by reducing the rate of data reading. The optimal implementation is |
olimexsmart | 0:32b177f0030e | 238 | // one which balances the competing rates so they are about the same; that is, the filter updates the sensor orientation |
olimexsmart | 0:32b177f0030e | 239 | // at about the same rate the data is changing. Of course, other implementations are possible. One might consider |
olimexsmart | 0:32b177f0030e | 240 | // updating the filter at twice the average new data rate to allow for finite filter convergence times. |
olimexsmart | 0:32b177f0030e | 241 | // The filter update rate is determined mostly by the mathematical steps in the respective algorithms, |
olimexsmart | 0:32b177f0030e | 242 | // the processor speed (8 MHz for the 3.3V Pro Mini), and the sensor ODRs, especially the magnetometer ODR: |
olimexsmart | 0:32b177f0030e | 243 | // smaller ODRs for the magnetometer produce the above rates, maximum magnetometer ODR of 100 Hz produces |
olimexsmart | 0:32b177f0030e | 244 | // filter update rates of ~110 and ~135 Hz for the Madgwick and Mahony schemes, respectively. |
olimexsmart | 0:32b177f0030e | 245 | // This is presumably because the magnetometer read takes longer than the gyro or accelerometer reads. |
olimexsmart | 0:32b177f0030e | 246 | // With low ODR settings of 100 Hz, 95 Hz, and 6.25 Hz for the accelerometer, gyro, and magnetometer, respectively, |
olimexsmart | 0:32b177f0030e | 247 | // the filter is updating at a ~150 Hz rate using the Madgwick scheme and ~200 Hz using the Mahony scheme. |
olimexsmart | 0:32b177f0030e | 248 | // These filter update rates should be fast enough to maintain accurate platform orientation for |
olimexsmart | 0:32b177f0030e | 249 | // stabilization control of a fast-moving robot or quadcopter. Compare to the update rate of 200 Hz |
olimexsmart | 0:32b177f0030e | 250 | // produced by the on-board Digital Motion Processor of Invensense's MPU6050 6 DoF and MPU9150 9DoF sensors. |
olimexsmart | 0:32b177f0030e | 251 | // The 3.3 V 8 MHz Pro Mini is doing pretty well! |
olimexsmart | 0:32b177f0030e | 252 | */ |
olimexsmart | 0:32b177f0030e | 253 | } |
olimexsmart | 0:32b177f0030e | 254 | } |
olimexsmart | 0:32b177f0030e | 255 | |
olimexsmart | 0:32b177f0030e | 256 | |
olimexsmart | 0:32b177f0030e | 257 | |
olimexsmart | 0:32b177f0030e | 258 | |
olimexsmart | 0:32b177f0030e | 259 | // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" |
olimexsmart | 0:32b177f0030e | 260 | // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) |
olimexsmart | 0:32b177f0030e | 261 | // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute |
olimexsmart | 0:32b177f0030e | 262 | // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. |
olimexsmart | 0:32b177f0030e | 263 | // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms |
olimexsmart | 0:32b177f0030e | 264 | // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! |
olimexsmart | 0:32b177f0030e | 265 | void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) |
olimexsmart | 0:32b177f0030e | 266 | { |
olimexsmart | 0:32b177f0030e | 267 | float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability |
olimexsmart | 0:32b177f0030e | 268 | float norm; |
olimexsmart | 0:32b177f0030e | 269 | float hx, hy, _2bx, _2bz; |
olimexsmart | 0:32b177f0030e | 270 | float s1, s2, s3, s4; |
olimexsmart | 0:32b177f0030e | 271 | float qDot1, qDot2, qDot3, qDot4; |
olimexsmart | 0:32b177f0030e | 272 | |
olimexsmart | 0:32b177f0030e | 273 | // Auxiliary variables to avoid repeated arithmetic |
olimexsmart | 0:32b177f0030e | 274 | float _2q1mx; |
olimexsmart | 0:32b177f0030e | 275 | float _2q1my; |
olimexsmart | 0:32b177f0030e | 276 | float _2q1mz; |
olimexsmart | 0:32b177f0030e | 277 | float _2q2mx; |
olimexsmart | 0:32b177f0030e | 278 | float _4bx; |
olimexsmart | 0:32b177f0030e | 279 | float _4bz; |
olimexsmart | 0:32b177f0030e | 280 | float _2q1 = 2.0f * q1; |
olimexsmart | 0:32b177f0030e | 281 | float _2q2 = 2.0f * q2; |
olimexsmart | 0:32b177f0030e | 282 | float _2q3 = 2.0f * q3; |
olimexsmart | 0:32b177f0030e | 283 | float _2q4 = 2.0f * q4; |
olimexsmart | 0:32b177f0030e | 284 | float _2q1q3 = 2.0f * q1 * q3; |
olimexsmart | 0:32b177f0030e | 285 | float _2q3q4 = 2.0f * q3 * q4; |
olimexsmart | 0:32b177f0030e | 286 | float q1q1 = q1 * q1; |
olimexsmart | 0:32b177f0030e | 287 | float q1q2 = q1 * q2; |
olimexsmart | 0:32b177f0030e | 288 | float q1q3 = q1 * q3; |
olimexsmart | 0:32b177f0030e | 289 | float q1q4 = q1 * q4; |
olimexsmart | 0:32b177f0030e | 290 | float q2q2 = q2 * q2; |
olimexsmart | 0:32b177f0030e | 291 | float q2q3 = q2 * q3; |
olimexsmart | 0:32b177f0030e | 292 | float q2q4 = q2 * q4; |
olimexsmart | 0:32b177f0030e | 293 | float q3q3 = q3 * q3; |
olimexsmart | 0:32b177f0030e | 294 | float q3q4 = q3 * q4; |
olimexsmart | 0:32b177f0030e | 295 | float q4q4 = q4 * q4; |
olimexsmart | 0:32b177f0030e | 296 | |
olimexsmart | 0:32b177f0030e | 297 | // Normalise accelerometer measurement |
olimexsmart | 0:32b177f0030e | 298 | norm = sqrt(ax * ax + ay * ay + az * az); |
olimexsmart | 0:32b177f0030e | 299 | if (norm == 0.0f) return; // handle NaN |
olimexsmart | 0:32b177f0030e | 300 | norm = 1.0f/norm; |
olimexsmart | 0:32b177f0030e | 301 | ax *= norm; |
olimexsmart | 0:32b177f0030e | 302 | ay *= norm; |
olimexsmart | 0:32b177f0030e | 303 | az *= norm; |
olimexsmart | 0:32b177f0030e | 304 | |
olimexsmart | 0:32b177f0030e | 305 | // Normalise magnetometer measurement |
olimexsmart | 0:32b177f0030e | 306 | norm = sqrt(mx * mx + my * my + mz * mz); |
olimexsmart | 0:32b177f0030e | 307 | if (norm == 0.0f) return; // handle NaN |
olimexsmart | 0:32b177f0030e | 308 | norm = 1.0f/norm; |
olimexsmart | 0:32b177f0030e | 309 | mx *= norm; |
olimexsmart | 0:32b177f0030e | 310 | my *= norm; |
olimexsmart | 0:32b177f0030e | 311 | mz *= norm; |
olimexsmart | 0:32b177f0030e | 312 | |
olimexsmart | 0:32b177f0030e | 313 | // Reference direction of Earth's magnetic field |
olimexsmart | 0:32b177f0030e | 314 | _2q1mx = 2.0f * q1 * mx; |
olimexsmart | 0:32b177f0030e | 315 | _2q1my = 2.0f * q1 * my; |
olimexsmart | 0:32b177f0030e | 316 | _2q1mz = 2.0f * q1 * mz; |
olimexsmart | 0:32b177f0030e | 317 | _2q2mx = 2.0f * q2 * mx; |
olimexsmart | 0:32b177f0030e | 318 | hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; |
olimexsmart | 0:32b177f0030e | 319 | hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; |
olimexsmart | 0:32b177f0030e | 320 | _2bx = sqrt(hx * hx + hy * hy); |
olimexsmart | 0:32b177f0030e | 321 | _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; |
olimexsmart | 0:32b177f0030e | 322 | _4bx = 2.0f * _2bx; |
olimexsmart | 0:32b177f0030e | 323 | _4bz = 2.0f * _2bz; |
olimexsmart | 0:32b177f0030e | 324 | |
olimexsmart | 0:32b177f0030e | 325 | // Gradient decent algorithm corrective step |
olimexsmart | 0:32b177f0030e | 326 | 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); |
olimexsmart | 0:32b177f0030e | 327 | 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); |
olimexsmart | 0:32b177f0030e | 328 | 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); |
olimexsmart | 0:32b177f0030e | 329 | 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); |
olimexsmart | 0:32b177f0030e | 330 | norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude |
olimexsmart | 0:32b177f0030e | 331 | norm = 1.0f/norm; |
olimexsmart | 0:32b177f0030e | 332 | s1 *= norm; |
olimexsmart | 0:32b177f0030e | 333 | s2 *= norm; |
olimexsmart | 0:32b177f0030e | 334 | s3 *= norm; |
olimexsmart | 0:32b177f0030e | 335 | s4 *= norm; |
olimexsmart | 0:32b177f0030e | 336 | |
olimexsmart | 0:32b177f0030e | 337 | // Compute rate of change of quaternion |
olimexsmart | 0:32b177f0030e | 338 | qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; |
olimexsmart | 0:32b177f0030e | 339 | qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; |
olimexsmart | 0:32b177f0030e | 340 | qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; |
olimexsmart | 0:32b177f0030e | 341 | qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; |
olimexsmart | 0:32b177f0030e | 342 | |
olimexsmart | 0:32b177f0030e | 343 | // Integrate to yield quaternion |
olimexsmart | 0:32b177f0030e | 344 | q1 += qDot1 * deltat; |
olimexsmart | 0:32b177f0030e | 345 | q2 += qDot2 * deltat; |
olimexsmart | 0:32b177f0030e | 346 | q3 += qDot3 * deltat; |
olimexsmart | 0:32b177f0030e | 347 | q4 += qDot4 * deltat; |
olimexsmart | 0:32b177f0030e | 348 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion |
olimexsmart | 0:32b177f0030e | 349 | norm = 1.0f/norm; |
olimexsmart | 0:32b177f0030e | 350 | q[0] = q1 * norm; |
olimexsmart | 0:32b177f0030e | 351 | q[1] = q2 * norm; |
olimexsmart | 0:32b177f0030e | 352 | q[2] = q3 * norm; |
olimexsmart | 0:32b177f0030e | 353 | q[3] = q4 * norm; |
olimexsmart | 0:32b177f0030e | 354 | |
olimexsmart | 0:32b177f0030e | 355 | } |
olimexsmart | 0:32b177f0030e | 356 | |
olimexsmart | 0:32b177f0030e | 357 | |
olimexsmart | 0:32b177f0030e | 358 | |
olimexsmart | 0:32b177f0030e | 359 | // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and |
olimexsmart | 0:32b177f0030e | 360 | // measured ones. |
olimexsmart | 0:32b177f0030e | 361 | void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) |
olimexsmart | 0:32b177f0030e | 362 | { |
olimexsmart | 0:32b177f0030e | 363 | float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability |
olimexsmart | 0:32b177f0030e | 364 | float norm; |
olimexsmart | 0:32b177f0030e | 365 | float hx, hy, bx, bz; |
olimexsmart | 0:32b177f0030e | 366 | float vx, vy, vz, wx, wy, wz; |
olimexsmart | 0:32b177f0030e | 367 | float ex, ey, ez; |
olimexsmart | 0:32b177f0030e | 368 | float pa, pb, pc; |
olimexsmart | 0:32b177f0030e | 369 | |
olimexsmart | 0:32b177f0030e | 370 | // Auxiliary variables to avoid repeated arithmetic |
olimexsmart | 0:32b177f0030e | 371 | float q1q1 = q1 * q1; |
olimexsmart | 0:32b177f0030e | 372 | float q1q2 = q1 * q2; |
olimexsmart | 0:32b177f0030e | 373 | float q1q3 = q1 * q3; |
olimexsmart | 0:32b177f0030e | 374 | float q1q4 = q1 * q4; |
olimexsmart | 0:32b177f0030e | 375 | float q2q2 = q2 * q2; |
olimexsmart | 0:32b177f0030e | 376 | float q2q3 = q2 * q3; |
olimexsmart | 0:32b177f0030e | 377 | float q2q4 = q2 * q4; |
olimexsmart | 0:32b177f0030e | 378 | float q3q3 = q3 * q3; |
olimexsmart | 0:32b177f0030e | 379 | float q3q4 = q3 * q4; |
olimexsmart | 0:32b177f0030e | 380 | float q4q4 = q4 * q4; |
olimexsmart | 0:32b177f0030e | 381 | |
olimexsmart | 0:32b177f0030e | 382 | // Normalise accelerometer measurement |
olimexsmart | 0:32b177f0030e | 383 | norm = sqrt(ax * ax + ay * ay + az * az); |
olimexsmart | 0:32b177f0030e | 384 | if (norm == 0.0f) return; // handle NaN |
olimexsmart | 0:32b177f0030e | 385 | norm = 1.0f / norm; // use reciprocal for division |
olimexsmart | 0:32b177f0030e | 386 | ax *= norm; |
olimexsmart | 0:32b177f0030e | 387 | ay *= norm; |
olimexsmart | 0:32b177f0030e | 388 | az *= norm; |
olimexsmart | 0:32b177f0030e | 389 | |
olimexsmart | 0:32b177f0030e | 390 | // Normalise magnetometer measurement |
olimexsmart | 0:32b177f0030e | 391 | norm = sqrt(mx * mx + my * my + mz * mz); |
olimexsmart | 0:32b177f0030e | 392 | if (norm == 0.0f) return; // handle NaN |
olimexsmart | 0:32b177f0030e | 393 | norm = 1.0f / norm; // use reciprocal for division |
olimexsmart | 0:32b177f0030e | 394 | mx *= norm; |
olimexsmart | 0:32b177f0030e | 395 | my *= norm; |
olimexsmart | 0:32b177f0030e | 396 | mz *= norm; |
olimexsmart | 0:32b177f0030e | 397 | |
olimexsmart | 0:32b177f0030e | 398 | // Reference direction of Earth's magnetic field |
olimexsmart | 0:32b177f0030e | 399 | hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); |
olimexsmart | 0:32b177f0030e | 400 | hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); |
olimexsmart | 0:32b177f0030e | 401 | bx = sqrt((hx * hx) + (hy * hy)); |
olimexsmart | 0:32b177f0030e | 402 | bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); |
olimexsmart | 0:32b177f0030e | 403 | |
olimexsmart | 0:32b177f0030e | 404 | // Estimated direction of gravity and magnetic field |
olimexsmart | 0:32b177f0030e | 405 | vx = 2.0f * (q2q4 - q1q3); |
olimexsmart | 0:32b177f0030e | 406 | vy = 2.0f * (q1q2 + q3q4); |
olimexsmart | 0:32b177f0030e | 407 | vz = q1q1 - q2q2 - q3q3 + q4q4; |
olimexsmart | 0:32b177f0030e | 408 | wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); |
olimexsmart | 0:32b177f0030e | 409 | wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); |
olimexsmart | 0:32b177f0030e | 410 | wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); |
olimexsmart | 0:32b177f0030e | 411 | |
olimexsmart | 0:32b177f0030e | 412 | // Error is cross product between estimated direction and measured direction of gravity |
olimexsmart | 0:32b177f0030e | 413 | ex = (ay * vz - az * vy) + (my * wz - mz * wy); |
olimexsmart | 0:32b177f0030e | 414 | ey = (az * vx - ax * vz) + (mz * wx - mx * wz); |
olimexsmart | 0:32b177f0030e | 415 | ez = (ax * vy - ay * vx) + (mx * wy - my * wx); |
olimexsmart | 0:32b177f0030e | 416 | if (Ki > 0.0f) { |
olimexsmart | 0:32b177f0030e | 417 | eInt[0] += ex; // accumulate integral error |
olimexsmart | 0:32b177f0030e | 418 | eInt[1] += ey; |
olimexsmart | 0:32b177f0030e | 419 | eInt[2] += ez; |
olimexsmart | 0:32b177f0030e | 420 | } else { |
olimexsmart | 0:32b177f0030e | 421 | eInt[0] = 0.0f; // prevent integral wind up |
olimexsmart | 0:32b177f0030e | 422 | eInt[1] = 0.0f; |
olimexsmart | 0:32b177f0030e | 423 | eInt[2] = 0.0f; |
olimexsmart | 0:32b177f0030e | 424 | } |
olimexsmart | 0:32b177f0030e | 425 | |
olimexsmart | 0:32b177f0030e | 426 | // Apply feedback terms |
olimexsmart | 0:32b177f0030e | 427 | gx = gx + Kp * ex + Ki * eInt[0]; |
olimexsmart | 0:32b177f0030e | 428 | gy = gy + Kp * ey + Ki * eInt[1]; |
olimexsmart | 0:32b177f0030e | 429 | gz = gz + Kp * ez + Ki * eInt[2]; |
olimexsmart | 0:32b177f0030e | 430 | |
olimexsmart | 0:32b177f0030e | 431 | // Integrate rate of change of quaternion |
olimexsmart | 0:32b177f0030e | 432 | pa = q2; |
olimexsmart | 0:32b177f0030e | 433 | pb = q3; |
olimexsmart | 0:32b177f0030e | 434 | pc = q4; |
olimexsmart | 0:32b177f0030e | 435 | q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat); |
olimexsmart | 0:32b177f0030e | 436 | q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat); |
olimexsmart | 0:32b177f0030e | 437 | q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat); |
olimexsmart | 0:32b177f0030e | 438 | q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat); |
olimexsmart | 0:32b177f0030e | 439 | |
olimexsmart | 0:32b177f0030e | 440 | // Normalise quaternion |
olimexsmart | 0:32b177f0030e | 441 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); |
olimexsmart | 0:32b177f0030e | 442 | norm = 1.0f / norm; |
olimexsmart | 0:32b177f0030e | 443 | q[0] = q1 * norm; |
olimexsmart | 0:32b177f0030e | 444 | q[1] = q2 * norm; |
olimexsmart | 0:32b177f0030e | 445 | q[2] = q3 * norm; |
olimexsmart | 0:32b177f0030e | 446 | q[3] = q4 * norm; |
olimexsmart | 0:32b177f0030e | 447 | |
olimexsmart | 0:32b177f0030e | 448 | } |