Implemented first Hangar-Service

Dependencies:   CalibrateMagneto QuaternionMath

Fork of SML2 by TobyRich GmbH

Files at this revision

API Documentation at this revision

Comitter:
pvaibhav
Date:
Wed May 27 13:01:43 2015 +0000
Parent:
43:6251c0169f4f
Commit message:
Code reformatted

Changed in this revision

Accelerometer.cpp Show annotated file Show diff for this revision Revisions of this file
Accelerometer.h Show annotated file Show diff for this revision Revisions of this file
Barometer.cpp Show annotated file Show diff for this revision Revisions of this file
Barometer.h Show annotated file Show diff for this revision Revisions of this file
CherryCam.cpp Show annotated file Show diff for this revision Revisions of this file
CherryCam.h Show annotated file Show diff for this revision Revisions of this file
Filter.h Show annotated file Show diff for this revision Revisions of this file
GPS.h Show annotated file Show diff for this revision Revisions of this file
Gyroscope.cpp Show annotated file Show diff for this revision Revisions of this file
Gyroscope.h Show annotated file Show diff for this revision Revisions of this file
LEDDriver.cpp Show annotated file Show diff for this revision Revisions of this file
Magnetometer.cpp Show annotated file Show diff for this revision Revisions of this file
Magnetometer.h Show annotated file Show diff for this revision Revisions of this file
MotorDriver.h Show annotated file Show diff for this revision Revisions of this file
PIDController.h Show annotated file Show diff for this revision Revisions of this file
PowerAwareI2C.h Show annotated file Show diff for this revision Revisions of this file
QuaternionMath.lib Show annotated file Show diff for this revision Revisions of this file
Sensor.h Show annotated file Show diff for this revision Revisions of this file
SensorFusion.cpp Show annotated file Show diff for this revision Revisions of this file
SensorFusion.h Show annotated file Show diff for this revision Revisions of this file
Utils.h Show annotated file Show diff for this revision Revisions of this file
diff -r 6251c0169f4f -r fd5a62296b12 Accelerometer.cpp
--- a/Accelerometer.cpp	Wed May 27 11:45:00 2015 +0000
+++ b/Accelerometer.cpp	Wed May 27 13:01:43 2015 +0000
@@ -48,9 +48,9 @@
     for (size_t i = 0; i < 6; i++)
         buffer[i] = read_reg(0x02 + i);
     */
-    
+
     read_reg(0x02, buffer, sizeof buffer);
-    
+
     const int16_t x = *(reinterpret_cast<const int16_t*>(buffer + 0)) / 16;
     const int16_t y = *(reinterpret_cast<const int16_t*>(buffer + 2)) / 16;
     const int16_t z = *(reinterpret_cast<const int16_t*>(buffer + 4)) / 16;
diff -r 6251c0169f4f -r fd5a62296b12 Accelerometer.h
--- a/Accelerometer.h	Wed May 27 11:45:00 2015 +0000
+++ b/Accelerometer.h	Wed May 27 13:01:43 2015 +0000
@@ -15,7 +15,7 @@
     virtual void stop();
 
     virtual Vector3 read();
-    
+
 private:
     InterruptIn int1;
     InterruptIn int2;
diff -r 6251c0169f4f -r fd5a62296b12 Barometer.cpp
--- a/Barometer.cpp	Wed May 27 11:45:00 2015 +0000
+++ b/Barometer.cpp	Wed May 27 13:01:43 2015 +0000
@@ -14,56 +14,62 @@
     }
 }
 
-bool Barometer::powerOn() {
+bool Barometer::powerOn()
+{
     write_reg(0xE0, 0xB6); // reset
     wait_ms(2); // cf. datasheet page 8, t_startup
     return read_reg(0xD0) == 0x58; // verify chip ID
 }
 
-void Barometer::powerOff() {
+void Barometer::powerOff()
+{
     // nothing to do
 }
 
-void Barometer::start() {
+void Barometer::start()
+{
     // reset our initial calibration
     nsamples = 0;
     sum = 0;
     avg = 0;
-    
+
     // set parameters for Bosch-recommended "Indoor navigation" preset
     write_reg(0xF5, 0x10); // 0.5ms t_standby, IIR coefficient=16
     write_reg(0xF4, 0x57); // 2x oversampling for temperature, 16x for pressure and power mode "normal"
 }
 
-void Barometer::stop() {
+void Barometer::stop()
+{
     write_reg(0xF4, 0x54); // keep the oversampling settings but set power mode to "sleep"
 }
 
-Vector3 Barometer::read() {
+Vector3 Barometer::read()
+{
     uint8_t buffer[6];
     /*
     for (int i = 0; i < 6; i++)
         buffer[i] =  read_reg(0xF7 + i);
     */
-    
+
     read_reg(0xF7, buffer, sizeof buffer);
-    
+
     const uint32_t adc_P = ((buffer[0] << 16) | (buffer[1] << 8) | buffer[2]) >> 4;
     const uint32_t adc_T = ((buffer[3] << 16) | (buffer[4] << 8) | buffer[5]) >> 4;
-    
+
     const float celsius = bmp280_val_to_temp(adc_T) - 20; // 20 degree offset (?)
     const float pa = bmp280_val_to_pa(adc_P);
     const float centimeter = pressureToAltitude(pa) * 100.0;
-    
+
     if (++nsamples < 10) {
         sum += centimeter;
         avg = sum / nsamples;
     }
-    
+
     return Vector3(celsius, pa, centimeter - avg);
 }
 
-float Barometer::pressureToAltitude(const float pa) const {    
+float Barometer::pressureToAltitude(const float pa) const
+{
     return -44330.7692 * (pow(pa * 0.0000098692, 0.1902632365) - 1);
 }
 
@@ -83,9 +89,9 @@
         int16_t  dig_P8;
         int16_t  dig_P9;
     } cal_data;
-    
+
     read_reg(0x88, (uint8_t*)&cal_data, sizeof cal_data);
-    
+
     dig_T1 = cal_data.dig_T1;
     dig_T2 = cal_data.dig_T2;
     dig_T3 = cal_data.dig_T3;
diff -r 6251c0169f4f -r fd5a62296b12 Barometer.h
--- a/Barometer.h	Wed May 27 11:45:00 2015 +0000
+++ b/Barometer.h	Wed May 27 13:01:43 2015 +0000
@@ -11,7 +11,7 @@
     typedef uint32_t BMP280_U32_t;
     typedef int32_t  BMP280_S32_t;
     typedef int64_t  BMP280_S64_t;
-    
+
     void  bmp280_read_calibration();
     float bmp280_val_to_temp(BMP280_S32_t adc_T);
     float bmp280_val_to_pa(BMP280_S32_t adc_P);
@@ -19,7 +19,7 @@
     float sum;
     float avg;
     int nsamples;
-    
+
     // Calibration parameters stored on chip
     // XXX: DO NOT modify the order, values are read into this section of the memory sequentially!
     uint16_t dig_T1;
diff -r 6251c0169f4f -r fd5a62296b12 CherryCam.cpp
--- a/CherryCam.cpp	Wed May 27 11:45:00 2015 +0000
+++ b/CherryCam.cpp	Wed May 27 13:01:43 2015 +0000
@@ -4,7 +4,7 @@
 {
     powerPin = 0; // keep off initially
 }
-    
+
 void CherryCam::powerOn()
 {
     powerPin = 1;
@@ -14,20 +14,20 @@
 {
     powerPin = 0;
 }
-    
+
 void CherryCam::start()
 {
     if (recording)
         return;
-        
+
     generateFallingEdge();
 }
-    
+
 void CherryCam::stop()
 {
     if (!recording)
         return;
-        
+
     generateFallingEdge();
 }
 
diff -r 6251c0169f4f -r fd5a62296b12 CherryCam.h
--- a/CherryCam.h	Wed May 27 11:45:00 2015 +0000
+++ b/CherryCam.h	Wed May 27 13:01:43 2015 +0000
@@ -8,12 +8,12 @@
 {
 public:
     CherryCam();            ///< Constructor
-    
+
     void powerOn();         ///< Turn the camera power on. Takes 10-12 sec to boot up.
     void powerOff();        ///< Turn the camera power off.
     void start();           ///< Start video recording. Camera power must be on.
     void stop();            ///< Stop the video recording.
-    
+
 private:
     void generateFallingEdge();
     void pulldownShutterPin();
diff -r 6251c0169f4f -r fd5a62296b12 Filter.h
--- a/Filter.h	Wed May 27 11:45:00 2015 +0000
+++ b/Filter.h	Wed May 27 13:01:43 2015 +0000
@@ -11,25 +11,23 @@
 protected:
     float y;
     float const alpha;
-    
+
 public:
     /// Construct the filter with given coefficient.
     /// @param a filter coefficient (0.0 to 1.0), higher values result in more filtering.
     LowPassFilter(float const a) : y(0), alpha(a) {}
-    
+
     /// Main processing function, passes given value to filter and returns the filter's output.
     /// Call repeatedly to filter an incoming stream of numbers.
     /// @param x one value to send to filter as input
     /// @return filtered output
-    float filter(float const x)
-    {
+    float filter(float const x) {
         y = x + alpha * (y - x);
         return y;
     }
-    
+
     /// Resets the internal state of the filter. Use to start filtering a new stream.
-    void reset()
-    {
+    void reset() {
         y = 0;
     }
 };
@@ -45,14 +43,12 @@
 
 public:
     HighPassFilter(float const a) : y(0), x_1(0), alpha(1 - a) {}
-    float filter(float const x)
-    {
+    float filter(float const x) {
         y = alpha * (y + x - x_1);
         x_1 = x;
         return y;
     }
-    void reset()
-    {
+    void reset() {
         y = 0;
         x_1 = 0;
     }
@@ -64,19 +60,17 @@
     float y;
     float dt;
     float clipmax;
-    
+
 public:
     Integrator( float const _dt = 1,
                 float const initial = 0,
                 float const _max = 1000000) : y(initial),
-                                    dt(_dt),
-                                    clipmax(_max) {}
-    float integrate(float const x)
-    {
+        dt(_dt),
+        clipmax(_max) {}
+    float integrate(float const x) {
         return (y = utils::clip(-clipmax, y + x * dt, clipmax));
     }
-    void reset(float const _dt = 1, float const initial = 0)
-    {
+    void reset(float const _dt = 1, float const initial = 0) {
         y = initial;
         dt = _dt;
     }
@@ -86,16 +80,14 @@
 {
 protected:
     float y;
-    
+
 public:
     Differentiator() : y(0) {}
-    float differentiate(float const x)
-    {
+    float differentiate(float const x) {
         return (y = x - y);
     }
-    
-    void reset()
-    {
+
+    void reset() {
         y = 0;
     }
 };
diff -r 6251c0169f4f -r fd5a62296b12 GPS.h
--- a/GPS.h	Wed May 27 11:45:00 2015 +0000
+++ b/GPS.h	Wed May 27 13:01:43 2015 +0000
@@ -10,18 +10,18 @@
     /// Constructor
     /// @param pc The serial (UART) port used to communicate with the GPS. Data is only received, nothing is sent to this port.
     GPS(Serial const &pc);
-    
+
     class Delegate
     {
         virtual void gpsSync() = 0;
     };
-    
+
     void powerOn();
     void powerOff();
-    
+
 private:
     Serial* uart;
-    
+
 };
 
 #endif//_H_GPS_H
\ No newline at end of file
diff -r 6251c0169f4f -r fd5a62296b12 Gyroscope.cpp
--- a/Gyroscope.cpp	Wed May 27 11:45:00 2015 +0000
+++ b/Gyroscope.cpp	Wed May 27 13:01:43 2015 +0000
@@ -64,15 +64,15 @@
     for (size_t i = 0; i < 6; i++)
         buffer[i] = read_reg(0x02 + i);
     */
-    
+
     read_reg(0x02, buffer, sizeof buffer);
-    
+
     const int16_t x = buffer[1] << 8 | buffer[0];
     const int16_t y = buffer[3] << 8 | buffer[2];
     const int16_t z = buffer[5] << 8 | buffer[4];
 
     //write_reg(0x15, 1 << 7); // new data interrupt enabled
-    
+
     //static Vector3 const offsets(-0.16, -0.17, 0.015);
 
     return (Vector3(x, y, z) * gyro_resolution);// - offsets;
diff -r 6251c0169f4f -r fd5a62296b12 Gyroscope.h
--- a/Gyroscope.h	Wed May 27 11:45:00 2015 +0000
+++ b/Gyroscope.h	Wed May 27 13:01:43 2015 +0000
@@ -16,7 +16,7 @@
     virtual void start();
     virtual void stop();
     virtual Vector3 read();
-    
+
     volatile bool interruptSet;
 
 protected:
diff -r 6251c0169f4f -r fd5a62296b12 LEDDriver.cpp
--- a/LEDDriver.cpp	Wed May 27 11:45:00 2015 +0000
+++ b/LEDDriver.cpp	Wed May 27 13:01:43 2015 +0000
@@ -42,10 +42,10 @@
 void LEDDriver::setWhiteLed(const float w)
 {
     uint8_t value = (uint8_t) (w * 255);
-    
+
     if (value > 255)
         value = 255;
-    
+
     write_reg(0x0e, value);
 }
 
diff -r 6251c0169f4f -r fd5a62296b12 Magnetometer.cpp
--- a/Magnetometer.cpp	Wed May 27 11:45:00 2015 +0000
+++ b/Magnetometer.cpp	Wed May 27 13:01:43 2015 +0000
@@ -8,13 +8,13 @@
 {
     if (powerOn()) {
         readCalibrationData(); // temperature calibration
-        
+
         // Initialise hard-iron and soft-iron correction. The minima and maxima values were measured
         // smartplane2 prototype gives a starting point for the background calibrator.
         float minimums[] = { -1536.0f, -2701.0f, -2112.0f };
         float maximums[] = { 187, 1665, 39 };
         calibrator.setExtremes(minimums, maximums);
-    
+
         INFO("Bosch Sensortec BMX055-Magneto found");
         powerOff();
     } else {
@@ -88,16 +88,16 @@
     const int16_t temp = ((int16_t)(((uint16_t)((((int32_t)dig_xyz1) << 14)/(data_r != 0 ? data_r : dig_xyz1))) - ((uint16_t)0x4000)));
     const int32_t temp2 = (((((int32_t)dig_xy2) * ((((int32_t)temp) * ((int32_t)temp)) >> 7)) + (((int32_t)temp) * ((int32_t)(((int16_t)dig_xy1) << 7)))) >> 9);
     input[0] = ((int16_t)((((int32_t)mdata_x) *
-                (((temp2 +
-                ((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_x2) + ((int16_t)0xA0)))) >> 12)) >> 13)) + (((int16_t)dig_x1) << 3);
+                           (((temp2 +
+                              ((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_x2) + ((int16_t)0xA0)))) >> 12)) >> 13)) + (((int16_t)dig_x1) << 3);
 
     input[1] = ((int16_t)((((int32_t)mdata_y) *
-                (((temp2 +
-                ((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_y2) + ((int16_t)0xA0)))) >> 12)) >> 13)) + (((int16_t)dig_y1) << 3);
+                           (((temp2 +
+                              ((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_y2) + ((int16_t)0xA0)))) >> 12)) >> 13)) + (((int16_t)dig_y1) << 3);
 
     input[2] = (((((int32_t)(mdata_z - dig_z4)) << 15) - ((((int32_t)dig_z3) * ((int32_t)(((int16_t)data_r) -
-                  ((int16_t)dig_xyz1))))>>2))/(dig_z2 + ((int16_t)(((((int32_t)dig_z1) * ((((int16_t)data_r) << 1)))+(1<<15))>>16))));
-                  
+                 ((int16_t)dig_xyz1))))>>2))/(dig_z2 + ((int16_t)(((((int32_t)dig_z1) * ((((int16_t)data_r) << 1)))+(1<<15))>>16))));
+
     float output[3];
     calibrator.run(input, output);
 
diff -r 6251c0169f4f -r fd5a62296b12 Magnetometer.h
--- a/Magnetometer.h	Wed May 27 11:45:00 2015 +0000
+++ b/Magnetometer.h	Wed May 27 13:01:43 2015 +0000
@@ -18,7 +18,7 @@
     virtual Vector3 read();
 
     bool performSelfTest();
-    
+
     void getCalibration(Vector3 &mins, Vector3 &maxs);
 
 private:
@@ -39,7 +39,7 @@
     CalibrateMagneto calibrator;
 
     void readCalibrationData();
-    
+
     InterruptIn int1;
     InterruptIn int2;
 };
diff -r 6251c0169f4f -r fd5a62296b12 MotorDriver.h
--- a/MotorDriver.h	Wed May 27 11:45:00 2015 +0000
+++ b/MotorDriver.h	Wed May 27 13:01:43 2015 +0000
@@ -9,7 +9,7 @@
     MotorDriver(I2C &i2c, const uint8_t address, PinName interruptPin);
     void setVoltage(float voltage);
     MotorDriver& operator=(const float voltage);
-    
+
 private:
     InterruptIn faultLine;
 };
diff -r 6251c0169f4f -r fd5a62296b12 PIDController.h
--- a/PIDController.h	Wed May 27 11:45:00 2015 +0000
+++ b/PIDController.h	Wed May 27 13:01:43 2015 +0000
@@ -23,10 +23,10 @@
                     float const _setpoint = 0.0f,
                     bool  const _clippingEnabled = false,
                     float const _maximum = 0.0)
-                    :   Kp(_Kp), Ki(_Ki), Kd(_Kd),
-                        setPoint(_setpoint),
-                        clippingEnabled(_clippingEnabled), maximum(_maximum),
-                        e(0), int_e(0), diff_e(0), prev_e(0) { }
+        :   Kp(_Kp), Ki(_Ki), Kd(_Kd),
+            setPoint(_setpoint),
+            clippingEnabled(_clippingEnabled), maximum(_maximum),
+            e(0), int_e(0), diff_e(0), prev_e(0) { }
 
     float Kp;               ///< The proportional term of the PID controller
     float Ki;               ///< The integral term of the PID controller
@@ -40,8 +40,7 @@
     float prev_e;           ///< error at t_-1
 
     /// Reset PID controller (integral, differential) to zero
-    void reset()
-    {
+    void reset() {
         prev_e = 0.0f;
         int_e  = 0.0f;
     }
@@ -49,27 +48,26 @@
     /// Performs one iteration of the PID control loop. If clipping
     /// @param input The input to the PID controller
     /// @return The PID controller's output
-    float output(float const input)
-    {
+    float output(float const input) {
         // find error from set point
         e = setPoint - input;
-        
+
         // differentiate error
         diff_e = (e - prev_e);
         prev_e = e;
-        
+
         // integral term
         int_e = int_e + e;
-        
+
         float const maxInte = maximum / Ki;
-        
+
         if (clippingEnabled) {
             if (int_e > maxInte)
                 int_e = maxInte;
             if (int_e < -maxInte)
                 int_e = -maxInte;
         }
-    
+
         return (e * Kp + int_e * Ki + diff_e * Kd);
     }
 };
diff -r 6251c0169f4f -r fd5a62296b12 PowerAwareI2C.h
--- a/PowerAwareI2C.h	Wed May 27 11:45:00 2015 +0000
+++ b/PowerAwareI2C.h	Wed May 27 13:01:43 2015 +0000
@@ -9,16 +9,14 @@
 {
 public:
     PowerAwareI2C(PinName sda, PinName scl) : I2C(sda, scl) {}
-    
+
     /// Power on the I2C peripheral
-    void powerOn()
-    {
+    void powerOn() {
         _i2c.i2c->ENABLE = (TWI_ENABLE_ENABLE_Enabled << TWI_ENABLE_ENABLE_Pos);
     }
-    
-    /// Power off the I2C peripheral     
-    void powerOff()
-    {
+
+    /// Power off the I2C peripheral
+    void powerOff() {
         _i2c.i2c->ENABLE = TWI_ENABLE_ENABLE_Disabled << TWI_ENABLE_ENABLE_Pos;
         _i2c.i2c->POWER  = 0;
     }
diff -r 6251c0169f4f -r fd5a62296b12 QuaternionMath.lib
--- a/QuaternionMath.lib	Wed May 27 11:45:00 2015 +0000
+++ b/QuaternionMath.lib	Wed May 27 13:01:43 2015 +0000
@@ -1,1 +1,1 @@
-http://developer.mbed.org/teams/TobyRich-GmbH/code/QuaternionMath/#7fc3fba01e2f
+http://developer.mbed.org/teams/TobyRich-GmbH/code/QuaternionMath/#69f240dbf0df
diff -r 6251c0169f4f -r fd5a62296b12 Sensor.h
--- a/Sensor.h	Wed May 27 11:45:00 2015 +0000
+++ b/Sensor.h	Wed May 27 13:01:43 2015 +0000
@@ -30,7 +30,7 @@
     virtual void stop() = 0; ///< Stop capturing data.
 
     virtual Vector3 read() = 0; ///< Read and return instantaneous (current) sensor data. No need to start the sensor.
-    
+
     Sensor() : delegate(&defaultDelegate) {}
 
 protected:
diff -r 6251c0169f4f -r fd5a62296b12 SensorFusion.cpp
--- a/SensorFusion.cpp	Wed May 27 11:45:00 2015 +0000
+++ b/SensorFusion.cpp	Wed May 27 13:01:43 2015 +0000
@@ -23,14 +23,14 @@
     lowpassX.reset();
     lowpassY.reset();
     lowpassZ.reset();
-    
+
     accel.powerOn();
     accel.start();
-        
+
     // Since everything is synced to gyro interrupt, start it last
     gyro.powerOn();
     gyro.start();
-    
+
     return true;
 }
 
@@ -38,7 +38,7 @@
 {
     gyro.stop();
     gyro.powerOff();
-    
+
     accel.stop();
     accel.powerOff();
 }
@@ -46,7 +46,7 @@
 static float const deg_to_radian =  0.0174532925f;
 
 void SensorFusion6::sensorUpdate(Vector3 gyro_degrees)
-{   
+{
     Vector3 const gyro_reading = gyro_degrees * deg_to_radian;
     Vector3 const accel_reading = accel.read();
     Vector3 const filtered_accel = Vector3( lowpassX.filter(accel_reading.x),
@@ -54,15 +54,15 @@
                                             lowpassZ.filter(accel_reading.z));
 
     updateFilter( filtered_accel.x,  filtered_accel.y,  filtered_accel.z,
-                    gyro_reading.x,    gyro_reading.y,    gyro_reading.z);
-                    
+                  gyro_reading.x,    gyro_reading.y,    gyro_reading.z);
+
     delegate->sensorTick(deltat, q.getEulerAngles(), filtered_accel, accel_reading, gyro_degrees, q);
 }
 
 void SensorFusion6::updateFilter(float ax, float ay, float az, float gx, float gy, float gz)
 {
     float q0 = q.w, q1 = q.v.x, q2 = q.v.y, q3 = q.v.z;   // short name local variable for readability
-    
+
     float recipNorm;
     float s0, s1, s2, s3;
     float qDot1, qDot2, qDot3, qDot4;
@@ -81,7 +81,7 @@
         recipNorm = 1.0 / sqrt(ax * ax + ay * ay + az * az);
         ax *= recipNorm;
         ay *= recipNorm;
-        az *= recipNorm;   
+        az *= recipNorm;
 
         // Auxiliary variables to avoid repeated arithmetic
         _2q0 = 2.0 * q0;
@@ -128,7 +128,7 @@
     q1 *= recipNorm;
     q2 *= recipNorm;
     q3 *= recipNorm;
-    
+
     // return
     q.w = q0;
     q.v.x = q1;
@@ -145,7 +145,7 @@
 {
     magneto.powerOn();
     magneto.start();
-    
+
     return SensorFusion6::start();
 }
 
@@ -161,15 +161,15 @@
     Vector3 const gyro_reading = gyro_degrees * deg_to_radian;
     Vector3 const accel_reading = accel.read();
     Vector3 const magneto_reading = magneto.read();
-    
+
     Vector3 const filtered_accel = Vector3( lowpassX.filter(accel_reading.x),
                                             lowpassY.filter(accel_reading.y),
                                             lowpassZ.filter(accel_reading.z));
 
     updateFilter( filtered_accel.x,  filtered_accel.y,  filtered_accel.z,
-                    gyro_reading.x,    gyro_reading.y,    gyro_reading.z,
-                 magneto_reading.x, magneto_reading.y, magneto_reading.z);
-                    
+                  gyro_reading.x,    gyro_reading.y,    gyro_reading.z,
+                  magneto_reading.x, magneto_reading.y, magneto_reading.z);
+
     delegate->sensorTick(deltat, q.getEulerAngles(), filtered_accel, magneto_reading, gyro_degrees, q);
 }
 
diff -r 6251c0169f4f -r fd5a62296b12 SensorFusion.h
--- a/SensorFusion.h	Wed May 27 11:45:00 2015 +0000
+++ b/SensorFusion.h	Wed May 27 13:01:43 2015 +0000
@@ -16,10 +16,14 @@
     public:
         virtual void sensorTick(float dt, Vector3 fused, Vector3 accel, Vector3 magneto, Vector3 gyro, Quaternion q) {}
     };
-    
-    void setDelegate(Delegate &d) { delegate = &d; }
 
-    virtual bool start() { return false; }
+    void setDelegate(Delegate &d) {
+        delegate = &d;
+    }
+
+    virtual bool start() {
+        return false;
+    }
     virtual void stop() {}
 
 protected:
@@ -37,16 +41,16 @@
     virtual void sensorUpdate(Vector3 gyro_degrees);
     virtual bool start();
     virtual void stop();
-    
+
 protected:
     Accelerometer   accel;
     Gyroscope       gyro;
     float const     deltat, beta;
-    
+
     LowPassFilter   lowpassX;
     LowPassFilter   lowpassY;
     LowPassFilter   lowpassZ;
-    
+
     void updateFilter(float ax, float ay, float az, float gx, float gy, float gz);
 };
 
@@ -57,7 +61,7 @@
     virtual void sensorUpdate(Vector3 gyro_degrees);
     virtual bool start();
     virtual void stop();
-    
+
 protected:
     Magnetometer    magneto;
     void updateFilter(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz);
diff -r 6251c0169f4f -r fd5a62296b12 Utils.h
--- a/Utils.h	Wed May 27 11:45:00 2015 +0000
+++ b/Utils.h	Wed May 27 13:01:43 2015 +0000
@@ -6,44 +6,39 @@
 class utils
 {
 public:
-    static float clip(float const minimum, float const val, float const maximum)
-    {
+    static float clip(float const minimum, float const val, float const maximum) {
         return (val < minimum) ? minimum : ((val > maximum) ? maximum : val);
     }
-    
-    static void debugPortSend(uint8_t const* src, size_t const size)
-    {
-    #if defined(DATA_OUTPUT)
+
+    static void debugPortSend(uint8_t const* src, size_t const size) {
+#if defined(DATA_OUTPUT)
         putc(0x10, stdout); // marker
         for (int i = 0; i < size; i++) {
             putc(src[i] & 0x0f, stdout);
             putc(src[i]   >> 4, stdout);
         }
-    #endif
+#endif
     }
 
     static void sendVectorOverUART( const Vector3 a = Vector3(0, 0, 0),
                                     const Vector3 b = Vector3(0, 0, 0),
                                     const Vector3 c = Vector3(0, 0, 0),
-                                    const Vector3 d = Vector3(0, 0, 0))
-    {
+                                    const Vector3 d = Vector3(0, 0, 0)) {
         float data[] = {
             a.x, a.y, a.z,
             b.x, b.y, b.z,
             c.x, c.y, c.z,
             d.x, d.y, d.z
         };
-        
+
         debugPortSend((const uint8_t*) data, sizeof data);
     }
-    
-    static float deg2rad(float const d)
-    {
+
+    static float deg2rad(float const d) {
         return d * 0.0174532925f;
     }
-    
-    static float rad2deg(float const r)
-    {
+
+    static float rad2deg(float const r) {
         return r * 57.2957795131f;
     }
 };