Implemented first Hangar-Service

Dependencies:   CalibrateMagneto QuaternionMath

Fork of SML2 by TobyRich GmbH

Committer:
pvaibhav
Date:
Wed May 27 13:01:43 2015 +0000
Revision:
46:fd5a62296b12
Parent:
43:6251c0169f4f
Code reformatted

Who changed what in which revision?

UserRevisionLine numberNew contents of line
pvaibhav 15:4488660e1a3b 1 #include "SensorFusion.h"
pvaibhav 15:4488660e1a3b 2
pvaibhav 15:4488660e1a3b 3 #define DEBUG "SensorFusion"
pvaibhav 15:4488660e1a3b 4 #include "Logger.h"
pvaibhav 15:4488660e1a3b 5
pvaibhav 34:01dec68de3ed 6 #include "Utils.h"
pvaibhav 34:01dec68de3ed 7
pvaibhav 40:8e852115fe55 8 SensorFusion6::SensorFusion6(I2C &i2c) :
pvaibhav 40:8e852115fe55 9 SensorFusion(),
pvaibhav 40:8e852115fe55 10 accel(i2c),
pvaibhav 40:8e852115fe55 11 gyro(i2c),
pvaibhav 40:8e852115fe55 12 deltat(0.010), // seconds
pvaibhav 43:6251c0169f4f 13 beta(50),
pvaibhav 43:6251c0169f4f 14 lowpassX(0.96),
pvaibhav 43:6251c0169f4f 15 lowpassY(0.96),
pvaibhav 43:6251c0169f4f 16 lowpassZ(0.96)
pvaibhav 15:4488660e1a3b 17 {
pvaibhav 40:8e852115fe55 18 gyro.setDelegate(*this);
pvaibhav 20:503cbe360419 19 }
pvaibhav 20:503cbe360419 20
pvaibhav 40:8e852115fe55 21 bool SensorFusion6::start()
pvaibhav 20:503cbe360419 22 {
pvaibhav 40:8e852115fe55 23 lowpassX.reset();
pvaibhav 40:8e852115fe55 24 lowpassY.reset();
pvaibhav 40:8e852115fe55 25 lowpassZ.reset();
pvaibhav 46:fd5a62296b12 26
pvaibhav 15:4488660e1a3b 27 accel.powerOn();
pvaibhav 15:4488660e1a3b 28 accel.start();
pvaibhav 46:fd5a62296b12 29
pvaibhav 15:4488660e1a3b 30 // Since everything is synced to gyro interrupt, start it last
pvaibhav 15:4488660e1a3b 31 gyro.powerOn();
pvaibhav 15:4488660e1a3b 32 gyro.start();
pvaibhav 46:fd5a62296b12 33
pvaibhav 15:4488660e1a3b 34 return true;
pvaibhav 15:4488660e1a3b 35 }
pvaibhav 15:4488660e1a3b 36
pvaibhav 40:8e852115fe55 37 void SensorFusion6::stop()
pvaibhav 15:4488660e1a3b 38 {
pvaibhav 15:4488660e1a3b 39 gyro.stop();
pvaibhav 40:8e852115fe55 40 gyro.powerOff();
pvaibhav 46:fd5a62296b12 41
pvaibhav 15:4488660e1a3b 42 accel.stop();
pvaibhav 15:4488660e1a3b 43 accel.powerOff();
pvaibhav 15:4488660e1a3b 44 }
pvaibhav 15:4488660e1a3b 45
pvaibhav 15:4488660e1a3b 46 static float const deg_to_radian = 0.0174532925f;
pvaibhav 15:4488660e1a3b 47
pvaibhav 40:8e852115fe55 48 void SensorFusion6::sensorUpdate(Vector3 gyro_degrees)
pvaibhav 46:fd5a62296b12 49 {
pvaibhav 15:4488660e1a3b 50 Vector3 const gyro_reading = gyro_degrees * deg_to_radian;
pvaibhav 15:4488660e1a3b 51 Vector3 const accel_reading = accel.read();
pvaibhav 40:8e852115fe55 52 Vector3 const filtered_accel = Vector3( lowpassX.filter(accel_reading.x),
pvaibhav 40:8e852115fe55 53 lowpassY.filter(accel_reading.y),
pvaibhav 40:8e852115fe55 54 lowpassZ.filter(accel_reading.z));
pvaibhav 15:4488660e1a3b 55
pvaibhav 40:8e852115fe55 56 updateFilter( filtered_accel.x, filtered_accel.y, filtered_accel.z,
pvaibhav 46:fd5a62296b12 57 gyro_reading.x, gyro_reading.y, gyro_reading.z);
pvaibhav 46:fd5a62296b12 58
pvaibhav 40:8e852115fe55 59 delegate->sensorTick(deltat, q.getEulerAngles(), filtered_accel, accel_reading, gyro_degrees, q);
pvaibhav 34:01dec68de3ed 60 }
pvaibhav 34:01dec68de3ed 61
pvaibhav 40:8e852115fe55 62 void SensorFusion6::updateFilter(float ax, float ay, float az, float gx, float gy, float gz)
pvaibhav 35:fb6e4601adf3 63 {
pvaibhav 35:fb6e4601adf3 64 float q0 = q.w, q1 = q.v.x, q2 = q.v.y, q3 = q.v.z; // short name local variable for readability
pvaibhav 46:fd5a62296b12 65
pvaibhav 35:fb6e4601adf3 66 float recipNorm;
pvaibhav 35:fb6e4601adf3 67 float s0, s1, s2, s3;
pvaibhav 35:fb6e4601adf3 68 float qDot1, qDot2, qDot3, qDot4;
pvaibhav 35:fb6e4601adf3 69 float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3;
pvaibhav 35:fb6e4601adf3 70
pvaibhav 35:fb6e4601adf3 71 // Rate of change of quaternion from gyroscope
pvaibhav 35:fb6e4601adf3 72 qDot1 = 0.5 * (-q1 * gx - q2 * gy - q3 * gz);
pvaibhav 35:fb6e4601adf3 73 qDot2 = 0.5 * (q0 * gx + q2 * gz - q3 * gy);
pvaibhav 35:fb6e4601adf3 74 qDot3 = 0.5 * (q0 * gy - q1 * gz + q3 * gx);
pvaibhav 35:fb6e4601adf3 75 qDot4 = 0.5 * (q0 * gz + q1 * gy - q2 * gx);
pvaibhav 35:fb6e4601adf3 76
pvaibhav 35:fb6e4601adf3 77 // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
pvaibhav 35:fb6e4601adf3 78 if(!((ax == 0.0) && (ay == 0.0) && (az == 0.0))) {
pvaibhav 35:fb6e4601adf3 79
pvaibhav 35:fb6e4601adf3 80 // Normalise accelerometer measurement
pvaibhav 35:fb6e4601adf3 81 recipNorm = 1.0 / sqrt(ax * ax + ay * ay + az * az);
pvaibhav 35:fb6e4601adf3 82 ax *= recipNorm;
pvaibhav 35:fb6e4601adf3 83 ay *= recipNorm;
pvaibhav 46:fd5a62296b12 84 az *= recipNorm;
pvaibhav 35:fb6e4601adf3 85
pvaibhav 35:fb6e4601adf3 86 // Auxiliary variables to avoid repeated arithmetic
pvaibhav 35:fb6e4601adf3 87 _2q0 = 2.0 * q0;
pvaibhav 35:fb6e4601adf3 88 _2q1 = 2.0 * q1;
pvaibhav 35:fb6e4601adf3 89 _2q2 = 2.0 * q2;
pvaibhav 35:fb6e4601adf3 90 _2q3 = 2.0 * q3;
pvaibhav 35:fb6e4601adf3 91 _4q0 = 4.0 * q0;
pvaibhav 35:fb6e4601adf3 92 _4q1 = 4.0 * q1;
pvaibhav 35:fb6e4601adf3 93 _4q2 = 4.0 * q2;
pvaibhav 35:fb6e4601adf3 94 _8q1 = 8.0 * q1;
pvaibhav 35:fb6e4601adf3 95 _8q2 = 8.0 * q2;
pvaibhav 35:fb6e4601adf3 96 q0q0 = q0 * q0;
pvaibhav 35:fb6e4601adf3 97 q1q1 = q1 * q1;
pvaibhav 35:fb6e4601adf3 98 q2q2 = q2 * q2;
pvaibhav 35:fb6e4601adf3 99 q3q3 = q3 * q3;
pvaibhav 35:fb6e4601adf3 100
pvaibhav 35:fb6e4601adf3 101 // Gradient decent algorithm corrective step
pvaibhav 35:fb6e4601adf3 102 s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay;
pvaibhav 35:fb6e4601adf3 103 s1 = _4q1 * q3q3 - _2q3 * ax + 4.0 * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az;
pvaibhav 35:fb6e4601adf3 104 s2 = 4.0 * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az;
pvaibhav 35:fb6e4601adf3 105 s3 = 4.0 * q1q1 * q3 - _2q1 * ax + 4.0 * q2q2 * q3 - _2q2 * ay;
pvaibhav 35:fb6e4601adf3 106 recipNorm = 1.0 / sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
pvaibhav 35:fb6e4601adf3 107 s0 *= recipNorm;
pvaibhav 35:fb6e4601adf3 108 s1 *= recipNorm;
pvaibhav 35:fb6e4601adf3 109 s2 *= recipNorm;
pvaibhav 35:fb6e4601adf3 110 s3 *= recipNorm;
pvaibhav 35:fb6e4601adf3 111
pvaibhav 35:fb6e4601adf3 112 // Apply feedback step
pvaibhav 35:fb6e4601adf3 113 qDot1 -= beta * s0;
pvaibhav 35:fb6e4601adf3 114 qDot2 -= beta * s1;
pvaibhav 35:fb6e4601adf3 115 qDot3 -= beta * s2;
pvaibhav 35:fb6e4601adf3 116 qDot4 -= beta * s3;
pvaibhav 35:fb6e4601adf3 117 }
pvaibhav 35:fb6e4601adf3 118
pvaibhav 35:fb6e4601adf3 119 // Integrate rate of change of quaternion to yield quaternion
pvaibhav 35:fb6e4601adf3 120 q0 += qDot1 * deltat;
pvaibhav 35:fb6e4601adf3 121 q1 += qDot2 * deltat;
pvaibhav 35:fb6e4601adf3 122 q2 += qDot3 * deltat;
pvaibhav 35:fb6e4601adf3 123 q3 += qDot4 * deltat;
pvaibhav 35:fb6e4601adf3 124
pvaibhav 35:fb6e4601adf3 125 // Normalise quaternion
pvaibhav 35:fb6e4601adf3 126 recipNorm = 1.0 / sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
pvaibhav 35:fb6e4601adf3 127 q0 *= recipNorm;
pvaibhav 35:fb6e4601adf3 128 q1 *= recipNorm;
pvaibhav 35:fb6e4601adf3 129 q2 *= recipNorm;
pvaibhav 35:fb6e4601adf3 130 q3 *= recipNorm;
pvaibhav 46:fd5a62296b12 131
pvaibhav 35:fb6e4601adf3 132 // return
pvaibhav 35:fb6e4601adf3 133 q.w = q0;
pvaibhav 35:fb6e4601adf3 134 q.v.x = q1;
pvaibhav 35:fb6e4601adf3 135 q.v.y = q2;
pvaibhav 35:fb6e4601adf3 136 q.v.z = q3;
pvaibhav 35:fb6e4601adf3 137 }
pvaibhav 35:fb6e4601adf3 138
pvaibhav 43:6251c0169f4f 139 SensorFusion9::SensorFusion9(I2C &i2c) : SensorFusion6(i2c), magneto(i2c)
pvaibhav 43:6251c0169f4f 140 {
pvaibhav 43:6251c0169f4f 141 gyro.setDelegate(*this);
pvaibhav 43:6251c0169f4f 142 }
pvaibhav 43:6251c0169f4f 143
pvaibhav 43:6251c0169f4f 144 bool SensorFusion9::start()
pvaibhav 43:6251c0169f4f 145 {
pvaibhav 43:6251c0169f4f 146 magneto.powerOn();
pvaibhav 43:6251c0169f4f 147 magneto.start();
pvaibhav 46:fd5a62296b12 148
pvaibhav 43:6251c0169f4f 149 return SensorFusion6::start();
pvaibhav 43:6251c0169f4f 150 }
pvaibhav 43:6251c0169f4f 151
pvaibhav 43:6251c0169f4f 152 void SensorFusion9::stop()
pvaibhav 43:6251c0169f4f 153 {
pvaibhav 43:6251c0169f4f 154 SensorFusion6::stop();
pvaibhav 43:6251c0169f4f 155 magneto.stop();
pvaibhav 43:6251c0169f4f 156 magneto.powerOff();
pvaibhav 43:6251c0169f4f 157 }
pvaibhav 43:6251c0169f4f 158
pvaibhav 43:6251c0169f4f 159 void SensorFusion9::sensorUpdate(Vector3 gyro_degrees)
pvaibhav 43:6251c0169f4f 160 {
pvaibhav 43:6251c0169f4f 161 Vector3 const gyro_reading = gyro_degrees * deg_to_radian;
pvaibhav 43:6251c0169f4f 162 Vector3 const accel_reading = accel.read();
pvaibhav 43:6251c0169f4f 163 Vector3 const magneto_reading = magneto.read();
pvaibhav 46:fd5a62296b12 164
pvaibhav 43:6251c0169f4f 165 Vector3 const filtered_accel = Vector3( lowpassX.filter(accel_reading.x),
pvaibhav 43:6251c0169f4f 166 lowpassY.filter(accel_reading.y),
pvaibhav 43:6251c0169f4f 167 lowpassZ.filter(accel_reading.z));
pvaibhav 43:6251c0169f4f 168
pvaibhav 43:6251c0169f4f 169 updateFilter( filtered_accel.x, filtered_accel.y, filtered_accel.z,
pvaibhav 46:fd5a62296b12 170 gyro_reading.x, gyro_reading.y, gyro_reading.z,
pvaibhav 46:fd5a62296b12 171 magneto_reading.x, magneto_reading.y, magneto_reading.z);
pvaibhav 46:fd5a62296b12 172
pvaibhav 43:6251c0169f4f 173 delegate->sensorTick(deltat, q.getEulerAngles(), filtered_accel, magneto_reading, gyro_degrees, q);
pvaibhav 43:6251c0169f4f 174 }
pvaibhav 43:6251c0169f4f 175
pvaibhav 40:8e852115fe55 176 void SensorFusion9::updateFilter(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
pvaibhav 15:4488660e1a3b 177 {
pvaibhav 15:4488660e1a3b 178 float q1 = q.w, q2 = q.v.x, q3 = q.v.y, q4 = q.v.z; // short name local variable for readability
pvaibhav 15:4488660e1a3b 179 float norm;
pvaibhav 15:4488660e1a3b 180 float s1, s2, s3, s4;
pvaibhav 15:4488660e1a3b 181
pvaibhav 15:4488660e1a3b 182 // Auxiliary variables to avoid repeated arithmetic
pvaibhav 15:4488660e1a3b 183 const float _2q1 = 2.0f * q1;
pvaibhav 15:4488660e1a3b 184 const float _2q2 = 2.0f * q2;
pvaibhav 15:4488660e1a3b 185 const float _2q3 = 2.0f * q3;
pvaibhav 15:4488660e1a3b 186 const float _2q4 = 2.0f * q4;
pvaibhav 15:4488660e1a3b 187 const float _2q1q3 = 2.0f * q1 * q3;
pvaibhav 15:4488660e1a3b 188 const float _2q3q4 = 2.0f * q3 * q4;
pvaibhav 15:4488660e1a3b 189 const float q1q1 = q1 * q1;
pvaibhav 15:4488660e1a3b 190 const float q1q2 = q1 * q2;
pvaibhav 15:4488660e1a3b 191 const float q1q3 = q1 * q3;
pvaibhav 15:4488660e1a3b 192 const float q1q4 = q1 * q4;
pvaibhav 15:4488660e1a3b 193 const float q2q2 = q2 * q2;
pvaibhav 15:4488660e1a3b 194 const float q2q3 = q2 * q3;
pvaibhav 15:4488660e1a3b 195 const float q2q4 = q2 * q4;
pvaibhav 15:4488660e1a3b 196 const float q3q3 = q3 * q3;
pvaibhav 15:4488660e1a3b 197 const float q3q4 = q3 * q4;
pvaibhav 15:4488660e1a3b 198 const float q4q4 = q4 * q4;
pvaibhav 15:4488660e1a3b 199
pvaibhav 15:4488660e1a3b 200 // Normalise accelerometer measurement
pvaibhav 15:4488660e1a3b 201 norm = sqrt(ax * ax + ay * ay + az * az);
pvaibhav 15:4488660e1a3b 202 if (norm == 0.0f) return; // handle NaN
pvaibhav 15:4488660e1a3b 203 norm = 1.0f/norm;
pvaibhav 15:4488660e1a3b 204 ax *= norm;
pvaibhav 15:4488660e1a3b 205 ay *= norm;
pvaibhav 15:4488660e1a3b 206 az *= norm;
pvaibhav 15:4488660e1a3b 207
pvaibhav 15:4488660e1a3b 208 // Normalise magnetometer measurement
pvaibhav 15:4488660e1a3b 209 norm = sqrt(mx * mx + my * my + mz * mz);
pvaibhav 15:4488660e1a3b 210 if (norm == 0.0f) return; // handle NaN
pvaibhav 15:4488660e1a3b 211 norm = 1.0f/norm;
pvaibhav 15:4488660e1a3b 212 mx *= norm;
pvaibhav 15:4488660e1a3b 213 my *= norm;
pvaibhav 15:4488660e1a3b 214 mz *= norm;
pvaibhav 15:4488660e1a3b 215
pvaibhav 15:4488660e1a3b 216 // Reference direction of Earth's magnetic field
pvaibhav 15:4488660e1a3b 217 const float _2q1mx = 2.0f * q1 * mx;
pvaibhav 15:4488660e1a3b 218 const float _2q1my = 2.0f * q1 * my;
pvaibhav 15:4488660e1a3b 219 const float _2q1mz = 2.0f * q1 * mz;
pvaibhav 15:4488660e1a3b 220 const float _2q2mx = 2.0f * q2 * mx;
pvaibhav 15:4488660e1a3b 221 const float hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
pvaibhav 15:4488660e1a3b 222 const float hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
pvaibhav 15:4488660e1a3b 223 const float _2bx = sqrt(hx * hx + hy * hy);
pvaibhav 15:4488660e1a3b 224 const float _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
pvaibhav 15:4488660e1a3b 225 const float _4bx = 2.0f * _2bx;
pvaibhav 15:4488660e1a3b 226 const float _4bz = 2.0f * _2bz;
pvaibhav 15:4488660e1a3b 227
pvaibhav 15:4488660e1a3b 228 // Gradient decent algorithm corrective step
pvaibhav 15:4488660e1a3b 229 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);
pvaibhav 15:4488660e1a3b 230 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);
pvaibhav 15:4488660e1a3b 231 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);
pvaibhav 15:4488660e1a3b 232 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);
pvaibhav 15:4488660e1a3b 233 norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude
pvaibhav 15:4488660e1a3b 234 norm = 1.0f/norm;
pvaibhav 15:4488660e1a3b 235 s1 *= norm;
pvaibhav 15:4488660e1a3b 236 s2 *= norm;
pvaibhav 15:4488660e1a3b 237 s3 *= norm;
pvaibhav 15:4488660e1a3b 238 s4 *= norm;
pvaibhav 15:4488660e1a3b 239
pvaibhav 15:4488660e1a3b 240 // Compute rate of change of quaternion
pvaibhav 15:4488660e1a3b 241 const float qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
pvaibhav 15:4488660e1a3b 242 const float qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
pvaibhav 15:4488660e1a3b 243 const float qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
pvaibhav 15:4488660e1a3b 244 const float qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
pvaibhav 15:4488660e1a3b 245
pvaibhav 15:4488660e1a3b 246 // Integrate to yield quaternion
pvaibhav 15:4488660e1a3b 247 q1 += qDot1 * deltat;
pvaibhav 15:4488660e1a3b 248 q2 += qDot2 * deltat;
pvaibhav 15:4488660e1a3b 249 q3 += qDot3 * deltat;
pvaibhav 15:4488660e1a3b 250 q4 += qDot4 * deltat;
pvaibhav 15:4488660e1a3b 251 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
pvaibhav 15:4488660e1a3b 252 norm = 1.0f/norm;
pvaibhav 15:4488660e1a3b 253 q.w = q1 * norm;
pvaibhav 15:4488660e1a3b 254 q.v.x = q2 * norm;
pvaibhav 15:4488660e1a3b 255 q.v.y = q3 * norm;
pvaibhav 15:4488660e1a3b 256 q.v.z = q4 * norm;
pvaibhav 15:4488660e1a3b 257 }
pvaibhav 43:6251c0169f4f 258