Mangue Baja team's code to frontal ECU

Files at this revision

API Documentation at this revision

Comitter:
einsteingustavo
Date:
Wed Jul 24 20:03:52 2019 +0000
Commit message:
Mangue Baja team's code to frontal ECU

Changed in this revision

.gitignore Show annotated file Show diff for this revision Revisions of this file
BAJADefs/definitions.h Show annotated file Show diff for this revision Revisions of this file
CANMsg/CANMsg.h Show annotated file Show diff for this revision Revisions of this file
Kalman/Kalman.cpp Show annotated file Show diff for this revision Revisions of this file
Kalman/Kalman.h Show annotated file Show diff for this revision Revisions of this file
LSM6DS3/LSM6DS3.cpp Show annotated file Show diff for this revision Revisions of this file
LSM6DS3/LSM6DS3.h Show annotated file Show diff for this revision Revisions of this file
Other_things/CONTRIBUTING.md Show annotated file Show diff for this revision Revisions of this file
Other_things/README.md Show annotated file Show diff for this revision Revisions of this file
Other_things/mbed_app.json Show annotated file Show diff for this revision Revisions of this file
Other_things/stats_report.h Show annotated file Show diff for this revision Revisions of this file
frontdefs.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
mbed-os.lib Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/.gitignore	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,4 @@
+.build
+.mbed
+projectfiles
+*.py*
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/BAJADefs/definitions.h	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,48 @@
+#ifndef DEFINITIONS_H
+#define DEFINITIONS_H
+
+#ifndef MBED_H
+    #include "mbed.h"
+    #define MBED_H
+#endif
+
+#define CAN_IER         (*((volatile unsigned long *)0x40006414))
+
+#define BUFFER_SIZE     50
+#define THROTTLE_MID    0x00
+#define THROTTLE_RUN    0x01
+#define THROTTLE_CHOKE  0x02
+
+#define SYNC_ID         0x001       // message for bus sync
+#define THROTTLE_ID     0x100       // 1by = throttle state (0x00, 0x01 or 0x02)
+#define FLAGS_ID        0x101       // 1by
+#define IMU_ACC_ID      0x200       // 8by = accelerometer data (3D) + timestamp
+#define IMU_DPS_ID      0x201       // 8by = gyroscope data (3D) + timestamp 
+#define SPEED_ID        0x300       // 4by = speed + timestamp
+#define RPM_ID          0x304       // 4by = rpm + timestamp
+#define TEMPERATURE_ID  0x400       // 4by = engine temp. + cvt temp. + timestamp
+#define FUEL_ID         0x500       // 3by = fuel level + timestamp
+
+
+typedef struct
+{
+    int16_t acc_x;
+    int16_t acc_y;
+    int16_t acc_z;
+    int16_t dps_x;
+    int16_t dps_y;
+    int16_t dps_z;
+} imu_t;
+    
+typedef struct
+{  
+    imu_t imu[4];
+    uint16_t rpm;
+    uint16_t speed;
+    uint8_t temperature;
+    uint8_t flags;      // MSB - BOX | BUFFER FULL | NC | NC | FUEL_LEVEL | SERVO_ERROR | CHK | RUN - LSB
+    uint32_t timestamp;
+} packet_t;
+
+#endif
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/CANMsg/CANMsg.h	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,67 @@
+#ifndef CANMSG_H
+#define CANMSG_H
+
+/* CAN message container.
+ * Provides "<<" (append) and ">>" (extract) operators to simplyfy
+ * adding/getting data items to/from a CAN message.
+ * Usage is similar to the C++ io-stream operators.
+ * Data length of CAN message is automatically updated when using "<<" or ">>" operators.
+ *
+ * See Wiki page <https://developer.mbed.org/users/hudakz/code/CAN_Hello/> for demo.
+ */
+#include "CAN.h"
+
+class CANMsg : public CANMessage
+{
+public:
+    /** Creates empty CAN message.
+     */
+    CANMsg() :
+        CANMessage(){ }
+
+    /** Creates CAN message with specific content.
+     */
+    CANMsg(int _id, const char *_data, char _len = 8, CANType _type = CANData, CANFormat _format = CANStandard) :
+        CANMessage(_id, _data, _len, _type, _format){ }
+
+    /** Creates CAN remote message.
+     */
+    CANMsg(int _id, CANFormat _format = CANStandard) :
+        CANMessage(_id, _format){ }
+
+    /** Clears CAN message content
+     */
+    void clear(int new_id) {
+        len    = 0;
+        type   = CANData;
+        format = CANStandard;
+        id     = new_id;
+        memset(data, 0, 8);
+    };
+
+    /** Append operator: Appends data (value) to CAN message
+     */
+    template<class T>
+    CANMsg &operator<<(const T val) {
+        MBED_ASSERT(len + sizeof(T) <= 8);
+        //*reinterpret_cast<T*>(&data[len]) = val; // This used to work but now it hangs at run time.
+        memcpy(&data[len], &val, sizeof(T));
+        len += sizeof(T);
+        return *this;
+    }
+
+    /** Extract operator: Extracts data (value) from CAN message
+     */
+    template<class T>
+    CANMsg &operator>>(T& val) {
+        MBED_ASSERT(sizeof(T) <= len);
+        val = *reinterpret_cast<T*>(&data[0]);
+        len -= sizeof(T);
+        memcpy(data, data + sizeof(T), len);
+        return *this;
+    }
+};
+
+#endif // CANMSG_H
+
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Kalman/Kalman.cpp	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,94 @@
+/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
+
+ This software may be distributed and modified under the terms of the GNU
+ General Public License version 2 (GPL2) as published by the Free Software
+ Foundation and appearing in the file GPL2.TXT included in the packaging of
+ this file. Please note that GPL2 Section 2[b] requires that all works based
+ on this software must also be made publicly available under the terms of
+ the GPL2 ("Copyleft").
+
+ Contact information
+ -------------------
+
+ Kristian Lauszus, TKJ Electronics
+ Web      :  http://www.tkjelectronics.com
+ e-mail   :  kristianl@tkjelectronics.com
+ */
+
+#include "Kalman.h"
+
+Kalman::Kalman() {
+    /* We will set the variables like so, these can also be tuned by the user */
+    Q_angle = 0.001f;
+    Q_bias = 0.003f;
+    R_measure = 0.03f;
+
+    angle = 0.0f; // Reset the angle
+    bias = 0.0f; // Reset bias
+
+    P[0][0] = 0.0f; // Since we assume that the bias is 0 and we know the starting angle (use setAngle), the error covariance matrix is set like so - see: http://en.wikipedia.org/wiki/Kalman_filter#Example_application.2C_technical
+    P[0][1] = 0.0f;
+    P[1][0] = 0.0f;
+    P[1][1] = 0.0f;
+};
+
+// The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds
+float Kalman::getAngle(float newAngle, float newRate, float dt) {
+    // KasBot V2  -  Kalman filter module - http://www.x-firm.com/?page_id=145
+    // Modified by Kristian Lauszus
+    // See my blog post for more information: http://blog.tkjelectronics.dk/2012/09/a-practical-approach-to-kalman-filter-and-how-to-implement-it
+
+    // Discrete Kalman filter time update equations - Time Update ("Predict")
+    // Update xhat - Project the state ahead
+    /* Step 1 */
+    rate = newRate - bias;
+    angle += dt * rate;
+
+    // Update estimation error covariance - Project the error covariance ahead
+    /* Step 2 */
+    P[0][0] += dt * (dt*P[1][1] - P[0][1] - P[1][0] + Q_angle);
+    P[0][1] -= dt * P[1][1];
+    P[1][0] -= dt * P[1][1];
+    P[1][1] += Q_bias * dt;
+
+    // Discrete Kalman filter measurement update equations - Measurement Update ("Correct")
+    // Calculate Kalman gain - Compute the Kalman gain
+    /* Step 4 */
+    float S = P[0][0] + R_measure; // Estimate error
+    /* Step 5 */
+    float K[2]; // Kalman gain - This is a 2x1 vector
+    K[0] = P[0][0] / S;
+    K[1] = P[1][0] / S;
+
+    // Calculate angle and bias - Update estimate with measurement zk (newAngle)
+    /* Step 3 */
+    float y = newAngle - angle; // Angle difference
+    /* Step 6 */
+    angle += K[0] * y;
+    bias += K[1] * y;
+
+    // Calculate estimation error covariance - Update the error covariance
+    /* Step 7 */
+    float P00_temp = P[0][0];
+    float P01_temp = P[0][1];
+
+    P[0][0] -= K[0] * P00_temp;
+    P[0][1] -= K[0] * P01_temp;
+    P[1][0] -= K[1] * P00_temp;
+    P[1][1] -= K[1] * P01_temp;
+
+    return angle;
+}
+
+void Kalman::setAngle(float angle) { this->angle = angle; }; // Used to set angle, this should be set as the starting angle
+float Kalman::getRate() { return this->rate; }; // Return the unbiased rate
+
+/* These are used to tune the Kalman filter */
+void Kalman::setQangle(float Q_angle) { this->Q_angle = Q_angle; };
+void Kalman::setQbias(float Q_bias) { this->Q_bias = Q_bias; };
+void Kalman::setRmeasure(float R_measure) { this->R_measure = R_measure; };
+
+float Kalman::getQangle() { return this->Q_angle; };
+float Kalman::getQbias() { return this->Q_bias; };
+float Kalman::getRmeasure() { return this->R_measure; };
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Kalman/Kalman.h	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,60 @@
+/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
+
+ This software may be distributed and modified under the terms of the GNU
+ General Public License version 2 (GPL2) as published by the Free Software
+ Foundation and appearing in the file GPL2.TXT included in the packaging of
+ this file. Please note that GPL2 Section 2[b] requires that all works based
+ on this software must also be made publicly available under the terms of
+ the GPL2 ("Copyleft").
+
+ Contact information
+ -------------------
+
+ Kristian Lauszus, TKJ Electronics
+ Web      :  http://www.tkjelectronics.com
+ e-mail   :  kristianl@tkjelectronics.com
+ */
+
+#ifndef KALMAN_H
+#define KALMAN_H
+
+class Kalman {
+public:
+    Kalman();
+
+    // The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds
+    float getAngle(float newAngle, float newRate, float dt);
+
+    void setAngle(float angle); // Used to set angle, this should be set as the starting angle
+    float getRate(); // Return the unbiased rate
+
+    /* These are used to tune the Kalman filter */
+    void setQangle(float Q_angle);
+    /**
+     * setQbias(float Q_bias)
+     * Default value (0.003f) is in Kalman.cpp. 
+     * Raise this to follow input more closely,
+     * lower this to smooth result of kalman filter.
+     */
+    void setQbias(float Q_bias);
+    void setRmeasure(float R_measure);
+
+    float getQangle();
+    float getQbias();
+    float getRmeasure();
+
+private:
+    /* Kalman filter variables */
+    float Q_angle; // Process noise variance for the accelerometer
+    float Q_bias; // Process noise variance for the gyro bias
+    float R_measure; // Measurement noise variance - this is actually the variance of the measurement noise
+
+    float angle; // The angle calculated by the Kalman filter - part of the 2x1 state vector
+    float bias; // The gyro bias calculated by the Kalman filter - part of the 2x1 state vector
+    float rate; // Unbiased rate calculated from the rate and the calculated bias - you have to call getAngle to update the rate
+
+    float P[2][2]; // Error covariance matrix - This is a 2x2 matrix
+};
+
+#endif
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/LSM6DS3/LSM6DS3.cpp	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,418 @@
+#include "LSM6DS3.h"
+
+LSM6DS3::LSM6DS3(PinName sda, PinName scl, uint8_t xgAddr)
+{
+    _sda = sda;
+    _scl = scl;
+    
+    i2c = new I2C(_sda, _scl);
+    // xgAddress will store the 7-bit I2C address, if using i2c.
+    i2c->frequency(100000);
+    xgAddress = xgAddr;
+}
+
+uint16_t LSM6DS3::begin(gyro_scale gScl, accel_scale aScl,  
+                        gyro_odr gODR, accel_odr aODR)
+{
+    // 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;
+    
+    // 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
+    calcaRes(); // Calculate g / ADC tick, stored in aRes variable
+    
+    delete i2c;
+    
+    i2c = new I2C(_sda, _scl);
+    // xgAddress will store the 7-bit I2C address, if using i2c.
+    i2c->frequency(100000);
+    
+    // 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.
+    // The start of the addresses we want to read from
+    char cmd[2] = {
+        WHO_AM_I_REG,
+        0
+    };
+
+    // Write the address we are going to read from and don't end the transaction
+    bool nack = i2c->write(xgAddress, cmd, 1, true);
+    // Read in all the 8 bits of data
+    nack = nack ? 1 : i2c->read(xgAddress, cmd+1, 1);
+    uint8_t xgTest = cmd[1];                    // Read the accel/gyro WHO_AM_I
+        
+    // Gyro initialization stuff:
+    nack = nack ? 1 : initGyro(); // This will "turn on" the gyro. Setting up interrupts, etc.
+    nack = nack ? 1 : setGyroODR(gODR); // Set the gyro output data rate and bandwidth.
+    nack = nack ? 1 : setGyroScale(gScale); // Set the gyro range
+    
+    // Accelerometer initialization stuff:
+    nack = nack ? 1 : initAccel(); // "Turn on" all axes of the accel. Set up interrupts, etc.
+    nack = nack ? 1 : setAccelODR(aODR); // Set the accel data rate.
+    nack = nack ? 1 : setAccelScale(aScale); // Set the accel range.
+    
+    // Interrupt initialization stuff;
+    nack = nack ? 1 : initIntr();
+    
+    // Once everything is initialized, return the WHO_AM_I registers we read:
+    return xgTest;
+}
+
+bool LSM6DS3::initGyro()
+{
+    char cmd[4] = {
+        CTRL2_G,
+        gScale | G_ODR_104,
+        0,          // Default data out and int out
+        0           // Default power mode and high pass settings
+    };
+
+    // Write the data to the gyro control registers
+    bool nack = i2c->write(xgAddress, cmd, 4);
+    
+    return nack;
+}
+
+bool LSM6DS3::initAccel()
+{
+    char cmd[4] = {
+        CTRL1_XL,
+        0x38,       // Enable all axis and don't decimate data in out Registers
+        (A_ODR_104 << 5) | (aScale << 3) | (A_BW_AUTO_SCALE),   // 119 Hz ODR, set scale, and auto BW
+        0           // Default resolution mode and filtering settings
+    };
+
+    // Write the data to the accel control registers
+    bool nack = i2c->write(xgAddress, cmd, 4);
+    
+    return nack;
+}
+
+bool LSM6DS3::initIntr()
+{
+    char cmd[2];
+    
+    cmd[0] = TAP_CFG;
+    cmd[1] = 0x0E;
+    bool nack = i2c->write(xgAddress, cmd, 2);
+    cmd[0] = TAP_THS_6D;
+    cmd[1] = 0x03;
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 2);
+    cmd[0] = INT_DUR2;
+    cmd[1] = 0x7F;
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 2);
+    cmd[0] = WAKE_UP_THS;
+    cmd[1] = 0x80;
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 2);
+    cmd[0] = MD1_CFG;
+    cmd[1] = 0x48;
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 2);
+    
+    return nack;
+}
+
+bool LSM6DS3::readAccel()
+{
+    // The data we are going to read from the accel
+    char data[6];
+
+    // Set addresses
+    char subAddressXL = OUTX_L_XL;
+    char subAddressXH = OUTX_H_XL;
+    char subAddressYL = OUTY_L_XL;
+    char subAddressYH = OUTY_H_XL;
+    char subAddressZL = OUTZ_L_XL;
+    char subAddressZH = OUTZ_H_XL;
+
+    // Write the address we are going to read from and don't end the transaction
+    bool nack = i2c->write(xgAddress, &subAddressXL, 1, true);
+    // Read in register containing the axes data and alocated to the correct index
+    nack = nack ? 1 : i2c->read(xgAddress, data, 1);
+    
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressXH, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 1), 1);
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressYL, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 2), 1);
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressYH, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 3), 1);
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressZL, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 4), 1);
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressZH, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 5), 1);
+
+    // Reassemble the data and convert to g
+    ax_raw = data[0] | (data[1] << 8);
+    ay_raw = data[2] | (data[3] << 8);
+    az_raw = data[4] | (data[5] << 8);
+//    ax = ax_raw * aRes;
+//    ay = ay_raw * aRes;
+//    az = az_raw * aRes;
+
+    return nack;
+}
+
+bool LSM6DS3::readIntr()
+{
+    char data[1];
+    char subAddress = TAP_SRC;
+
+    bool nack = i2c->write(xgAddress, &subAddress, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, data, 1);
+
+    intr = (float)data[0];
+    
+    return nack;
+}
+
+bool LSM6DS3::readTemp()
+{
+    // The data we are going to read from the temp
+    char data[2];
+
+    // Set addresses
+    char subAddressL = OUT_TEMP_L;
+    char subAddressH = OUT_TEMP_H;
+
+    // Write the address we are going to read from and don't end the transaction
+    bool nack = i2c->write(xgAddress, &subAddressL, 1, true);
+    // Read in register containing the temperature data and alocated to the correct index
+    nack = nack ? 1 : i2c->read(xgAddress, data, 1);
+    
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressH, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 1), 1);
+
+    // Temperature is a 12-bit signed integer   
+    temperature_raw = data[0] | (data[1] << 8);
+
+    temperature_c = (float)temperature_raw / 16.0 + 25.0;
+    temperature_f = temperature_c * 1.8 + 32.0;
+    
+    return nack;
+}
+
+
+bool LSM6DS3::readGyro()
+{
+    // The data we are going to read from the gyro
+    char data[6];
+
+    // Set addresses
+    char subAddressXL = OUTX_L_G;
+    char subAddressXH = OUTX_H_G;
+    char subAddressYL = OUTY_L_G;
+    char subAddressYH = OUTY_H_G;
+    char subAddressZL = OUTZ_L_G;
+    char subAddressZH = OUTZ_H_G;
+
+    // Write the address we are going to read from and don't end the transaction
+    bool nack = i2c->write(xgAddress, &subAddressXL, 1, true);
+    // Read in register containing the axes data and alocated to the correct index
+    nack = nack ? 1 : i2c->read(xgAddress, data, 1);
+    
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressXH, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 1), 1);
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressYL, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 2), 1);
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressYH, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 3), 1);
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressZL, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 4), 1);
+    nack = nack ? 1 : i2c->write(xgAddress, &subAddressZH, 1, true);
+    nack = nack ? 1 : i2c->read(xgAddress, (data + 5), 1);
+
+    // Reassemble the data and convert to degrees/sec
+    gx_raw = data[0] | (data[1] << 8);
+    gy_raw = data[2] | (data[3] << 8);
+    gz_raw = data[4] | (data[5] << 8);
+//    gx = gx_raw * gRes;
+//    gy = gy_raw * gRes;
+//    gz = gz_raw * gRes;
+
+    return nack;
+}
+
+bool LSM6DS3::setGyroScale(gyro_scale gScl)
+{
+    // The start of the addresses we want to read from
+    char cmd[2] = {
+        CTRL2_G,
+        0
+    };
+
+    // Write the address we are going to read from and don't end the transaction
+    bool nack = i2c->write(xgAddress, cmd, 1, true);
+    // Read in all the 8 bits of data
+    nack = nack ? 1 : i2c->read(xgAddress, cmd+1, 1);
+
+    // Then mask out the gyro scale bits:
+    cmd[1] &= 0xFF^(0x3 << 3);
+    // Then shift in our new scale bits:
+    cmd[1] |= gScl << 3;
+
+    // Write the gyroscale out to the gyro
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 2);
+    
+    // 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();
+    
+    return nack;
+}
+
+bool LSM6DS3::setAccelScale(accel_scale aScl)
+{
+    // The start of the addresses we want to read from
+    char cmd[2] = {
+        CTRL1_XL,
+        0
+    };
+
+    // Write the address we are going to read from and don't end the transaction
+    bool nack = i2c->write(xgAddress, cmd, 1, true);
+    // Read in all the 8 bits of data
+    nack = nack ? 1 : i2c->read(xgAddress, cmd+1, 1);
+
+    // Then mask out the accel scale bits:
+    cmd[1] &= 0xFF^(0x3 << 3);
+    // Then shift in our new scale bits:
+    cmd[1] |= aScl << 3;
+
+    // Write the accelscale out to the accel
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 2);
+    
+    // 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();
+    
+    return nack;
+}
+
+bool LSM6DS3::setGyroODR(gyro_odr gRate)
+{
+    bool nack = 0;
+    // The start of the addresses we want to read from
+    char cmd[2] = {
+        CTRL2_G,
+        0
+    };
+    
+    // Set low power based on ODR, else keep sensor on high performance
+    if(gRate == G_ODR_13_BW_0 | gRate == G_ODR_26_BW_2 | gRate == G_ODR_52_BW_16) {
+        char cmdLow[2] ={
+            CTRL7_G,
+            1
+        };
+        
+        nack = i2c->write(xgAddress, cmdLow, 2);
+    }
+    else {
+        char cmdLow[2] ={
+            CTRL7_G,
+            0
+        };
+        
+        nack = i2c->write(xgAddress, cmdLow, 2);
+    }
+
+    // Write the address we are going to read from and don't end the transaction
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 1, true);
+    // Read in all the 8 bits of data
+    nack = nack ? 1 : i2c->read(xgAddress, cmd+1, 1);
+
+    // Then mask out the gyro odr bits:
+    cmd[1] &= (0x3 << 3);
+    // Then shift in our new odr bits:
+    cmd[1] |= gRate;
+
+    // Write the gyroodr out to the gyro
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 2);
+}
+
+bool LSM6DS3::setAccelODR(accel_odr aRate)
+{
+    bool nack = 0;
+    // The start of the addresses we want to read from
+    char cmd[2] = {
+        CTRL1_XL,
+        0
+    };
+    
+    // Set low power based on ODR, else keep sensor on high performance
+    if(aRate == A_ODR_13 | aRate == A_ODR_26 | aRate == A_ODR_52) {
+        char cmdLow[2] ={
+            CTRL6_C,
+            1
+        };
+        
+        nack = i2c->write(xgAddress, cmdLow, 2);
+    }
+    else {
+        char cmdLow[2] ={
+            CTRL6_C,
+            0
+        };
+        
+        nack = i2c->write(xgAddress, cmdLow, 2);
+    }
+
+    // Write the address we are going to read from and don't end the transaction
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 1, true);
+    // Read in all the 8 bits of data
+    nack = nack ? 1 : i2c->read(xgAddress, cmd+1, 1);
+
+    // Then mask out the accel odr bits:
+    cmd[1] &= 0xFF^(0x7 << 5);
+    // Then shift in our new odr bits:
+    cmd[1] |= aRate << 5;
+
+    // Write the accelodr out to the accel
+    nack = nack ? 1 : i2c->write(xgAddress, cmd, 2);
+    
+    return nack;
+}
+
+void LSM6DS3::calcgRes()
+{
+    // Possible gyro scales (and their register bit settings) are:
+    // 245 DPS (00), 500 DPS (01), 2000 DPS (10).
+    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 LSM6DS3::calcaRes()
+{
+    // Possible accelerometer scales (and their register bit settings) are:
+    // 2 g (000), 4g (001), 6g (010) 8g (011), 16g (100).
+    switch (aScale)
+    {
+        case A_SCALE_2G:
+            aRes = 2.0 / 32768.0;
+            break;
+        case A_SCALE_4G:
+            aRes = 4.0 / 32768.0;
+            break;
+        case A_SCALE_8G:
+            aRes = 8.0 / 32768.0;
+            break;
+        case A_SCALE_16G:
+            aRes = 16.0 / 32768.0;
+            break;
+    }
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/LSM6DS3/LSM6DS3.h	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,307 @@
+// Based on Eugene Gonzalez's version of LSM9DS1_Demo
+// Modified by Sherry Yang for LSM6DS3 sensor
+#ifndef LSM6DS3_H
+#define LSM6DS3_H
+
+#include "mbed.h"
+
+/////////////////////////////////////////
+// LSM6DS3 Accel/Gyro (XL/G) Registers //
+/////////////////////////////////////////
+#define RAM_ACCESS            0x01
+#define SENSOR_SYNC_TIME      0x04
+#define SENSOR_SYNC_EN        0x05
+#define FIFO_CTRL1            0x06
+#define FIFO_CTRL2            0x07
+#define FIFO_CTRL3            0x08
+#define FIFO_CTRL4            0x09
+#define FIFO_CTRL5            0x0A
+#define ORIENT_CFG_G          0x0B
+#define REFERENCE_G           0x0C
+#define INT1_CTRL             0x0D
+#define INT2_CTRL             0x0E
+#define WHO_AM_I_REG          0X0F
+#define CTRL1_XL              0x10
+#define CTRL2_G               0x11
+#define CTRL3_C               0x12
+#define CTRL4_C               0x13
+#define CTRL5_C               0x14
+#define CTRL6_C               0x15
+#define CTRL7_G               0x16
+#define CTRL8_XL              0x17
+#define CTRL9_XL              0x18
+#define CTRL10_C              0x19
+#define MASTER_CONFIG         0x1A
+#define WAKE_UP_SRC           0x1B
+#define TAP_SRC               0x1C
+#define D6D_SRC               0x1D
+#define STATUS_REG            0x1E
+#define OUT_TEMP_L            0x20
+#define OUT_TEMP_H            0x21
+#define OUTX_L_G              0x22
+#define OUTX_H_G              0x23
+#define OUTY_L_G              0x24
+#define OUTY_H_G              0x25
+#define OUTZ_L_G              0x26
+#define OUTZ_H_G              0x27
+#define OUTX_L_XL             0x28
+#define OUTX_H_XL             0x29
+#define OUTY_L_XL             0x2A
+#define OUTY_H_XL             0x2B
+#define OUTZ_L_XL             0x2C
+#define OUTZ_H_XL             0x2D
+#define SENSORHUB1_REG        0x2E
+#define SENSORHUB2_REG        0x2F
+#define SENSORHUB3_REG        0x30
+#define SENSORHUB4_REG        0x31
+#define SENSORHUB5_REG        0x32
+#define SENSORHUB6_REG        0x33
+#define SENSORHUB7_REG        0x34
+#define SENSORHUB8_REG        0x35
+#define SENSORHUB9_REG        0x36
+#define SENSORHUB10_REG       0x37
+#define SENSORHUB11_REG       0x38
+#define SENSORHUB12_REG       0x39
+#define FIFO_STATUS1          0x3A
+#define FIFO_STATUS2          0x3B
+#define FIFO_STATUS3          0x3C
+#define FIFO_STATUS4          0x3D
+#define FIFO_DATA_OUT_L       0x3E
+#define FIFO_DATA_OUT_H       0x3F
+#define TIMESTAMP0_REG        0x40
+#define TIMESTAMP1_REG        0x41
+#define TIMESTAMP2_REG        0x42
+#define STEP_COUNTER_L        0x4B
+#define STEP_COUNTER_H        0x4C
+#define FUNC_SR               0x53
+#define TAP_CFG               0x58
+#define TAP_THS_6D            0x59
+#define INT_DUR2              0x5A
+#define WAKE_UP_THS           0x5B
+#define WAKE_UP_DUR           0x5C
+#define FREE_FALL             0x5D
+#define MD1_CFG               0x5E
+#define MD2_CFG               0x5F
+
+// Possible I2C addresses for the accel/gyro
+#define LSM6DS3_AG_I2C_ADDR(sa0) ((sa0) ? 0xD6 : 0xD4)
+
+/**
+ * LSM6DS3 Class - driver for the 9 DoF IMU
+ */
+class LSM6DS3
+{
+public:
+
+    /// gyro_scale defines the possible full-scale ranges of the gyroscope:
+    enum gyro_scale
+    {
+        G_SCALE_245DPS = 0x0 << 3,     // 00 << 3: +/- 245 degrees per second
+        G_SCALE_500DPS = 0x1 << 3,     // 01 << 3: +/- 500 dps
+        G_SCALE_1000DPS = 0x2 << 3,    // 10 << 3: +/- 1000 dps
+        G_SCALE_2000DPS = 0x3 << 3     // 11 << 3: +/- 2000 dps
+    };
+
+    /// gyro_odr defines all possible data rate/bandwidth combos of the gyro:
+    enum gyro_odr
+    {                               // ODR (Hz) --- Cutoff
+        G_POWER_DOWN     = 0x00,    //  0           0
+        G_ODR_13_BW_0    = 0x10,    //  12.5        0.0081      low power
+        G_ODR_26_BW_2    = 0x20,    //  26          2.07        low power
+        G_ODR_52_BW_16   = 0x30,    //  52          16.32       low power
+        G_ODR_104        = 0x40,    //  104         
+        G_ODR_208        = 0x50,    //  208         
+        G_ODR_416        = 0x60,    //  416         
+        G_ODR_833        = 0x70,    //  833         
+        G_ODR_1660       = 0x80     //  1660
+    };
+
+    /// accel_scale defines all possible FSR's of the accelerometer:
+    enum accel_scale
+    {
+        A_SCALE_2G, // 00: +/- 2g
+        A_SCALE_16G,// 01: +/- 16g
+        A_SCALE_4G, // 10: +/- 4g
+        A_SCALE_8G  // 11: +/- 8g
+    };
+
+    /// accel_oder defines all possible output data rates of the accelerometer:
+    enum accel_odr
+    {
+        A_POWER_DOWN,   // Power-down mode (0x0)
+        A_ODR_13,       // 12.5 Hz (0x1)        low power
+        A_ODR_26,       // 26 Hz (0x2)          low power
+        A_ODR_52,       // 52 Hz (0x3)          low power
+        A_ODR_104,      // 104 Hz (0x4)         normal mode
+        A_ODR_208,      // 208 Hz (0x5)         normal mode
+        A_ODR_416,      // 416 Hz (0x6)         high performance
+        A_ODR_833,      // 833 Hz (0x7)         high performance
+        A_ODR_1660,     // 1.66 kHz (0x8)       high performance
+        A_ODR_3330,     // 3.33 kHz (0x9)       high performance
+        A_ODR_6660,     // 6.66 kHz (0xA)       high performance
+    };
+
+    // accel_bw defines all possible bandwiths for low-pass filter of the accelerometer:
+    enum accel_bw
+    {
+        A_BW_AUTO_SCALE = 0x0,  // Automatic BW scaling (0x0)
+        A_BW_408 = 0x4,         // 408 Hz (0x4)
+        A_BW_211 = 0x5,         // 211 Hz (0x5)
+        A_BW_105 = 0x6,         // 105 Hz (0x6)
+        A_BW_50 = 0x7           // 50 Hz (0x7)
+    };
+    
+    
+
+    // We'll store the gyro, and accel, readings in a series of
+    // public class variables. Each sensor gets three variables -- one for each
+    // axis. Call readGyro(), and readAccel() first, before using
+    // these variables!
+    // These values are the RAW signed 16-bit readings from the sensors.
+    int16_t gx_raw, gy_raw, gz_raw; // x, y, and z axis readings of the gyroscope
+    int16_t ax_raw, ay_raw, az_raw; // x, y, and z axis readings of the accelerometer
+    int16_t temperature_raw;
+
+    // floating-point values of scaled data in real-world units
+    float gx, gy, gz;
+    float ax, ay, az;
+    float temperature_c, temperature_f; // temperature in celcius and fahrenheit
+    float intr;
+
+    
+    /**  LSM6DS3 -- LSM6DS3 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.
+    *   - xgAddr = If MODE_I2C, this is the I2C address of the accel/gyro.
+    *               If MODE_SPI, this is the chip select pin of the accel/gyro (CS_A/G)
+    */
+    LSM6DS3(PinName sda, PinName scl, uint8_t xgAddr = LSM6DS3_AG_I2C_ADDR(1));
+    
+    /**  begin() -- Initialize the gyro, and accelerometer.
+    *  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.
+    *   - gODR = Output data rate of the gyroscope. gyro_odr value.
+    *   - aODR = Output data rate of the accelerometer. accel_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/gyro.
+    *  All parameters have a defaulted value, so you can call just "begin()".
+    *  Default values are FSR's of: +/- 245DPS, 4g, 2Gs; ODRs of 119 Hz for 
+    *  gyro, 119 Hz for accelerometer.
+    *  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, gyro_odr gODR = G_ODR_104, 
+                accel_odr aODR = A_ODR_104);
+    
+    /**  readGyro() -- Read the gyroscope output registers.
+    *  This function will read all six gyroscope output registers.
+    *  The readings are stored in the class' gx_raw, gy_raw, and gz_raw variables. Read
+    *  those _after_ calling readGyro().
+    */
+    bool readGyro();
+    
+    /**  readAccel() -- Read the accelerometer output registers.
+    *  This function will read all six accelerometer output registers.
+    *  The readings are stored in the class' ax_raw, ay_raw, and az_raw variables. Read
+    *  those _after_ calling readAccel().
+    */
+    bool readAccel();
+    
+    /**  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().
+    */
+    bool readTemp();
+    
+    /** Read Interrupt **/
+    bool readIntr();
+    
+    /**  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 2000 degrees per second.
+    *  Input:
+    *   - gScl = The desired gyroscope scale. Must be one of three possible
+    *       values from the gyro_scale enum.
+    */
+    bool 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, 8, or 16 g's.
+    *  Input:
+    *   - aScl = The desired accelerometer scale. Must be one of five possible
+    *       values from the accel_scale enum.
+    */
+    bool setAccelScale(accel_scale aScl);
+    
+    /**  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).
+    */
+    bool 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).
+    */
+    bool setAccelODR(accel_odr aRate);
+
+
+private:    
+    /**  xgAddress store the I2C address
+    *  for each sensor.
+    */
+    uint8_t xgAddress;
+    
+    // I2C bus
+    I2C *i2c;
+    PinName _sda;
+    PinName _scl;
+    /**  gScale, and aScale store the current scale range for each 
+    *  sensor. Should be updated whenever that value changes.
+    */
+    gyro_scale gScale;
+    accel_scale aScale;
+    
+    /**  gRes, and aRes 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;
+    
+    /**  initGyro() -- Sets up the gyroscope to begin reading.
+    *  This function steps through all three gyroscope control registers.
+    */
+    bool initGyro();
+    
+    /**  initAccel() -- Sets up the accelerometer to begin reading.
+    *  This function steps through all accelerometer related control registers.
+    */
+    bool initAccel();
+    
+    /** Setup Interrupt **/
+    bool initIntr();
+    
+    /**  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();
+    
+    /**  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();
+};
+
+#endif // _LSM6DS3_H //
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Other_things/CONTRIBUTING.md	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,5 @@
+# Contributing to Mbed OS
+
+Mbed OS is an open-source, device software platform for the Internet of Things. Contributions are an important part of the platform, and our goal is to make it as simple as possible to become a contributor.
+
+To encourage productive collaboration, as well as robust, consistent and maintainable code, we have a set of guidelines for [contributing to Mbed OS](https://os.mbed.com/docs/mbed-os/latest/contributing/index.html).
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Other_things/README.md	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,171 @@
+# Getting started example for Mbed OS
+
+This guide reviews the steps required to get Blinky with the addition of dynamic OS statistics working on an Mbed OS platform. (Note: To see a rendered example you can import into the Arm Online Compiler, please see our [quick start](https://os.mbed.com/docs/mbed-os/latest/quick-start/online-with-the-online-compiler.html#importing-the-code).)
+
+Please install [Mbed CLI](https://github.com/ARMmbed/mbed-cli#installing-mbed-cli).
+
+## Import the example application
+
+From the command-line, import the example:
+
+```
+mbed import mbed-os-example-blinky
+cd mbed-os-example-blinky
+```
+
+### Now compile
+
+Invoke `mbed compile`, and specify the name of your platform and your favorite toolchain (`GCC_ARM`, `ARM`, `IAR`). For example, for the ARM Compiler 5:
+
+```
+mbed compile -m K64F -t ARM
+```
+
+Your PC may take a few minutes to compile your code. At the end, you see the following result:
+
+```
+[snip]
++----------------------------+-------+-------+------+
+| Module             |     .text |    .data |     .bss |
+|--------------------|-----------|----------|----------|
+| [fill]             |    98(+0) |    0(+0) | 2211(+0) |
+| [lib]/c.a          | 27835(+0) | 2472(+0) |   89(+0) |
+| [lib]/gcc.a        |  3168(+0) |    0(+0) |    0(+0) |
+| [lib]/misc         |   248(+0) |    8(+0) |   28(+0) |
+| [lib]/nosys.a      |    32(+0) |    0(+0) |    0(+0) |
+| main.o             |   924(+0) |    0(+0) |   12(+0) |
+| mbed-os/components |   134(+0) |    0(+0) |    0(+0) |
+| mbed-os/drivers    |    56(+0) |    0(+0) |    0(+0) |
+| mbed-os/features   |    42(+0) |    0(+0) |  184(+0) |
+| mbed-os/hal        |  2087(+0) |    8(+0) |  152(+0) |
+| mbed-os/platform   |  3633(+0) |  260(+0) |  209(+0) |
+| mbed-os/rtos       |  9370(+0) |  168(+0) | 6053(+0) |
+| mbed-os/targets    |  9536(+0) |   12(+0) |  382(+0) |
+| Subtotals          | 57163(+0) | 2928(+0) | 9320(+0) |
+Total Static RAM memory (data + bss): 12248(+0) bytes
+Total Flash memory (text + data): 60091(+0) bytes
+
+Image: ./BUILD/K64F/GCC_ARM/mbed-os-example-blinky.bin
+```
+
+### Program your board
+
+1. Connect your Mbed device to the computer over USB.
+1. Copy the binary file to the Mbed device.
+1. Press the reset button to start the program.
+
+The LED on your platform turns on and off. The main thread will additionally take a snapshot of the device's runtime statistics and display it over serial to your PC. The snapshot includes:
+
+* System Information:
+    * Mbed OS Version: Will currently default to 999999
+    * Compiler ID
+        * ARM = 1
+        * GCC_ARM = 2
+        * IAR = 3
+    * [CPUID Register Information](#cpuid-register-information)
+    * [Compiler Version](#compiler-version)
+* CPU Statistics
+    * Percentage of runtime that the device has spent awake versus in sleep
+* Heap Statistics
+    * Current heap size
+    * Max heap size which refers to the largest the heap has grown to
+* Thread Statistics
+    * Provides information on all running threads in the OS including
+        * Thread ID
+        * Thread Name
+        * Thread State
+        * Thread Priority
+        * Thread Stack Size
+        * Thread Stack Space
+
+#### Compiler Version
+
+| Compiler | Version Layout |
+| -------- | -------------- |
+| ARM      | PVVbbbb (P = Major; VV = Minor; bbbb = build number) |
+| GCC      | VVRRPP  (VV = Version; RR = Revision; PP = Patch)    |
+| IAR      | VRRRPPP (V = Version; RRR = Revision; PPP = Patch)   |
+
+#### CPUID Register Information
+
+| Bit Field | Field Description | Values |
+| --------- | ----------------- | ------ |
+|[31:24]    | Implementer       | 0x41 = ARM |
+|[23:20]    | Variant           | Major revision 0x0  =  Revision 0 |
+|[19:16]    | Architecture      | 0xC  = Baseline Architecture |
+|           |                   | 0xF  = Constant (Mainline Architecture) |
+|[15:4]     | Part Number       | 0xC20 =  Cortex-M0 |
+|           |                   | 0xC60 = Cortex-M0+ |
+|           |                   | 0xC23 = Cortex-M3  |
+|           |                   | 0xC24 = Cortex-M4  |
+|           |                   | 0xC27 = Cortex-M7  |
+|           |                   | 0xD20 = Cortex-M23 |
+|           |                   | 0xD21 = Cortex-M33 |
+|[3:0]      | Revision          | Minor revision: 0x1 = Patch 1 |
+
+
+
+You can view individual examples and additional API information of the statistics collection tools at the bottom of the page in the [related links section](#related-links).
+
+
+### Output
+
+To view the serial output you can use any terminal client of your choosing such as [PuTTY](http://www.putty.org/) or [CoolTerm](http://freeware.the-meiers.org/). Unless otherwise specified, printf defaults to a baud rate of 9600 on Mbed OS.
+
+You can find more information on the Mbed OS configuration tools and serial communication in Mbed OS in the related [related links section](#related-links).
+
+The output should contain the following block transmitted at the blinking LED frequency (actual values may vary depending on your target, build profile, and toolchain):
+
+```
+=============================== SYSTEM INFO  ================================
+Mbed OS Version: 999999
+CPU ID: 0x410fc241
+Compiler ID: 2
+Compiler Version: 60300
+RAM0: Start 0x20000000 Size: 0x30000
+RAM1: Start 0x1fff0000 Size: 0x10000
+ROM0: Start 0x0 Size: 0x100000
+================= CPU STATS =================
+Idle: 98% Usage: 2%
+================ HEAP STATS =================
+Current heap: 1096
+Max heap size: 1096
+================ THREAD STATS ===============
+ID: 0x20001eac
+Name: main_thread
+State: 2
+Priority: 24
+Stack Size: 4096
+Stack Space: 3296
+
+ID: 0x20000f5c
+Name: idle_thread
+State: 1
+Priority: 1
+Stack Size: 512
+Stack Space: 352
+
+ID: 0x20000f18
+Name: timer_thread
+State: 3
+Priority: 40
+Stack Size: 768
+Stack Space: 664
+
+```
+
+## Troubleshooting
+
+If you have problems, you can review the [documentation](https://os.mbed.com/docs/latest/tutorials/debugging.html) for suggestions on what could be wrong and how to fix it.
+
+## Related Links
+
+* [Mbed OS Stats API](https://os.mbed.com/docs/latest/apis/mbed-statistics.html)
+* [Mbed OS Configuration](https://os.mbed.com/docs/latest/reference/configuration.html)
+* [Mbed OS Serial Communication](https://os.mbed.com/docs/latest/tutorials/serial-communication.html)
+
+### License and contributions
+
+The software is provided under Apache-2.0 license. Contributions to this project are accepted under the same license. Please see contributing.md for more info.
+
+This project contains code from other projects. The original license text is included in those source files. They must comply with our license guide.
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Other_things/mbed_app.json	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,11 @@
+{
+    "target_overrides": {
+        "*": {
+            "platform.stack-stats-enabled": true,
+            "platform.heap-stats-enabled": true,
+            "platform.cpu-stats-enabled": true,
+            "platform.thread-stats-enabled": true,
+            "platform.sys-stats-enabled": true
+        }
+    }
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Other_things/stats_report.h	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,132 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2018 ARM Limited
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#ifndef STATS_REPORT_H
+#define STATS_REPORT
+
+#include "mbed.h"
+
+/**
+ *  System Reporting library. Provides runtime information on device:
+ *      - CPU sleep, idle, and wake times
+ *      - Heap and stack usage
+ *      - Thread information
+ *      - Static system information
+ */
+class SystemReport {
+    mbed_stats_heap_t   heap_stats;
+    mbed_stats_cpu_t    cpu_stats;
+    mbed_stats_sys_t    sys_stats;
+
+    mbed_stats_thread_t *thread_stats;
+    uint8_t   thread_count;
+    uint8_t   max_thread_count;
+    uint32_t  sample_time_ms;
+
+public:
+    /**
+     *  SystemReport - Sample rate in ms is required to handle the CPU percent awake logic
+     */
+    SystemReport(uint32_t sample_rate) : max_thread_count(8), sample_time_ms(sample_rate)
+    {
+        thread_stats = new mbed_stats_thread_t[max_thread_count];
+
+        // Collect the static system information
+        mbed_stats_sys_get(&sys_stats);
+
+        printf("=============================== SYSTEM INFO  ================================\r\n");
+        printf("Mbed OS Version: %ld \r\n", sys_stats.os_version);
+        printf("CPU ID: 0x%lx \r\n", sys_stats.cpu_id);
+        printf("Compiler ID: %d \r\n", sys_stats.compiler_id);
+        printf("Compiler Version: %ld \r\n", sys_stats.compiler_version);
+
+        for (int i = 0; i < MBED_MAX_MEM_REGIONS; i++) {
+            if (sys_stats.ram_size[i] != 0) {
+                printf("RAM%d: Start 0x%lx Size: 0x%lx \r\n", i, sys_stats.ram_start[i], sys_stats.ram_size[i]);
+            }
+        }
+        for (int i = 0; i < MBED_MAX_MEM_REGIONS; i++) {
+            if (sys_stats.rom_size[i] != 0) {
+                printf("ROM%d: Start 0x%lx Size: 0x%lx \r\n", i, sys_stats.rom_start[i], sys_stats.rom_size[i]);
+            }
+        }
+    }
+
+    ~SystemReport(void)
+    {
+        free(thread_stats);
+    }
+
+    /**
+     *  Report on each Mbed OS Platform stats API
+     */
+    void report_state(void)
+    {
+        report_cpu_stats();
+        report_heap_stats();
+        report_thread_stats();
+
+        // Clear next line to separate subsequent report logs
+        printf("\r\n");
+    }
+
+    /**
+     *  Report CPU idle and awake time in terms of percentage
+     */
+    void report_cpu_stats(void)
+    {
+        static uint64_t prev_idle_time = 0;
+
+        printf("================= CPU STATS =================\r\n");
+
+        // Collect and print cpu stats
+        mbed_stats_cpu_get(&cpu_stats);
+
+        uint64_t diff = (cpu_stats.idle_time - prev_idle_time);
+        uint8_t idle = (diff * 100) / (sample_time_ms * 1000);  // usec;
+        uint8_t usage = 100 - ((diff * 100) / (sample_time_ms * 1000));  // usec;;
+        prev_idle_time = cpu_stats.idle_time;
+
+        printf("Idle: %d%% Usage: %d%% \r\n", idle, usage);
+    }
+
+    /**
+     *  Report current heap stats. Current heap refers to the current amount of
+     *  allocated heap. Max heap refers to the highest amount of heap allocated
+     *  since reset.
+     */
+    void report_heap_stats(void)
+    {
+        printf("================ HEAP STATS =================\r\n");
+
+        // Collect and print heap stats
+        mbed_stats_heap_get(&heap_stats);
+
+        printf("Current heap: %lu\r\n", heap_stats.current_size);
+        printf("Max heap size: %lu\r\n", heap_stats.max_size);
+    }
+
+    /**
+     *  Report active thread stats
+     */
+    void report_thread_stats(void)
+    {
+        printf("================ THREAD STATS ===============\r\n");
+
+        // Collect and print running thread stats
+        int count = mbed_stats_thread_get_each(thread_stats, max_thread_count);
+
+        for (int i = 0; i < count; i++) {
+            printf("ID: 0x%lx \r\n",        thread_stats[i].id);
+            printf("Name: %s \r\n",         thread_stats[i].name);
+            printf("State: %ld \r\n",       thread_stats[i].state);
+            printf("Priority: %ld \r\n",    thread_stats[i].priority);
+            printf("Stack Size: %ld \r\n",  thread_stats[i].stack_size);
+            printf("Stack Space: %ld \r\n", thread_stats[i].stack_space);
+        }
+    }
+};
+
+#endif // STATS_REPORT_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/frontdefs.h	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,27 @@
+#ifndef FRONTDEFS_H
+#define FRONTDEFS_H
+
+/* Conversion definitions */
+#define WHEEL_DIAMETER      0.5842      // m
+#define PI                  3.1416
+#define RAD_TO_DEGREE       180.0/PI
+#define TO_G                2.0/32768.0
+#define TO_DPS              245.0/32768.0
+#define WHEEL_HOLES_NUMBER  24
+#define HORN_PERIOD         2
+#define DEBOUNCE_TIME       0.1         // s
+#define IMU_TRIES           10
+
+typedef enum
+{
+    IDLE_ST,        // wait
+    SLOWACQ_ST,     // acquire battery level data
+    IMU_ST,         // acquire accelerometer and gyroscope data
+    SPEED_ST,       // calculate speed
+    THROTTLE_ST,    // check throttle position (from user button)
+    DISPLAY_ST,     // send data for display over serial port
+    DEBUG_ST        // send data for debug
+} state_t;
+
+#endif
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,500 @@
+#include "mbed.h"
+#include "stats_report.h"
+/* User libraries */
+#include "definitions.h"
+#include "frontdefs.h"
+#include "CANMsg.h"
+#include "LSM6DS3.h"
+#include "Kalman.h"
+
+#define MB1
+//#define MB2
+
+/* Communication protocols */
+CAN can(PB_8, PB_9, 1000000);
+Serial serial(PA_2, PA_3, 115200);
+LSM6DS3 LSM6DS3(PB_7, PB_6);
+
+/* I/O pins */
+InterruptIn freq_sensor(PB_10, PullNone);
+InterruptIn choke_switch(PA_5, PullUp);     // servomotor CHOKE mode
+InterruptIn run_switch(PA_7, PullUp);       // servomotor RUN mode
+InterruptIn horn_button(PB_1, PullUp);
+InterruptIn headlight_switch(PB_0, PullUp);
+DigitalOut horn(PB_11);
+DigitalOut headlight(PA_1);
+/* Debug pins */
+DigitalOut led(PC_13);
+PwmOut signal(PA_6);
+DigitalOut dbg1(PC_14);
+DigitalOut dbg2(PC_15);
+DigitalOut dbg3(PA_4);
+
+/* Interrupt services routine */
+void canISR();
+void servoSwitchISR();
+void ticker2HzISR();
+void ticker5HzISR();
+void ticker20HzISR();
+void tickerTrottleISR();
+void frequencyCounterISR();
+void hornISR();
+void headlightISR();
+/* Interrupt handlers */
+void canHandler();
+void throttleDebounceHandler();
+void hornDebounceHandler();
+void headlightDebounceHandler();
+/* General functions*/
+void setupInterrupts();
+void filterMessage(CANMsg msg);
+void calcAngles(int16_t accx, int16_t accy, int16_t accz, int16_t grx, int16_t gry, int16_t grz, int16_t dt);
+void displayData(uint16_t vel, uint16_t Hz, uint16_t temp, bool comb, \
+                    bool b, bool tl, bool fl, int16_t gp, int16_t gr, bool box);
+
+/* Debug variables */
+Timer t;
+bool buffer_full = false;
+unsigned int t0, t1;
+/* Mbed OS tools */
+Thread eventThread;
+EventQueue queue(1024);
+Ticker ticker2Hz;
+Ticker ticker5Hz;
+Ticker ticker20Hz;
+Ticker tickerTrottle;
+Timeout debounce_throttle;
+Timeout debounce_horn;
+Timeout debounce_headlight;
+// Timeout horn_limiter;                       // stop sound of horn after a determined period
+CircularBuffer <state_t, BUFFER_SIZE> state_buffer;
+/* Global variables */
+bool switch_clicked = false;
+uint8_t switch_state = 0x00, flags = 0x00, pulse_counter = 0, temp_motor = 0;
+state_t current_state = IDLE_ST;
+uint64_t current_period = 0, last_count = 0, last_acq = 0;
+uint8_t imu_failed = 0;                         // number of times before a new connection attempt with imu 
+float speed_hz = 0;
+uint16_t rpm_hz = 0, speed_display = 0, speed_radio = 0, dt = 0;
+int16_t angle_roll = 0, angle_pitch = 0; 
+packet_t data;
+
+int main()
+{
+    /* Main variables */
+    CANMsg txMsg;
+    /* Initialization */
+    t.start();
+    horn = horn_button.read();                               // horn OFF
+    headlight = headlight_switch.read();                          // headlight OFF
+    led = 1;                                // led OFF
+    eventThread.start(callback(&queue, &EventQueue::dispatch_forever));
+    t0 = t.read_us();
+    uint16_t lsm_addr = LSM6DS3.begin(LSM6DS3.G_SCALE_245DPS, LSM6DS3.A_SCALE_2G, LSM6DS3.G_ODR_26_BW_2, LSM6DS3.A_ODR_26); 
+    t1 = t.read_us();
+//    serial.printf("%d\r\n", (t1 - t0));
+    setupInterrupts();          
+
+    while (true) {
+        if (state_buffer.full())
+        {
+            buffer_full = true;
+            led = 0;
+            state_buffer.pop(current_state);
+        }
+        else
+        {
+            led = 1;
+            buffer_full = false;
+            if (!state_buffer.empty())
+                state_buffer.pop(current_state);
+            else
+                current_state = IDLE_ST;
+        }
+        
+        switch (current_state)
+        {
+            case IDLE_ST:
+//                Thread::wait(2);
+                break;
+            case SLOWACQ_ST:
+                break;
+            case IMU_ST:
+                t0 = t.read_us();
+                dbg1 = !dbg1;
+                if (lsm_addr)
+                {
+                    bool nack = LSM6DS3.readAccel();                        // read accelerometer data into LSM6DS3.aN_raw
+                    if (!nack)
+                        nack = LSM6DS3.readGyro();                         //  "   gyroscope data into LSM6DS3.gN_raw
+                    
+                    if (nack)
+                    {
+                        lsm_addr = 0;
+                        LSM6DS3.ax_raw = 0;
+                        LSM6DS3.ay_raw = 0;
+                        LSM6DS3.az_raw = 0;
+                        LSM6DS3.gx_raw = 0;
+                        LSM6DS3.gy_raw = 0;
+                        LSM6DS3.gz_raw = 0;
+                    }
+                }
+                else if (imu_failed == IMU_TRIES)
+                {
+                    lsm_addr = LSM6DS3.begin(LSM6DS3.G_SCALE_245DPS, LSM6DS3.A_SCALE_2G, LSM6DS3.G_ODR_26_BW_2, LSM6DS3.A_ODR_26);                                    
+                    t1 = t.read_us();
+                    imu_failed = 0;
+//                    serial.printf("%d\r\n", (t1 - t0));
+                }
+                else
+                {
+                    imu_failed++;
+                }
+                
+                last_acq = t.read_ms();
+//                serial.printf("accz = %d\r\n", LSM6DS3.gz_raw);
+                calcAngles(LSM6DS3.ax_raw, LSM6DS3.ay_raw, LSM6DS3.az_raw, LSM6DS3.gx_raw, LSM6DS3.gy_raw, LSM6DS3.gz_raw, dt);
+                 /* Send accelerometer data */
+                txMsg.clear(IMU_ACC_ID);
+                txMsg << LSM6DS3.ax_raw << LSM6DS3.ay_raw << LSM6DS3.az_raw;
+                if(can.write(txMsg))
+                {
+                    /* Send gyroscope data only if accelerometer data succeeds */
+                    txMsg.clear(IMU_DPS_ID);
+                    txMsg << LSM6DS3.gx_raw << LSM6DS3.gy_raw << LSM6DS3.gz_raw << dt;
+                    can.write(txMsg);
+                }
+                break;
+            case SPEED_ST:
+//            serial.printf("speed ok\r\n");
+                dbg2 = !dbg2;
+                freq_sensor.fall(NULL);         // disable interrupt
+                if (current_period != 0)
+                {
+                    speed_hz = 1000000*((float)pulse_counter/current_period);    //calculates frequency in Hz
+                }
+                else
+                {
+                    speed_hz = 0;
+                }
+                speed_display = ((float)(PI*WHEEL_DIAMETER*speed_hz)/WHEEL_HOLES_NUMBER);    // make conversion hz to km/h
+                speed_radio = ((float)((speed_display)/60.0)*65535);
+                pulse_counter = 0;                          
+                current_period = 0;                         //|-> reset pulses related variables
+                last_count = t.read_us();        
+                freq_sensor.fall(&frequencyCounterISR);     // enable interrupt
+                /* Send speed data */
+                txMsg.clear(SPEED_ID);
+                txMsg << speed_radio;
+                can.write(txMsg);
+//                state_buffer.push(DEBUG_ST);                // debug
+                break;
+            case THROTTLE_ST:
+//                serial.printf("throttle ok\r\n");
+                dbg3 = !dbg3;
+                if (switch_clicked)
+                {                    
+                    switch_state = !choke_switch.read() << 1 | !run_switch.read() << 0;
+                    //serial.printf("switch_state = %d\r\n", switch_state);
+                    /* Send CAN message */
+                    txMsg.clear(THROTTLE_ID);
+                    txMsg << switch_state;
+//                    serial.printf("can ok\r/n");                  // append data (8 bytes max)
+                    can.write(txMsg);
+                    
+                    switch_clicked = false;
+                }
+                break;
+            case DISPLAY_ST:
+//                serial.printf("rpm_hz=%d\r\n", rpm_hz);
+                displayData(speed_display, rpm_hz, temp_motor, (flags & 0x08), false, true, false, angle_pitch, angle_roll, (flags & 0x80));
+//                state_buffer.push(DEBUG_ST);
+                break;
+            case DEBUG_ST:
+//                serial.printf("r= %d, p=%d\r\n", angle_roll, angle_pitch);
+//                serial.printf("imu acc x =%d\r\n", LSM6DS3.ax_raw);
+//                serial.printf("imu acc y =%d\r\n", LSM6DS3.ay_raw);
+//                serial.printf("imu acc z =%d\r\n", LSM6DS3.az_raw);
+//                serial.printf("imu dps x =%d\r\n", LSM6DS3.gx_raw);
+//                serial.printf("imu dps y =%d\r\n", LSM6DS3.gy_raw);
+//                serial.printf("imu dps z =%d\r\n", LSM6DS3.gz_raw);
+                break;
+            default:
+                break;
+        }
+    }
+}
+
+/* Interrupt services routine */
+void canISR()
+{
+    CAN_IER &= ~CAN_IER_FMPIE0;                 // disable RX interrupt
+    queue.call(&canHandler);                    // add canHandler() to events queue
+}
+
+void servoSwitchISR()
+{
+    choke_switch.rise(NULL);     //  throttle interrupt in both edges dettach
+    run_switch.rise(NULL);       //  throttle interrupt in both edges dettach
+    choke_switch.fall(NULL);     //  throttle interrupt in both edges dettach
+    run_switch.fall(NULL);       //  throttle interrupt in both edges dettach
+    switch_clicked = true;
+    debounce_throttle.attach(&throttleDebounceHandler, 0.1);
+}
+
+void ticker2HzISR()
+{
+    state_buffer.push(DISPLAY_ST);
+}
+
+void ticker5HzISR()
+{
+    state_buffer.push(SPEED_ST);
+    state_buffer.push(DISPLAY_ST);
+}
+
+void ticker20HzISR()
+{
+    state_buffer.push(IMU_ST);
+}
+
+void frequencyCounterISR()
+{
+    pulse_counter++;
+    current_period += t.read_us() - last_count;
+    last_count = t.read_us();        
+}
+
+//void hornISR()
+//{
+//    debounce_horn.attach(&hornDebounceHandler, DEBOUNCE_TIME);
+//}
+
+void headlightISR()
+{
+    debounce_headlight.attach(&headlightDebounceHandler, DEBOUNCE_TIME);
+}
+
+/* Interrupt handlers */
+void canHandler()
+{
+    CANMsg rxMsg;
+
+    can.read(rxMsg);
+    filterMessage(rxMsg);
+    CAN_IER |= CAN_IER_FMPIE0;                  // enable RX interrupt
+}
+
+void throttleDebounceHandler()
+{
+    state_buffer.push(THROTTLE_ST);
+    choke_switch.rise(&servoSwitchISR);     // trigger throttle interrupt in both edges
+    run_switch.rise(&servoSwitchISR);       // trigger throttle interrupt in both edges
+    choke_switch.fall(&servoSwitchISR);     // trigger throttle interrupt in both edges
+    run_switch.fall(&servoSwitchISR);       // trigger throttle interrupt in both edges
+}
+
+//void hornDebounceHandler()
+//{
+//    horn = horn_button.read();
+//}
+
+void headlightDebounceHandler()
+{
+    headlight = headlight_switch.read();
+}
+
+/* General functions */
+void setupInterrupts()
+{
+    can.attach(&canISR, CAN::RxIrq);
+    choke_switch.rise(&servoSwitchISR);     // trigger throttle interrupt in both edges
+    choke_switch.fall(&servoSwitchISR);     // trigger throttle interrupt in both edges
+    run_switch.rise(&servoSwitchISR);       // trigger throttle interrupt in both edges
+    run_switch.fall(&servoSwitchISR);       // trigger throttle interrupt in both edges
+//    horn_button.rise(&hornISR);
+//    horn_button.fall(&hornISR);
+    headlight_switch.rise(&headlightISR);
+    headlight_switch.fall(&headlightISR);
+//    ticker2Hz.attach(&ticker2HzISR, 0.4);
+    ticker5Hz.attach(&ticker5HzISR, 0.2);
+    ticker20Hz.attach(&ticker20HzISR, 0.05);
+    signal.period_ms(2);
+    signal.write(0.5f);
+}
+
+void filterMessage(CANMsg msg)
+{
+  //  serial.printf("id: %d\r\n", msg.id);
+
+    if(msg.id == RPM_ID)
+ {
+        msg >> rpm_hz;
+    }
+    
+    else if(msg.id == TEMPERATURE_ID)
+    {
+        msg >> temp_motor;
+    }
+    
+    else if (msg.id == FLAGS_ID)
+    {
+        msg >> flags;
+    }
+}
+
+/* Function adapted from Kristian Lauszus library example, source: https://github.com/TKJElectronics/KalmanFilter*/
+void calcAngles(int16_t accx, int16_t accy, int16_t accz, int16_t grx, int16_t gry, int16_t grz, int16_t dt){
+    static Kalman kalmanX, kalmanY;
+    float kalAngleX, kalAngleY;
+    float pitch, roll;
+    float gyroXrate, gyroYrate;
+    float ax, ay, az;
+    static bool first_execution = true;
+    
+    ax = (float) accx * TO_G;
+    ay = (float) accy * TO_G;
+    az = (float) accz * TO_G;
+    pitch = atan2(ay, az) * RAD_TO_DEGREE;
+    roll = atan(-ax / sqrt(ay * ay + az * az)) * RAD_TO_DEGREE;
+    gyroXrate = grx / TO_DPS;                            // Convert to deg/s
+    gyroYrate = gry / TO_DPS;                            // Convert to deg/s
+
+    if (first_execution)
+    {
+        // set starting angle if first execution
+        first_execution = false;
+        kalmanX.setAngle(roll);
+        kalmanY.setAngle(pitch);
+    }
+    // This fixes the transition problem when the accelerometer angle jumps between -180 and 180 degrees
+    if((roll < -90 && kalAngleX > 90) || (roll > 90 && kalAngleX < -90))
+    {
+        kalmanX.setAngle(roll);
+        kalAngleX = roll;
+    }
+    else
+    {
+        kalAngleX = kalmanX.getAngle(roll, gyroXrate, dt); // Calculate the angle using a Kalman filter
+    }
+
+    if(abs(kalAngleX) > 90)
+    {
+        gyroYrate = -gyroYrate; // Invert rate, so it fits the restriced accelerometer reading
+    }
+    kalAngleY = kalmanY.getAngle(pitch, gyroYrate, dt);
+
+    angle_roll = roll;
+    angle_pitch = pitch;
+}
+
+void displayData(uint16_t vel, uint16_t Hz, uint16_t temp, bool comb, \
+                    bool b, bool tl, bool fl, int16_t gp, int16_t gr, bool box)
+{
+    static uint16_t vel2 = -1, Hz2 = -1, temp2 = -1;
+    static int16_t gr2 = -1, gp2 = -1;
+    static bool box2 = false;
+    static bool comb2 = true, b2 = true, tl2 = false, fl2 = false;
+
+    char str[512];
+    int aux=0;
+    strcpy(str,"");
+    
+    if(box!=box2)
+        sprintf(str + strlen(str), "page1.box.val=%d%c%c%c",box,0xff,0xff,0xff);
+    if(vel!=vel2)
+        sprintf(str + strlen(str), "page1.v.val=%d%c%c%c",vel,0xff,0xff,0xff);
+    if(Hz!=Hz2)
+    {
+        int r = (Hz*6000)/(5000.0);
+        sprintf(str + strlen(str), "page1.r.val=%d%c%c%c",r,0xff,0xff,0xff);
+    }
+    if(comb!=comb2)
+    {
+        if (!comb)
+            sprintf(str + strlen(str),"page1.c.val=%d%c%c%c",25,0xff,0xff,0xff);
+        else
+            sprintf(str + strlen(str),"page1.c.val=%d%c%c%c",100,0xff,0xff,0xff);
+    }
+    if(temp!=temp2)
+    {
+        int tp = (100*temp)/120;
+        sprintf(str + strlen(str),"page1.tp.val=%d%c%c%c",tp,0xff,0xff,0xff);
+    }        
+    if(b!=b2)
+        sprintf(str + strlen(str),"page1.b.val=%d%c%c%c",b,0xff,0xff,0xff);
+    if(tl!=tl2)
+        sprintf(str + strlen(str),"page1.tl.val=%d%c%c%c",tl,0xff,0xff,0xff);
+    if(fl!=fl2)
+        sprintf(str + strlen(str),"page1.fl.val=%d%c%c%c",fl,0xff,0xff,0xff);
+    if(gp!=gp2)
+    {
+        int gpn = 7;
+        if(gp<=-35){gpn=0;}
+        else if(gp>=-30&&gp<-25){gpn=1;}
+        else if(gp>=-25&&gp<-20){gpn=2;}
+        else if(gp>=-20&&gp<-15){gpn=3;}
+        else if(gp>=-15&&gp<-10){gpn=4;}
+        else if(gp>=-10&&gp<-5){gpn=5;}
+        else if(gp>=-5&&gp<0){gpn=6;}
+        else if(gp==0){gpn=7;}
+        else if(gp>0&&gp<=5){gpn=8;}
+        else if(gp>5&&gp<=10){gpn=9;}
+        else if(gp>10&&gp<=15){gpn=10;}
+        else if(gp>15&&gp<=20){gpn=11;}
+        else if(gp>20&&gp<=25){gpn=12;}
+        else if(gp>25&&gp<=30){gpn=13;}
+        else if(gp>=35){gpn=14;}
+        #ifdef MB2
+            sprintf(str + strlen(str),"page3.gr.val=%d%c%c%c",gpn,0xff,0xff,0xff);
+            sprintf(str + strlen(str),"page3.gr_n.val=%d%c%c%c",gp*(-1),0xff,0xff,0xff);
+        #endif
+        #ifdef MB1
+            sprintf(str + strlen(str),"page2.gp.val=%d%c%c%c",gpn,0xff,0xff,0xff);
+            sprintf(str + strlen(str),"page2.gp_n.val=%d%c%c%c",gp,0xff,0xff,0xff);
+        #endif
+    }
+    if(gr!=gr2)
+    {
+        int grn = 7;
+        if(gr<=-35){grn=0;}
+        else if(gr>=-30&&gr<-25){grn=1;}
+        else if(gr>=-25&&gr<-20){grn=2;}
+        else if(gr>=-20&&gr<-15){grn=3;}
+        else if(gr>=-15&&gr<-10){grn=4;}
+        else if(gr>=-10&&gr<-5){grn=5;}
+        else if(gr>=-5&&gr<0){grn=6;}
+        else if(gr==0){grn=7;}
+        else if(gr>0&&gr<=5){grn=8;}
+        else if(gr>5&&gr<=10){grn=9;}
+        else if(gr>10&&gr<=15){grn=10;}
+        else if(gr>15&&gr<=20){grn=11;}
+        else if(gr>20&&gr<=25){grn=12;}
+        else if(gr>25&&gr<=30){grn=13;}
+        else if(gr>=35){grn=14;}
+        #ifdef MB2
+            sprintf(str + strlen(str),"page3.gp.val=%d%c%c%c",grn,0xff,0xff,0xff);
+            sprintf(str + strlen(str),"page3.gp_n.val=%d%c%c%c",gr,0xff,0xff,0xff);
+        #endif
+        #ifdef MB1
+            sprintf(str + strlen(str),"page2.gr.val=%d%c%c%c",grn,0xff,0xff,0xff);
+            sprintf(str + strlen(str),"page2.gr_n.val=%d%c%c%c",gr,0xff,0xff,0xff);
+        #endif
+    }
+    
+    while(str[aux]!='\0')
+    {
+        serial.putc(str[aux]);
+        aux++;
+    }
+    box2 = box;
+    vel2 = vel;
+    Hz2 = Hz;
+    temp2 = temp;
+    gr2=gr;
+    gp2=gp;
+    comb2 = comb;
+    b2=b;
+    tl2=tl;
+    fl2=fl;
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed-os.lib	Wed Jul 24 20:03:52 2019 +0000
@@ -0,0 +1,1 @@
+https://github.com/ARMmbed/mbed-os/#51d55508e8400b60af467005646c4e2164738d48