CSSE4011_BLE_IMU IMU Seeed Tiny Ble

Dependencies:   BLE_API_Tiny_BLE MPU6050-DMP-Seeed-Tiny-BLE mbed

Revision:
0:f90c3452d779
Child:
1:3723e08bf4fd
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Wed Jun 10 09:46:16 2015 +0000
@@ -0,0 +1,557 @@
+
+#include "mbed.h"
+
+
+#include "MPU6050_6Axis_MotionApps20.h"
+
+
+
+#include "tiny_ble.h"
+//#include "kalman.h"
+
+
+#include "BLEDevice.h"
+#include "MPUService.h"
+//#include "UARTService.h"
+#include "HeartRateService.h"
+#include "DeviceInformationService.h"
+
+
+/* Starting sampling rate. */
+
+#define LOG(...)    { pc.printf(__VA_ARGS__); }
+
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
+// is used in I2Cdev.h
+//#include "Wire.h"
+
+// I2Cdev and MPU6050 must be installed as libraries, or else the .cpp/.h files
+// for both classes must be in the include path of your project
+#include "MPU6050_6Axis_MotionApps20.h"
+#include "mbed_i2c.h"
+
+//#include "MPU6050.h" // not necessary if using MotionApps include file
+
+// class default I2C address is 0x68
+// specific I2C addresses may be passed as a parameter here
+// AD0 low = 0x68 (default for SparkFun breakout and InvenSense evaluation board)
+// AD0 high = 0x69
+
+
+/* =========================================================================
+   NOTE: In addition to connection 3.3v, GND, SDA, and SCL, this sketch
+   depends on the MPU-6050's INT pin being connected to the Arduino's
+   external interrupt #0 pin. On the Arduino Uno and Mega 2560, this is
+   digital I/O pin 2.
+ * ========================================================================= */
+
+/* =========================================================================
+   NOTE: Arduino v1.0.1 with the Leonardo board generates a compile error
+   when using Serial.write(buf, len). The Teapot output uses this method.
+   The solution requires a modification to the Arduino USBAPI.h file, which
+   is fortunately simple, but annoying. This will be fixed in the next IDE
+   release. For more info, see these links:
+
+   http://arduino.cc/forum/index.php/topic,109987.0.html
+   http://code.google.com/p/arduino/issues/detail?id=958
+ * ========================================================================= */
+
+
+
+// uncomment "OUTPUT_READABLE_QUATERNION" if you want to see the actual
+// quaternion components in a [w, x, y, z] format (not best for parsing
+// on a remote host such as Processing or something though)
+#define OUTPUT_READABLE_QUATERNION
+
+// uncomment "OUTPUT_READABLE_EULER" if you want to see Euler angles
+// (in degrees) calculated from the quaternions coming from the FIFO.
+// Note that Euler angles suffer from gimbal lock (for more info, see
+// http://en.wikipedia.org/wiki/Gimbal_lock)
+#define OUTPUT_READABLE_EULER
+
+// uncomment "OUTPUT_READABLE_YAWPITCHROLL" if you want to see the yaw/
+// pitch/roll angles (in degrees) calculated from the quaternions coming
+// from the FIFO. Note this also requires gravity vector calculations.
+// Also note that yaw/pitch/roll angles suffer from gimbal lock (for
+// more info, see: http://en.wikipedia.org/wiki/Gimbal_lock)
+#define OUTPUT_READABLE_YAWPITCHROLL
+
+// uncomment "OUTPUT_READABLE_REALACCEL" if you want to see acceleration
+// components with gravity removed. This acceleration reference frame is
+// not compensated for orientation, so +X is always +X according to the
+// sensor, just without the effects of gravity. If you want acceleration
+// compensated for orientation, us OUTPUT_READABLE_WORLDACCEL instead.
+#define OUTPUT_READABLE_REALACCEL
+
+// uncomment "OUTPUT_READABLE_WORLDACCEL" if you want to see acceleration
+// components with gravity removed and adjusted for the world frame of
+// reference (yaw is relative to initial orientation, since no magnetometer
+// is present in this case). Could be quite handy in some cases.
+#define OUTPUT_READABLE_WORLDACCEL
+
+// uncomment "OUTPUT_TEAPOT" if you want output that matches the
+// format used for the InvenSense teapot demo
+//#define OUTPUT_TEAPOT
+
+
+// uncomment "OUTPUT_READABLE_ACCEL" if you want output that matches the
+// format used for the InvenSense teapot demo
+//#define OUTPUT_READABLE_ACCEL
+
+// uncomment "OUTPUT_READABLE_ACCEL" if you want output that matches the
+// format used for the InvenSense teapot demo
+//#define OUTPUT_READABLE_ACCEL
+
+/*
+* ====================================================================================================================================
+
+
+* =====================================================================================================================================
+*/
+
+DigitalOut blue(LED_BLUE);
+DigitalOut green(LED_GREEN);
+DigitalOut red(LED_RED);
+
+InterruptIn button(BUTTON_PIN);
+AnalogIn    battery(BATTERY_PIN);
+Serial pc(USBTX, USBRX);
+//Serial pc(UART_TX, UART_RX);
+
+/*
+* ====================================================================================================================================
+
+
+* =====================================================================================================================================
+*/
+const static char     DEVICE_NAME[]        = "CSSE BLE";
+static const uint16_t uuid16_list[]        = {GattService::UUID_HEART_RATE_SERVICE,
+        GattService::UUID_DEVICE_INFORMATION_SERVICE
+                                             };
+volatile bool bleIsConnected = false;
+BLEDevice  ble;
+//UARTService *uartServicePtr;
+MPUService *mpuServicePtr;
+static volatile bool  triggerSensorPolling = false;
+/*
+* ====================================================================================================================================
+
+
+* =====================================================================================================================================
+*/
+
+
+MPU6050 mpu(MPU6050_SDA, MPU6050_SCL);
+void check_i2c_bus(void);
+void mpuInitialSetup();
+void mpuData();
+// MPU control/status vars
+bool dmpReady = false;  // set true if DMP init was successful
+uint8_t mpuIntStatus;   // holds actual interrupt status byte from MPU
+uint8_t devStatus;      // return status after each device operation (0 = success, !0 = error)
+uint16_t packetSize;    // expected DMP packet size (default is 42 bytes)
+uint16_t fifoCount;     // count of all bytes currently in FIFO
+uint8_t fifoBuffer[64]; // FIFO storage buffer
+
+// orientation/motion vars
+Quaternion q;           // [w, x, y, z]         quaternion container
+VectorInt16 aa;         // [x, y, z]            accel sensor measurements
+VectorInt16 aaReal;     // [x, y, z]            gravity-free accel sensor measurements
+VectorInt16 aaWorld;    // [x, y, z]            world-frame accel sensor measurements
+VectorFloat gravity;    // [x, y, z]            gravity vector
+float euler[3]={0};         // [psi, theta, phi]    Euler angle container
+float ypr[3]={0};           // [yaw, pitch, roll]   yaw/pitch/roll container and gravity vector
+
+// packet structure for InvenSense teapot demo
+uint8_t teapotPacket[14] = { '$', 0x02, 0,0, 0,0, 0,0, 0,0, 0x00, 0x00, '\r', '\n' };
+
+InterruptIn checkpin(p14);
+
+volatile bool mpuInterrupt = false;     // indicates whether MPU interrupt pin has gone high
+void dmpDataReady()
+{
+    mpuInterrupt = true;
+}
+
+//kalman_data pitch_data;
+//kalman_data roll_data;
+
+/*
+* ====================================================================================================================================
+
+
+* =====================================================================================================================================
+*/
+void connectionCallback(Gap::Handle_t handle, Gap::addr_type_t peerAddrType, const Gap::address_t peerAddr, const Gap::ConnectionParams_t *params)
+{
+    LOG("Connected!\n");
+    bleIsConnected = true;
+}
+
+void disconnectionCallback(Gap::Handle_t handle, Gap::DisconnectionReason_t reason)
+{
+    LOG("Disconnected!\n");
+    LOG("Restarting the advertising process\n");
+    ble.startAdvertising();
+    bleIsConnected = false;
+}
+
+void tick(void)
+{
+    if(dmpReady)
+    {
+    green = !green;
+    }
+    else{
+    red  = !red;
+    }
+    triggerSensorPolling = true;
+}
+
+void detect(void)
+{
+    LOG("Button pressed\n");
+    blue = !blue;
+}
+
+void tap_cb(unsigned char direction, unsigned char count)
+{
+    LOG("Tap motion detected\n");
+}
+
+void android_orient_cb(unsigned char orientation)
+{
+    LOG("Oriention changed\n");
+}
+
+
+int main(void)
+{
+    blue  = 1;
+    green = 1;
+    red   = 1;
+
+    pc.baud(115200);
+
+    LOG("---- Seeed Tiny BLE ----\n");
+
+    Ticker ticker;
+    ticker.attach(tick, 0.5);
+
+    button.fall(detect);
+
+    LOG("Initialising the nRF51822\n");
+
+
+    /*
+    * ====================================================================================================================================
+
+
+    * =====================================================================================================================================
+    */
+    ble.init();
+    ble.onDisconnection(disconnectionCallback);
+    ble.onConnection(connectionCallback);
+
+
+
+    /* setup advertising */
+    ble.accumulateAdvertisingPayload(GapAdvertisingData::BREDR_NOT_SUPPORTED| GapAdvertisingData::LE_GENERAL_DISCOVERABLE);
+
+    ble.accumulateAdvertisingPayload(GapAdvertisingData::COMPLETE_LOCAL_NAME, (uint8_t *)DEVICE_NAME, sizeof(DEVICE_NAME));
+
+    ble.accumulateAdvertisingPayload(GapAdvertisingData::GENERIC_REMOTE_CONTROL);
+
+    ble.accumulateAdvertisingPayload(GapAdvertisingData::COMPLETE_LIST_16BIT_SERVICE_IDS,
+                                     (uint8_t *)uuid16_list, sizeof(uuid16_list));
+
+    //ble.accumulateAdvertisingPayload(GapAdvertisingData::COMPLETE_LIST_128BIT_SERVICE_IDS,(const uint8_t *)UARTServiceUUID_reversed, sizeof(UARTServiceUUID_reversed));
+    ble.accumulateAdvertisingPayload(GapAdvertisingData::COMPLETE_LIST_16BIT_SERVICE_IDS,
+                                     (const uint8_t *)MPUServiceUUID, sizeof(MPUServiceUUID));
+
+    ble.setAdvertisingType(GapAdvertisingParams::ADV_CONNECTABLE_UNDIRECTED);
+
+    // UARTService uartService(ble);
+    // uartServicePtr = &uartService;
+
+    MPUService mpuServices(ble,ypr);
+
+    /* Setup primary service. */
+    uint8_t hrmCounter = 50; // init HRM to 100bps
+    HeartRateService hrService(ble, hrmCounter, HeartRateService::LOCATION_FINGER);
+
+    /* Setup auxiliary service. */
+    DeviceInformationService deviceInfo(ble, "Seeed", "Tniy BLE", "SN1", "hw-rev1", "fw-rev1", "soft-rev1");
+
+
+    ble.setAdvertisingInterval(50); /* 100ms; in multiples of 0.625ms. */
+    ble.startAdvertising();
+
+
+
+    /*
+    * ====================================================================================================================================
+
+
+    * =====================================================================================================================================
+    */
+    check_i2c_bus();
+    mpuInitialSetup();
+
+
+    while (true) {
+        if(dmpReady && (mpuInterrupt || fifoCount >= packetSize)) {
+            mpuData();
+            mpuServices.updateYawPitchRoll(ypr);
+
+        }
+        if (triggerSensorPolling) {
+            triggerSensorPolling = false;
+
+            // Do blocking calls or whatever is necessary for sensor polling.
+            // In our case, we simply update the HRM measurement.
+            hrmCounter++;
+
+            //  100 <= HRM bps <=175
+            if (hrmCounter == 175) {
+                hrmCounter = 50;
+
+            }
+
+            // update bps
+            hrService.updateHeartRate(hrmCounter);
+
+
+        } else {
+            ble.waitForEvent();
+        }
+    }
+}
+
+// ================================================================
+// ===                      INITIAL SETUP                       ===
+// ================================================================
+
+void mpuInitialSetup()
+{
+    // NOTE: 8MHz or slower host processors, like the Teensy @ 3.3v or Ardunio
+    // Pro Mini running at 3.3v, cannot handle this baud rate reliably due to
+    // the baud timing being too misaligned with processor ticks. You must use
+    // 38400 or slower in these cases, or use some kind of external separate
+    // crystal solution for the UART timer.
+
+    // initialize device
+    pc.printf("Initializing I2C devices...\r\n");
+    mpu.initialize();
+
+    // verify connection
+    pc.printf("Testing device connections...\r\n");
+    if (mpu.testConnection()) pc.printf("MPU6050 connection successful\r\n");
+    else pc.printf("MPU6050 connection failed\r\n");
+
+    // wait for ready
+    //Serial.println(F("\nSend any character to begin DMP programming and demo: "));
+    //while (Serial.available() && Serial.read()); // empty buffer
+    //while (!Serial.available());                 // wait for data
+    //while (Serial.available() && Serial.read()); // empty buffer again
+
+    // load and configure the DMP
+    pc.printf("Initializing DMP...\r\n");
+    devStatus = mpu.dmpInitialize();
+
+    // make sure it worked (returns 0 if so)
+    if (devStatus == 0) {
+        // turn on the DMP, now that it's ready
+        pc.printf("Enabling DMP...\r\n");
+        mpu.setDMPEnabled(true);
+
+        // enable Arduino interrupt detection
+        pc.printf("Enabling interrupt detection (Arduino external interrupt 0)...\r\n");
+        checkpin.rise(&dmpDataReady);
+
+        mpuIntStatus = mpu.getIntStatus();
+
+        // set our DMP Ready flag so the main loop() function knows it's okay to use it
+        pc.printf("DMP ready! Waiting for first interrupt...\r\n");
+        dmpReady = true;
+
+        // get expected DMP packet size for later comparison
+        packetSize = mpu.dmpGetFIFOPacketSize();
+        red = 1;
+    } else {
+        // ERROR!
+        // 1 = initial memory load failed
+        // 2 = DMP configuration updates failed
+        // (if it's going to break, usually the code will be 1)
+
+        pc.printf("DDMP Initialization failed (code ");
+        pc.printf("%d", devStatus);
+        pc.printf(")\r\n");
+    }
+
+}
+
+// ================================================================
+// ===                      MPU6050 DATA                        ===
+// ================================================================
+
+void mpuData()
+{
+    // reset interrupt flag and get INT_STATUS byte
+    mpuInterrupt = false;
+    mpuIntStatus = mpu.getIntStatus();
+
+    // get current FIFO count
+    fifoCount = mpu.getFIFOCount();
+
+    // check for overflow (this should never happen unless our code is too inefficient)
+    if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
+        // reset so we can continue cleanly
+        mpu.resetFIFO();
+        //Serial.println(F("FIFO overflow!"));
+
+        // otherwise, check for DMP data ready interrupt (this should happen frequently)
+    } else if (mpuIntStatus & 0x02) {
+        // wait for correct available data length, should be a VERY short wait
+        while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
+
+        // read a packet from FIFO
+        mpu.getFIFOBytes(fifoBuffer, packetSize);
+
+        // track FIFO count here in case there is > 1 packet available
+        // (this lets us immediately read more without waiting for an interrupt)
+        fifoCount -= packetSize;
+
+#ifdef OUTPUT_READABLE_QUATERNION
+        // display quaternion values in easy matrix form: w x y z
+        mpu.dmpGetQuaternion(&q, fifoBuffer);
+        pc.printf("quat\t");
+        pc.printf("%f\t", q.w);
+        pc.printf("%f\t", q.x);
+        pc.printf("%f\t", q.y);
+        pc.printf("%f\t\r\n", q.z);
+#endif
+
+#ifdef OUTPUT_READABLE_EULER
+        // display Euler angles in degrees
+        mpu.dmpGetQuaternion(&q, fifoBuffer);
+        mpu.dmpGetEuler(euler, &q);
+        pc.printf("euler\t");
+        pc.printf("%f\t", euler[0] * 180/M_PI);
+        pc.printf("%f\t", euler[1] * 180/M_PI);
+        pc.printf("%f\t\r\n", euler[2] * 180/M_PI);
+#endif
+
+#ifdef OUTPUT_READABLE_YAWPITCHROLL
+        // display Euler angles in degrees
+        mpu.dmpGetQuaternion(&q, fifoBuffer);
+        mpu.dmpGetGravity(&gravity, &q);
+        mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
+        pc.printf("ypr\t");
+        pc.printf("%f\t", ypr[0] * 180/M_PI);
+        pc.printf("%f\t", ypr[1] * 180/M_PI);
+        pc.printf("%f\t\r\n", ypr[2] * 180/M_PI);
+#endif
+
+#ifdef OUTPUT_READABLE_REALACCEL
+        // display real acceleration, adjusted to remove gravity
+        mpu.dmpGetQuaternion(&q, fifoBuffer);
+        mpu.dmpGetAccel(&aa, fifoBuffer);
+        mpu.dmpGetGravity(&gravity, &q);
+        mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);
+        pc.printf("areal\t");
+        pc.printf("%f\t", aaReal.x);
+        pc.printf("%f\t", aaReal.y);
+        pc.printf("%f\t\r\n", aaReal.z);
+#endif
+
+#ifdef OUTPUT_READABLE_WORLDACCEL
+        // display initial world-frame acceleration, adjusted to remove gravity
+        // and rotated based on known orientation from quaternion
+        mpu.dmpGetQuaternion(&q, fifoBuffer);
+        mpu.dmpGetAccel(&aa, fifoBuffer);
+        mpu.dmpGetGravity(&gravity, &q);
+        mpu.dmpGetLinearAccelInWorld(&aaWorld, &aaReal, &q);
+        pc.printf("aworld\t");
+        pc.printf("%f\t", aaWorld.x);
+        pc.printf("%f\t", aaWorld.y);
+        pc.printf("%f\t\r\n", aaWorld.z);
+#endif
+
+#ifdef OUTPUT_TEAPOT
+        // display quaternion values in InvenSense Teapot demo format:
+        teapotPacket[2] = fifoBuffer[0];
+        teapotPacket[3] = fifoBuffer[1];
+        teapotPacket[4] = fifoBuffer[4];
+        teapotPacket[5] = fifoBuffer[5];
+        teapotPacket[6] = fifoBuffer[8];
+        teapotPacket[7] = fifoBuffer[9];
+        teapotPacket[8] = fifoBuffer[12];
+        teapotPacket[9] = fifoBuffer[13];
+        for (int i = 0; i < 14; ++i) {
+            pc.putc(teapotPacket[i]);
+        }
+        teapotPacket[11]++; // packetCount, loops at 0xFF on purpose
+#endif
+
+    }
+}
+
+void check_i2c_bus(void)
+{
+
+    DigitalInOut scl(MPU6050_SCL);
+    DigitalInOut sda(MPU6050_SDA);
+
+    scl.input();
+    sda.input();
+    int scl_level = scl;
+    int sda_level = sda;
+    if (scl_level == 0 || sda_level == 0) {
+        printf("scl: %d, sda: %d, i2c bus is not released\r\n", scl_level, sda_level);
+
+        scl.output();
+        for (int i = 0; i < 8; i++) {
+            scl = 0;
+            wait_us(10);
+            scl = 1;
+            wait_us(10);
+        }
+    } else {
+        printf("scl: %d, sda: %d, i2c bus is released\r\n", scl_level, sda_level);
+    }
+    scl.input();
+    scl_level = scl;
+    sda_level = sda;
+    if (scl_level == 0 || sda_level == 0) {
+        printf("scl: %d, sda: %d, i2c bus is still not released\r\n", scl_level, sda_level);
+    } else {
+        printf("scl: %d, sda: %d, i2c bus is released\r\n", scl_level, sda_level);
+    }
+
+}