Code for our FYDP -only one IMU works right now -RTOS is working

Dependencies:   mbed

Files at this revision

API Documentation at this revision

Comitter:
majik
Date:
Wed Mar 18 22:23:48 2015 +0000
Commit message:
This is our FYDP code, but only one IMU works with the RTOS.

Changed in this revision

DMP/DMP.cpp Show annotated file Show diff for this revision Revisions of this file
DMP/DMP.h Show annotated file Show diff for this revision Revisions of this file
DMP/IMUDATA.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/machine_interface/keybindings.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/machine_interface/py_machine_interface.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/machine_interface/ros_machine_interface.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/shell/bt_shell.cpp Show annotated file Show diff for this revision Revisions of this file
bt_shell/shell/bt_shell.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/shell/calibrate_fnt.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/shell/motor_fnt.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/shell/recon_fnt.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/shell/remotecontrol_fnt.h Show annotated file Show diff for this revision Revisions of this file
bt_shell/shell/tinyshell/tinysh.c Show annotated file Show diff for this revision Revisions of this file
bt_shell/shell/tinyshell/tinysh.h Show annotated file Show diff for this revision Revisions of this file
drivers/ACS712/ACS712.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/ACS712/ACS712.h Show annotated file Show diff for this revision Revisions of this file
drivers/ADNS5090/ADNS5090.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/ADNS5090/ADNS5090.h Show annotated file Show diff for this revision Revisions of this file
drivers/HC05/HC05.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/HC05/HC05.h Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/I2C/I2Cdev.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/I2C/I2Cdev.h Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/I2C/I2Cdev2.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/I2C/I2Cdev2.h Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/MPU/inc/MPU6050.h Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/MPU/inc/MPU6050_6Axis_MotionApps20.h Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/MPU/inc/MPU6051.h Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/MPU/inc/MPU6051_6Axis_MotionApps20.h Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/MPU/src/MPU6050.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/MPU/src/MPU6050_6Axis_MotionApps20.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/MPU/src/MPU6051.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/MPU/src/MPU6051_6Axis_MotionApps20.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/MPU6050-DMP-Ian/Math/helper_3dmath.h Show annotated file Show diff for this revision Revisions of this file
drivers/RF_Network/RF_node.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/RF_Network/RF_node.h Show annotated file Show diff for this revision Revisions of this file
drivers/TB6612FNG2/TB6612.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/TB6612FNG2/TB6612.h Show annotated file Show diff for this revision Revisions of this file
drivers/nRF24L01P/nRF24L01P.cpp Show annotated file Show diff for this revision Revisions of this file
drivers/nRF24L01P/nRF24L01P.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/MODSERIAL/ChangeLog.c Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/AddingDevice.h Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_K64F.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_K64F.h Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_KL05Z.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_KL05Z.h Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_KL25Z.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_KL25Z.h Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_LPC11U24.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_LPC11U24.h Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_LPC1768.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/Device/MODSERIAL_LPC1768.h Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/FLUSH.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/GETC.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/INIT.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/ISR_RX.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/ISR_TX.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/MACROS.h Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/MODSERIAL.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/MODSERIAL.h Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/MODSERIAL_IRQ_INFO.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/PUTC.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/RESIZE.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/example1.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/example2.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/example3a.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/MODSERIAL/example3b.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/SWSPI/SWSPI.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/SWSPI/SWSPI.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/Mail.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/MemoryPool.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/Mutex.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/Mutex.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/Queue.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/RtosTimer.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/RtosTimer.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/Semaphore.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/Semaphore.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/Thread.cpp Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/Thread.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtos/rtos.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/HAL_CM.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/RTX_CM_lib.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/RTX_Conf.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/RTX_Conf_CM.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_ARM/HAL_CM0.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_ARM/SVC_Table.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_GCC/HAL_CM0.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_GCC/SVC_Table.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_ARM/HAL_CM0.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_ARM/SVC_Table.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_GCC/HAL_CM0.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_GCC/SVC_Table.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_ARM/HAL_CM3.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_ARM/SVC_Table.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_GCC/HAL_CM3.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_GCC/SVC_Table.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_ARM/HAL_CM4.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_ARM/SVC_Table.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_GCC/HAL_CM4.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_GCC/SVC_Table.s Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/cmsis_os.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/os_tcb.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_CMSIS.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Event.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Event.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_HAL_CM.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_List.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_List.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Mailbox.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Mailbox.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_MemBox.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_MemBox.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Mutex.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Mutex.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Robin.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Robin.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Semaphore.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Semaphore.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_System.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_System.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Task.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Task.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Time.c Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_Time.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed-rtos/rtx/rt_TypeDef.h Show annotated file Show diff for this revision Revisions of this file
mbed/mbed.bld Show annotated file Show diff for this revision Revisions of this file
motors/motors.cpp Show annotated file Show diff for this revision Revisions of this file
motors/motors.h Show annotated file Show diff for this revision Revisions of this file
reckon/reckon.cpp Show annotated file Show diff for this revision Revisions of this file
reckon/reckon.h Show annotated file Show diff for this revision Revisions of this file
robot/calibration/bot08_cal.h Show annotated file Show diff for this revision Revisions of this file
robot/calibration/bot32_cal.h Show annotated file Show diff for this revision Revisions of this file
robot/calibration/bot36_cal.h Show annotated file Show diff for this revision Revisions of this file
robot/robot.cpp Show annotated file Show diff for this revision Revisions of this file
robot/robot.h Show annotated file Show diff for this revision Revisions of this file
diff -r 000000000000 -r 964eb6a2ef00 DMP/DMP.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/DMP/DMP.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,366 @@
+//Copied MPU6050.h and MPU6050.cpp from another library (otherwise MPU gets stuck randomly)
+
+/*** THIS IS THE BEST VERSION OF DMP CODE
+    This code demonstrates how to access the MPU6050 IMU and fix the 
+    connection errors that occur, using a hardware hack.
+    It requires two hardware fixes: A transistor (PTE5) and an extra GPIO pin (PTE23) connected
+    to the SDA line.
+    Error 1: The SDA line gets stuck on ground.
+    Solution 1: Use the transistor to raise the SDA voltage off of ground. This resets the I2C bus. (line 71)
+    Error 2: The SDA line gets stuck on 3.3V
+    Solution 2: Use the GPIO line to pull the SDA voltage down a bit to reset the I2C bus. (line 96)
+    (I am currently trying to find a software solution for the above hack)
+    
+    This code works for using the DMP. (See "DMP" for implementation that can do raw accel data)
+    It appears all connection issues have been fixed.
+    Next step: make code neater (in progress)
+    
+    LEARNED: Do not need the PTE23 line. Only fix necessary is the transistor (PTE5)
+***/
+
+#include "mbed.h"
+#include "DMP.h"
+
+
+//******* MPU DECLARATION THINGS *****************//
+int dmp_test = 1;    //if this is 0, get raw MPU values
+                 //if this is 1, get DMP values
+
+int acc_offset[3];  //this saves the offset for acceleration
+ 
+int16_t ax, ay, az;
+int16_t gx, gy, gz;
+
+//******* DMP things ****************//
+// MPU control/status vars
+bool dmpReady = false;  // set true if DMP init was succesfful
+uint8_t mpuIntStatus;   // holds interrupt status byte from MPU
+uint8_t devStatus;      // return status after each device operation (0 = success)
+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
+bool dmpReady2 = false;  // set true if DMP init was succesfful
+uint8_t mpuIntStatus2;   // holds interrupt status byte from MPU
+uint8_t devStatus2;      // return status after each device operation (0 = success)
+uint16_t packetSize2;    // expected DMP packet size (default is 42 bytes)
+uint16_t fifoCount2;     // count of all bytes currently in FIFO
+uint8_t fifoBuffer2[64]; // FIFO storage buffer
+
+    
+    
+uint8_t MPU_CONNECTION;
+        
+// 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];         // [psi,theta,phi]  Euler angle container
+float ypr[3];           // [yaw,pitch,roll] yaw/pitch/roll container [rad]. Multiply by 180, divide by PI for [deg]
+InterruptIn checkpin(PTD7); //interrupt
+InterruptIn checkpin2(PTD5); //PTD5
+//*** Interrupt Detection Routine ***//
+volatile bool mpuInterrupt = false; //indicates whether interrupt pin has gone high
+void dmpDataReady(){
+    mpuInterrupt = true;
+}
+volatile bool mpuInterrupt2 = false; //indicates whether interrupt pin has gone high
+void dmpDataReady2(){
+    mpuInterrupt2 = true;
+}
+        
+//****** END MPU DECLARATION ********************//
+
+
+int test_dmp();    //this wraps up the code req'd to start the DMP
+void start_dmp(MPU6050);    //this will get the DMP ready
+void update_dmp();   //call this frequently
+
+//*********************FUNCTIONS***************************************************************//
+int test_dmp(){ //returns 1 if ok (right now, it doesn't return at all if there is a problem    
+    imuSwitch = 1;
+    LED_OFF;
+    Thread::wait(100);
+    
+    while(mpu.testConnection()==0)
+    {
+        imuSwitch = 0;
+        Thread::wait(100);
+        imuSwitch = 1;
+        Thread::wait(100);
+        bt.lock();
+        bt.printf("Stuck on IMU1");
+        bt.unlock();
+    }
+    imuSwitch = 1;
+    LED_ON  //turn ON LED
+    return 1;
+}
+int test_dmp2(){ //returns 1 if ok (right now, it doesn't return at all if there is a problem    
+    imu2Switch = 1;
+    LED_OFF;
+    Thread::wait(100);
+    
+    while(mpu2.testConnection()==0)
+    {
+        imu2Switch = 0;
+        Thread::wait(100);
+        imu2Switch = 1;
+        Thread::wait(100);
+        bt.lock();
+        bt.printf("Stuck on IMU2");
+        bt.unlock();
+    }
+    imu2Switch = 1;
+    LED_ON  //turn ON LED
+    return 1;
+}
+
+void start_dmp(MPU6050 mpu1){    //this will get the DMP ready
+    //initialize device
+    mpu1.reset();
+    DMP_DBG_MSG("\n\rInitializing I2C devices...")
+    devStatus = mpu1.dmpInitialize();
+    //insert gyro offsets here// Write a calibration algorithm in the future
+    mpu1.setXGyroOffset(0); //800/25=32 //-31 is the largest offset available
+    mpu1.setYGyroOffset(0);
+    mpu1.setZGyroOffset(0);
+    mpu1.setXAccelOffset(0);     //the accel offsets don't do anything
+    mpu1.setYAccelOffset(0);
+    mpu1.setZAccelOffset(0);
+    
+    mpu1.setFullScaleGyroRange(MPU6050_GYRO_FS_2000);
+    
+    if(devStatus == 0){     //this means initialize was successful
+        //turn on DMP
+        DMP_DBG_MSG("\n\rEnabling DMP")
+        mpu1.setDMPEnabled(true);
+        
+        // enable  interrupt detection
+        DMP_DBG_MSG("Enabling interrupt detection (Arduino external interrupt 0)...\r\n")
+        checkpin.rise(&dmpDataReady);
+    
+        mpuIntStatus = mpu1.getIntStatus();
+        
+        //set the DMP ready flag so main loop knows when it is ok to use
+        DMP_DBG_MSG("DMP ready! Waiting for first interrupt")
+        dmpReady = true;
+        
+        //get expected DMP packet size
+        packetSize = mpu1.dmpGetFIFOPacketSize();
+    }else{
+        DMP_DBG_MSG("\n\rDMP Initialization failed")
+        DMP_DBG_MSG("\t%d",devStatus)
+        Thread::wait(1000);
+    }
+    acc_offset[0]=0;
+    acc_offset[1]=0;
+    acc_offset[2]=0;
+    mpu.setDLPFMode(MPU6050_DLPF_BW_42);
+}
+void start_dmp2(MPU6051 mpu1){    //this will get the DMP ready
+    //initialize device
+    mpu2.reset();
+    DMP_DBG_MSG("\n\rInitializing I2C devices...")
+    devStatus2 = mpu2.dmpInitialize();
+    //insert gyro offsets here// Write a calibration algorithm in the future
+    mpu2.setXGyroOffset(0); //800/25=32 //-31 is the largest offset available
+    mpu2.setYGyroOffset(0);
+    mpu2.setZGyroOffset(0);
+    mpu2.setXAccelOffset(0);     //the accel offsets don't do anything
+    mpu2.setYAccelOffset(0);
+    mpu2.setZAccelOffset(0);
+    
+    mpu2.setFullScaleGyroRange(MPU6050_GYRO_FS_2000);
+    
+    if(devStatus2 == 0){     //this means initialize was successful
+        //turn on DMP
+        DMP_DBG_MSG("\n\rEnabling DMP")
+        mpu2.setDMPEnabled(true);
+        
+        // enable  interrupt detection
+        DMP_DBG_MSG("Enabling interrupt detection (Arduino external interrupt 0)...\r\n")
+        checkpin2.rise(&dmpDataReady2);
+    
+        mpuIntStatus2 = mpu2.getIntStatus();
+        
+        //set the DMP ready flag so main loop knows when it is ok to use
+        DMP_DBG_MSG("DMP ready! Waiting for first interrupt")
+        dmpReady2 = true;
+        
+        //get expected DMP packet size
+        packetSize2 = mpu2.dmpGetFIFOPacketSize();
+    }else{
+        DMP_DBG_MSG("\n\rDMP Initialization failed")
+        DMP_DBG_MSG("\t%d",devStatus2)
+        Thread::wait(1000);
+    }
+    acc_offset[0]=0;
+    acc_offset[1]=0;
+    acc_offset[2]=0;
+    mpu2.setDLPFMode(MPU6050_DLPF_BW_42);
+}
+
+void update_dmp(){
+    if (!dmpReady) return;
+    while (!mpuInterrupt && fifoCount < packetSize) {
+        // other program behavior stuff here
+        // if you are really paranoid you can frequently test in between other
+        // stuff to see if mpuInterrupt is true, and if so, "break;" from the
+        // while() loop to immediately process the MPU data
+        // .
+    }
+    // reset interrupt flag and get INT_STATUS byte
+    mpuInterrupt = false;   //this resets the interrupt flag
+    mpuIntStatus = mpu.getIntStatus();
+    
+    //get current FIFO count;
+    fifoCount = mpu.getFIFOCount();
+    
+    //check for overflow (only happens if your code sucks)
+    if((mpuIntStatus & 0x10) || fifoCount == 1024){
+        //reset so we can continue cleanly
+        mpu.resetFIFO();
+        DMP_DBG_MSG("\n\rFIFO overflow")
+    } else if (mpuIntStatus & 0x02){
+        int16_t x,y,z;
+        //wait for correct available data length (should be very short)
+        while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
+
+        //read a packet from FIFO
+        mpu.getFIFOBytes(fifoBuffer, packetSize);
+        
+        //track FIFO count here in the case there is > 1 packet available
+        //(allows us to immediately read more w/o waiting for interrupt)
+        fifoCount -= packetSize;
+        
+        mpu.dmpGetQuaternion(&q,fifoBuffer);
+        imu_data.quat[0]=q.w;
+        imu_data.quat[1]=q.x;
+        imu_data.quat[2]=q.y;
+        imu_data.quat[3]=q.z;
+        mpu.dmpGetGravity(&gravity, &q);
+        mpu.dmpGetYawPitchRoll(ypr,&q,&gravity);
+        imu_data.ypr[0] = ypr[0]*180/M_PI;//MARK - this saves the yaw data so everyone can access it
+        imu_data.ypr[1] = ypr[1]*180/M_PI;
+        imu_data.ypr[2] = ypr[2]*180/M_PI;
+        
+        mpu.getAcceleration(&x,&y,&z);
+        imu_data.acc[0] = (x-acc_offset[0]) *9.81/16384;
+        imu_data.acc[1] = (y-acc_offset[1]) *9.81/16384;
+        imu_data.acc[2] = (z-acc_offset[2]) *9.81/16384;
+        #ifdef PRINT_GYR
+        DMP_DBG_MSG("\n\rypr\t %f\t %f\t %f",ypr[0]*180/PI,ypr[1]*180/PI,ypr[2]*180/PI)
+        #endif
+        
+        mpu.dmpGetAccel(&aa, fifoBuffer);
+        mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);
+        #ifdef PRINT_ACC
+        DMP_DBG_MSG("\n\rareal\t%d\t%d\t%d",aaReal.x,aaReal.y,aaReal.z)
+        #endif
+                 //get rotations
+        mpu.getMotion6(&x,&y,&z,&gx,&gy,&gz);
+        float scale = 250/16384;
+        imu_data.gyr[0] = gx*scale;
+        imu_data.gyr[1] = gy*scale;
+        imu_data.gyr[2] = gz*scale;
+        
+   }     
+}
+void update_dmp2(){
+    if (!dmpReady2) return;
+    while (!mpuInterrupt2 && fifoCount2 < packetSize2) {
+        // other program behavior stuff here
+        // if you are really paranoid you can frequently test in between other
+        // stuff to see if mpuInterrupt is true, and if so, "break;" from the
+        // while() loop to immediately process the MPU data
+        // .
+    }
+    // reset interrupt flag and get INT_STATUS byte
+    mpuInterrupt2 = false;   //this resets the interrupt flag
+    mpuIntStatus2 = mpu2.getIntStatus();
+    
+    //get current FIFO count;
+    fifoCount2 = mpu2.getFIFOCount();
+    
+    //check for overflow (only happens if your code sucks)
+    if((mpuIntStatus2 & 0x10) || fifoCount2 == 1024){
+        //reset so we can continue cleanly
+        mpu2.resetFIFO();
+        DMP_DBG_MSG("\n\rFIFO overflow")
+    } else if (mpuIntStatus2 & 0x02){
+        int16_t x,y,z;
+        //wait for correct available data length (should be very short)
+        while (fifoCount2 < packetSize2) fifoCount2 = mpu2.getFIFOCount();
+
+        //read a packet from FIFO
+        mpu2.getFIFOBytes(fifoBuffer2, packetSize2);
+        
+        //track FIFO count here in the case there is > 1 packet available
+        //(allows us to immediately read more w/o waiting for interrupt)
+        fifoCount2 -= packetSize2;
+        
+        mpu2.dmpGetQuaternion(&q,fifoBuffer2);
+        imu2_data.quat[0]=q.w;
+        imu2_data.quat[1]=q.x;
+        imu2_data.quat[2]=q.y;
+        imu2_data.quat[3]=q.z;
+        mpu2.dmpGetGravity(&gravity, &q);
+        mpu2.dmpGetYawPitchRoll(ypr,&q,&gravity);
+        imu2_data.ypr[0] = ypr[0]*180/M_PI;//MARK - this saves the yaw data so everyone can access it
+        imu2_data.ypr[1] = ypr[1]*180/M_PI;
+        imu2_data.ypr[2] = ypr[2]*180/M_PI;
+        
+        mpu2.getAcceleration(&x,&y,&z);
+        imu2_data.acc[0] = (x-acc_offset[0]) *9.81/16384;
+        imu2_data.acc[1] = (y-acc_offset[1]) *9.81/16384;
+        imu2_data.acc[2] = (z-acc_offset[2]) *9.81/16384;
+        #ifdef PRINT_GYR
+        DMP_DBG_MSG("\n\rypr\t %f\t %f\t %f",ypr[0]*180/PI,ypr[1]*180/PI,ypr[2]*180/PI)
+        #endif
+        
+        mpu2.dmpGetAccel(&aa, fifoBuffer2);
+        mpu2.dmpGetLinearAccel(&aaReal, &aa, &gravity);
+        #ifdef PRINT_ACC
+        DMP_DBG_MSG("\n\rareal\t%d\t%d\t%d",aaReal.x,aaReal.y,aaReal.z)
+        #endif
+                 //get rotations
+        mpu2.getMotion6(&x,&y,&z,&gx,&gy,&gz);
+        float scale = 250/16384;
+        imu2_data.gyr[0] = gx*scale;
+        imu2_data.gyr[1] = gy*scale;
+        imu2_data.gyr[2] = gz*scale;
+        
+   }     
+}
+void update_acc()
+{
+    int16_t x,y,z;
+    mpu.getAcceleration(&x,&y,&z);
+    imu_data.acc[0] = (x-acc_offset[0]) *9.81/16384;
+    imu_data.acc[1] = (y-acc_offset[1]) *9.81/16384;
+    imu_data.acc[2] = (z-acc_offset[2]) *9.81/16384;
+}
+void calibrate_1()    //call this to calibrate the accelerometer
+{   //in the future, modify the OFFSET REGISTERS to make the DMP converge faster
+    //right now, I am only calculating the offset for the accelerometers
+    int sum[3] = {0,0,0};
+    int i;
+    int16_t x,y,z;
+    
+    int count=0;
+    int t_now = t.read_ms();
+    while((t.read_ms()-t_now) < 1000) //loop for one second
+    {
+        mpu.getAcceleration(&x,&y,&z);
+        sum[0] += x;
+        sum[1] += y;
+        sum[2] += z;
+        Thread::wait(5);
+        count++;
+    }
+    for(i = 0; i<3; i++)
+        acc_offset[i] = (sum[i]/count);
+    //bt.printf("ACC_OFF:%d;%d;%d;",acc_offset[0],acc_offset[1],acc_offset[2]);//print the offset used by accelerometer
+}
diff -r 000000000000 -r 964eb6a2ef00 DMP/DMP.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/DMP/DMP.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,39 @@
+#ifndef DMP_H
+#define DMP_H
+
+#include "MPU6050_6Axis_MotionApps20.h"
+#include "IMUDATA.h"
+#include "robot.h"
+
+#define PRINT_GYR     //uncomment this to print gyro data
+//#define PRINT_ACC     //uncomment this to print accel data
+
+#define PI 3.1415926
+
+#define DMP_RESET_PIN           IMU_RESET_PIN
+#define DMP_SDA_PIN             IMU_SDA_PIN
+#define DMP_NOTUSED_PIN         IMU_NOTUSED_PIN
+#define  MPU_LED_ON              LED_ON  
+#define  MPU_LED_OFF             LED_OFF      
+
+#define DMP_DBG_MSG(...)        //bt.printf(__VA_ARGS__);   //uncomment this to print debug messages
+
+#define  RESET_BAUD_RATE        bt.baud(BT_BAUD_RATE);     
+    
+extern volatile bool mpuInterrupt; //indicates whether interrupt pin has gone high
+extern uint16_t packetSize;    // expected DMP packet size (default is 42 bytes)
+extern uint16_t fifoCount;     // count of all bytes currently in FIFO
+
+int test_dmp();
+int test_dmp2();
+void start_dmp(MPU6050 mpu1);    //this will get the DMP ready
+void start_dmp2(MPU6051 mpu1);    //this will get the DMP ready
+void update_dmp();   //call this frequently
+void update_dmp2();   //call this frequently
+void update_yaw(MPU6050);   //this only updates yaw
+void update_acc();   //this only updates the acceleration
+void calibrate_1();
+void calibrate_optFlow();
+
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 DMP/IMUDATA.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/DMP/IMUDATA.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,14 @@
+#ifndef IMUDATA_H
+#define IMUDATA_H
+
+/**This struct is required for several function in DMP.cpp, ros_machine_interface.h, and reckon.cpp
+*/
+struct IMU_DATA
+{
+    float ypr[3];   //save yaw/pitch/roll
+    float acc[3];   //save acceleration in x/y/z
+    float gyr[3];   //rate of rotation x/y/z
+    float quat[4];  //quaternion w/x/y/z
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/machine_interface/keybindings.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/machine_interface/keybindings.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,40 @@
+/** This file contains the keybindings/commands for the python interface
+**/
+
+#ifndef KEYBINDINGS_H
+#define KEYBINDINGS_H
+
+#define CONNECTION  '?'     //leave this as question mark. Returns confirmation of connection when sent
+#define END_CONNECTION '$'  //end connection
+
+//sensors
+#define ALL_SENSOR  'A'     //returns all sensor data: 
+#define IMU_READ    'i'     //returns the IMU data in the form XXX.XXX,YYY.YYY,ZZZ.ZZZ,xxx.xxx,yyy.yyy.zzz.zzz [m/s2],[rad/s]
+#define IMU_YAW     'Y'     //returns only the YAW
+#define IMU_CALIBRATE 'U'   //calibrates IMU
+#define OPT_CALIBRATE 'u'   //calibrate optical flow
+
+#define IR_READ     'I'     //returns the IR sensor data in the form 000.000,000.000... [cm] for the 5 IR sensors
+#define IR_1        'L'    //left IR
+#define IR_2        'C'     //right IR
+#define IR_3        'R'     //centre IR
+#define IR_4        'r'     //rear right IR
+#define IR_5        'l'     //rear left IR
+
+#define CURRENT_SENSE 'c'   //returns current [mA]
+#define OPT_READ    'O'     //returns the velocity of each optical flow sensor X1,Y1,x2,y2 [pixels per second]
+#define LOCATION    'q'     //returns the current (x,y) location of robot [cm] (needs to be implemented)
+
+//commands
+//#define IMU_CTRL    'q'     //Toggle the IMU to keep the robot driving straight
+#define MOTOR_R     'd'     //Command to run right motor
+#define MOTOR_L     'a'     //Command to run left motor
+#define MOTOR       'w'     //Command to run both motors - specify both speeds
+
+//#define MOTOR_FWD   'W'     //Command to run both motors straight forward
+//#define ROTATE      'A'     //Command to rotate by specified rotation [degrees]
+
+#define MOTOR_STOP  's'     //Command to stop both motors
+#define GO_TO       'G'     //Command robot to go to specified coordinate
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/machine_interface/py_machine_interface.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/machine_interface/py_machine_interface.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,148 @@
+#ifndef PY_MACHINE_INTERFACE_H
+#define PY_MACHINE_INTERFACE_H
+
+/**This file contains the implementations for the controls through a python interface
+//The brain file uses ';' to separate lines
+Read IMU [acceleration and gyros]
+Read Gyro
+Read Angle
+Read Acceleration
+Read IR sensors
+Read Optical flow sensors
+Read current sensor
+Read voltage sensor
+
+Drive to [x,y] (x,y)
+Drive fwd      (speed, time)
+Run R motor    (speed,time)
+Run L motor     (speed,time)
+Set Direction   (direction)
+Enable IMU control (bool)   //if this is enabled, IMU will keep robot straight
+*/
+#include "keybindings.h"
+
+int get_cmd(); //this reads from the bt connection
+int q_pow10(int n);     //this calculates 10^n quickly (only up to 10^6)
+
+char C;
+char buffer[10];
+
+
+bool python_shell_connection(char c)
+{
+    float dum;
+    int arg_in1;
+    int arg_in2;
+    switch (c)
+    {
+        case CONNECTION:   //Return query if connection is ready
+            bt.printf("\nEBOTDEMO\n");
+            break;
+        
+        case CURRENT_SENSE:
+            dum = current_sensor.get_current();
+            bt.printf("I%3.3f;",dum);
+            break; 
+        case IMU_READ:
+            bt.printf("i;%3.3f;%3.3f;%3.3f;%3.3f;%3.3f;%3.3f;",imu_data.acc[0],imu_data.acc[1],imu_data.acc[2],imu_data.ypr[0],imu_data.ypr[1],imu_data.ypr[2]);
+            break;
+        case IMU_YAW:
+            dum = imu_data.ypr[0]*180/PI;
+            bt.printf("y;%3.3f;",dum);
+            break;
+        //optical flow
+        case OPT_READ:
+            //return optical flow (pixels/second for left and right)
+            //TODO: include second optical flow sensor
+            //bt.printf("O;%3.3f;%3.3f;",opt_flow.dx_px,opt_flow.dy_px);
+            break;
+        case IR_READ:
+            //return 5 IR sensors clockwise (Front, right_front, right_rear, left_rear, left_front)
+            //ask Wen to fill out this function
+ 
+            
+            break;
+        case LOCATION:
+            //return x,y,z,theta (maybe not z)
+            break;
+        /*case MOTOR_R:
+            arg_in1 = get_cmd();
+            *motors.Right = arg_in1;
+        case MOTOR_L:
+            arg_in1 = get_cmd();
+            *motors.Left = arg_in1;
+        */
+        case MOTOR:   //command: 'w[L_speed],[R_speed]      //I should write an actual function to receive data from serial
+            //Another argument should be included: time to run motors.
+            arg_in1 = get_cmd();
+            arg_in2 = get_cmd();
+            *motors.Right = arg_in2;
+            *motors.Left = arg_in1;
+            bt.printf("\tL=%d\tR=%d;",arg_in1,arg_in2);
+            break;
+        case (MOTOR_STOP):
+            *motors.Right = 0;
+            *motors.Left = 0;
+            break;
+        case END_CONNECTION:
+            bt.printf("End Connection\n");
+            return 0;
+            ///break;
+        default:
+            bt.putc(c); //echo command
+            break;
+    }
+    bt.printf("\n\r");
+    return 1;
+}
+
+void interface_send_data(interface x)
+{
+    bt.printf("#%f;",t.read());    //indicate start of line, output system time
+    //send all the requested data
+    if (x.list[0]){ //send all imu data
+        //bt.printf("A%3.3f,%3.3f,%3.3f,G%3.3f,%3.3f,%3.3f",mpu.ax,mpu.ay,mpu.az,mpu.gx,mpu.gy,mpu.gz);
+    }
+    
+        //0 - IMU_all
+        //1 - IMU_acc
+        //2 - IMU_gyr
+        //3 - IMU_rotation
+        //4 - IR_sensors
+        //5 - Optical_flow_sensors
+        //6 - Current_sensor
+        //7 - Voltage_sensor
+}
+
+int get_cmd()   //this requires a comma at the end of every command
+{
+    char c = '0';
+    char C[10];     //stores the array of chars read
+    int n=0;        //counter
+    int timeout = 0;    //timeout counter
+    int accum = 0;  //accumulates value of array
+    
+    while(c != ',' && c != 13 && c !=';'){    //keep looping until a comma/semicolon is read (or enter is pressed)
+        while(! bt.readable()){
+            Thread::wait(20);   //wait for char input
+            timeout++;
+            if(timeout > 100)
+            return -1;
+        }
+        timeout = 0;
+        c = bt.getc();   //read the next char in the buffer
+        C[n] = c;
+        n++;
+        if(c == '.' || n >=9) break;  //concatenate decimals. I'm not handling decimals. No reason.
+    }
+    for(int i = 0; i<n-1; i++){
+        accum += (C[i]-48)* q_pow10(n-i-2);     //need to subtract 2: 1 b/c n is incremented at the end of each iteration, 2 b/c comma is read.
+    }
+    return accum;
+}
+/*int q_pow10(int n){     //returns 10^n, up to 10^7  [8 sig figs]
+    static int pow10[8] = {1,10,100,1000,10000,100000,1000000,10000000};
+    return pow10[n];
+}*/
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/machine_interface/ros_machine_interface.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/machine_interface/ros_machine_interface.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,339 @@
+#ifndef ROS_MACHINE_INTERFACE_H
+#define ROS_MACHINE_INTERFACE_H
+//THIS FILE IS INCOMPLETE///
+
+
+/**This file contains the implementations for the controls through a python interface
+//The brain file uses ';' to separate lines
+Read IMU [acceleration and gyros]
+Read Gyro
+Read Angle
+Read Acceleration
+Read IR sensors
+Read Optical flow sensors
+Read current sensor
+Read voltage sensor
+
+Drive to [x,y] (x,y)
+Drive fwd      (speed, time)
+Run R motor    (speed,time)
+Run L motor     (speed,time)
+Set Direction   (direction)
+Enable IMU control (bool)   //if this is enabled, IMU will keep robot straight
+*/
+#include "keybindings.h"
+
+
+int ros_get_cmd(); //this reads from the bt connection
+int q_pow10(int n);     //this calculates 10^n quickly (only up to 10^6)
+void print_all();
+int ros_get_cmd(char s[16], int n);
+//char C;
+//char buffer[10];
+int IR_mm(float x);
+
+bool ros_shell_connection(char c)
+{
+    char S[16];
+    float dum;
+    float param[5];
+    int arg_in[10];
+    char run_time;
+    int m_offset = 100; //use this so that the MATLAB can send motor values between 0 and 200 instead of -100 and 100
+    //bt.printf("&%f;",t.read());
+
+    switch (c)
+    {
+        case CONNECTION:   //Return query if connection is ready
+            bt.lock();
+            bt.printf("\nEBOTDEMO\n");
+            bt.unlock();
+            reckon.reset();
+            break;
+        case ALL_SENSOR:    //returns ALL sensor data //while robot is moving, send things every 50milliseconds
+            print_all();
+            break;
+        case CURRENT_SENSE:
+            break; 
+        case IMU_READ:
+            send_flag = 1;
+            //bt.lock();
+            //bt.printf("i;%3.3f;%3.3f;%3.3f;%3.3f;%3.3f;%3.3f;",imu_data.acc[0],imu_data.acc[1],imu_data.acc[2],imu_data.ypr[0],imu_data.ypr[1],imu_data.ypr[2]);
+            //bt.unlock();
+            break;
+        case IMU_YAW:
+            dum = imu_data.ypr[0]*180/PI;
+            bt.lock();
+            bt.printf("y;%3.3f;",dum);
+            bt.unlock();
+            break;
+        //optical flow
+        case OPT_READ:
+            //return optical flow (pixels/second for left and right)
+            //TODO: include second optical flow sensor
+            //bt.printf("O;%3.3f;%3.3f;",opt_flow.dx_px,opt_flow.dy_px);
+            bt.lock();
+            bt.printf("%c;%d;%d;%d;%d;",OPT_READ,reckon.flow_dx_L,reckon.flow_dy_L,reckon.flow_dx_R,reckon.flow_dy_R);
+            bt.unlock();
+            reckon.reset();
+            break;
+        case IR_READ:
+            //return 5 IR sensors clockwise (Front, right_front, right_rear, left_rear, left_front)
+            //ask Wen to fill out this function
+            extern AnalogIn irL;
+            extern AnalogIn irC;
+            extern AnalogIn irR;
+            extern DigitalOut irBack;
+            if(irBack){
+                irBack = 0; //read from IR
+                Thread::wait(50);
+            }
+            param[0] = irL.read();
+            Thread::wait(10);
+            param[1] = irC.read();
+            Thread::wait(10);
+            param[2] = irR.read();
+            param[3] = 0;
+            param[4]=0;
+            //irBack = 1; //read back IR
+            /*Thread::wait(50);
+            param[3] = irL.read();
+            Thread::wait(10);
+            param[4] = irR.read();
+            irBack = 0;*/
+            //bt.printf("%f;%f;%f;%f;%f;",param[0],param[1],param[2],param[3],param[4]);
+            for(int i = 0; i<5; i++)
+                arg_in[i]=IR_mm(param[i]);
+            bt.lock();
+            bt.printf("%d;%d;%d;%d;%d;",arg_in[0],arg_in[1],arg_in[2],arg_in[3],arg_in[4]);
+            bt.unlock();
+            //Thread::wait(40);
+            break;
+        /*case IR_1:
+            if(irBack){
+                irBack = 0;
+                Thread::wait(50);
+            }
+            param[0] = irL.read();
+            bt.printf("%c;%f;",IR_1,param[0]);
+            break;
+        case IR_2:
+            if(irBack){
+                irBack = 0;
+                Thread::wait(50);
+            }
+            param[0] = irC.read();
+            bt.printf("%c;%f;",IR_2,param[0]);
+        break;
+        case IR_3:
+            if(irBack){
+                irBack = 0;
+                Thread::wait(50);
+            }
+            param[0] = irR.read();
+            bt.printf("%c;%f;",IR_3,param[0]);
+        break;
+        case IR_4:
+            if(!irBack){
+                irBack = 1;
+                Thread::wait(50);
+            }
+            param[0] = irR.read();
+            bt.printf("%c;%f;",IR_4,param[0]);
+            break;
+        case IR_5:
+            if(!irBack){
+                irBack = 1;
+                Thread::wait(50);
+            }
+            param[0] = irL.read();
+            bt.printf("%c;%f;",IR_5,param[0]);
+        break;*/
+        case LOCATION:
+            //return x,y,z,theta (maybe not z)
+            break;
+            
+        case MOTOR:   //command: 'w[L_speed],[R_speed]      //I should write an actual function to receive data from serial
+            //Another argument should be included: time to run motors.
+            arg_in[0] = ros_get_cmd();
+            arg_in[1] = ros_get_cmd();
+            arg_in[2] = ros_get_cmd();
+            if(arg_in[0] == arg_in[1] && arg_in[0] > 100){
+                if(IR_mm(irC.read()) < 260 && IR_mm(irC.read()) > 0) //if there is an obstacle, don't drive fwd
+                {   
+                    bt.lock();
+                    bt.printf("&;OBSTACLE;");
+                    bt.unlock();
+                    break;
+                }
+                fwd_flag = 1;
+            }
+            moveMotors(arg_in[0]-m_offset,arg_in[1]-m_offset,arg_in[2]);
+            bt.lock();
+            bt.printf("L=%d;R=%d;t=%d",arg_in[0],arg_in[1],arg_in[2]); //don't need to respond. Maybe have a confirmation?
+            bt.unlock();
+            send_flag = 1;
+            break;
+
+        case (MOTOR_STOP):
+            *motors.Right = 0;
+            *motors.Left = 0;
+            send_flag = 0;  //
+            break;
+            
+        
+        
+        
+        case (IMU_CALIBRATE):
+            calibrate_flag = 1;
+            break;
+        case (OPT_CALIBRATE):
+            calibrate_optFlow_flag=1;
+            break;
+        case END_CONNECTION:
+            bt.lock();
+            bt.printf("End Connection\n");
+            bt.unlock();
+            return 0;
+            ///break;
+        default:
+            bt.lock();
+            bt.putc(c); //echo command
+            bt.unlock();
+            break;
+    }
+    bt.lock();     
+    bt.printf("\n\r");
+    bt.unlock();
+    return 1;
+}
+int ros_get_cmd(char s[16], int n)
+{
+    int i= 0, j = 0;
+    char S[16];
+    int count = 0;
+    while(count < n && i<13)
+    {
+        if(s[i] == ';')
+            count++;
+        i++;
+    }
+    count = 0;
+    while(i<13)
+    {
+        if(s[i] == ';')
+            break;
+        S[j] = s[i];
+        j++;
+        i++;
+    }
+    for(i=0;i<j;i++)
+    {
+        count += ((S[i])-48)* q_pow10(j-i-1);
+    }
+    return count;
+}
+void ros_interface_send_data()
+{
+    //int mseconds = (int)time(NULL)+(int)t.read_ms();
+    bt.lock();            
+    bt.printf("&%d;",t.read_ms());//indicate start of line, output system time
+    bt.unlock();
+    //send all the requested data
+    //if (x.list[0]){ //send all imu data
+        //bt.printf("A%3.3f,%3.3f,%3.3f,G%3.3f,%3.3f,%3.3f",mpu.ax,mpu.ay,mpu.az,mpu.gx,mpu.gy,mpu.gz);
+    //}
+    
+        //0 - IMU_all
+        //1 - IMU_acc
+        //2 - IMU_gyr
+        //3 - IMU_rotation
+        //4 - IR_sensors
+        //5 - Optical_flow_sensors
+        //6 - Current_sensor
+        //7 - Voltage_sensor
+        
+        
+}
+
+int  ros_get_cmd()   //this requires a ',' or ';' or <enter> at the end of every command
+{
+    char c = '0';
+    char C[10];     //stores the array of chars read
+    int n=0;        //counter
+    int timeout = 0;    //timeout counter
+    int accum=0;  //accumulates value of array
+    
+   while(c != ',' && c != 13 && c !=';' && c!='x'){    //keep looping until a comma/semicolon is read (or enter is pressed)
+        bt.lock();            
+        while(! bt.readable()){
+            bt.unlock();
+            Thread::yield();   //wait for char input
+            timeout++;
+            if(timeout > 10000)   //if one second has passed, give up on this command
+                return -1;
+            bt.lock();
+        }            
+        c= bt.getc();   //read the next char in the buffer
+        bt.unlock();
+        
+        //bt.printf("%c",c);  //REMOVE THIS. DEBUG ONLY
+        //if(c == '.' || n >=9) break;  //concatenate decimals. I'm not handling decimals. No reason.
+        C[n]=c;
+        n++;
+   }
+    
+    for(int i = 0; i<n-1; i++){
+          //need to subtract 2: 1 b/c n is incremented at the end of each iteration, 2 b/c comma is read.
+          accum += ((C[i])-48)* q_pow10(n-i-2);
+    }
+  // memset(buffer, 0 , sizeof buffer);
+    return accum;
+}
+
+int q_pow10(int n){     //returns 10^n, up to 10^7  [8 sig figs]
+    static int pow10[8] = {1,10,100,1000,10000,100000,1000000,10000000};
+    return pow10[n];
+}
+void print_all(){   //call this function to print all sensor data
+    float data[13];
+    data[0]= getTime();
+    data[1]= imu_data.ypr[0];
+    data[2]= imu_data.ypr[1];
+    data[3]= imu_data.ypr[2];
+    
+    data[4]= imu2_data.ypr[0];
+    data[5]= imu2_data.ypr[1];
+    data[6]= imu2_data.ypr[2];
+    
+    
+    bt.lock();
+    bt.printf("&;");
+    bt.printf("%f;",data[0]);       //print time as an integer (milliseconds)
+    for(int i = 1; i<=6; i++){
+            bt.printf("%.3f;",data[i]);
+    }
+    bt.printf("\n\r");
+    bt.unlock();
+    //commented out the below code because we want to ignore the rear IR sensors
+    /*dt = t.read() - data[0];
+    irBack = 1;
+    if(dt < 50)
+        Thread::wait(50-dt);
+    
+    data[6]= irR.read();
+    data[7]= irL.read();
+    data[8]= imu_data.ypr[0]*180/PI;
+    irBack = 0;
+    */
+
+}
+int IR_mm(float x)  //converts IR sensor value to millimeters
+{
+    //return 9462/(x*3.3/5*1024 - 16.92);
+    if (x <= 0.24)
+        return -1;
+    return 170/x;
+}
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/shell/bt_shell.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/shell/bt_shell.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,149 @@
+//you could save some memory by disabling the bt_shell (the shell is not used with the PYTHON interface)
+
+#include "bt_shell.h"
+#include "tinysh.h"
+#include "motor_fnt.h"
+#include "remotecontrol_fnt.h"
+#include "recon_fnt.h"
+#include "calibrate_fnt.h"
+#include "py_machine_interface.h"
+#include "ros_machine_interface.h"
+//#include "keybindings.h"
+
+tinysh_cmd_t movecmd= {0,"move","command motor movements","[L_speed] [R_speed] [duration_ms](optional)",move_fnt,0,0,0};
+tinysh_cmd_t reconpositioncmd= {0,"resetposition","reset recon position",0,reset_position_fnt,0,0,0};
+tinysh_cmd_t flipmotorscmd= {0,"flipmotors","left right motors swap",0,flip_motors_fnt,0,0,0};
+tinysh_cmd_t remotecontrolcmd= {0,"rc","control using keyboard","[speed](optional)",remotecontrol_fnt,0,0,0};
+tinysh_cmd_t stopmotorscmd= {0,"stop","stop motors",0,stop_motors_fnt,0,0,0};
+tinysh_cmd_t gotocoordcmd= {0,"gotocoord","goto coordinates",0,goto_coord_fnt,0,0,0};
+tinysh_cmd_t calibratecmd= {0,"calibrate","calibration settings","[module] [setting] [value]",calibrate_fnt,0,0,0};
+tinysh_cmd_t scalemotorscmd= {0,"scale","scale motor output","[value]",motor_scale_fnt,0,0,0};
+//the following functions are for the python interface
+
+//save a struct that indicates which data is to be returned
+
+interface iface;
+bool send_prev = 0;
+
+//mandatory tiny shell output function
+void tinysh_char_out(unsigned char c)
+{
+    bt.lock();
+    bt.putc(c);
+    bt.unlock();
+}
+
+//mandatory tiny shell output function
+void bt_shell_init()
+{ 
+    //set prompt
+    tinysh_set_prompt("$ ");
+t.start();
+    //add custom commands here
+    tinysh_add_command(&movecmd);
+    tinysh_add_command(&reconpositioncmd);
+    tinysh_add_command(&flipmotorscmd);
+    tinysh_add_command(&remotecontrolcmd);
+    tinysh_add_command(&stopmotorscmd);
+    tinysh_add_command(&gotocoordcmd);
+    tinysh_add_command(&calibratecmd);
+    tinysh_add_command(&scalemotorscmd);
+ 
+    bt.lock();
+    while(bt.readable())
+        bt.getc();
+    bt.unlock();
+        
+    tinysh_char_in('\r');
+    tinysh_char_in('\n');
+}
+
+void bt_shell_run(){
+
+    static bool py_machine_input = false;   //this is for the python and brain file connection (not finished)
+    static bool ros_machine_input = false;  //this is for the connection to ROS
+send_flag=1; //always send stuff
+    bt.lock();
+    
+    if(!bt.readable()){
+        bt.unlock();
+        return;
+    }
+        
+    char c = bt.getc();
+    bt.unlock();
+       
+    if( c == '#' )
+        py_machine_input = true;
+    else if(c== '&'){
+        ros_machine_input = true;
+        bt.lock();
+        bt.printf("&\n\r");
+        bt.unlock();
+    }
+    if(py_machine_input)
+    {
+        bt.lock();
+        bt.baud(BT_BAUD_RATE);
+        bt.unlock();
+        //This is for the python interface
+        while(py_machine_input)
+        {
+            bt.lock();
+            if(bt.readable()) 
+            {
+                c = bt.getc();
+                bt.unlock();
+                //if(c!= '?')
+                //interface_send_data(iface);
+                py_machine_input = python_shell_connection(c);
+            }
+            bt.unlock();
+            Thread::wait(10);
+        }
+    }
+    else if(ros_machine_input)
+    {
+        while(ros_machine_input)
+        {
+            bt.lock();
+            if(bt.readable())
+            {
+                c= bt.getc();
+                bt.unlock();
+                ros_machine_input = ros_shell_connection(c);
+            }
+            bt.unlock();
+            if(send_flag)
+            {
+                print_all();
+                send_prev = 1;
+            }else if(send_prev)
+            {   
+                bt.lock();
+                bt.printf("&;STOPPED;\n\r");
+                bt.unlock();
+                send_prev = 0;
+            }
+            if(obstacle_flag && fwd_flag && !calibrate_flag) 
+            {
+                moveMotors(0,0,0);
+                obstacle_flag = 0;
+                send_flag = 0;
+                send_prev = 0;
+                fwd_flag = 0;
+                bt.lock();
+                bt.printf("&;OBSTACLE;\n\r");
+                bt.unlock();
+            }
+            Thread::yield();
+        }
+    }
+    else
+    {
+        tinysh_char_in(c);
+    }
+          
+    if ( c == '$')//c == '\n' || c == '\r')
+        py_machine_input = false;
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/shell/bt_shell.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/shell/bt_shell.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,23 @@
+#ifndef BT_shell_H
+#define BT_shell_H
+
+#include "robot.h"
+ 
+void bt_shell_init();
+void bt_shell_run();
+
+
+struct interface{
+    bool list[16];  //list saves which pieces of data must be returned
+        //0 - IMU_all
+        //1 - IMU_acc
+        //2 - IMU_gyr
+        //3 - IMU_rotation
+        //4 - IR_sensors
+        //5 - Optical_flow_sensors
+        //6 - Current_sensor
+        //7 - Voltage_sensor
+    int period; //this is the refresh rate at which the python wants data [ms]
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/shell/calibrate_fnt.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/shell/calibrate_fnt.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,87 @@
+void calibrate_fnt(int argc, char **argv)
+{
+    //to fix for updated reckon
+    /*
+    if(argc != 4){
+        if(echo){
+            bt.lock();
+            bt.printf("Usage: calibrate [module] [setting] [value]\r\n");
+            bt.unlock();
+            return;
+        }
+    }
+    
+    if( !strcmp(argv[1],"flow")){
+        if( !strcmp(argv[2],"dpmm") ){
+            float val = atof( argv[3] );
+            if (val != 0)
+                opt_flow_L.pxPerMM = val;
+                opt_flow_R.pxPerMM = val;
+            if(echo){
+                bt.lock();
+                bt.printf("\r\npxPerMM = %.2f\r\n", opt_flow_L.pxPerMM);
+                bt.unlock();
+                }
+        }     
+        else if ( !strcmp(argv[2],"DPI") ){
+            if(!strcmp(argv[3],"high")){
+                opt_flow_L.reset();
+                opt_flow_R.reset();
+                if(echo){
+                    bt.lock();
+                    bt.printf("\r\nDPI set to high\r\n");
+                    bt.unlock();
+                }   
+            }
+            else if(!strcmp(argv[3],"low")){
+                opt_flow_L.setDPI();
+                opt_flow_R.setDPI();
+                if(echo){
+                    bt.lock();
+                    bt.printf("\r\nDPI set to low\r\n");
+                    bt.unlock();
+                }                
+            }
+            else{
+                if(echo)
+                bt.printf("\r\nvalue can be \"low\" or \"high\"\r\n");                
+            }               
+        }else{
+            if(echo)
+                bt.printf("\r\nInvalid Setting Parameters\r\n");
+        }
+    }
+    else if( !strcmp(argv[1],"recon")){
+        if( !strcmp(argv[2],"k")){
+            float val = atof( argv[3] );
+            if (val > 0)
+                k = val;
+            if(echo)
+                bt.printf("\r\nk = %.2f\r\n", k);  
+            }
+        else if ( !strcmp(argv[2],"xproj") ){
+            float val = atof( argv[3] );
+            if (val != 0)
+                reckon.forward_to_x_projection = val;
+            if(echo)
+                bt.printf("\r\nforward to x projection = %.5f\r\n", reckon.forward_to_x_projection);  
+        }      
+        else if ( !strcmp(argv[2],"radius") ){
+            float val = atof( argv[3] );
+            if (val != 0)
+                reckon.r = val;
+            if(echo)
+                bt.printf("\r\nradius = %.2fmm\r\n", reckon.r);                
+        }   
+        else
+        {
+            if(echo)
+                bt.printf("\r\nInvalid Setting Parameters\r\n");
+        }
+    }
+    else{
+        if(echo)
+            bt.printf("\r\nInvalid Module Parameter\r\n");
+    }            
+    */
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/shell/motor_fnt.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/shell/motor_fnt.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,117 @@
+void move_fnt(int argc, char **argv)
+{
+    if(echo)
+        bt.printf("move command called\r\n");
+    
+    if(argc == 1){
+        if(echo){
+            bt.lock();
+            bt.printf("Usage: move [L_speed] [R_speed] [duration_ms]\r\n");
+            bt.unlock();
+        }
+    }else if(argc == 2){
+        if(echo){
+            bt.lock();
+            bt.printf("\r\nInvalid Parameters\r\n");
+            bt.unlock();
+        }
+    }else{
+        
+        int param[3];
+            
+        for(int i = 0; i < 2; i++)
+        {
+            param[i] = tinysh_atoxi(argv[i+1]);
+    
+            if(param[i] > 100)
+                param[i] = 100;
+            else if (param[i] < -100)
+                param[i] = -100;
+        }
+        
+        if(echo){
+            bt.lock();
+            bt.printf("Setting motor speeds Left = %d  Right = %d\r\n" ,param[0],param[1]);
+            bt.unlock();
+        }
+            
+        if(argc == 4)
+        {
+            param[2] = tinysh_atoxi(argv[3]);
+            if( param[2] > 0)
+            {
+                if(echo){
+                    bt.lock();
+                    bt.printf("moving duration: %sms\r\n", argv[3]);
+                    bt.unlock();
+                }
+
+                moveMotors(param[0],param[1],param[2]);
+            }
+            else
+            {
+                if(echo){
+                    bt.lock();                
+                    bt.printf("invalid duration: %sms\r\n", argv[3]);    
+                    bt.unlock();
+                }                
+            }
+        }
+        else
+        {   
+            *motors.Left = param[0];
+            *motors.Right = param[1];
+        }
+    }
+}
+
+//////////////////////////////////////////////////////////////////////////
+void stop_motors_fnt(int argc, char **argv)
+{
+    if(echo){
+        bt.lock();
+        bt.printf("motors stopped\r\n");
+        bt.unlock();
+    }
+    *motors.Left = 0;
+    *motors.Right = 0;
+}
+
+///////////////////////////////////////////////////////////////////////
+void flip_motors_fnt(int argc, char **argv)
+{
+    if(echo){
+        bt.lock();
+        bt.printf("L/R motors swapped\r\n");
+        bt.unlock();
+    }
+    motors.flip();    
+}
+
+void motor_scale_fnt(int argc, char **argv)
+{
+    if(echo){
+        bt.lock();
+        bt.printf("motor scale command called\r\n");
+        bt.unlock();
+    }
+    
+    if(argc == 2){
+        float val = atof(argv[1]);
+        
+        motors.Left->scale = val;
+        motors.Right->scale = val;                 
+        
+        if(echo){
+            bt.lock();
+            bt.printf("Scale set to %s\r\n", argv[1]); 
+            bt.unlock();
+        }
+    }else{
+        if(echo){
+            bt.lock();
+            bt.printf("Usage: scale [value]\r\n");
+            bt.unlock();
+        }
+    }
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/shell/recon_fnt.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/shell/recon_fnt.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,92 @@
+void reset_position_fnt(int argc, char **argv)
+{
+    if(echo){
+        bt.lock();    
+        bt.printf("recon position reset to x = 0, y = 0, angle = 0\r\n");
+        bt.unlock();
+    }
+    reckon.reset();    
+}
+
+int Vav = 40;
+float k = 3;
+
+void goto_coord_fnt(int argc, char **argv)
+{   
+//to fix for updated reckon
+/*
+    if(argc != 3){
+        if(echo){
+            bt.lock();
+            bt.printf("Usage: gotocoord [x] [y]\r\n");
+            bt.unlock();
+            return;
+        }
+    }    
+    
+    float x_dest = atof( argv[1] );
+    float y_dest = atof( argv[2] );
+    
+    bt.lock();
+    bt.printf("going to coordinates [%.2f, %.2f]...\r\n", x_dest, y_dest);
+    bt.printf("Press enter to exit\r\n");
+    bt.unlock();
+    
+    float return_angle_offset;
+    int Vt, Lspeed, Rspeed;
+    
+    char c = 0;
+    
+    while(c != '\r' && c != '\n' && reckon.dest_distance(x_dest, y_dest) > 20)
+    {   
+        bt.lock();
+        if(bt.readable())
+        {
+            c = bt.getc();
+            bt.unlock();
+        }else
+            bt.unlock();
+        
+        return_angle_offset = (reckon.dest_angle(x_dest, y_dest) - reckon.angle)*180/3.14159265359;
+        
+        if(return_angle_offset > 90){
+            Vt =(int)(-k*(180-return_angle_offset));
+        }
+        else if(return_angle_offset < -90)
+            Vt =(int)(k*(180+return_angle_offset));
+        else        
+            Vt =(int)(k*return_angle_offset);
+
+        Lspeed = - Vt;
+        Rspeed = + Vt;
+        
+        if(abs(return_angle_offset)> 90)
+        {
+             Lspeed -= Vav;
+             Rspeed -= Vav;
+        }
+        else
+        {
+            Lspeed += Vav;
+            Rspeed += Vav;
+        }
+        
+        if(Lspeed > Vav*2)
+            Lspeed = Vav*2;
+        else if(Lspeed < -Vav*2)
+            Lspeed = -Vav*2;
+            
+        if(Rspeed > Vav*2)
+            Rspeed = Vav*2;
+        else if(Rspeed < -Vav*2)
+            Rspeed = -Vav*2;
+            
+        *motors.Left = Lspeed;
+        *motors.Right = Rspeed;
+        
+        Thread::wait(30);
+    }    
+        *motors.Left = 0;
+        *motors.Right = 0;        
+        */
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/shell/remotecontrol_fnt.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/shell/remotecontrol_fnt.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,103 @@
+void remotecontrol_fnt(int argc, char **argv)
+{
+    int speed = 40;
+    
+    bt.lock();
+    bt.printf("Remote Control Mode\r\n");
+    bt.printf("Controls:\r\n");
+    bt.printf("     wasd & qezc to move\r\n");
+    bt.printf("     r/f for speed +/-\r\n");
+    bt.printf("     enter key to exit\r\n");
+    bt.unlock();
+    
+    if(argc == 2){
+        speed = tinysh_atoxi(argv[1]);        
+        if( speed <= 0 || speed > 100)
+            speed = 100;
+    }        
+    
+    int Lspeed = 0;
+    int Rspeed = 0;
+
+    char c = 0;
+    
+    while(c != '\r' && c != '\n')
+    {
+        bt.lock();
+        
+        if(bt.readable())
+        {
+        c = bt.getc();
+        bt.unlock();
+               
+        switch ( c ) {
+            case 'w':
+                Lspeed = speed;
+                Rspeed = speed;            
+            break;
+            case 'a':
+                Lspeed = -speed;
+                Rspeed = speed;
+            break;
+            case 's':
+                Lspeed = -speed;
+                Rspeed = -speed;
+            break;
+            case 'x':
+                Lspeed = -speed;
+                Rspeed = -speed;
+            break;
+            case 'd':
+                Lspeed = speed;
+                Rspeed = -speed;
+            break;
+            case 'q':
+                Lspeed = 0;
+                Rspeed = speed;
+            break;
+            case 'e':
+                Lspeed = speed;
+                Rspeed = 0;
+            break;      
+            case 'c':
+                Lspeed = -speed;
+                Rspeed = 0;
+            break;       
+            case 'z':
+                Lspeed = 0;
+                Rspeed = -speed;
+            break;        
+            case 'r':
+                speed += 10;
+                if(speed > 100)
+                    speed = 100;
+                bt.lock();
+                bt.printf("speed = %d\r\n", speed);
+                bt.unlock();
+                Lspeed = 0;
+                Rspeed = 0;
+            break;  
+            case 'f':
+                speed -= 10;
+                if(speed < 0)
+                    speed = 0;
+                bt.lock();
+                bt.printf("speed = %d\r\n", speed);      
+                bt.unlock();
+                Lspeed = 0;
+                Rspeed = 0;              
+            break;         
+            default:
+                Lspeed = 0;
+                Rspeed = 0;
+            break;
+        }
+        
+        moveMotors(Lspeed,Rspeed,100);
+        
+        }else
+            bt.unlock();
+            
+        Thread::wait(25);   
+    }
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/shell/tinyshell/tinysh.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/shell/tinyshell/tinysh.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,693 @@
+/*
+ * tinysh.c
+ *
+ * Minimal portable shell
+ *
+ * Copyright (C) 2001 Michel Gutierrez <mig@nerim.net>
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free
+ * Software Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
+ */
+
+#include "tinysh.h"
+
+#ifndef BUFFER_SIZE
+#define BUFFER_SIZE 64
+#endif
+#ifndef HISTORY_DEPTH
+#define HISTORY_DEPTH 3
+#endif
+#ifndef MAX_ARGS
+#define MAX_ARGS 4
+#endif
+#ifndef PROMPT_SIZE
+#define PROMPT_SIZE 4
+#endif
+#ifndef TOPCHAR
+#define TOPCHAR '/'
+#endif
+
+
+typedef unsigned char uchar;
+/* redefine some useful and maybe missing utilities to avoid conflicts */
+#define strlen tinysh_strlen
+#define puts tinysh_puts
+#define putchar tinysh_char_out
+
+static void help_fnt(int argc, char **argv);
+
+static tinysh_cmd_t help_cmd={ 
+  0,"help","display help","<cr>",help_fnt,0,0,0 };
+
+static uchar input_buffers[HISTORY_DEPTH][BUFFER_SIZE+1]={0};
+static uchar trash_buffer[BUFFER_SIZE+1]={0};
+static int cur_buf_index=0;
+static uchar context_buffer[BUFFER_SIZE+1]={0};
+static int cur_context=0;
+static int cur_index=0;
+int echo=1;
+static char prompt[PROMPT_SIZE+1]="$ ";
+static tinysh_cmd_t *root_cmd=&help_cmd;
+static tinysh_cmd_t *cur_cmd_ctx=0;
+static void *tinysh_arg=0;
+
+/* few useful utilities that may be missing */
+
+static int strlen(uchar *s)
+{
+  int i;
+  for(i=0;*s;s++,i++);
+  return i;
+}
+
+static void puts(char *s)
+{
+  while(*s)
+    putchar(*s++);
+}
+
+/* callback for help function
+ */
+static void help_fnt(int argc, char **argv)
+{
+  puts("?            display help on given or available commands\r\n");
+  puts("<TAB>        auto-completion\r\n");
+  puts("<cr>         execute command line\r\n");
+  puts("CTRL-P       recall previous input line\r\n");
+  puts("CTRL-N       recall next input line\r\n");
+  puts("<any>        treat as input character\r\n");
+}
+
+/*
+ */
+
+enum { NULLMATCH,FULLMATCH,PARTMATCH,UNMATCH,MATCH,AMBIG };
+
+/* verify if the non-spaced part of s2 is included at the begining
+ * of s1.
+ * return FULLMATCH if s2 equal to s1, PARTMATCH if s1 starts with s2
+ * but there are remaining chars in s1, UNMATCH if s1 does not start with
+ * s2
+ */
+int strstart(uchar *s1, uchar *s2)
+{
+  while(*s1 && *s1==*s2) { s1++; s2++; }
+
+  if(*s2==' ' || *s2==0)
+    {
+      if(*s1==0)
+        return FULLMATCH; /* full match */
+      else
+        return PARTMATCH; /* partial match */ 
+    }
+  else
+    return UNMATCH;     /* no match */
+}
+
+/*
+ * check commands at given level with input string.
+ * _cmd: point to first command at this level, return matched cmd
+ * _str: point to current unprocessed input, return next unprocessed
+ */
+static int parse_command(tinysh_cmd_t **_cmd, uchar **_str)
+{
+  uchar *str=*_str;
+  tinysh_cmd_t *cmd;
+  int matched_len=0;
+  tinysh_cmd_t *matched_cmd=0;
+
+  /* first eliminate first blanks */
+  while(*str==' ') str++;
+  if(!*str)
+    {
+      *_str=str;
+      return NULLMATCH; /* end of input */
+    }
+  
+  /* first pass: count matches */
+  for(cmd=*_cmd;cmd;cmd=cmd->next)
+    {
+      int ret=strstart(cmd->name,str);
+
+      if(ret==FULLMATCH)
+        {
+          /* found full match */
+          while(*str && *str!=' ') str++; 
+          while(*str==' ') str++;
+          *_str=str;
+          *_cmd=cmd;
+          return MATCH;
+        }
+      else if (ret==PARTMATCH)
+        {
+          if(matched_cmd)
+            {
+              *_cmd=matched_cmd;
+              return AMBIG;
+            }
+          else
+            {
+              matched_cmd=cmd;
+            }
+        }
+      else /* UNMATCH */
+        {
+        }
+    }
+  if(matched_cmd)
+    {
+      while(*str && *str!=' ') str++; 
+      while(*str==' ') str++;
+      *_cmd=matched_cmd;
+      *_str=str;
+      return MATCH;
+    }
+  else
+    return UNMATCH;
+}
+
+/* create a context from current input line
+ */
+static void do_context(tinysh_cmd_t *cmd, uchar *str)
+{
+  while(*str) 
+    context_buffer[cur_context++]=*str++;
+  context_buffer[cur_context]=0;
+  cur_cmd_ctx=cmd;
+}
+
+/* execute the given command by calling callback with appropriate 
+ * arguments
+ */
+static void exec_command(tinysh_cmd_t *cmd, uchar *str)
+{
+  char *argv[MAX_ARGS];
+  int argc=0;
+  int i;
+
+/* copy command line to preserve it for history */
+  for(i=0;i<BUFFER_SIZE;i++)
+    trash_buffer[i]=str[i];
+  str=trash_buffer;
+  
+/* cut into arguments */
+  argv[argc++]=cmd->name;
+  while(*str && argc<MAX_ARGS)
+    {
+      while(*str==' ') str++;
+      if(*str==0)
+        break;
+      argv[argc++]=str;
+      while(*str!=' ' && *str) str++;
+      if(!*str) break;
+      *str++=0;
+    }
+/* call command function if present */
+  if(cmd->function)
+    {
+      tinysh_arg=cmd->arg;
+      cmd->function(argc,&argv[0]);
+    }
+}
+
+/* try to execute the current command line
+ */
+static int exec_command_line(tinysh_cmd_t *cmd, uchar *_str)
+{
+  uchar *str=_str;
+
+  while(1)
+    {
+      int ret;
+      ret=parse_command(&cmd,&str);
+      if(ret==MATCH) /* found unique match */
+        {
+          if(cmd)
+            {
+              if(!cmd->child) /* no sub-command, execute */
+                {
+                  exec_command(cmd,str);
+                  return 0;
+                }
+              else
+                {
+                  if(*str==0) /* no more input, this is a context */
+                    {
+                      do_context(cmd,_str);
+                      return 0;
+                    }
+                  else /* process next command word */
+                    {
+                      cmd=cmd->child;
+                    }
+                }
+            } 
+          else /* cmd == 0 */
+            {
+              return 0;
+            }
+        }
+      else if(ret==AMBIG)
+        {
+          puts("ambiguity: ");
+          puts(str);
+          puts("\r\n");
+          return 0;
+        }
+      else if(ret==UNMATCH) /* UNMATCH */
+        {
+          puts("no match: ");
+          puts(str);
+          puts("\r\n");
+          return 0;
+        }
+      else /* NULLMATCH */
+        return 0;
+    }
+}
+
+/* display help for list of commands 
+*/
+static void display_child_help(tinysh_cmd_t *cmd)
+{
+  tinysh_cmd_t *cm;
+  int len=0;
+
+  puts("\r\n");
+  for(cm=cmd;cm;cm=cm->next)
+    if(len<strlen(cm->name))
+      len=strlen(cm->name);
+  for(cm=cmd;cm;cm=cm->next)
+    if(cm->help)
+      {
+        int i;
+        puts(cm->name);
+        for(i=strlen(cm->name);i<len+2;i++)
+          putchar(' ');
+        puts(cm->help);
+        puts("\r\n");
+      }
+}
+
+/* try to display help for current comand line
+ */
+static int help_command_line(tinysh_cmd_t *cmd, uchar *_str)
+{
+  uchar *str=_str;
+
+  while(1)
+    {
+      int ret;
+      ret=parse_command(&cmd,&str);
+      if(ret==MATCH && *str==0) /* found unique match or empty line */
+        {
+          tinysh_cmd_t *cm;
+          int len=0;
+              
+          if(cmd->child) /* display sub-commands help */
+            {
+              display_child_help(cmd->child);
+              return 0;
+            }
+          else  /* no sub-command, show single help */
+            {
+              if(*(str-1)!=' ')
+                putchar(' ');
+              if(cmd->usage)
+                puts(cmd->usage);
+              puts(": ");
+              if(cmd->help)
+                puts(cmd->help);
+              else
+                puts("no help available");
+              puts("\r\n");
+            }
+          return 0;
+        }
+      else if(ret==MATCH && *str)
+        { /* continue processing the line */
+          cmd=cmd->child;
+        }
+      else if(ret==AMBIG)
+        {
+          puts("\r\nambiguity: ");
+          puts(str);
+          puts("\r\n");
+          return 0;
+        }
+      else if(ret==UNMATCH)
+        {
+          puts("\r\nno match: ");
+          puts(str);
+          puts("\r\n");
+          return 0;
+        }
+      else /* NULLMATCH */
+        {
+          if(cur_cmd_ctx)
+            display_child_help(cur_cmd_ctx->child);
+          else
+            display_child_help(root_cmd);
+          return 0;
+        }
+    }
+}
+
+/* try to complete current command line
+ */
+static int complete_command_line(tinysh_cmd_t *cmd, uchar *_str)
+{
+  uchar *str=_str;
+
+  while(1)
+    {
+      int ret;
+      int common_len=BUFFER_SIZE;
+      int _str_len;
+      int i;
+      uchar *__str=str;
+
+      tinysh_cmd_t *_cmd=cmd;
+      ret=parse_command(&cmd,&str);
+      for(_str_len=0;__str[_str_len]&&__str[_str_len]!=' ';_str_len++);
+      if(ret==MATCH && *str)
+        {
+          cmd=cmd->child;
+        }
+      else if(ret==AMBIG || ret==MATCH || ret==NULLMATCH)
+        {
+          tinysh_cmd_t *cm;
+          tinysh_cmd_t *matched_cmd=0;
+          int nb_match=0;
+              
+          for(cm=cmd;cm;cm=cm->next)
+            {
+              int r=strstart(cm->name,__str);
+              if(r==FULLMATCH)
+                {
+                  for(i=_str_len;cmd->name[i];i++)
+                    tinysh_char_in(cmd->name[i]);
+                  if(*(str-1)!=' ')
+                    tinysh_char_in(' ');
+                  if(!cmd->child)
+                    {
+                      if(cmd->usage)
+                        {
+                          puts(cmd->usage);
+                          putchar('\n');
+                          return 1;
+                        }
+                      else
+                        return 0;
+                    }
+                  else
+                    {
+                      cmd=cmd->child;
+                      break;
+                    }
+                }
+              else if(r==PARTMATCH)
+                {
+                  nb_match++;
+                  if(!matched_cmd)
+                    {
+                      matched_cmd=cm;
+                      common_len=strlen(cm->name);
+                    }
+                  else
+                    {
+                      for(i=_str_len;cm->name[i] && i<common_len &&
+                            cm->name[i]==matched_cmd->name[i];i++);
+                      if(i<common_len)
+                        common_len=i;
+                    }
+                }
+            }
+          if(cm)
+            continue;
+          if(matched_cmd)
+            {
+              if(_str_len==common_len)
+                {
+                  puts("\r\n");
+                  for(cm=cmd;cm;cm=cm->next)
+                    {
+                      int r=strstart(cm->name,__str);
+                      if(r==FULLMATCH || r==PARTMATCH)
+                        {
+                          puts(cm->name);
+                          puts("\r\n");
+                        }
+                    }
+                  return 1;
+                }
+              else
+                {
+                  for(i=_str_len;i<common_len;i++)
+                    tinysh_char_in(matched_cmd->name[i]);
+                  if(nb_match==1)
+                    tinysh_char_in(' ');
+                }
+            }
+          return 0;
+        }
+      else /* UNMATCH */
+        { 
+          return 0;
+        }
+    }
+}
+
+/* start a new line 
+ */
+static void start_of_line()
+{
+  /* display start of new line */
+  puts(prompt);
+  if(cur_context)
+    {
+      puts(context_buffer);
+      puts("> ");
+    }
+  cur_index=0;
+}
+
+/* character input 
+ */
+static void _tinysh_char_in(uchar c)
+{
+  uchar *line=input_buffers[cur_buf_index];
+
+  if(c=='\n' || c=='\r') /* validate command */
+    {
+      tinysh_cmd_t *cmd;
+      int context=0;
+      
+/* first, echo the newline */
+      if(echo)
+        putchar(c);
+
+      while(*line && *line==' ') line++;
+      if(*line) /* not empty line */
+        {
+          cmd=cur_cmd_ctx?cur_cmd_ctx->child:root_cmd;
+          exec_command_line(cmd,line);
+          cur_buf_index=(cur_buf_index+1)%HISTORY_DEPTH;
+          cur_index=0;
+          input_buffers[cur_buf_index][0]=0;
+        }
+      start_of_line();
+    }
+  else if(c==TOPCHAR) /* return to top level */
+    {
+      if(echo)
+        putchar(c);
+
+      cur_context=0;
+      cur_cmd_ctx=0;
+      
+    }
+  else if(c==8 || c==127) /* backspace */
+    {
+      if(cur_index>0)
+        {
+          puts("\b \b");
+          cur_index--;
+          line[cur_index]=0;
+        }
+    }
+  else if(c==16) /* CTRL-P: back in history */
+    {
+      int prevline=(cur_buf_index+HISTORY_DEPTH-1)%HISTORY_DEPTH;
+
+      if(input_buffers[prevline][0])
+        {
+          line=input_buffers[prevline];
+          /* fill the rest of the line with spaces */
+          while(cur_index-->strlen(line))
+            puts("\b \b");
+          putchar('\r');
+          start_of_line();
+          puts(line);
+          cur_index=strlen(line);
+          cur_buf_index=prevline;
+        }
+    }
+  else if(c==14) /* CTRL-N: next in history */
+    {
+      int nextline=(cur_buf_index+1)%HISTORY_DEPTH;
+
+      if(input_buffers[nextline][0])
+        {
+          line=input_buffers[nextline];
+          /* fill the rest of the line with spaces */
+          while(cur_index-->strlen(line))
+            puts("\b \b");
+          putchar('\r');
+          start_of_line();
+          puts(line);
+          cur_index=strlen(line);
+          cur_buf_index=nextline;
+        }
+    }
+  else if(c=='?') /* display help */
+    {
+      tinysh_cmd_t *cmd;
+      cmd=cur_cmd_ctx?cur_cmd_ctx->child:root_cmd;
+      help_command_line(cmd,line);
+      start_of_line();
+      puts(line);
+      cur_index=strlen(line);
+    }
+  else if(c==9 || c=='!') /* TAB: autocompletion */
+    {
+      tinysh_cmd_t *cmd;
+      cmd=cur_cmd_ctx?cur_cmd_ctx->child:root_cmd;
+      if(complete_command_line(cmd,line))
+        {
+          start_of_line();
+          puts(line);
+        }
+      cur_index=strlen(line);
+    }      
+  else /* any input character */
+    {
+      if(cur_index<BUFFER_SIZE)
+        {
+          if(echo)
+            putchar(c);
+          line[cur_index++]=c;
+          line[cur_index]=0;
+        }
+    }
+}
+
+/* new character input */
+void tinysh_char_in(uchar c)
+{
+  /*
+   * filter characters here
+   */
+  _tinysh_char_in(c);
+}
+
+/* add a new command */
+void tinysh_add_command(tinysh_cmd_t *cmd)
+{
+  tinysh_cmd_t *cm;
+
+  if(cmd->parent)
+    {
+      cm=cmd->parent->child;
+      if(!cm)
+        {
+          cmd->parent->child=cmd;
+        }
+      else
+        {
+          while(cm->next) cm=cm->next;
+          cm->next=cmd;
+        }
+    }
+  else if(!root_cmd)
+    {
+      root_cmd=cmd;
+    }
+  else
+    {
+      cm=root_cmd;
+      while(cm->next) cm=cm->next;
+      cm->next=cmd;      
+    }
+}
+
+/* modify shell prompt
+ */
+void tinysh_set_prompt(char *str)
+{
+  int i;
+  for(i=0;str[i] && i<PROMPT_SIZE;i++)
+    prompt[i]=str[i];
+  prompt[i]=0;
+  /* force prompt display by generating empty command */
+  tinysh_char_in('\r');
+}
+
+/* return current command argument
+ */
+void *tinysh_get_arg()
+{
+  return tinysh_arg;
+}
+
+/* string to decimal/hexadecimal conversion
+ */
+unsigned long tinysh_atoxi(char *s)
+{
+  int ishex=0;
+  unsigned long res=0;
+  int sign = 1;
+
+  if(*s==0) return 0;
+
+  if(*s=='0' && *(s+1)=='x')
+    {
+      ishex=1;
+      s+=2;
+    }
+
+  while(*s)
+    {
+      if(ishex)
+	res*=16;
+      else
+	res*=10;
+
+      if(*s>='0' && *s<='9')
+	res+=*s-'0';
+      else if(ishex && *s>='a' && *s<='f')
+	res+=*s+10-'a';
+      else if(ishex && *s>='A' && *s<='F')
+	res+=*s+10-'A';
+      else if(*s=='-')
+    sign=-1;
+      else
+	break;
+      
+      s++;
+    }
+
+  return sign*res;
+}
+
diff -r 000000000000 -r 964eb6a2ef00 bt_shell/shell/tinyshell/tinysh.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bt_shell/shell/tinyshell/tinysh.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,72 @@
+/*
+ * tinysh.h
+ *
+ * Header for minimal portable shell
+ *
+ * Copyright (C) 2001 Michel Gutierrez <mig@nerim.net>
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free
+ * Software Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
+ */
+
+typedef void (*tinysh_fnt_t)(int argc, char **argv);
+
+typedef struct tinysh_cmd_t {
+  struct tinysh_cmd_t *parent; /* 0 if top level command */
+  char *name;                  /* command input name, not 0 */
+  char *help;                  /* help string, can be 0 */
+  char *usage;                 /* usage string, can be 0 */
+  tinysh_fnt_t function;       /* function to launch on cmd, can be 0 */
+  void *arg;                   /* current argument when function called */
+  struct tinysh_cmd_t *next;   /* must be set to 0 at init */
+  struct tinysh_cmd_t *child;  /* must be set to 0 at init */
+} tinysh_cmd_t;
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+extern int echo;
+
+/*
+ * function void tinysh_char_out(unsigned char) must be provided by
+ * the application
+ */
+void tinysh_char_out(unsigned char c);
+
+/*
+ * Functions below are provided by the tinysh module
+ */
+
+/* new character input */
+void tinysh_char_in(unsigned char c);
+
+/* add a new command */
+void tinysh_add_command(tinysh_cmd_t *cmd);
+
+/* change tinysh prompt */
+void tinysh_set_prompt(char *str);
+
+/* get command argument back */
+void *tinysh_get_arg();
+
+/* provide conversion string to scalar (decimal or hexadecimal) */
+unsigned long tinysh_atoxi(char *s);
+
+#ifdef __cplusplus
+}
+#endif
+
+
diff -r 000000000000 -r 964eb6a2ef00 drivers/ACS712/ACS712.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/ACS712/ACS712.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,46 @@
+#include "ACS712.h"
+
+ACS712::ACS712() : sensor(SENSOR_PIN),
+                   currentSwitch(SWITCH_PIN)
+{
+    currentSwitch = 1;      //turn off the currentSwitch (1 = off, 0 = on)
+    m = 0;
+    b = 0;
+}
+
+void ACS712::calibrate(){
+    float V1,V2,A1,A2;
+    A1 = LOW_CURRENT;
+    A2 = HIGH_CURRENT;
+    
+    currentSwitch = 1;
+    wait_ms(100);
+//wait_ms(5000);//MARK
+    V1 = read_sensor(CALIBRATION_SAMPLES,10);
+
+    currentSwitch = 0;
+    //Thread::wait(100);
+//wait_ms(5000);//MARK
+    wait_ms(100);
+    V2 = read_sensor(CALIBRATION_SAMPLES,10);
+    currentSwitch = 1;
+    m = (A2-A1)/(V2-V1);
+    b = A1 - V1*m;
+}
+float ACS712::get_current(){
+    return m*read_sensor(10,0) + b;
+}
+float ACS712::read_sensor(){
+    sensor_val = sensor.read();
+    return sensor_val;
+}
+float ACS712::read_sensor(int n, int t){
+    sensor_val = 0;
+    for(int i = 0; i<n; i++){
+        sensor_val += sensor.read();
+        wait_ms(t);
+        //Thread::wait(10);
+    }
+    sensor_val = sensor_val/float(n);
+    return sensor_val;
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/ACS712/ACS712.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/ACS712/ACS712.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,43 @@
+#ifndef ACS712_H
+#define ACS712_H
+
+/****
+    This class calculates the current drawn by the robot. It requires that EVERYTHING else is turned off when
+    calibration is in progress.
+    Requirement: Turn off mouse sensors somehow.
+*/
+
+#include "mbed.h"
+//#include "robot.h"
+
+#define HIGH_CURRENT 130       //increase of current when switch is turned on [mA]
+#define LOW_CURRENT 36          //current draw when everything is turned off [mA]
+#define SWITCH_PIN PTB18//HIGH_CURRENT_SWITCH
+#define SENSOR_PIN PTC2//CURRENTSENSOR_PIN
+
+#define CALIBRATION_SAMPLES 50 //the number of samples taken for the calibration
+
+class ACS712
+{
+private:
+
+    AnalogIn sensor;            //reads the value from current sensor
+    DigitalOut currentSwitch;   //turn this on to send current through a resistor
+    
+    float b;        //offset
+    float m;        //slope
+    float current;  //[mA]
+    float sensor_val;   //[% of 3.3V]
+    
+public:
+    
+    ACS712();
+    void calibrate();          //calculates m and b
+    float get_current();        //returns the current [mA]
+    float read_sensor();        //reads sensor [% of 3.3V]
+    float read_sensor(int n, int t);    //reads sensor <n> times and returns the average
+};
+
+
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/ADNS5090/ADNS5090.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/ADNS5090/ADNS5090.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,78 @@
+#include "ADNS5090.h"
+
+ADNS5090::ADNS5090(PinName mosi_pin, PinName miso_pin, PinName sclk_pin, PinName ncs_pin, float pxPerMM_) :
+    spi(mosi_pin, miso_pin, sclk_pin),
+    ncs(ncs_pin),
+    dx_px(0), dy_px(0),
+    pxPerMM(pxPerMM_)
+{
+    ncs = 1;
+    spi.format(8,3);
+    spi.frequency(1000000);    
+    reset();
+}
+
+
+bool ADNS5090::updateMotion()
+{
+    bool ret = false;    
+    dx_px = 0;
+    dy_px = 0;    
+    
+    ncs = 0;    
+    spi.write(ADNS5090_MOTION_ST_REG);    
+    
+    if(0x80 & spi.write(0))
+    {
+        spi.write(ADNS5090_MOTION_BURST_REG);
+        dx_px = (int8_t)spi.write(0);
+        dy_px = (int8_t)spi.write(0);
+        sq = (uint8_t)spi.write(0);
+        ret = true;
+    }
+    ncs = 1;    
+    return ret;
+}
+
+float ADNS5090::dx()
+{
+    return dx_px/pxPerMM;
+}
+
+float ADNS5090::dy()
+{
+    return dy_px/pxPerMM;
+}
+
+void ADNS5090::reset()
+{
+    ncs = 0;
+    spi.write(ADNS5090_WRITE_VAL |
+        ADNS5090_RESET_REG);
+    spi.write(ADNS5090_RESET_VAL);
+    ncs = 1;
+}
+
+void ADNS5090::powerDown()
+{
+    ncs = 0;
+    spi.write(ADNS5090_WRITE_VAL |
+        ADNS5090_MOUSE_CTRL_REG);
+    spi.write(ADNS5090_POWERDOWN_VAL);
+    ncs = 1;
+}
+
+void ADNS5090::setDPI()
+{    
+    ncs = 0;
+    spi.write(ADNS5090_WRITE_VAL|
+        ADNS5090_MOUSE_CTRL_REG);
+    spi.write(0x24);
+    ncs = 1;
+    
+    ncs = 0;
+    spi.write(ADNS5090_WRITE_VAL|
+        0x21);        
+    spi.write(0x10);
+    ncs = 1; 
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/ADNS5090/ADNS5090.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/ADNS5090/ADNS5090.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,41 @@
+#ifndef ADNS5090_H
+#define ADNS5090_H
+
+#include "stdint.h"
+#include "mbed.h"
+#include "SWSPI.h"
+
+#define ADNS5090_WRITE_VAL          (0x80)
+#define ADNS5090_MOTION_ST_REG      (0x02)
+#define ADNS5090_MOTION_BURST_REG   (0x63)
+#define ADNS5090_RESET_REG          (0x3a)
+#define ADNS5090_RESET_VAL          (0x5a)
+#define ADNS5090_MOUSE_CTRL_REG     (0x0d)
+#define ADNS5090_POWERDOWN_VAL      (0x02)
+
+
+class ADNS5090
+{
+private:
+
+    SWSPI spi;
+    DigitalOut ncs;
+    
+public:
+
+    ADNS5090(PinName mosi_pin, PinName miso_pin, PinName sclk_pin, PinName ncs_pin, float pxPerMM_);
+    
+    int8_t dx_px, dy_px;
+    uint8_t sq;  //surface quality, higher better, ~30 is good, 0= no surface
+    float pxPerMM;
+    
+    float dx();
+    float dy();
+    
+    bool updateMotion();
+    void reset();
+    void powerDown();
+    void setDPI();
+};
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 drivers/HC05/HC05.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/HC05/HC05.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,15 @@
+#include "HC05.h"
+
+HC05::HC05(PinName tx_pin, PinName rx_pin, PinName en_pin):
+    MODSERIAL(tx_pin, rx_pin),
+    on_switch(en_pin)
+{
+    //wait_ms(5000);  //mark
+    on_switch = 0;
+}
+void HC05::start(){
+    on_switch = 1;
+}
+//void HCO5::stop(){
+//    on_switch = 0;
+//}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/HC05/HC05.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/HC05/HC05.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,18 @@
+#ifndef HC05_H
+#define HC05_H
+
+#include "mbed.h"
+#include "rtos.h"
+#include "MODSERIAL.h"
+
+class HC05 : public MODSERIAL, public Mutex
+{
+private:
+public:
+    HC05(PinName tx_pin, PinName rx_pin, PinName en_pin);
+    void start();
+    void stop();
+    DigitalOut on_switch;    
+};
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/I2C/I2Cdev.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/I2C/I2Cdev.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,275 @@
+// ported from arduino library: https://github.com/jrowberg/i2cdevlib
+// written by szymon gaertig (email: szymon@gaertig.com.pl, website: szymongaertig.pl)
+// Changelog:
+// 2013-01-08 - first release
+
+#include "I2Cdev.h"
+
+//#define useDebugSerial
+
+I2Cdev::I2Cdev(): i2c(I2C_SDA,I2C_SCL)//, debugSerial(USBTX, USBRX)
+{
+
+}
+
+I2Cdev::I2Cdev(PinName i2cSda, PinName i2cScl): i2c(i2cSda,i2cScl)//, debugSerial(USBTX, USBRX)
+{
+
+}
+
+/** Read a single bit from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitNum Bit position to read (0-7)
+ * @param data Container for single bit value
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout) {
+    uint8_t b;
+    uint8_t count = readByte(devAddr, regAddr, &b, timeout);
+    *data = b & (1 << bitNum);
+    return count;
+}
+
+/** Read a single bit from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitNum Bit position to read (0-15)
+ * @param data Container for single bit value
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout) {
+    uint16_t b;
+    uint8_t count = readWord(devAddr, regAddr, &b, timeout);
+    *data = b & (1 << bitNum);
+    return count;
+}
+
+/** Read multiple bits from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitStart First bit position to read (0-7)
+ * @param length Number of bits to read (not more than 8)
+ * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05)
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout) {
+    // 01101001 read byte
+    // 76543210 bit numbers
+    //    xxx   args: bitStart=4, length=3
+    //    010   masked
+    //   -> 010 shifted
+    uint8_t count, b;
+    if ((count = readByte(devAddr, regAddr, &b, timeout)) != 0) {
+        uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+        b &= mask;
+        b >>= (bitStart - length + 1);
+        *data = b;
+    }
+    return count;
+}
+
+/** Read multiple bits from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitStart First bit position to read (0-15)
+ * @param length Number of bits to read (not more than 16)
+ * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05)
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (1 = success, 0 = failure, -1 = timeout)
+ */
+int8_t I2Cdev::readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout) {
+    // 1101011001101001 read byte
+    // fedcba9876543210 bit numbers
+    //    xxx           args: bitStart=12, length=3
+    //    010           masked
+    //           -> 010 shifted
+    uint8_t count;
+    uint16_t w;
+    if ((count = readWord(devAddr, regAddr, &w, timeout)) != 0) {
+        uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+        w &= mask;
+        w >>= (bitStart - length + 1);
+        *data = w;
+    }
+    return count;
+}
+/** Read single byte from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param data Container for byte value read from device
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout) {
+    return readBytes(devAddr, regAddr, 1, data, timeout);
+}
+
+/** Read single word from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param data Container for word value read from device
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout) {
+    return readWords(devAddr, regAddr, 1, data, timeout);
+}
+
+/** Read multiple bytes from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr First register regAddr to read from
+ * @param length Number of bytes to read
+ * @param data Buffer to store read data in
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Number of bytes read (-1 indicates failure)
+ */
+int8_t I2Cdev::readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout)
+{
+    char command[1];
+    command[0] = regAddr;
+    char *redData = (char*)malloc(length);
+    i2c.write(devAddr<<1, command, 1, true);
+    i2c.read(devAddr<<1, redData, length);
+    for(int i =0; i < length; i++) {
+        data[i] = redData[i];
+    }
+    free (redData);
+    return length;
+}
+
+int8_t I2Cdev::readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout)
+{
+    return 0;
+}
+
+/** write a single bit in an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitNum Bit position to write (0-7)
+ * @param value New bit value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data) {
+    uint8_t b;
+    readByte(devAddr, regAddr, &b);
+    b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum));
+    return writeByte(devAddr, regAddr, b);
+}
+
+/** write a single bit in a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitNum Bit position to write (0-15)
+ * @param value New bit value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data) {
+    uint16_t w;
+    readWord(devAddr, regAddr, &w);
+    w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum));
+    return writeWord(devAddr, regAddr, w);
+}
+
+/** Write multiple bits in an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitStart First bit position to write (0-7)
+ * @param length Number of bits to write (not more than 8)
+ * @param data Right-aligned value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) {
+    //      010 value to write
+    // 76543210 bit numbers
+    //    xxx   args: bitStart=4, length=3
+    // 00011100 mask byte
+    // 10101111 original value (sample)
+    // 10100011 original & ~mask
+    // 10101011 masked | value
+    uint8_t b;
+    if (readByte(devAddr, regAddr, &b) != 0) {
+        uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+        data <<= (bitStart - length + 1); // shift data into correct position
+        data &= mask; // zero all non-important bits in data
+        b &= ~(mask); // zero all important bits in existing byte
+        b |= data; // combine data with existing byte
+        return writeByte(devAddr, regAddr, b);
+    } else {
+        return false;
+    }
+}
+
+/** Write multiple bits in a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitStart First bit position to write (0-15)
+ * @param length Number of bits to write (not more than 16)
+ * @param data Right-aligned value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data) {
+    //              010 value to write
+    // fedcba9876543210 bit numbers
+    //    xxx           args: bitStart=12, length=3
+    // 0001110000000000 mask byte
+    // 1010111110010110 original value (sample)
+    // 1010001110010110 original & ~mask
+    // 1010101110010110 masked | value
+    uint16_t w;
+    if (readWord(devAddr, regAddr, &w) != 0) {
+        uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+        data <<= (bitStart - length + 1); // shift data into correct position
+        data &= mask; // zero all non-important bits in data
+        w &= ~(mask); // zero all important bits in existing word
+        w |= data; // combine data with existing word
+        return writeWord(devAddr, regAddr, w);
+    } else {
+        return false;
+    }
+}
+
+/** Write single byte to an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register address to write to
+ * @param data New byte value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data) {
+    return writeBytes(devAddr, regAddr, 1, &data);
+}
+
+/** Write single word to a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register address to write to
+ * @param data New word value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data) {
+    return writeWords(devAddr, regAddr, 1, &data);
+}
+
+bool I2Cdev::writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data)
+{
+    i2c.start();
+    i2c.write(devAddr<<1);
+    i2c.write(regAddr);
+    for(int i = 0; i < length; i++) {
+        i2c.write(data[i]);
+    }
+    i2c.stop();
+    return true;
+}
+
+bool I2Cdev::writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data)
+{
+    return true;
+}
+
+uint16_t I2Cdev::readTimeout(void)
+{
+    return 0;
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/I2C/I2Cdev.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/I2C/I2Cdev.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,44 @@
+//ported from arduino library: https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
+//written by szymon gaertig (email: szymon@gaertig.com.pl)
+//
+//Changelog: 
+//2013-01-08 - first beta release
+
+#ifndef I2Cdev_h
+#define I2Cdev_h
+
+#include "mbed.h"
+
+#define I2C_SDA PTE0
+#define I2C_SCL PTE1
+
+class I2Cdev {
+    private:
+        I2C i2c;
+        //Serial debugSerial;
+    public:
+        I2Cdev();
+        I2Cdev(PinName i2cSda, PinName i2cScl);        
+        
+        int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout());
+        int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout());
+        int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout());
+        int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout());
+        int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout());
+        int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout());
+        int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout());
+        int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout());
+
+        bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data);
+        bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data);
+        bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
+        bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
+        bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data);
+        bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data);
+        bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data);
+        bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data);
+
+        static uint16_t readTimeout(void);
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/I2C/I2Cdev2.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/I2C/I2Cdev2.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,275 @@
+// ported from arduino library: https://github.com/jrowberg/i2cdevlib
+// written by szymon gaertig (email: szymon@gaertig.com.pl, website: szymongaertig.pl)
+// Changelog:
+// 2013-01-08 - first release
+
+#include "I2Cdev2.h"
+
+//#define useDebugSerial
+
+I2Cdev2::I2Cdev2(): i2c(I2C2_SDA,I2C2_SCL)//, debugSerial(USBTX, USBRX)
+{
+
+}
+
+I2Cdev2::I2Cdev2(PinName i2cSda, PinName i2cScl): i2c(i2cSda,i2cScl)//, debugSerial(USBTX, USBRX)
+{
+
+}
+
+/** Read a single bit from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitNum Bit position to read (0-7)
+ * @param data Container for single bit value
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev2::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev2::readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout) {
+    uint8_t b;
+    uint8_t count = readByte(devAddr, regAddr, &b, timeout);
+    *data = b & (1 << bitNum);
+    return count;
+}
+
+/** Read a single bit from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitNum Bit position to read (0-15)
+ * @param data Container for single bit value
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev2::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev2::readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout) {
+    uint16_t b;
+    uint8_t count = readWord(devAddr, regAddr, &b, timeout);
+    *data = b & (1 << bitNum);
+    return count;
+}
+
+/** Read multiple bits from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitStart First bit position to read (0-7)
+ * @param length Number of bits to read (not more than 8)
+ * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05)
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev2::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev2::readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout) {
+    // 01101001 read byte
+    // 76543210 bit numbers
+    //    xxx   args: bitStart=4, length=3
+    //    010   masked
+    //   -> 010 shifted
+    uint8_t count, b;
+    if ((count = readByte(devAddr, regAddr, &b, timeout)) != 0) {
+        uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+        b &= mask;
+        b >>= (bitStart - length + 1);
+        *data = b;
+    }
+    return count;
+}
+
+/** Read multiple bits from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitStart First bit position to read (0-15)
+ * @param length Number of bits to read (not more than 16)
+ * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05)
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev2::readTimeout)
+ * @return Status of read operation (1 = success, 0 = failure, -1 = timeout)
+ */
+int8_t I2Cdev2::readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout) {
+    // 1101011001101001 read byte
+    // fedcba9876543210 bit numbers
+    //    xxx           args: bitStart=12, length=3
+    //    010           masked
+    //           -> 010 shifted
+    uint8_t count;
+    uint16_t w;
+    if ((count = readWord(devAddr, regAddr, &w, timeout)) != 0) {
+        uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+        w &= mask;
+        w >>= (bitStart - length + 1);
+        *data = w;
+    }
+    return count;
+}
+/** Read single byte from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param data Container for byte value read from device
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev2::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev2::readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout) {
+    return readBytes(devAddr, regAddr, 1, data, timeout);
+}
+
+/** Read single word from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param data Container for word value read from device
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev2::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev2::readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout) {
+    return readWords(devAddr, regAddr, 1, data, timeout);
+}
+
+/** Read multiple bytes from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr First register regAddr to read from
+ * @param length Number of bytes to read
+ * @param data Buffer to store read data in
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev2::readTimeout)
+ * @return Number of bytes read (-1 indicates failure)
+ */
+int8_t I2Cdev2::readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout)
+{
+    char command[1];
+    command[0] = regAddr;
+    char *redData = (char*)malloc(length);
+    i2c.write(devAddr<<1, command, 1, true);
+    i2c.read(devAddr<<1, redData, length);
+    for(int i =0; i < length; i++) {
+        data[i] = redData[i];
+    }
+    free (redData);
+    return length;
+}
+
+int8_t I2Cdev2::readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout)
+{
+    return 0;
+}
+
+/** write a single bit in an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitNum Bit position to write (0-7)
+ * @param value New bit value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev2::writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data) {
+    uint8_t b;
+    readByte(devAddr, regAddr, &b);
+    b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum));
+    return writeByte(devAddr, regAddr, b);
+}
+
+/** write a single bit in a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitNum Bit position to write (0-15)
+ * @param value New bit value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev2::writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data) {
+    uint16_t w;
+    readWord(devAddr, regAddr, &w);
+    w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum));
+    return writeWord(devAddr, regAddr, w);
+}
+
+/** Write multiple bits in an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitStart First bit position to write (0-7)
+ * @param length Number of bits to write (not more than 8)
+ * @param data Right-aligned value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev2::writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) {
+    //      010 value to write
+    // 76543210 bit numbers
+    //    xxx   args: bitStart=4, length=3
+    // 00011100 mask byte
+    // 10101111 original value (sample)
+    // 10100011 original & ~mask
+    // 10101011 masked | value
+    uint8_t b;
+    if (readByte(devAddr, regAddr, &b) != 0) {
+        uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+        data <<= (bitStart - length + 1); // shift data into correct position
+        data &= mask; // zero all non-important bits in data
+        b &= ~(mask); // zero all important bits in existing byte
+        b |= data; // combine data with existing byte
+        return writeByte(devAddr, regAddr, b);
+    } else {
+        return false;
+    }
+}
+
+/** Write multiple bits in a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitStart First bit position to write (0-15)
+ * @param length Number of bits to write (not more than 16)
+ * @param data Right-aligned value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev2::writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data) {
+    //              010 value to write
+    // fedcba9876543210 bit numbers
+    //    xxx           args: bitStart=12, length=3
+    // 0001110000000000 mask byte
+    // 1010111110010110 original value (sample)
+    // 1010001110010110 original & ~mask
+    // 1010101110010110 masked | value
+    uint16_t w;
+    if (readWord(devAddr, regAddr, &w) != 0) {
+        uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+        data <<= (bitStart - length + 1); // shift data into correct position
+        data &= mask; // zero all non-important bits in data
+        w &= ~(mask); // zero all important bits in existing word
+        w |= data; // combine data with existing word
+        return writeWord(devAddr, regAddr, w);
+    } else {
+        return false;
+    }
+}
+
+/** Write single byte to an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register address to write to
+ * @param data New byte value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev2::writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data) {
+    return writeBytes(devAddr, regAddr, 1, &data);
+}
+
+/** Write single word to a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register address to write to
+ * @param data New word value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev2::writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data) {
+    return writeWords(devAddr, regAddr, 1, &data);
+}
+
+bool I2Cdev2::writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data)
+{
+    i2c.start();
+    i2c.write(devAddr<<1);
+    i2c.write(regAddr);
+    for(int i = 0; i < length; i++) {
+        i2c.write(data[i]);
+    }
+    i2c.stop();
+    return true;
+}
+
+bool I2Cdev2::writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data)
+{
+    return true;
+}
+
+uint16_t I2Cdev2::readTimeout(void)
+{
+    return 0;
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/I2C/I2Cdev2.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/I2C/I2Cdev2.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,44 @@
+//ported from arduino library: https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
+//written by szymon gaertig (email: szymon@gaertig.com.pl)
+//
+//Changelog: 
+//2013-01-08 - first beta release
+
+#ifndef I2Cdev2_h
+#define I2Cdev2_h
+
+#include "mbed.h"
+
+#define I2C2_SDA PTC9
+#define I2C2_SCL PTC8
+
+class I2Cdev2 {
+    private:
+        I2C i2c;
+        //Serial debugSerial;
+    public:
+        I2Cdev2();
+        I2Cdev2(PinName i2cSda, PinName i2cScl);        
+        
+        int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev2::readTimeout());
+        int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev2::readTimeout());
+        int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev2::readTimeout());
+        int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev2::readTimeout());
+        int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev2::readTimeout());
+        int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev2::readTimeout());
+        int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev2::readTimeout());
+        int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev2::readTimeout());
+
+        bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data);
+        bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data);
+        bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
+        bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
+        bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data);
+        bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data);
+        bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data);
+        bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data);
+
+        static uint16_t readTimeout(void);
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/MPU/inc/MPU6050.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/MPU/inc/MPU6050.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,1006 @@
+//ported from arduino library: https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
+//written by szymon gaertig (email: szymon@gaertig.com.pl)
+//
+//Changelog: 
+//2013-01-08 - first beta release
+
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+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.
+===============================================
+*/
+
+#ifndef _MPU6050_H_
+#define _MPU6050_H_
+
+#include "I2Cdev.h"
+#include "helper_3dmath.h"
+
+#define MPU6050_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU6050_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU6050_DEFAULT_ADDRESS     MPU6050_ADDRESS_AD0_LOW
+
+#define MPU6050_RA_XG_OFFS_TC       0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_YG_OFFS_TC       0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_ZG_OFFS_TC       0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_X_FINE_GAIN      0x03 //[7:0] X_FINE_GAIN
+#define MPU6050_RA_Y_FINE_GAIN      0x04 //[7:0] Y_FINE_GAIN
+#define MPU6050_RA_Z_FINE_GAIN      0x05 //[7:0] Z_FINE_GAIN
+#define MPU6050_RA_XA_OFFS_H        0x06 //[15:0] XA_OFFS
+#define MPU6050_RA_XA_OFFS_L_TC     0x07
+#define MPU6050_RA_YA_OFFS_H        0x08 //[15:0] YA_OFFS
+#define MPU6050_RA_YA_OFFS_L_TC     0x09
+#define MPU6050_RA_ZA_OFFS_H        0x0A //[15:0] ZA_OFFS
+#define MPU6050_RA_ZA_OFFS_L_TC     0x0B
+#define MPU6050_RA_XG_OFFS_USRH     0x13 //[15:0] XG_OFFS_USR
+#define MPU6050_RA_XG_OFFS_USRL     0x14
+#define MPU6050_RA_YG_OFFS_USRH     0x15 //[15:0] YG_OFFS_USR
+#define MPU6050_RA_YG_OFFS_USRL     0x16
+#define MPU6050_RA_ZG_OFFS_USRH     0x17 //[15:0] ZG_OFFS_USR
+#define MPU6050_RA_ZG_OFFS_USRL     0x18
+#define MPU6050_RA_SMPLRT_DIV       0x19
+#define MPU6050_RA_CONFIG           0x1A
+#define MPU6050_RA_GYRO_CONFIG      0x1B
+#define MPU6050_RA_ACCEL_CONFIG     0x1C
+#define MPU6050_RA_FF_THR           0x1D
+#define MPU6050_RA_FF_DUR           0x1E
+#define MPU6050_RA_MOT_THR          0x1F
+#define MPU6050_RA_MOT_DUR          0x20
+#define MPU6050_RA_ZRMOT_THR        0x21
+#define MPU6050_RA_ZRMOT_DUR        0x22
+#define MPU6050_RA_FIFO_EN          0x23
+#define MPU6050_RA_I2C_MST_CTRL     0x24
+#define MPU6050_RA_I2C_SLV0_ADDR    0x25
+#define MPU6050_RA_I2C_SLV0_REG     0x26
+#define MPU6050_RA_I2C_SLV0_CTRL    0x27
+#define MPU6050_RA_I2C_SLV1_ADDR    0x28
+#define MPU6050_RA_I2C_SLV1_REG     0x29
+#define MPU6050_RA_I2C_SLV1_CTRL    0x2A
+#define MPU6050_RA_I2C_SLV2_ADDR    0x2B
+#define MPU6050_RA_I2C_SLV2_REG     0x2C
+#define MPU6050_RA_I2C_SLV2_CTRL    0x2D
+#define MPU6050_RA_I2C_SLV3_ADDR    0x2E
+#define MPU6050_RA_I2C_SLV3_REG     0x2F
+#define MPU6050_RA_I2C_SLV3_CTRL    0x30
+#define MPU6050_RA_I2C_SLV4_ADDR    0x31
+#define MPU6050_RA_I2C_SLV4_REG     0x32
+#define MPU6050_RA_I2C_SLV4_DO      0x33
+#define MPU6050_RA_I2C_SLV4_CTRL    0x34
+#define MPU6050_RA_I2C_SLV4_DI      0x35
+#define MPU6050_RA_I2C_MST_STATUS   0x36
+#define MPU6050_RA_INT_PIN_CFG      0x37
+#define MPU6050_RA_INT_ENABLE       0x38
+#define MPU6050_RA_DMP_INT_STATUS   0x39
+#define MPU6050_RA_INT_STATUS       0x3A
+
+#define MPU6050_RA_ACCEL_XOUT_H     0x3B
+#define MPU6050_RA_ACCEL_XOUT_L     0x3C
+#define MPU6050_RA_ACCEL_YOUT_H     0x3D
+#define MPU6050_RA_ACCEL_YOUT_L     0x3E
+#define MPU6050_RA_ACCEL_ZOUT_H     0x3F
+#define MPU6050_RA_ACCEL_ZOUT_L     0x40
+
+#define MPU6050_RA_TEMP_OUT_H       0x41
+#define MPU6050_RA_TEMP_OUT_L       0x42
+
+#define MPU6050_RA_GYRO_XOUT_H      0x43
+#define MPU6050_RA_GYRO_XOUT_L      0x44
+#define MPU6050_RA_GYRO_YOUT_H      0x45
+#define MPU6050_RA_GYRO_YOUT_L      0x46
+#define MPU6050_RA_GYRO_ZOUT_H      0x47
+#define MPU6050_RA_GYRO_ZOUT_L      0x48
+
+#define MPU9150_RA_MAG_ADDRESS      0x0C
+#define MPU9150_RA_MAG_XOUT_L       0x03
+#define MPU9150_RA_MAG_XOUT_H       0x04
+#define MPU9150_RA_MAG_YOUT_L       0x05
+#define MPU9150_RA_MAG_YOUT_H       0x06
+#define MPU9150_RA_MAG_ZOUT_L       0x07
+#define MPU9150_RA_MAG_ZOUT_H       0x08
+
+#define MPU6050_RA_EXT_SENS_DATA_00 0x49
+#define MPU6050_RA_EXT_SENS_DATA_01 0x4A
+#define MPU6050_RA_EXT_SENS_DATA_02 0x4B
+#define MPU6050_RA_EXT_SENS_DATA_03 0x4C
+#define MPU6050_RA_EXT_SENS_DATA_04 0x4D
+#define MPU6050_RA_EXT_SENS_DATA_05 0x4E
+#define MPU6050_RA_EXT_SENS_DATA_06 0x4F
+#define MPU6050_RA_EXT_SENS_DATA_07 0x50
+#define MPU6050_RA_EXT_SENS_DATA_08 0x51
+#define MPU6050_RA_EXT_SENS_DATA_09 0x52
+#define MPU6050_RA_EXT_SENS_DATA_10 0x53
+#define MPU6050_RA_EXT_SENS_DATA_11 0x54
+#define MPU6050_RA_EXT_SENS_DATA_12 0x55
+#define MPU6050_RA_EXT_SENS_DATA_13 0x56
+#define MPU6050_RA_EXT_SENS_DATA_14 0x57
+#define MPU6050_RA_EXT_SENS_DATA_15 0x58
+#define MPU6050_RA_EXT_SENS_DATA_16 0x59
+#define MPU6050_RA_EXT_SENS_DATA_17 0x5A
+#define MPU6050_RA_EXT_SENS_DATA_18 0x5B
+#define MPU6050_RA_EXT_SENS_DATA_19 0x5C
+#define MPU6050_RA_EXT_SENS_DATA_20 0x5D
+#define MPU6050_RA_EXT_SENS_DATA_21 0x5E
+#define MPU6050_RA_EXT_SENS_DATA_22 0x5F
+#define MPU6050_RA_EXT_SENS_DATA_23 0x60
+#define MPU6050_RA_MOT_DETECT_STATUS    0x61
+#define MPU6050_RA_I2C_SLV0_DO      0x63
+#define MPU6050_RA_I2C_SLV1_DO      0x64
+#define MPU6050_RA_I2C_SLV2_DO      0x65
+#define MPU6050_RA_I2C_SLV3_DO      0x66
+#define MPU6050_RA_I2C_MST_DELAY_CTRL   0x67
+#define MPU6050_RA_SIGNAL_PATH_RESET    0x68
+#define MPU6050_RA_MOT_DETECT_CTRL      0x69
+#define MPU6050_RA_USER_CTRL        0x6A
+#define MPU6050_RA_PWR_MGMT_1       0x6B
+#define MPU6050_RA_PWR_MGMT_2       0x6C
+#define MPU6050_RA_BANK_SEL         0x6D
+#define MPU6050_RA_MEM_START_ADDR   0x6E
+#define MPU6050_RA_MEM_R_W          0x6F
+#define MPU6050_RA_DMP_CFG_1        0x70
+#define MPU6050_RA_DMP_CFG_2        0x71
+#define MPU6050_RA_FIFO_COUNTH      0x72
+#define MPU6050_RA_FIFO_COUNTL      0x73
+#define MPU6050_RA_FIFO_R_W         0x74
+#define MPU6050_RA_WHO_AM_I         0x75
+
+#define MPU6050_TC_PWR_MODE_BIT     7
+#define MPU6050_TC_OFFSET_BIT       6
+#define MPU6050_TC_OFFSET_LENGTH    6
+#define MPU6050_TC_OTP_BNK_VLD_BIT  0
+
+#define MPU6050_VDDIO_LEVEL_VLOGIC  0
+#define MPU6050_VDDIO_LEVEL_VDD     1
+
+#define MPU6050_CFG_EXT_SYNC_SET_BIT    5
+#define MPU6050_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU6050_CFG_DLPF_CFG_BIT    2
+#define MPU6050_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU6050_EXT_SYNC_DISABLED       0x0
+#define MPU6050_EXT_SYNC_TEMP_OUT_L     0x1
+#define MPU6050_EXT_SYNC_GYRO_XOUT_L    0x2
+#define MPU6050_EXT_SYNC_GYRO_YOUT_L    0x3
+#define MPU6050_EXT_SYNC_GYRO_ZOUT_L    0x4
+#define MPU6050_EXT_SYNC_ACCEL_XOUT_L   0x5
+#define MPU6050_EXT_SYNC_ACCEL_YOUT_L   0x6
+#define MPU6050_EXT_SYNC_ACCEL_ZOUT_L   0x7
+
+#define MPU6050_DLPF_BW_256         0x00
+#define MPU6050_DLPF_BW_188         0x01
+#define MPU6050_DLPF_BW_98          0x02
+#define MPU6050_DLPF_BW_42          0x03
+#define MPU6050_DLPF_BW_20          0x04
+#define MPU6050_DLPF_BW_10          0x05
+#define MPU6050_DLPF_BW_5           0x06
+
+#define MPU6050_GCONFIG_FS_SEL_BIT      4
+#define MPU6050_GCONFIG_FS_SEL_LENGTH   2
+
+#define MPU6050_GYRO_FS_250         0x00
+#define MPU6050_GYRO_FS_500         0x01
+#define MPU6050_GYRO_FS_1000        0x02
+#define MPU6050_GYRO_FS_2000        0x03
+
+#define MPU6050_ACONFIG_XA_ST_BIT           7
+#define MPU6050_ACONFIG_YA_ST_BIT           6
+#define MPU6050_ACONFIG_ZA_ST_BIT           5
+#define MPU6050_ACONFIG_AFS_SEL_BIT         4
+#define MPU6050_ACONFIG_AFS_SEL_LENGTH      2
+#define MPU6050_ACONFIG_ACCEL_HPF_BIT       2
+#define MPU6050_ACONFIG_ACCEL_HPF_LENGTH    3
+
+#define MPU6050_ACCEL_FS_2          0x00
+#define MPU6050_ACCEL_FS_4          0x01
+#define MPU6050_ACCEL_FS_8          0x02
+#define MPU6050_ACCEL_FS_16         0x03
+
+#define MPU6050_DHPF_RESET          0x00
+#define MPU6050_DHPF_5              0x01
+#define MPU6050_DHPF_2P5            0x02
+#define MPU6050_DHPF_1P25           0x03
+#define MPU6050_DHPF_0P63           0x04
+#define MPU6050_DHPF_HOLD           0x07
+
+#define MPU6050_TEMP_FIFO_EN_BIT    7
+#define MPU6050_XG_FIFO_EN_BIT      6
+#define MPU6050_YG_FIFO_EN_BIT      5
+#define MPU6050_ZG_FIFO_EN_BIT      4
+#define MPU6050_ACCEL_FIFO_EN_BIT   3
+#define MPU6050_SLV2_FIFO_EN_BIT    2
+#define MPU6050_SLV1_FIFO_EN_BIT    1
+#define MPU6050_SLV0_FIFO_EN_BIT    0
+
+#define MPU6050_MULT_MST_EN_BIT     7
+#define MPU6050_WAIT_FOR_ES_BIT     6
+#define MPU6050_SLV_3_FIFO_EN_BIT   5
+#define MPU6050_I2C_MST_P_NSR_BIT   4
+#define MPU6050_I2C_MST_CLK_BIT     3
+#define MPU6050_I2C_MST_CLK_LENGTH  4
+
+#define MPU6050_CLOCK_DIV_348       0x0
+#define MPU6050_CLOCK_DIV_333       0x1
+#define MPU6050_CLOCK_DIV_320       0x2
+#define MPU6050_CLOCK_DIV_308       0x3
+#define MPU6050_CLOCK_DIV_296       0x4
+#define MPU6050_CLOCK_DIV_286       0x5
+#define MPU6050_CLOCK_DIV_276       0x6
+#define MPU6050_CLOCK_DIV_267       0x7
+#define MPU6050_CLOCK_DIV_258       0x8
+#define MPU6050_CLOCK_DIV_500       0x9
+#define MPU6050_CLOCK_DIV_471       0xA
+#define MPU6050_CLOCK_DIV_444       0xB
+#define MPU6050_CLOCK_DIV_421       0xC
+#define MPU6050_CLOCK_DIV_400       0xD
+#define MPU6050_CLOCK_DIV_381       0xE
+#define MPU6050_CLOCK_DIV_364       0xF
+
+#define MPU6050_I2C_SLV_RW_BIT      7
+#define MPU6050_I2C_SLV_ADDR_BIT    6
+#define MPU6050_I2C_SLV_ADDR_LENGTH 7
+#define MPU6050_I2C_SLV_EN_BIT      7
+#define MPU6050_I2C_SLV_BYTE_SW_BIT 6
+#define MPU6050_I2C_SLV_REG_DIS_BIT 5
+#define MPU6050_I2C_SLV_GRP_BIT     4
+#define MPU6050_I2C_SLV_LEN_BIT     3
+#define MPU6050_I2C_SLV_LEN_LENGTH  4
+
+#define MPU6050_I2C_SLV4_RW_BIT         7
+#define MPU6050_I2C_SLV4_ADDR_BIT       6
+#define MPU6050_I2C_SLV4_ADDR_LENGTH    7
+#define MPU6050_I2C_SLV4_EN_BIT         7
+#define MPU6050_I2C_SLV4_INT_EN_BIT     6
+#define MPU6050_I2C_SLV4_REG_DIS_BIT    5
+#define MPU6050_I2C_SLV4_MST_DLY_BIT    4
+#define MPU6050_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU6050_MST_PASS_THROUGH_BIT    7
+#define MPU6050_MST_I2C_SLV4_DONE_BIT   6
+#define MPU6050_MST_I2C_LOST_ARB_BIT    5
+#define MPU6050_MST_I2C_SLV4_NACK_BIT   4
+#define MPU6050_MST_I2C_SLV3_NACK_BIT   3
+#define MPU6050_MST_I2C_SLV2_NACK_BIT   2
+#define MPU6050_MST_I2C_SLV1_NACK_BIT   1
+#define MPU6050_MST_I2C_SLV0_NACK_BIT   0
+
+#define MPU6050_INTCFG_INT_LEVEL_BIT        7
+#define MPU6050_INTCFG_INT_OPEN_BIT         6
+#define MPU6050_INTCFG_LATCH_INT_EN_BIT     5
+#define MPU6050_INTCFG_INT_RD_CLEAR_BIT     4
+#define MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT  3
+#define MPU6050_INTCFG_FSYNC_INT_EN_BIT     2
+#define MPU6050_INTCFG_I2C_BYPASS_EN_BIT    1
+#define MPU6050_INTCFG_CLKOUT_EN_BIT        0
+
+#define MPU6050_INTMODE_ACTIVEHIGH  0x00
+#define MPU6050_INTMODE_ACTIVELOW   0x01
+
+#define MPU6050_INTDRV_PUSHPULL     0x00
+#define MPU6050_INTDRV_OPENDRAIN    0x01
+
+#define MPU6050_INTLATCH_50USPULSE  0x00
+#define MPU6050_INTLATCH_WAITCLEAR  0x01
+
+#define MPU6050_INTCLEAR_STATUSREAD 0x00
+#define MPU6050_INTCLEAR_ANYREAD    0x01
+
+#define MPU6050_INTERRUPT_FF_BIT            7
+#define MPU6050_INTERRUPT_MOT_BIT           6
+#define MPU6050_INTERRUPT_ZMOT_BIT          5
+#define MPU6050_INTERRUPT_FIFO_OFLOW_BIT    4
+#define MPU6050_INTERRUPT_I2C_MST_INT_BIT   3
+#define MPU6050_INTERRUPT_PLL_RDY_INT_BIT   2
+#define MPU6050_INTERRUPT_DMP_INT_BIT       1
+#define MPU6050_INTERRUPT_DATA_RDY_BIT      0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU6050_DMPINT_5_BIT            5
+#define MPU6050_DMPINT_4_BIT            4
+#define MPU6050_DMPINT_3_BIT            3
+#define MPU6050_DMPINT_2_BIT            2
+#define MPU6050_DMPINT_1_BIT            1
+#define MPU6050_DMPINT_0_BIT            0
+
+#define MPU6050_MOTION_MOT_XNEG_BIT     7
+#define MPU6050_MOTION_MOT_XPOS_BIT     6
+#define MPU6050_MOTION_MOT_YNEG_BIT     5
+#define MPU6050_MOTION_MOT_YPOS_BIT     4
+#define MPU6050_MOTION_MOT_ZNEG_BIT     3
+#define MPU6050_MOTION_MOT_ZPOS_BIT     2
+#define MPU6050_MOTION_MOT_ZRMOT_BIT    0
+
+#define MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT   7
+#define MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT   4
+#define MPU6050_DELAYCTRL_I2C_SLV3_DLY_EN_BIT   3
+#define MPU6050_DELAYCTRL_I2C_SLV2_DLY_EN_BIT   2
+#define MPU6050_DELAYCTRL_I2C_SLV1_DLY_EN_BIT   1
+#define MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT   0
+
+#define MPU6050_PATHRESET_GYRO_RESET_BIT    2
+#define MPU6050_PATHRESET_ACCEL_RESET_BIT   1
+#define MPU6050_PATHRESET_TEMP_RESET_BIT    0
+
+#define MPU6050_DETECT_ACCEL_ON_DELAY_BIT       5
+#define MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH    2
+#define MPU6050_DETECT_FF_COUNT_BIT             3
+#define MPU6050_DETECT_FF_COUNT_LENGTH          2
+#define MPU6050_DETECT_MOT_COUNT_BIT            1
+#define MPU6050_DETECT_MOT_COUNT_LENGTH         2
+
+#define MPU6050_DETECT_DECREMENT_RESET  0x0
+#define MPU6050_DETECT_DECREMENT_1      0x1
+#define MPU6050_DETECT_DECREMENT_2      0x2
+#define MPU6050_DETECT_DECREMENT_4      0x3
+
+#define MPU6050_USERCTRL_DMP_EN_BIT             7
+#define MPU6050_USERCTRL_FIFO_EN_BIT            6
+#define MPU6050_USERCTRL_I2C_MST_EN_BIT         5
+#define MPU6050_USERCTRL_I2C_IF_DIS_BIT         4
+#define MPU6050_USERCTRL_DMP_RESET_BIT          3
+#define MPU6050_USERCTRL_FIFO_RESET_BIT         2
+#define MPU6050_USERCTRL_I2C_MST_RESET_BIT      1
+#define MPU6050_USERCTRL_SIG_COND_RESET_BIT     0
+
+#define MPU6050_PWR1_DEVICE_RESET_BIT   7
+#define MPU6050_PWR1_SLEEP_BIT          6
+#define MPU6050_PWR1_CYCLE_BIT          5
+#define MPU6050_PWR1_TEMP_DIS_BIT       3
+#define MPU6050_PWR1_CLKSEL_BIT         2
+#define MPU6050_PWR1_CLKSEL_LENGTH      3
+
+#define MPU6050_CLOCK_INTERNAL          0x00
+#define MPU6050_CLOCK_PLL_XGYRO         0x01
+#define MPU6050_CLOCK_PLL_YGYRO         0x02
+#define MPU6050_CLOCK_PLL_ZGYRO         0x03
+#define MPU6050_CLOCK_PLL_EXT32K        0x04
+#define MPU6050_CLOCK_PLL_EXT19M        0x05
+#define MPU6050_CLOCK_KEEP_RESET        0x07
+
+#define MPU6050_PWR2_LP_WAKE_CTRL_BIT       7
+#define MPU6050_PWR2_LP_WAKE_CTRL_LENGTH    2
+#define MPU6050_PWR2_STBY_XA_BIT            5
+#define MPU6050_PWR2_STBY_YA_BIT            4
+#define MPU6050_PWR2_STBY_ZA_BIT            3
+#define MPU6050_PWR2_STBY_XG_BIT            2
+#define MPU6050_PWR2_STBY_YG_BIT            1
+#define MPU6050_PWR2_STBY_ZG_BIT            0
+
+#define MPU6050_WAKE_FREQ_1P25      0x0
+#define MPU6050_WAKE_FREQ_2P5       0x1
+#define MPU6050_WAKE_FREQ_5         0x2
+#define MPU6050_WAKE_FREQ_10        0x3
+
+#define MPU6050_BANKSEL_PRFTCH_EN_BIT       6
+#define MPU6050_BANKSEL_CFG_USER_BANK_BIT   5
+#define MPU6050_BANKSEL_MEM_SEL_BIT         4
+#define MPU6050_BANKSEL_MEM_SEL_LENGTH      5
+
+#define MPU6050_WHO_AM_I_BIT        6
+#define MPU6050_WHO_AM_I_LENGTH     6
+
+#define MPU6050_DMP_MEMORY_BANKS        8
+#define MPU6050_DMP_MEMORY_BANK_SIZE    256
+#define MPU6050_DMP_MEMORY_CHUNK_SIZE   16
+
+// note: DMP code memory blocks defined at end of header file
+
+class MPU6050 {
+    private:
+        I2Cdev i2Cdev;
+//        Serial debugSerial;
+    public:
+        MPU6050();
+        MPU6050(uint8_t address);
+
+        void initialize();
+        bool testConnection();
+
+        // AUX_VDDIO register
+        uint8_t getAuxVDDIOLevel();
+        void setAuxVDDIOLevel(uint8_t level);
+
+        // SMPLRT_DIV register
+        uint8_t getRate();
+        void setRate(uint8_t rate);
+
+        // CONFIG register
+        uint8_t getExternalFrameSync();
+        void setExternalFrameSync(uint8_t sync);
+        uint8_t getDLPFMode();
+        void setDLPFMode(uint8_t bandwidth);
+
+        // GYRO_CONFIG register
+        uint8_t getFullScaleGyroRange();
+        void setFullScaleGyroRange(uint8_t range);
+
+        // ACCEL_CONFIG register
+        bool getAccelXSelfTest();
+        void setAccelXSelfTest(bool enabled);
+        bool getAccelYSelfTest();
+        void setAccelYSelfTest(bool enabled);
+        bool getAccelZSelfTest();
+        void setAccelZSelfTest(bool enabled);
+        uint8_t getFullScaleAccelRange();
+        void setFullScaleAccelRange(uint8_t range);
+        uint8_t getDHPFMode();
+        void setDHPFMode(uint8_t mode);
+
+        // FF_THR register
+        uint8_t getFreefallDetectionThreshold();
+        void setFreefallDetectionThreshold(uint8_t threshold);
+
+        // FF_DUR register
+        uint8_t getFreefallDetectionDuration();
+        void setFreefallDetectionDuration(uint8_t duration);
+
+        // MOT_THR register
+        uint8_t getMotionDetectionThreshold();
+        void setMotionDetectionThreshold(uint8_t threshold);
+
+        // MOT_DUR register
+        uint8_t getMotionDetectionDuration();
+        void setMotionDetectionDuration(uint8_t duration);
+
+        // ZRMOT_THR register
+        uint8_t getZeroMotionDetectionThreshold();
+        void setZeroMotionDetectionThreshold(uint8_t threshold);
+
+        // ZRMOT_DUR register
+        uint8_t getZeroMotionDetectionDuration();
+        void setZeroMotionDetectionDuration(uint8_t duration);
+
+        // FIFO_EN register
+        bool getTempFIFOEnabled();
+        void setTempFIFOEnabled(bool enabled);
+        bool getXGyroFIFOEnabled();
+        void setXGyroFIFOEnabled(bool enabled);
+        bool getYGyroFIFOEnabled();
+        void setYGyroFIFOEnabled(bool enabled);
+        bool getZGyroFIFOEnabled();
+        void setZGyroFIFOEnabled(bool enabled);
+        bool getAccelFIFOEnabled();
+        void setAccelFIFOEnabled(bool enabled);
+        bool getSlave2FIFOEnabled();
+        void setSlave2FIFOEnabled(bool enabled);
+        bool getSlave1FIFOEnabled();
+        void setSlave1FIFOEnabled(bool enabled);
+        bool getSlave0FIFOEnabled();
+        void setSlave0FIFOEnabled(bool enabled);
+
+        // I2C_MST_CTRL register
+        bool getMultiMasterEnabled();
+        void setMultiMasterEnabled(bool enabled);
+        bool getWaitForExternalSensorEnabled();
+        void setWaitForExternalSensorEnabled(bool enabled);
+        bool getSlave3FIFOEnabled();
+        void setSlave3FIFOEnabled(bool enabled);
+        bool getSlaveReadWriteTransitionEnabled();
+        void setSlaveReadWriteTransitionEnabled(bool enabled);
+        uint8_t getMasterClockSpeed();
+        void setMasterClockSpeed(uint8_t speed);
+
+        // I2C_SLV* registers (Slave 0-3)
+        uint8_t getSlaveAddress(uint8_t num);
+        void setSlaveAddress(uint8_t num, uint8_t address);
+        uint8_t getSlaveRegister(uint8_t num);
+        void setSlaveRegister(uint8_t num, uint8_t reg);
+        bool getSlaveEnabled(uint8_t num);
+        void setSlaveEnabled(uint8_t num, bool enabled);
+        bool getSlaveWordByteSwap(uint8_t num);
+        void setSlaveWordByteSwap(uint8_t num, bool enabled);
+        bool getSlaveWriteMode(uint8_t num);
+        void setSlaveWriteMode(uint8_t num, bool mode);
+        bool getSlaveWordGroupOffset(uint8_t num);
+        void setSlaveWordGroupOffset(uint8_t num, bool enabled);
+        uint8_t getSlaveDataLength(uint8_t num);
+        void setSlaveDataLength(uint8_t num, uint8_t length);
+
+        // I2C_SLV* registers (Slave 4)
+        uint8_t getSlave4Address();
+        void setSlave4Address(uint8_t address);
+        uint8_t getSlave4Register();
+        void setSlave4Register(uint8_t reg);
+        void setSlave4OutputByte(uint8_t data);
+        bool getSlave4Enabled();
+        void setSlave4Enabled(bool enabled);
+        bool getSlave4InterruptEnabled();
+        void setSlave4InterruptEnabled(bool enabled);
+        bool getSlave4WriteMode();
+        void setSlave4WriteMode(bool mode);
+        uint8_t getSlave4MasterDelay();
+        void setSlave4MasterDelay(uint8_t delay);
+        uint8_t getSlate4InputByte();
+
+        // I2C_MST_STATUS register
+        bool getPassthroughStatus();
+        bool getSlave4IsDone();
+        bool getLostArbitration();
+        bool getSlave4Nack();
+        bool getSlave3Nack();
+        bool getSlave2Nack();
+        bool getSlave1Nack();
+        bool getSlave0Nack();
+
+        // INT_PIN_CFG register
+        bool getInterruptMode();
+        void setInterruptMode(bool mode);
+        bool getInterruptDrive();
+        void setInterruptDrive(bool drive);
+        bool getInterruptLatch();
+        void setInterruptLatch(bool latch);
+        bool getInterruptLatchClear();
+        void setInterruptLatchClear(bool clear);
+        bool getFSyncInterruptLevel();
+        void setFSyncInterruptLevel(bool level);
+        bool getFSyncInterruptEnabled();
+        void setFSyncInterruptEnabled(bool enabled);
+        bool getI2CBypassEnabled();
+        void setI2CBypassEnabled(bool enabled);
+        bool getClockOutputEnabled();
+        void setClockOutputEnabled(bool enabled);
+
+        // INT_ENABLE register
+        uint8_t getIntEnabled();
+        void setIntEnabled(uint8_t enabled);
+        bool getIntFreefallEnabled();
+        void setIntFreefallEnabled(bool enabled);
+        bool getIntMotionEnabled();
+        void setIntMotionEnabled(bool enabled);
+        bool getIntZeroMotionEnabled();
+        void setIntZeroMotionEnabled(bool enabled);
+        bool getIntFIFOBufferOverflowEnabled();
+        void setIntFIFOBufferOverflowEnabled(bool enabled);
+        bool getIntI2CMasterEnabled();
+        void setIntI2CMasterEnabled(bool enabled);
+        bool getIntDataReadyEnabled();
+        void setIntDataReadyEnabled(bool enabled);
+
+        // INT_STATUS register
+        uint8_t getIntStatus();
+        bool getIntFreefallStatus();
+        bool getIntMotionStatus();
+        bool getIntZeroMotionStatus();
+        bool getIntFIFOBufferOverflowStatus();
+        bool getIntI2CMasterStatus();
+        bool getIntDataReadyStatus();
+
+        // ACCEL_*OUT_* registers
+        void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+        void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+        void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getAccelerationX();
+        int16_t getAccelerationY();
+        int16_t getAccelerationZ();
+
+        // TEMP_OUT_* registers
+        int16_t getTemperature();
+
+        // GYRO_*OUT_* registers
+        void getRotation(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getRotationX();
+        int16_t getRotationY();
+        int16_t getRotationZ();
+
+        // EXT_SENS_DATA_* registers
+        uint8_t getExternalSensorByte(int position);
+        uint16_t getExternalSensorWord(int position);
+        uint32_t getExternalSensorDWord(int position);
+
+        // MOT_DETECT_STATUS register
+        bool getXNegMotionDetected();
+        bool getXPosMotionDetected();
+        bool getYNegMotionDetected();
+        bool getYPosMotionDetected();
+        bool getZNegMotionDetected();
+        bool getZPosMotionDetected();
+        bool getZeroMotionDetected();
+
+        // I2C_SLV*_DO register
+        void setSlaveOutputByte(uint8_t num, uint8_t data);
+
+        // I2C_MST_DELAY_CTRL register
+        bool getExternalShadowDelayEnabled();
+        void setExternalShadowDelayEnabled(bool enabled);
+        bool getSlaveDelayEnabled(uint8_t num);
+        void setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+        // SIGNAL_PATH_RESET register
+        void resetGyroscopePath();
+        void resetAccelerometerPath();
+        void resetTemperaturePath();
+
+        // MOT_DETECT_CTRL register
+        uint8_t getAccelerometerPowerOnDelay();
+        void setAccelerometerPowerOnDelay(uint8_t delay);
+        uint8_t getFreefallDetectionCounterDecrement();
+        void setFreefallDetectionCounterDecrement(uint8_t decrement);
+        uint8_t getMotionDetectionCounterDecrement();
+        void setMotionDetectionCounterDecrement(uint8_t decrement);
+
+        // USER_CTRL register
+        bool getFIFOEnabled();
+        void setFIFOEnabled(bool enabled);
+        bool getI2CMasterModeEnabled();
+        void setI2CMasterModeEnabled(bool enabled);
+        void switchSPIEnabled(bool enabled);
+        void resetFIFO();
+        void resetI2CMaster();
+        void resetSensors();
+
+        // PWR_MGMT_1 register
+        void reset();
+        bool getSleepEnabled();
+        void setSleepEnabled(bool enabled);
+        bool getWakeCycleEnabled();
+        void setWakeCycleEnabled(bool enabled);
+        bool getTempSensorEnabled();
+        void setTempSensorEnabled(bool enabled);
+        uint8_t getClockSource();
+        void setClockSource(uint8_t source);
+
+        // PWR_MGMT_2 register
+        uint8_t getWakeFrequency();
+        void setWakeFrequency(uint8_t frequency);
+        bool getStandbyXAccelEnabled();
+        void setStandbyXAccelEnabled(bool enabled);
+        bool getStandbyYAccelEnabled();
+        void setStandbyYAccelEnabled(bool enabled);
+        bool getStandbyZAccelEnabled();
+        void setStandbyZAccelEnabled(bool enabled);
+        bool getStandbyXGyroEnabled();
+        void setStandbyXGyroEnabled(bool enabled);
+        bool getStandbyYGyroEnabled();
+        void setStandbyYGyroEnabled(bool enabled);
+        bool getStandbyZGyroEnabled();
+        void setStandbyZGyroEnabled(bool enabled);
+
+        // FIFO_COUNT_* registers
+        uint16_t getFIFOCount();
+
+        // FIFO_R_W register
+        uint8_t getFIFOByte();
+        void setFIFOByte(uint8_t data);
+        void getFIFOBytes(uint8_t *data, uint8_t length);
+
+        // WHO_AM_I register
+        uint8_t getDeviceID();
+        void setDeviceID(uint8_t id);
+        
+        // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+        
+        // XG_OFFS_TC register
+        uint8_t getOTPBankValid();
+        void setOTPBankValid(bool enabled);
+        int8_t getXGyroOffset();
+        void setXGyroOffset(int8_t offset);
+
+        // YG_OFFS_TC register
+        int8_t getYGyroOffset();
+        void setYGyroOffset(int8_t offset);
+
+        // ZG_OFFS_TC register
+        int8_t getZGyroOffset();
+        void setZGyroOffset(int8_t offset);
+
+        // X_FINE_GAIN register
+        int8_t getXFineGain();
+        void setXFineGain(int8_t gain);
+
+        // Y_FINE_GAIN register
+        int8_t getYFineGain();
+        void setYFineGain(int8_t gain);
+
+        // Z_FINE_GAIN register
+        int8_t getZFineGain();
+        void setZFineGain(int8_t gain);
+
+        // XA_OFFS_* registers
+        int16_t getXAccelOffset();
+        void setXAccelOffset(int16_t offset);
+
+        // YA_OFFS_* register
+        int16_t getYAccelOffset();
+        void setYAccelOffset(int16_t offset);
+
+        // ZA_OFFS_* register
+        int16_t getZAccelOffset();
+        void setZAccelOffset(int16_t offset);
+
+        // XG_OFFS_USR* registers
+        int16_t getXGyroOffsetUser();
+        void setXGyroOffsetUser(int16_t offset);
+
+        // YG_OFFS_USR* register
+        int16_t getYGyroOffsetUser();
+        void setYGyroOffsetUser(int16_t offset);
+
+        // ZG_OFFS_USR* register
+        int16_t getZGyroOffsetUser();
+        void setZGyroOffsetUser(int16_t offset);
+        
+        // INT_ENABLE register (DMP functions)
+        bool getIntPLLReadyEnabled();
+        void setIntPLLReadyEnabled(bool enabled);
+        bool getIntDMPEnabled();
+        void setIntDMPEnabled(bool enabled);
+        
+        // DMP_INT_STATUS
+        bool getDMPInt5Status();
+        bool getDMPInt4Status();
+        bool getDMPInt3Status();
+        bool getDMPInt2Status();
+        bool getDMPInt1Status();
+        bool getDMPInt0Status();
+
+        // INT_STATUS register (DMP functions)
+        bool getIntPLLReadyStatus();
+        bool getIntDMPStatus();
+        
+        // USER_CTRL register (DMP functions)
+        bool getDMPEnabled();
+        void setDMPEnabled(bool enabled);
+        void resetDMP();
+        
+        // BANK_SEL register
+        void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false);
+        
+        // MEM_START_ADDR register
+        void setMemoryStartAddress(uint8_t address);
+        
+        // MEM_R_W register
+        uint8_t readMemoryByte();
+        void writeMemoryByte(uint8_t data);
+        void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0);
+        bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false);
+        bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true);
+
+        bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false);
+        bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+        // DMP_CFG_1 register
+        uint8_t getDMPConfig1();
+        void setDMPConfig1(uint8_t config);
+
+        // DMP_CFG_2 register
+        uint8_t getDMPConfig2();
+        void setDMPConfig2(uint8_t config);
+
+        // special methods for MotionApps 2.0 implementation
+        #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS20
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+        // special methods for MotionApps 4.1 implementation
+        #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS41
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+    private:
+        uint8_t devAddr;
+        uint8_t buffer[14];
+};
+
+#endif /* _MPU6050_H_ */
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/MPU/inc/MPU6050_6Axis_MotionApps20.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/MPU/inc/MPU6050_6Axis_MotionApps20.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,385 @@
+// I2Cdev library collection - MPU6050 I2C device class, 6-axis MotionApps 2.0 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 5/20/2013 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+ 
+/* ============================================
+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.
+===============================================
+*/
+
+//#include "tasks.h"
+
+#ifndef _MPU6050_6AXIS_MOTIONAPPS20_H_
+#define _MPU6050_6AXIS_MOTIONAPPS20_H_
+
+//#include <iostream>
+
+#include "I2Cdev.h"
+#include "helper_3dmath.h"
+
+// MotionApps 2.0 DMP implementation, built using the MPU-6050EVB evaluation board
+#define MPU6050_INCLUDE_DMP_MOTIONAPPS20
+
+#include "MPU6050.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifndef __arm__
+    #include <avr/pgmspace.h>
+#else
+    // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+    #ifndef __PGMSPACE_H_
+        #define __PGMSPACE_H_ 1
+        #include <inttypes.h>
+
+        #define PROGMEM
+        #define PGM_P  const char *
+        #define PSTR(str) (str)
+        #define F(x) x
+
+        typedef void prog_void;
+        typedef char prog_char;
+        typedef unsigned char prog_uchar;
+        typedef int8_t prog_int8_t;
+        typedef uint8_t prog_uint8_t;
+        typedef int16_t prog_int16_t;
+        typedef uint16_t prog_uint16_t;
+        typedef int32_t prog_int32_t;
+        typedef uint32_t prog_uint32_t;
+        
+        #define strcpy_P(dest, src) strcpy((dest), (src))
+        #define strcat_P(dest, src) strcat((dest), (src))
+        #define strcmp_P(a, b) strcmp((a), (b))
+        
+        #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+        #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+        #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+        #define pgm_read_float(addr) (*(const float *)(addr))
+        
+        #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+        #define pgm_read_word_near(addr) pgm_read_word(addr)
+        #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+        #define pgm_read_float_near(addr) pgm_read_float(addr)
+        #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+        #define pgm_read_word_far(addr) pgm_read_word(addr)
+        #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+        #define pgm_read_float_far(addr) pgm_read_float(addr)
+    #endif
+#endif
+
+/* Source is from the InvenSense MotionApps v2 demo code. Original source is
+ * unavailable, unless you happen to be amazing as decompiling binary by
+ * hand (in which case, please contact me, and I'm totally serious).
+ *
+ * Also, I'd like to offer many, many thanks to Noah Zerkin for all of the
+ * DMP reverse-engineering he did to help make this bit of wizardry
+ * possible.
+ */
+
+// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size.
+// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno)
+// after moving string constants to flash memory storage using the F()
+// compiler macro (Arduino IDE 1.0+ required).
+
+//#define DEBUG
+#ifdef DEBUG
+    #define DEBUG_PRINT(x) pc.printf(x)   //Serial.print(x)
+    #define DEBUG_PRINTF(x, y) pc.printf(x,y)   //Serial.print(x, y)
+
+    #define F(x) x
+#else
+    #define DEBUG_PRINT(x)
+    #define DEBUG_PRINTF(x, y)
+
+#endif
+
+#define MPU6050_DMP_CODE_SIZE       1929    // dmpMemory[]
+#define MPU6050_DMP_CONFIG_SIZE     192     // dmpConfig[]
+#define MPU6050_DMP_UPDATES_SIZE    47      // dmpUpdates[]
+
+/* ================================================================================================ *
+ | Default MotionApps v2.0 42-byte FIFO packet structure:                                           |
+ |                                                                                                  |
+ | [QUAT W][      ][QUAT X][      ][QUAT Y][      ][QUAT Z][      ][GYRO X][      ][GYRO Y][      ] |
+ |   0   1   2   3   4   5   6   7   8   9  10  11  12  13  14  15  16  17  18  19  20  21  22  23  |
+ |                                                                                                  |
+ | [GYRO Z][      ][ACC X ][      ][ACC Y ][      ][ACC Z ][      ][      ]                         |
+ |  24  25  26  27  28  29  30  31  32  33  34  35  36  37  38  39  40  41                          |
+ * ================================================================================================ */
+
+// this block of memory gets written to the MPU on start-up, and it seems
+// to be volatile memory, so it has to be done each time (it only takes ~1
+// second though)
+const unsigned char dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = {
+    // bank 0, 256 bytes
+    0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+    0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+    0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+    0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+    0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+    0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+    0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+    0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+
+    // bank 1, 256 bytes
+    0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+    0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+    0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+    0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+
+    // bank 2, 256 bytes
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+
+    // bank 3, 256 bytes
+    0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F,
+    0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2,
+    0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF,
+    0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C,
+    0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1,
+    0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01,
+    0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80,
+    0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C,
+    0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80,
+    0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E,
+    0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9,
+    0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24,
+    0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0,
+    0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86,
+    0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+    0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+
+    // bank 4, 256 bytes
+    0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+    0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+    0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+    0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+    0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+    0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+    0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+    0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+    0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+    0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+    0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+    0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+    0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+    0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+    0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+    0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+
+    // bank 5, 256 bytes
+    0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+    0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+    0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+    0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+    0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+    0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+    0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+    0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+    0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A,
+    0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60,
+    0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97,
+    0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04,
+    0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78,
+    0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79,
+    0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68,
+    0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68,
+
+    // bank 6, 256 bytes
+    0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04,
+    0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66,
+    0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31,
+    0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60,
+    0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76,
+    0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56,
+    0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD,
+    0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91,
+    0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8,
+    0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE,
+    0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9,
+    0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD,
+    0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E,
+    0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8,
+    0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89,
+    0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79,
+
+    // bank 7, 138 bytes (remainder)
+    0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8,
+    0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA,
+    0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB,
+    0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3,
+    0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3,
+    0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+    0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, 0xA3,
+    0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC,
+    0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
+};
+
+// thanks to Noah Zerkin for piecing this stuff together!
+const unsigned char dmpConfig[MPU6050_DMP_CONFIG_SIZE] PROGMEM = {
+//  BANK    OFFSET  LENGTH  [DATA]
+    0x03,   0x7B,   0x03,   0x4C, 0xCD, 0x6C,         // FCFG_1 inv_set_gyro_calibration
+    0x03,   0xAB,   0x03,   0x36, 0x56, 0x76,         // FCFG_3 inv_set_gyro_calibration
+    0x00,   0x68,   0x04,   0x02, 0xCB, 0x47, 0xA2,   // D_0_104 inv_set_gyro_calibration
+    0x02,   0x18,   0x04,   0x00, 0x05, 0x8B, 0xC1,   // D_0_24 inv_set_gyro_calibration
+    0x01,   0x0C,   0x04,   0x00, 0x00, 0x00, 0x00,   // D_1_152 inv_set_accel_calibration
+    0x03,   0x7F,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_accel_calibration
+    0x03,   0x89,   0x03,   0x26, 0x46, 0x66,         // FCFG_7 inv_set_accel_calibration
+    0x00,   0x6C,   0x02,   0x20, 0x00,               // D_0_108 inv_set_accel_calibration
+    0x02,   0x40,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_00 inv_set_compass_calibration
+    0x02,   0x44,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_01
+    0x02,   0x48,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_02
+    0x02,   0x4C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_10
+    0x02,   0x50,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_11
+    0x02,   0x54,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_12
+    0x02,   0x58,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_20
+    0x02,   0x5C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_21
+    0x02,   0xBC,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_22
+    0x01,   0xEC,   0x04,   0x00, 0x00, 0x40, 0x00,   // D_1_236 inv_apply_endian_accel
+    0x03,   0x7F,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
+    0x04,   0x02,   0x03,   0x0D, 0x35, 0x5D,         // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
+    0x04,   0x09,   0x04,   0x87, 0x2D, 0x35, 0x3D,   // FCFG_5 inv_set_bias_update
+    0x00,   0xA3,   0x01,   0x00,                     // D_0_163 inv_set_dead_zone
+                 // SPECIAL 0x01 = enable interrupts
+    0x00,   0x00,   0x00,   0x01, // SET INT_ENABLE at i=22, SPECIAL INSTRUCTION
+    0x07,   0x86,   0x01,   0xFE,                     // CFG_6 inv_set_fifo_interupt
+    0x07,   0x41,   0x05,   0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
+    0x07,   0x7E,   0x01,   0x30,                     // CFG_16 inv_set_footer
+    0x07,   0x46,   0x01,   0x9A,                     // CFG_GYRO_SOURCE inv_send_gyro
+    0x07,   0x47,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_9 inv_send_gyro -> inv_construct3_fifo
+    0x07,   0x6C,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_12 inv_send_accel -> inv_construct3_fifo
+    0x02,   0x16,   0x02,   0x00, 0x07                // D_0_22 inv_set_fifo_rate
+
+    // This very last 0x01 WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz,
+    // 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data.
+    // DMP output frequency is calculated easily using this equation: (200Hz / (1 + value))
+
+    // It is important to make sure the host processor can keep up with reading and processing
+    // the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea.
+};
+
+const unsigned char dmpUpdates[MPU6050_DMP_UPDATES_SIZE] PROGMEM = {
+    0x01,   0xB2,   0x02,   0xFF, 0xFF,
+    0x01,   0x90,   0x04,   0x09, 0x23, 0xA1, 0x35,
+    0x01,   0x6A,   0x02,   0x06, 0x00,
+    0x01,   0x60,   0x08,   0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00,   0x60,   0x04,   0x40, 0x00, 0x00, 0x00,
+    0x01,   0x62,   0x02,   0x00, 0x00,
+    0x00,   0x60,   0x04,   0x00, 0x40, 0x00, 0x00
+};
+
+/* See MPU6050 under MotionApps 2.0 Section */
+
+// uint8_t MPU6050::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6050::dmpGetFIFORate();
+// uint8_t MPU6050::dmpGetSampleStepSizeMS();
+// uint8_t MPU6050::dmpGetSampleFrequency();
+// int32_t MPU6050::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6050::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6050::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6050::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6050::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+// uint8_t MPU6050::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6050::dmpGetLinearAccel(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGravity(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetEIS(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpSetFIFOProcessedCallback(void (*func) (void));
+// uint8_t MPU6050::dmpInitFIFOParam();
+// uint8_t MPU6050::dmpCloseFIFO();
+// uint8_t MPU6050::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6050::dmpDecodeQuantizedAccel();
+// uint32_t MPU6050::dmpGetGyroSumOfSquare();
+// uint32_t MPU6050::dmpGetAccelSumOfSquare();
+// void MPU6050::dmpOverrideQuaternion(long *q);
+
+
+#endif /* _MPU6050_6AXIS_MOTIONAPPS20_H_ */
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/MPU/inc/MPU6051.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/MPU/inc/MPU6051.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,1006 @@
+//ported from arduino library: https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
+//written by szymon gaertig (email: szymon@gaertig.com.pl)
+//
+//Changelog: 
+//2013-01-08 - first beta release
+
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+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.
+===============================================
+*/
+
+#ifndef _MPU6051_H_
+#define _MPU6051_H_
+
+#include "I2Cdev2.h"
+#include "helper_3dmath.h"
+
+#define MPU6050_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU6050_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU6050_DEFAULT_ADDRESS     MPU6050_ADDRESS_AD0_LOW
+
+#define MPU6050_RA_XG_OFFS_TC       0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_YG_OFFS_TC       0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_ZG_OFFS_TC       0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_X_FINE_GAIN      0x03 //[7:0] X_FINE_GAIN
+#define MPU6050_RA_Y_FINE_GAIN      0x04 //[7:0] Y_FINE_GAIN
+#define MPU6050_RA_Z_FINE_GAIN      0x05 //[7:0] Z_FINE_GAIN
+#define MPU6050_RA_XA_OFFS_H        0x06 //[15:0] XA_OFFS
+#define MPU6050_RA_XA_OFFS_L_TC     0x07
+#define MPU6050_RA_YA_OFFS_H        0x08 //[15:0] YA_OFFS
+#define MPU6050_RA_YA_OFFS_L_TC     0x09
+#define MPU6050_RA_ZA_OFFS_H        0x0A //[15:0] ZA_OFFS
+#define MPU6050_RA_ZA_OFFS_L_TC     0x0B
+#define MPU6050_RA_XG_OFFS_USRH     0x13 //[15:0] XG_OFFS_USR
+#define MPU6050_RA_XG_OFFS_USRL     0x14
+#define MPU6050_RA_YG_OFFS_USRH     0x15 //[15:0] YG_OFFS_USR
+#define MPU6050_RA_YG_OFFS_USRL     0x16
+#define MPU6050_RA_ZG_OFFS_USRH     0x17 //[15:0] ZG_OFFS_USR
+#define MPU6050_RA_ZG_OFFS_USRL     0x18
+#define MPU6050_RA_SMPLRT_DIV       0x19
+#define MPU6050_RA_CONFIG           0x1A
+#define MPU6050_RA_GYRO_CONFIG      0x1B
+#define MPU6050_RA_ACCEL_CONFIG     0x1C
+#define MPU6050_RA_FF_THR           0x1D
+#define MPU6050_RA_FF_DUR           0x1E
+#define MPU6050_RA_MOT_THR          0x1F
+#define MPU6050_RA_MOT_DUR          0x20
+#define MPU6050_RA_ZRMOT_THR        0x21
+#define MPU6050_RA_ZRMOT_DUR        0x22
+#define MPU6050_RA_FIFO_EN          0x23
+#define MPU6050_RA_I2C_MST_CTRL     0x24
+#define MPU6050_RA_I2C_SLV0_ADDR    0x25
+#define MPU6050_RA_I2C_SLV0_REG     0x26
+#define MPU6050_RA_I2C_SLV0_CTRL    0x27
+#define MPU6050_RA_I2C_SLV1_ADDR    0x28
+#define MPU6050_RA_I2C_SLV1_REG     0x29
+#define MPU6050_RA_I2C_SLV1_CTRL    0x2A
+#define MPU6050_RA_I2C_SLV2_ADDR    0x2B
+#define MPU6050_RA_I2C_SLV2_REG     0x2C
+#define MPU6050_RA_I2C_SLV2_CTRL    0x2D
+#define MPU6050_RA_I2C_SLV3_ADDR    0x2E
+#define MPU6050_RA_I2C_SLV3_REG     0x2F
+#define MPU6050_RA_I2C_SLV3_CTRL    0x30
+#define MPU6050_RA_I2C_SLV4_ADDR    0x31
+#define MPU6050_RA_I2C_SLV4_REG     0x32
+#define MPU6050_RA_I2C_SLV4_DO      0x33
+#define MPU6050_RA_I2C_SLV4_CTRL    0x34
+#define MPU6050_RA_I2C_SLV4_DI      0x35
+#define MPU6050_RA_I2C_MST_STATUS   0x36
+#define MPU6050_RA_INT_PIN_CFG      0x37
+#define MPU6050_RA_INT_ENABLE       0x38
+#define MPU6050_RA_DMP_INT_STATUS   0x39
+#define MPU6050_RA_INT_STATUS       0x3A
+
+#define MPU6050_RA_ACCEL_XOUT_H     0x3B
+#define MPU6050_RA_ACCEL_XOUT_L     0x3C
+#define MPU6050_RA_ACCEL_YOUT_H     0x3D
+#define MPU6050_RA_ACCEL_YOUT_L     0x3E
+#define MPU6050_RA_ACCEL_ZOUT_H     0x3F
+#define MPU6050_RA_ACCEL_ZOUT_L     0x40
+
+#define MPU6050_RA_TEMP_OUT_H       0x41
+#define MPU6050_RA_TEMP_OUT_L       0x42
+
+#define MPU6050_RA_GYRO_XOUT_H      0x43
+#define MPU6050_RA_GYRO_XOUT_L      0x44
+#define MPU6050_RA_GYRO_YOUT_H      0x45
+#define MPU6050_RA_GYRO_YOUT_L      0x46
+#define MPU6050_RA_GYRO_ZOUT_H      0x47
+#define MPU6050_RA_GYRO_ZOUT_L      0x48
+
+#define MPU9150_RA_MAG_ADDRESS      0x0C
+#define MPU9150_RA_MAG_XOUT_L       0x03
+#define MPU9150_RA_MAG_XOUT_H       0x04
+#define MPU9150_RA_MAG_YOUT_L       0x05
+#define MPU9150_RA_MAG_YOUT_H       0x06
+#define MPU9150_RA_MAG_ZOUT_L       0x07
+#define MPU9150_RA_MAG_ZOUT_H       0x08
+
+#define MPU6050_RA_EXT_SENS_DATA_00 0x49
+#define MPU6050_RA_EXT_SENS_DATA_01 0x4A
+#define MPU6050_RA_EXT_SENS_DATA_02 0x4B
+#define MPU6050_RA_EXT_SENS_DATA_03 0x4C
+#define MPU6050_RA_EXT_SENS_DATA_04 0x4D
+#define MPU6050_RA_EXT_SENS_DATA_05 0x4E
+#define MPU6050_RA_EXT_SENS_DATA_06 0x4F
+#define MPU6050_RA_EXT_SENS_DATA_07 0x50
+#define MPU6050_RA_EXT_SENS_DATA_08 0x51
+#define MPU6050_RA_EXT_SENS_DATA_09 0x52
+#define MPU6050_RA_EXT_SENS_DATA_10 0x53
+#define MPU6050_RA_EXT_SENS_DATA_11 0x54
+#define MPU6050_RA_EXT_SENS_DATA_12 0x55
+#define MPU6050_RA_EXT_SENS_DATA_13 0x56
+#define MPU6050_RA_EXT_SENS_DATA_14 0x57
+#define MPU6050_RA_EXT_SENS_DATA_15 0x58
+#define MPU6050_RA_EXT_SENS_DATA_16 0x59
+#define MPU6050_RA_EXT_SENS_DATA_17 0x5A
+#define MPU6050_RA_EXT_SENS_DATA_18 0x5B
+#define MPU6050_RA_EXT_SENS_DATA_19 0x5C
+#define MPU6050_RA_EXT_SENS_DATA_20 0x5D
+#define MPU6050_RA_EXT_SENS_DATA_21 0x5E
+#define MPU6050_RA_EXT_SENS_DATA_22 0x5F
+#define MPU6050_RA_EXT_SENS_DATA_23 0x60
+#define MPU6050_RA_MOT_DETECT_STATUS    0x61
+#define MPU6050_RA_I2C_SLV0_DO      0x63
+#define MPU6050_RA_I2C_SLV1_DO      0x64
+#define MPU6050_RA_I2C_SLV2_DO      0x65
+#define MPU6050_RA_I2C_SLV3_DO      0x66
+#define MPU6050_RA_I2C_MST_DELAY_CTRL   0x67
+#define MPU6050_RA_SIGNAL_PATH_RESET    0x68
+#define MPU6050_RA_MOT_DETECT_CTRL      0x69
+#define MPU6050_RA_USER_CTRL        0x6A
+#define MPU6050_RA_PWR_MGMT_1       0x6B
+#define MPU6050_RA_PWR_MGMT_2       0x6C
+#define MPU6050_RA_BANK_SEL         0x6D
+#define MPU6050_RA_MEM_START_ADDR   0x6E
+#define MPU6050_RA_MEM_R_W          0x6F
+#define MPU6050_RA_DMP_CFG_1        0x70
+#define MPU6050_RA_DMP_CFG_2        0x71
+#define MPU6050_RA_FIFO_COUNTH      0x72
+#define MPU6050_RA_FIFO_COUNTL      0x73
+#define MPU6050_RA_FIFO_R_W         0x74
+#define MPU6050_RA_WHO_AM_I         0x75
+
+#define MPU6050_TC_PWR_MODE_BIT     7
+#define MPU6050_TC_OFFSET_BIT       6
+#define MPU6050_TC_OFFSET_LENGTH    6
+#define MPU6050_TC_OTP_BNK_VLD_BIT  0
+
+#define MPU6050_VDDIO_LEVEL_VLOGIC  0
+#define MPU6050_VDDIO_LEVEL_VDD     1
+
+#define MPU6050_CFG_EXT_SYNC_SET_BIT    5
+#define MPU6050_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU6050_CFG_DLPF_CFG_BIT    2
+#define MPU6050_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU6050_EXT_SYNC_DISABLED       0x0
+#define MPU6050_EXT_SYNC_TEMP_OUT_L     0x1
+#define MPU6050_EXT_SYNC_GYRO_XOUT_L    0x2
+#define MPU6050_EXT_SYNC_GYRO_YOUT_L    0x3
+#define MPU6050_EXT_SYNC_GYRO_ZOUT_L    0x4
+#define MPU6050_EXT_SYNC_ACCEL_XOUT_L   0x5
+#define MPU6050_EXT_SYNC_ACCEL_YOUT_L   0x6
+#define MPU6050_EXT_SYNC_ACCEL_ZOUT_L   0x7
+
+#define MPU6050_DLPF_BW_256         0x00
+#define MPU6050_DLPF_BW_188         0x01
+#define MPU6050_DLPF_BW_98          0x02
+#define MPU6050_DLPF_BW_42          0x03
+#define MPU6050_DLPF_BW_20          0x04
+#define MPU6050_DLPF_BW_10          0x05
+#define MPU6050_DLPF_BW_5           0x06
+
+#define MPU6050_GCONFIG_FS_SEL_BIT      4
+#define MPU6050_GCONFIG_FS_SEL_LENGTH   2
+
+#define MPU6050_GYRO_FS_250         0x00
+#define MPU6050_GYRO_FS_500         0x01
+#define MPU6050_GYRO_FS_1000        0x02
+#define MPU6050_GYRO_FS_2000        0x03
+
+#define MPU6050_ACONFIG_XA_ST_BIT           7
+#define MPU6050_ACONFIG_YA_ST_BIT           6
+#define MPU6050_ACONFIG_ZA_ST_BIT           5
+#define MPU6050_ACONFIG_AFS_SEL_BIT         4
+#define MPU6050_ACONFIG_AFS_SEL_LENGTH      2
+#define MPU6050_ACONFIG_ACCEL_HPF_BIT       2
+#define MPU6050_ACONFIG_ACCEL_HPF_LENGTH    3
+
+#define MPU6050_ACCEL_FS_2          0x00
+#define MPU6050_ACCEL_FS_4          0x01
+#define MPU6050_ACCEL_FS_8          0x02
+#define MPU6050_ACCEL_FS_16         0x03
+
+#define MPU6050_DHPF_RESET          0x00
+#define MPU6050_DHPF_5              0x01
+#define MPU6050_DHPF_2P5            0x02
+#define MPU6050_DHPF_1P25           0x03
+#define MPU6050_DHPF_0P63           0x04
+#define MPU6050_DHPF_HOLD           0x07
+
+#define MPU6050_TEMP_FIFO_EN_BIT    7
+#define MPU6050_XG_FIFO_EN_BIT      6
+#define MPU6050_YG_FIFO_EN_BIT      5
+#define MPU6050_ZG_FIFO_EN_BIT      4
+#define MPU6050_ACCEL_FIFO_EN_BIT   3
+#define MPU6050_SLV2_FIFO_EN_BIT    2
+#define MPU6050_SLV1_FIFO_EN_BIT    1
+#define MPU6050_SLV0_FIFO_EN_BIT    0
+
+#define MPU6050_MULT_MST_EN_BIT     7
+#define MPU6050_WAIT_FOR_ES_BIT     6
+#define MPU6050_SLV_3_FIFO_EN_BIT   5
+#define MPU6050_I2C_MST_P_NSR_BIT   4
+#define MPU6050_I2C_MST_CLK_BIT     3
+#define MPU6050_I2C_MST_CLK_LENGTH  4
+
+#define MPU6050_CLOCK_DIV_348       0x0
+#define MPU6050_CLOCK_DIV_333       0x1
+#define MPU6050_CLOCK_DIV_320       0x2
+#define MPU6050_CLOCK_DIV_308       0x3
+#define MPU6050_CLOCK_DIV_296       0x4
+#define MPU6050_CLOCK_DIV_286       0x5
+#define MPU6050_CLOCK_DIV_276       0x6
+#define MPU6050_CLOCK_DIV_267       0x7
+#define MPU6050_CLOCK_DIV_258       0x8
+#define MPU6050_CLOCK_DIV_500       0x9
+#define MPU6050_CLOCK_DIV_471       0xA
+#define MPU6050_CLOCK_DIV_444       0xB
+#define MPU6050_CLOCK_DIV_421       0xC
+#define MPU6050_CLOCK_DIV_400       0xD
+#define MPU6050_CLOCK_DIV_381       0xE
+#define MPU6050_CLOCK_DIV_364       0xF
+
+#define MPU6050_I2C_SLV_RW_BIT      7
+#define MPU6050_I2C_SLV_ADDR_BIT    6
+#define MPU6050_I2C_SLV_ADDR_LENGTH 7
+#define MPU6050_I2C_SLV_EN_BIT      7
+#define MPU6050_I2C_SLV_BYTE_SW_BIT 6
+#define MPU6050_I2C_SLV_REG_DIS_BIT 5
+#define MPU6050_I2C_SLV_GRP_BIT     4
+#define MPU6050_I2C_SLV_LEN_BIT     3
+#define MPU6050_I2C_SLV_LEN_LENGTH  4
+
+#define MPU6050_I2C_SLV4_RW_BIT         7
+#define MPU6050_I2C_SLV4_ADDR_BIT       6
+#define MPU6050_I2C_SLV4_ADDR_LENGTH    7
+#define MPU6050_I2C_SLV4_EN_BIT         7
+#define MPU6050_I2C_SLV4_INT_EN_BIT     6
+#define MPU6050_I2C_SLV4_REG_DIS_BIT    5
+#define MPU6050_I2C_SLV4_MST_DLY_BIT    4
+#define MPU6050_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU6050_MST_PASS_THROUGH_BIT    7
+#define MPU6050_MST_I2C_SLV4_DONE_BIT   6
+#define MPU6050_MST_I2C_LOST_ARB_BIT    5
+#define MPU6050_MST_I2C_SLV4_NACK_BIT   4
+#define MPU6050_MST_I2C_SLV3_NACK_BIT   3
+#define MPU6050_MST_I2C_SLV2_NACK_BIT   2
+#define MPU6050_MST_I2C_SLV1_NACK_BIT   1
+#define MPU6050_MST_I2C_SLV0_NACK_BIT   0
+
+#define MPU6050_INTCFG_INT_LEVEL_BIT        7
+#define MPU6050_INTCFG_INT_OPEN_BIT         6
+#define MPU6050_INTCFG_LATCH_INT_EN_BIT     5
+#define MPU6050_INTCFG_INT_RD_CLEAR_BIT     4
+#define MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT  3
+#define MPU6050_INTCFG_FSYNC_INT_EN_BIT     2
+#define MPU6050_INTCFG_I2C_BYPASS_EN_BIT    1
+#define MPU6050_INTCFG_CLKOUT_EN_BIT        0
+
+#define MPU6050_INTMODE_ACTIVEHIGH  0x00
+#define MPU6050_INTMODE_ACTIVELOW   0x01
+
+#define MPU6050_INTDRV_PUSHPULL     0x00
+#define MPU6050_INTDRV_OPENDRAIN    0x01
+
+#define MPU6050_INTLATCH_50USPULSE  0x00
+#define MPU6050_INTLATCH_WAITCLEAR  0x01
+
+#define MPU6050_INTCLEAR_STATUSREAD 0x00
+#define MPU6050_INTCLEAR_ANYREAD    0x01
+
+#define MPU6050_INTERRUPT_FF_BIT            7
+#define MPU6050_INTERRUPT_MOT_BIT           6
+#define MPU6050_INTERRUPT_ZMOT_BIT          5
+#define MPU6050_INTERRUPT_FIFO_OFLOW_BIT    4
+#define MPU6050_INTERRUPT_I2C_MST_INT_BIT   3
+#define MPU6050_INTERRUPT_PLL_RDY_INT_BIT   2
+#define MPU6050_INTERRUPT_DMP_INT_BIT       1
+#define MPU6050_INTERRUPT_DATA_RDY_BIT      0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU6050_DMPINT_5_BIT            5
+#define MPU6050_DMPINT_4_BIT            4
+#define MPU6050_DMPINT_3_BIT            3
+#define MPU6050_DMPINT_2_BIT            2
+#define MPU6050_DMPINT_1_BIT            1
+#define MPU6050_DMPINT_0_BIT            0
+
+#define MPU6050_MOTION_MOT_XNEG_BIT     7
+#define MPU6050_MOTION_MOT_XPOS_BIT     6
+#define MPU6050_MOTION_MOT_YNEG_BIT     5
+#define MPU6050_MOTION_MOT_YPOS_BIT     4
+#define MPU6050_MOTION_MOT_ZNEG_BIT     3
+#define MPU6050_MOTION_MOT_ZPOS_BIT     2
+#define MPU6050_MOTION_MOT_ZRMOT_BIT    0
+
+#define MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT   7
+#define MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT   4
+#define MPU6050_DELAYCTRL_I2C_SLV3_DLY_EN_BIT   3
+#define MPU6050_DELAYCTRL_I2C_SLV2_DLY_EN_BIT   2
+#define MPU6050_DELAYCTRL_I2C_SLV1_DLY_EN_BIT   1
+#define MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT   0
+
+#define MPU6050_PATHRESET_GYRO_RESET_BIT    2
+#define MPU6050_PATHRESET_ACCEL_RESET_BIT   1
+#define MPU6050_PATHRESET_TEMP_RESET_BIT    0
+
+#define MPU6050_DETECT_ACCEL_ON_DELAY_BIT       5
+#define MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH    2
+#define MPU6050_DETECT_FF_COUNT_BIT             3
+#define MPU6050_DETECT_FF_COUNT_LENGTH          2
+#define MPU6050_DETECT_MOT_COUNT_BIT            1
+#define MPU6050_DETECT_MOT_COUNT_LENGTH         2
+
+#define MPU6050_DETECT_DECREMENT_RESET  0x0
+#define MPU6050_DETECT_DECREMENT_1      0x1
+#define MPU6050_DETECT_DECREMENT_2      0x2
+#define MPU6050_DETECT_DECREMENT_4      0x3
+
+#define MPU6050_USERCTRL_DMP_EN_BIT             7
+#define MPU6050_USERCTRL_FIFO_EN_BIT            6
+#define MPU6050_USERCTRL_I2C_MST_EN_BIT         5
+#define MPU6050_USERCTRL_I2C_IF_DIS_BIT         4
+#define MPU6050_USERCTRL_DMP_RESET_BIT          3
+#define MPU6050_USERCTRL_FIFO_RESET_BIT         2
+#define MPU6050_USERCTRL_I2C_MST_RESET_BIT      1
+#define MPU6050_USERCTRL_SIG_COND_RESET_BIT     0
+
+#define MPU6050_PWR1_DEVICE_RESET_BIT   7
+#define MPU6050_PWR1_SLEEP_BIT          6
+#define MPU6050_PWR1_CYCLE_BIT          5
+#define MPU6050_PWR1_TEMP_DIS_BIT       3
+#define MPU6050_PWR1_CLKSEL_BIT         2
+#define MPU6050_PWR1_CLKSEL_LENGTH      3
+
+#define MPU6050_CLOCK_INTERNAL          0x00
+#define MPU6050_CLOCK_PLL_XGYRO         0x01
+#define MPU6050_CLOCK_PLL_YGYRO         0x02
+#define MPU6050_CLOCK_PLL_ZGYRO         0x03
+#define MPU6050_CLOCK_PLL_EXT32K        0x04
+#define MPU6050_CLOCK_PLL_EXT19M        0x05
+#define MPU6050_CLOCK_KEEP_RESET        0x07
+
+#define MPU6050_PWR2_LP_WAKE_CTRL_BIT       7
+#define MPU6050_PWR2_LP_WAKE_CTRL_LENGTH    2
+#define MPU6050_PWR2_STBY_XA_BIT            5
+#define MPU6050_PWR2_STBY_YA_BIT            4
+#define MPU6050_PWR2_STBY_ZA_BIT            3
+#define MPU6050_PWR2_STBY_XG_BIT            2
+#define MPU6050_PWR2_STBY_YG_BIT            1
+#define MPU6050_PWR2_STBY_ZG_BIT            0
+
+#define MPU6050_WAKE_FREQ_1P25      0x0
+#define MPU6050_WAKE_FREQ_2P5       0x1
+#define MPU6050_WAKE_FREQ_5         0x2
+#define MPU6050_WAKE_FREQ_10        0x3
+
+#define MPU6050_BANKSEL_PRFTCH_EN_BIT       6
+#define MPU6050_BANKSEL_CFG_USER_BANK_BIT   5
+#define MPU6050_BANKSEL_MEM_SEL_BIT         4
+#define MPU6050_BANKSEL_MEM_SEL_LENGTH      5
+
+#define MPU6050_WHO_AM_I_BIT        6
+#define MPU6050_WHO_AM_I_LENGTH     6
+
+#define MPU6050_DMP_MEMORY_BANKS        8
+#define MPU6050_DMP_MEMORY_BANK_SIZE    256
+#define MPU6050_DMP_MEMORY_CHUNK_SIZE   16
+
+// note: DMP code memory blocks defined at end of header file
+
+class MPU6051 {
+    private:
+        I2Cdev2 i2Cdev;
+//        Serial debugSerial;
+    public:
+        MPU6051();
+        MPU6051(uint8_t address);
+
+        void initialize();
+        bool testConnection();
+
+        // AUX_VDDIO register
+        uint8_t getAuxVDDIOLevel();
+        void setAuxVDDIOLevel(uint8_t level);
+
+        // SMPLRT_DIV register
+        uint8_t getRate();
+        void setRate(uint8_t rate);
+
+        // CONFIG register
+        uint8_t getExternalFrameSync();
+        void setExternalFrameSync(uint8_t sync);
+        uint8_t getDLPFMode();
+        void setDLPFMode(uint8_t bandwidth);
+
+        // GYRO_CONFIG register
+        uint8_t getFullScaleGyroRange();
+        void setFullScaleGyroRange(uint8_t range);
+
+        // ACCEL_CONFIG register
+        bool getAccelXSelfTest();
+        void setAccelXSelfTest(bool enabled);
+        bool getAccelYSelfTest();
+        void setAccelYSelfTest(bool enabled);
+        bool getAccelZSelfTest();
+        void setAccelZSelfTest(bool enabled);
+        uint8_t getFullScaleAccelRange();
+        void setFullScaleAccelRange(uint8_t range);
+        uint8_t getDHPFMode();
+        void setDHPFMode(uint8_t mode);
+
+        // FF_THR register
+        uint8_t getFreefallDetectionThreshold();
+        void setFreefallDetectionThreshold(uint8_t threshold);
+
+        // FF_DUR register
+        uint8_t getFreefallDetectionDuration();
+        void setFreefallDetectionDuration(uint8_t duration);
+
+        // MOT_THR register
+        uint8_t getMotionDetectionThreshold();
+        void setMotionDetectionThreshold(uint8_t threshold);
+
+        // MOT_DUR register
+        uint8_t getMotionDetectionDuration();
+        void setMotionDetectionDuration(uint8_t duration);
+
+        // ZRMOT_THR register
+        uint8_t getZeroMotionDetectionThreshold();
+        void setZeroMotionDetectionThreshold(uint8_t threshold);
+
+        // ZRMOT_DUR register
+        uint8_t getZeroMotionDetectionDuration();
+        void setZeroMotionDetectionDuration(uint8_t duration);
+
+        // FIFO_EN register
+        bool getTempFIFOEnabled();
+        void setTempFIFOEnabled(bool enabled);
+        bool getXGyroFIFOEnabled();
+        void setXGyroFIFOEnabled(bool enabled);
+        bool getYGyroFIFOEnabled();
+        void setYGyroFIFOEnabled(bool enabled);
+        bool getZGyroFIFOEnabled();
+        void setZGyroFIFOEnabled(bool enabled);
+        bool getAccelFIFOEnabled();
+        void setAccelFIFOEnabled(bool enabled);
+        bool getSlave2FIFOEnabled();
+        void setSlave2FIFOEnabled(bool enabled);
+        bool getSlave1FIFOEnabled();
+        void setSlave1FIFOEnabled(bool enabled);
+        bool getSlave0FIFOEnabled();
+        void setSlave0FIFOEnabled(bool enabled);
+
+        // I2C_MST_CTRL register
+        bool getMultiMasterEnabled();
+        void setMultiMasterEnabled(bool enabled);
+        bool getWaitForExternalSensorEnabled();
+        void setWaitForExternalSensorEnabled(bool enabled);
+        bool getSlave3FIFOEnabled();
+        void setSlave3FIFOEnabled(bool enabled);
+        bool getSlaveReadWriteTransitionEnabled();
+        void setSlaveReadWriteTransitionEnabled(bool enabled);
+        uint8_t getMasterClockSpeed();
+        void setMasterClockSpeed(uint8_t speed);
+
+        // I2C_SLV* registers (Slave 0-3)
+        uint8_t getSlaveAddress(uint8_t num);
+        void setSlaveAddress(uint8_t num, uint8_t address);
+        uint8_t getSlaveRegister(uint8_t num);
+        void setSlaveRegister(uint8_t num, uint8_t reg);
+        bool getSlaveEnabled(uint8_t num);
+        void setSlaveEnabled(uint8_t num, bool enabled);
+        bool getSlaveWordByteSwap(uint8_t num);
+        void setSlaveWordByteSwap(uint8_t num, bool enabled);
+        bool getSlaveWriteMode(uint8_t num);
+        void setSlaveWriteMode(uint8_t num, bool mode);
+        bool getSlaveWordGroupOffset(uint8_t num);
+        void setSlaveWordGroupOffset(uint8_t num, bool enabled);
+        uint8_t getSlaveDataLength(uint8_t num);
+        void setSlaveDataLength(uint8_t num, uint8_t length);
+
+        // I2C_SLV* registers (Slave 4)
+        uint8_t getSlave4Address();
+        void setSlave4Address(uint8_t address);
+        uint8_t getSlave4Register();
+        void setSlave4Register(uint8_t reg);
+        void setSlave4OutputByte(uint8_t data);
+        bool getSlave4Enabled();
+        void setSlave4Enabled(bool enabled);
+        bool getSlave4InterruptEnabled();
+        void setSlave4InterruptEnabled(bool enabled);
+        bool getSlave4WriteMode();
+        void setSlave4WriteMode(bool mode);
+        uint8_t getSlave4MasterDelay();
+        void setSlave4MasterDelay(uint8_t delay);
+        uint8_t getSlate4InputByte();
+
+        // I2C_MST_STATUS register
+        bool getPassthroughStatus();
+        bool getSlave4IsDone();
+        bool getLostArbitration();
+        bool getSlave4Nack();
+        bool getSlave3Nack();
+        bool getSlave2Nack();
+        bool getSlave1Nack();
+        bool getSlave0Nack();
+
+        // INT_PIN_CFG register
+        bool getInterruptMode();
+        void setInterruptMode(bool mode);
+        bool getInterruptDrive();
+        void setInterruptDrive(bool drive);
+        bool getInterruptLatch();
+        void setInterruptLatch(bool latch);
+        bool getInterruptLatchClear();
+        void setInterruptLatchClear(bool clear);
+        bool getFSyncInterruptLevel();
+        void setFSyncInterruptLevel(bool level);
+        bool getFSyncInterruptEnabled();
+        void setFSyncInterruptEnabled(bool enabled);
+        bool getI2CBypassEnabled();
+        void setI2CBypassEnabled(bool enabled);
+        bool getClockOutputEnabled();
+        void setClockOutputEnabled(bool enabled);
+
+        // INT_ENABLE register
+        uint8_t getIntEnabled();
+        void setIntEnabled(uint8_t enabled);
+        bool getIntFreefallEnabled();
+        void setIntFreefallEnabled(bool enabled);
+        bool getIntMotionEnabled();
+        void setIntMotionEnabled(bool enabled);
+        bool getIntZeroMotionEnabled();
+        void setIntZeroMotionEnabled(bool enabled);
+        bool getIntFIFOBufferOverflowEnabled();
+        void setIntFIFOBufferOverflowEnabled(bool enabled);
+        bool getIntI2CMasterEnabled();
+        void setIntI2CMasterEnabled(bool enabled);
+        bool getIntDataReadyEnabled();
+        void setIntDataReadyEnabled(bool enabled);
+
+        // INT_STATUS register
+        uint8_t getIntStatus();
+        bool getIntFreefallStatus();
+        bool getIntMotionStatus();
+        bool getIntZeroMotionStatus();
+        bool getIntFIFOBufferOverflowStatus();
+        bool getIntI2CMasterStatus();
+        bool getIntDataReadyStatus();
+
+        // ACCEL_*OUT_* registers
+        void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+        void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+        void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getAccelerationX();
+        int16_t getAccelerationY();
+        int16_t getAccelerationZ();
+
+        // TEMP_OUT_* registers
+        int16_t getTemperature();
+
+        // GYRO_*OUT_* registers
+        void getRotation(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getRotationX();
+        int16_t getRotationY();
+        int16_t getRotationZ();
+
+        // EXT_SENS_DATA_* registers
+        uint8_t getExternalSensorByte(int position);
+        uint16_t getExternalSensorWord(int position);
+        uint32_t getExternalSensorDWord(int position);
+
+        // MOT_DETECT_STATUS register
+        bool getXNegMotionDetected();
+        bool getXPosMotionDetected();
+        bool getYNegMotionDetected();
+        bool getYPosMotionDetected();
+        bool getZNegMotionDetected();
+        bool getZPosMotionDetected();
+        bool getZeroMotionDetected();
+
+        // I2C_SLV*_DO register
+        void setSlaveOutputByte(uint8_t num, uint8_t data);
+
+        // I2C_MST_DELAY_CTRL register
+        bool getExternalShadowDelayEnabled();
+        void setExternalShadowDelayEnabled(bool enabled);
+        bool getSlaveDelayEnabled(uint8_t num);
+        void setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+        // SIGNAL_PATH_RESET register
+        void resetGyroscopePath();
+        void resetAccelerometerPath();
+        void resetTemperaturePath();
+
+        // MOT_DETECT_CTRL register
+        uint8_t getAccelerometerPowerOnDelay();
+        void setAccelerometerPowerOnDelay(uint8_t delay);
+        uint8_t getFreefallDetectionCounterDecrement();
+        void setFreefallDetectionCounterDecrement(uint8_t decrement);
+        uint8_t getMotionDetectionCounterDecrement();
+        void setMotionDetectionCounterDecrement(uint8_t decrement);
+
+        // USER_CTRL register
+        bool getFIFOEnabled();
+        void setFIFOEnabled(bool enabled);
+        bool getI2CMasterModeEnabled();
+        void setI2CMasterModeEnabled(bool enabled);
+        void switchSPIEnabled(bool enabled);
+        void resetFIFO();
+        void resetI2CMaster();
+        void resetSensors();
+
+        // PWR_MGMT_1 register
+        void reset();
+        bool getSleepEnabled();
+        void setSleepEnabled(bool enabled);
+        bool getWakeCycleEnabled();
+        void setWakeCycleEnabled(bool enabled);
+        bool getTempSensorEnabled();
+        void setTempSensorEnabled(bool enabled);
+        uint8_t getClockSource();
+        void setClockSource(uint8_t source);
+
+        // PWR_MGMT_2 register
+        uint8_t getWakeFrequency();
+        void setWakeFrequency(uint8_t frequency);
+        bool getStandbyXAccelEnabled();
+        void setStandbyXAccelEnabled(bool enabled);
+        bool getStandbyYAccelEnabled();
+        void setStandbyYAccelEnabled(bool enabled);
+        bool getStandbyZAccelEnabled();
+        void setStandbyZAccelEnabled(bool enabled);
+        bool getStandbyXGyroEnabled();
+        void setStandbyXGyroEnabled(bool enabled);
+        bool getStandbyYGyroEnabled();
+        void setStandbyYGyroEnabled(bool enabled);
+        bool getStandbyZGyroEnabled();
+        void setStandbyZGyroEnabled(bool enabled);
+
+        // FIFO_COUNT_* registers
+        uint16_t getFIFOCount();
+
+        // FIFO_R_W register
+        uint8_t getFIFOByte();
+        void setFIFOByte(uint8_t data);
+        void getFIFOBytes(uint8_t *data, uint8_t length);
+
+        // WHO_AM_I register
+        uint8_t getDeviceID();
+        void setDeviceID(uint8_t id);
+        
+        // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+        
+        // XG_OFFS_TC register
+        uint8_t getOTPBankValid();
+        void setOTPBankValid(bool enabled);
+        int8_t getXGyroOffset();
+        void setXGyroOffset(int8_t offset);
+
+        // YG_OFFS_TC register
+        int8_t getYGyroOffset();
+        void setYGyroOffset(int8_t offset);
+
+        // ZG_OFFS_TC register
+        int8_t getZGyroOffset();
+        void setZGyroOffset(int8_t offset);
+
+        // X_FINE_GAIN register
+        int8_t getXFineGain();
+        void setXFineGain(int8_t gain);
+
+        // Y_FINE_GAIN register
+        int8_t getYFineGain();
+        void setYFineGain(int8_t gain);
+
+        // Z_FINE_GAIN register
+        int8_t getZFineGain();
+        void setZFineGain(int8_t gain);
+
+        // XA_OFFS_* registers
+        int16_t getXAccelOffset();
+        void setXAccelOffset(int16_t offset);
+
+        // YA_OFFS_* register
+        int16_t getYAccelOffset();
+        void setYAccelOffset(int16_t offset);
+
+        // ZA_OFFS_* register
+        int16_t getZAccelOffset();
+        void setZAccelOffset(int16_t offset);
+
+        // XG_OFFS_USR* registers
+        int16_t getXGyroOffsetUser();
+        void setXGyroOffsetUser(int16_t offset);
+
+        // YG_OFFS_USR* register
+        int16_t getYGyroOffsetUser();
+        void setYGyroOffsetUser(int16_t offset);
+
+        // ZG_OFFS_USR* register
+        int16_t getZGyroOffsetUser();
+        void setZGyroOffsetUser(int16_t offset);
+        
+        // INT_ENABLE register (DMP functions)
+        bool getIntPLLReadyEnabled();
+        void setIntPLLReadyEnabled(bool enabled);
+        bool getIntDMPEnabled();
+        void setIntDMPEnabled(bool enabled);
+        
+        // DMP_INT_STATUS
+        bool getDMPInt5Status();
+        bool getDMPInt4Status();
+        bool getDMPInt3Status();
+        bool getDMPInt2Status();
+        bool getDMPInt1Status();
+        bool getDMPInt0Status();
+
+        // INT_STATUS register (DMP functions)
+        bool getIntPLLReadyStatus();
+        bool getIntDMPStatus();
+        
+        // USER_CTRL register (DMP functions)
+        bool getDMPEnabled();
+        void setDMPEnabled(bool enabled);
+        void resetDMP();
+        
+        // BANK_SEL register
+        void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false);
+        
+        // MEM_START_ADDR register
+        void setMemoryStartAddress(uint8_t address);
+        
+        // MEM_R_W register
+        uint8_t readMemoryByte();
+        void writeMemoryByte(uint8_t data);
+        void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0);
+        bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false);
+        bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true);
+
+        bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false);
+        bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+        // DMP_CFG_1 register
+        uint8_t getDMPConfig1();
+        void setDMPConfig1(uint8_t config);
+
+        // DMP_CFG_2 register
+        uint8_t getDMPConfig2();
+        void setDMPConfig2(uint8_t config);
+
+        // special methods for MotionApps 2.0 implementation
+        #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS20
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+        // special methods for MotionApps 4.1 implementation
+        #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS41
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+    private:
+        uint8_t devAddr;
+        uint8_t buffer[14];
+};
+
+#endif /* _MPU6050_H_ */
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/MPU/inc/MPU6051_6Axis_MotionApps20.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/MPU/inc/MPU6051_6Axis_MotionApps20.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,385 @@
+// I2Cdev library collection - MPU6050 I2C device class, 6-axis MotionApps 2.0 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 5/20/2013 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+ 
+/* ============================================
+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.
+===============================================
+*/
+
+//#include "tasks.h"
+
+#ifndef _MPU6051_6AXIS_MOTIONAPPS20_H_
+#define _MPU6051_6AXIS_MOTIONAPPS20_H_
+
+//#include <iostream>
+
+#include "I2Cdev2.h"
+#include "helper_3dmath.h"
+
+// MotionApps 2.0 DMP implementation, built using the MPU-6050EVB evaluation board
+#define MPU6050_INCLUDE_DMP_MOTIONAPPS20
+
+#include "MPU6051.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifndef __arm__
+    #include <avr/pgmspace.h>
+#else
+    // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+    #ifndef __PGMSPACE_H_
+        #define __PGMSPACE_H_ 1
+        #include <inttypes.h>
+
+        #define PROGMEM
+        #define PGM_P  const char *
+        #define PSTR(str) (str)
+        #define F(x) x
+
+        typedef void prog_void;
+        typedef char prog_char;
+        typedef unsigned char prog_uchar;
+        typedef int8_t prog_int8_t;
+        typedef uint8_t prog_uint8_t;
+        typedef int16_t prog_int16_t;
+        typedef uint16_t prog_uint16_t;
+        typedef int32_t prog_int32_t;
+        typedef uint32_t prog_uint32_t;
+        
+        #define strcpy_P(dest, src) strcpy((dest), (src))
+        #define strcat_P(dest, src) strcat((dest), (src))
+        #define strcmp_P(a, b) strcmp((a), (b))
+        
+        #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+        #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+        #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+        #define pgm_read_float(addr) (*(const float *)(addr))
+        
+        #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+        #define pgm_read_word_near(addr) pgm_read_word(addr)
+        #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+        #define pgm_read_float_near(addr) pgm_read_float(addr)
+        #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+        #define pgm_read_word_far(addr) pgm_read_word(addr)
+        #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+        #define pgm_read_float_far(addr) pgm_read_float(addr)
+    #endif
+#endif
+
+/* Source is from the InvenSense MotionApps v2 demo code. Original source is
+ * unavailable, unless you happen to be amazing as decompiling binary by
+ * hand (in which case, please contact me, and I'm totally serious).
+ *
+ * Also, I'd like to offer many, many thanks to Noah Zerkin for all of the
+ * DMP reverse-engineering he did to help make this bit of wizardry
+ * possible.
+ */
+
+// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size.
+// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno)
+// after moving string constants to flash memory storage using the F()
+// compiler macro (Arduino IDE 1.0+ required).
+
+//#define DEBUG
+#ifdef DEBUG
+    #define DEBUG_PRINT(x) pc.printf(x)   //Serial.print(x)
+    #define DEBUG_PRINTF(x, y) pc.printf(x,y)   //Serial.print(x, y)
+
+    #define F(x) x
+#else
+    #define DEBUG_PRINT(x)
+    #define DEBUG_PRINTF(x, y)
+
+#endif
+
+#define MPU6050_DMP_CODE_SIZE       1929    // dmpMemory[]
+#define MPU6050_DMP_CONFIG_SIZE     192     // dmpConfig[]
+#define MPU6050_DMP_UPDATES_SIZE    47      // dmpUpdates[]
+
+/* ================================================================================================ *
+ | Default MotionApps v2.0 42-byte FIFO packet structure:                                           |
+ |                                                                                                  |
+ | [QUAT W][      ][QUAT X][      ][QUAT Y][      ][QUAT Z][      ][GYRO X][      ][GYRO Y][      ] |
+ |   0   1   2   3   4   5   6   7   8   9  10  11  12  13  14  15  16  17  18  19  20  21  22  23  |
+ |                                                                                                  |
+ | [GYRO Z][      ][ACC X ][      ][ACC Y ][      ][ACC Z ][      ][      ]                         |
+ |  24  25  26  27  28  29  30  31  32  33  34  35  36  37  38  39  40  41                          |
+ * ================================================================================================ */
+
+// this block of memory gets written to the MPU on start-up, and it seems
+// to be volatile memory, so it has to be done each time (it only takes ~1
+// second though)
+const unsigned char dmpMemory2[MPU6050_DMP_CODE_SIZE] PROGMEM = {
+    // bank 0, 256 bytes
+    0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+    0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+    0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+    0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+    0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+    0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+    0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+    0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+
+    // bank 1, 256 bytes
+    0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+    0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+    0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+    0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+
+    // bank 2, 256 bytes
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+
+    // bank 3, 256 bytes
+    0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F,
+    0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2,
+    0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF,
+    0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C,
+    0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1,
+    0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01,
+    0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80,
+    0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C,
+    0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80,
+    0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E,
+    0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9,
+    0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24,
+    0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0,
+    0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86,
+    0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+    0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+
+    // bank 4, 256 bytes
+    0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+    0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+    0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+    0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+    0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+    0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+    0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+    0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+    0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+    0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+    0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+    0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+    0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+    0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+    0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+    0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+
+    // bank 5, 256 bytes
+    0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+    0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+    0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+    0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+    0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+    0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+    0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+    0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+    0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A,
+    0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60,
+    0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97,
+    0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04,
+    0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78,
+    0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79,
+    0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68,
+    0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68,
+
+    // bank 6, 256 bytes
+    0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04,
+    0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66,
+    0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31,
+    0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60,
+    0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76,
+    0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56,
+    0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD,
+    0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91,
+    0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8,
+    0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE,
+    0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9,
+    0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD,
+    0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E,
+    0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8,
+    0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89,
+    0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79,
+
+    // bank 7, 138 bytes (remainder)
+    0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8,
+    0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA,
+    0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB,
+    0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3,
+    0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3,
+    0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+    0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, 0xA3,
+    0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC,
+    0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
+};
+
+// thanks to Noah Zerkin for piecing this stuff together!
+const unsigned char dmpConfig2[MPU6050_DMP_CONFIG_SIZE] PROGMEM = {
+//  BANK    OFFSET  LENGTH  [DATA]
+    0x03,   0x7B,   0x03,   0x4C, 0xCD, 0x6C,         // FCFG_1 inv_set_gyro_calibration
+    0x03,   0xAB,   0x03,   0x36, 0x56, 0x76,         // FCFG_3 inv_set_gyro_calibration
+    0x00,   0x68,   0x04,   0x02, 0xCB, 0x47, 0xA2,   // D_0_104 inv_set_gyro_calibration
+    0x02,   0x18,   0x04,   0x00, 0x05, 0x8B, 0xC1,   // D_0_24 inv_set_gyro_calibration
+    0x01,   0x0C,   0x04,   0x00, 0x00, 0x00, 0x00,   // D_1_152 inv_set_accel_calibration
+    0x03,   0x7F,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_accel_calibration
+    0x03,   0x89,   0x03,   0x26, 0x46, 0x66,         // FCFG_7 inv_set_accel_calibration
+    0x00,   0x6C,   0x02,   0x20, 0x00,               // D_0_108 inv_set_accel_calibration
+    0x02,   0x40,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_00 inv_set_compass_calibration
+    0x02,   0x44,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_01
+    0x02,   0x48,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_02
+    0x02,   0x4C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_10
+    0x02,   0x50,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_11
+    0x02,   0x54,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_12
+    0x02,   0x58,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_20
+    0x02,   0x5C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_21
+    0x02,   0xBC,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_22
+    0x01,   0xEC,   0x04,   0x00, 0x00, 0x40, 0x00,   // D_1_236 inv_apply_endian_accel
+    0x03,   0x7F,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
+    0x04,   0x02,   0x03,   0x0D, 0x35, 0x5D,         // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
+    0x04,   0x09,   0x04,   0x87, 0x2D, 0x35, 0x3D,   // FCFG_5 inv_set_bias_update
+    0x00,   0xA3,   0x01,   0x00,                     // D_0_163 inv_set_dead_zone
+                 // SPECIAL 0x01 = enable interrupts
+    0x00,   0x00,   0x00,   0x01, // SET INT_ENABLE at i=22, SPECIAL INSTRUCTION
+    0x07,   0x86,   0x01,   0xFE,                     // CFG_6 inv_set_fifo_interupt
+    0x07,   0x41,   0x05,   0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
+    0x07,   0x7E,   0x01,   0x30,                     // CFG_16 inv_set_footer
+    0x07,   0x46,   0x01,   0x9A,                     // CFG_GYRO_SOURCE inv_send_gyro
+    0x07,   0x47,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_9 inv_send_gyro -> inv_construct3_fifo
+    0x07,   0x6C,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_12 inv_send_accel -> inv_construct3_fifo
+    0x02,   0x16,   0x02,   0x00, 0x07                // D_0_22 inv_set_fifo_rate
+
+    // This very last 0x01 (0x05) WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz,
+    // 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data.
+    // DMP output frequency is calculated easily using this equation: (200Hz / (1 + value))
+
+    // It is important to make sure the host processor can keep up with reading and processing
+    // the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea.
+};
+
+const unsigned char dmpUpdates2[MPU6050_DMP_UPDATES_SIZE] PROGMEM = {
+    0x01,   0xB2,   0x02,   0xFF, 0xFF,
+    0x01,   0x90,   0x04,   0x09, 0x23, 0xA1, 0x35,
+    0x01,   0x6A,   0x02,   0x06, 0x00,
+    0x01,   0x60,   0x08,   0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00,   0x60,   0x04,   0x40, 0x00, 0x00, 0x00,
+    0x01,   0x62,   0x02,   0x00, 0x00,
+    0x00,   0x60,   0x04,   0x00, 0x40, 0x00, 0x00
+};
+
+/* See MPU6050 under MotionApps 2.0 Section */
+
+// uint8_t MPU6050::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6050::dmpGetFIFORate();
+// uint8_t MPU6050::dmpGetSampleStepSizeMS();
+// uint8_t MPU6050::dmpGetSampleFrequency();
+// int32_t MPU6050::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6050::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6050::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6050::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6050::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+// uint8_t MPU6050::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6050::dmpGetLinearAccel(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGravity(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetEIS(long *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+// uint8_t MPU6050::dmpSetFIFOProcessedCallback(void (*func) (void));
+// uint8_t MPU6050::dmpInitFIFOParam();
+// uint8_t MPU6050::dmpCloseFIFO();
+// uint8_t MPU6050::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6050::dmpDecodeQuantizedAccel();
+// uint32_t MPU6050::dmpGetGyroSumOfSquare();
+// uint32_t MPU6050::dmpGetAccelSumOfSquare();
+// void MPU6050::dmpOverrideQuaternion(long *q);
+
+
+#endif /* _MPU6050_6AXIS_MOTIONAPPS20_H_ */
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/MPU/src/MPU6050.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/MPU/src/MPU6050.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,3442 @@
+//ported from arduino library: https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
+//written by szymon gaertig (email: szymon@gaertig.com.pl)
+//
+//Changelog:
+//2013-01-08 - first beta release
+
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 8/24/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+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.
+===============================================
+*/
+
+#include "MPU6050.h"
+
+//#define useDebugSerial
+
+//instead of using pgmspace.h
+typedef const unsigned char prog_uchar;
+#define pgm_read_byte_near(x) (*(prog_uchar*)(x))//<- I modified here
+#define pgm_read_byte(x) (*(prog_uchar*)(x))//<- I modified here
+
+/** Default constructor, uses default I2C address.
+ * @see MPU6050_DEFAULT_ADDRESS
+ */
+MPU6050::MPU6050() //: debugSerial(USBTX, USBRX)
+{
+    devAddr = MPU6050_DEFAULT_ADDRESS;
+}
+
+/** Specific address constructor.
+ * @param address I2C address
+ * @see MPU6050_DEFAULT_ADDRESS
+ * @see MPU6050_ADDRESS_AD0_LOW
+ * @see MPU6050_ADDRESS_AD0_HIGH
+ */
+MPU6050::MPU6050(uint8_t address) //: debugSerial(USBTX, USBRX)
+{
+    devAddr = address;
+}
+
+/** Power on and prepare for general usage.
+ * This will activate the device and take it out of sleep mode (which must be done
+ * after start-up). This function also sets both the accelerometer and the gyroscope
+ * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets
+ * the clock source to use the X Gyro for reference, which is slightly better than
+ * the default internal clock source.
+ */
+void MPU6050::initialize()
+{
+
+#ifdef useDebugSerial
+    debugSerial.printf("MPU6050::initialize start\n");
+#endif
+
+    setClockSource(MPU6050_CLOCK_PLL_XGYRO);
+    setFullScaleGyroRange(MPU6050_GYRO_FS_250);
+    setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
+    setSleepEnabled(false); // thanks to Jack Elston for pointing this one out!
+
+#ifdef useDebugSerial
+    debugSerial.printf("MPU6050::initialize end\n");
+#endif
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool MPU6050::testConnection()
+{
+#ifdef useDebugSerial
+    debugSerial.printf("MPU6050::testConnection start\n");
+#endif
+    uint8_t deviceId = getDeviceID();
+#ifdef useDebugSerial
+    debugSerial.printf("DeviceId = %d\n",deviceId);
+#endif
+    return deviceId == 0x34;
+}
+
+// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC)
+
+/** Get the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @return I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+uint8_t MPU6050::getAuxVDDIOLevel()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, buffer);
+    return buffer[0];
+}
+/** Set the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @param level I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+void MPU6050::setAuxVDDIOLevel(uint8_t level)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, level);
+}
+
+// SMPLRT_DIV register
+
+/** Get gyroscope output rate divider.
+ * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero
+ * Motion detection, and Free Fall detection are all based on the Sample Rate.
+ * The Sample Rate is generated by dividing the gyroscope output rate by
+ * SMPLRT_DIV:
+ *
+ * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
+ *
+ * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or
+ * 7), and 1kHz when the DLPF is enabled (see Register 26).
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * For a diagram of the gyroscope and accelerometer signal paths, see Section 8
+ * of the MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current sample rate
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+uint8_t MPU6050::getRate()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_SMPLRT_DIV, buffer);
+    return buffer[0];
+}
+/** Set gyroscope sample rate divider.
+ * @param rate New sample rate divider
+ * @see getRate()
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+void MPU6050::setRate(uint8_t rate)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_SMPLRT_DIV, rate);
+}
+
+// CONFIG register
+
+/** Get external FSYNC configuration.
+ * Configures the external Frame Synchronization (FSYNC) pin sampling. An
+ * external signal connected to the FSYNC pin can be sampled by configuring
+ * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short
+ * strobes may be captured. The latched FSYNC signal will be sampled at the
+ * Sampling Rate, as defined in register 25. After sampling, the latch will
+ * reset to the current FSYNC signal state.
+ *
+ * The sampled value will be reported in place of the least significant bit in
+ * a sensor data register determined by the value of EXT_SYNC_SET according to
+ * the following table.
+ *
+ * <pre>
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0            | Input disabled
+ * 1            | TEMP_OUT_L[0]
+ * 2            | GYRO_XOUT_L[0]
+ * 3            | GYRO_YOUT_L[0]
+ * 4            | GYRO_ZOUT_L[0]
+ * 5            | ACCEL_XOUT_L[0]
+ * 6            | ACCEL_YOUT_L[0]
+ * 7            | ACCEL_ZOUT_L[0]
+ * </pre>
+ *
+ * @return FSYNC configuration value
+ */
+uint8_t MPU6050::getExternalFrameSync()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set external FSYNC configuration.
+ * @see getExternalFrameSync()
+ * @see MPU6050_RA_CONFIG
+ * @param sync New FSYNC configuration value
+ */
+void MPU6050::setExternalFrameSync(uint8_t sync)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, sync);
+}
+/** Get digital low-pass filter configuration.
+ * The DLPF_CFG parameter sets the digital low pass filter configuration. It
+ * also determines the internal sampling rate used by the device as shown in
+ * the table below.
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * <pre>
+ *          |   ACCELEROMETER    |           GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
+ * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
+ * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
+ * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
+ * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
+ * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
+ * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
+ * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
+ * </pre>
+ *
+ * @return DLFP configuration
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+uint8_t MPU6050::getDLPFMode()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set digital low-pass filter configuration.
+ * @param mode New DLFP configuration setting
+ * @see getDLPFBandwidth()
+ * @see MPU6050_DLPF_BW_256
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+void MPU6050::setDLPFMode(uint8_t mode)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, mode);
+}
+
+// GYRO_CONFIG register
+
+/** Get full-scale gyroscope range.
+ * The FS_SEL parameter allows setting the full-scale range of the gyro sensors,
+ * as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * </pre>
+ *
+ * @return Current full-scale gyroscope range setting
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+uint8_t MPU6050::getFullScaleGyroRange()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set full-scale gyroscope range.
+ * @param range New full-scale gyroscope range value
+ * @see getFullScaleRange()
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+void MPU6050::setFullScaleGyroRange(uint8_t range)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, range);
+}
+
+// ACCEL_CONFIG register
+
+/** Get self-test enabled setting for accelerometer X axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050::getAccelXSelfTest()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, buffer);
+    return buffer[0];
+}
+/** Get self-test enabled setting for accelerometer X axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050::setAccelXSelfTest(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050::getAccelYSelfTest()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, buffer);
+    return buffer[0];
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050::setAccelYSelfTest(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Z axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050::getAccelZSelfTest()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, buffer);
+    return buffer[0];
+}
+/** Set self-test enabled value for accelerometer Z axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050::setAccelZSelfTest(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, enabled);
+}
+/** Get full-scale accelerometer range.
+ * The FS_SEL parameter allows setting the full-scale range of the accelerometer
+ * sensors, as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * </pre>
+ *
+ * @return Current full-scale accelerometer range setting
+ * @see MPU6050_ACCEL_FS_2
+ * @see MPU6050_RA_ACCEL_CONFIG
+ * @see MPU6050_ACONFIG_AFS_SEL_BIT
+ * @see MPU6050_ACONFIG_AFS_SEL_LENGTH
+ */
+uint8_t MPU6050::getFullScaleAccelRange()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set full-scale accelerometer range.
+ * @param range New full-scale accelerometer range setting
+ * @see getFullScaleAccelRange()
+ */
+void MPU6050::setFullScaleAccelRange(uint8_t range)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, range);
+}
+/** Get the high-pass filter configuration.
+ * The DHPF is a filter module in the path leading to motion detectors (Free
+ * Fall, Motion threshold, and Zero Motion). The high pass filter output is not
+ * available to the data registers (see Figure in Section 8 of the MPU-6000/
+ * MPU-6050 Product Specification document).
+ *
+ * The high pass filter has three modes:
+ *
+ * <pre>
+ *    Reset: The filter output settles to zero within one sample. This
+ *           effectively disables the high pass filter. This mode may be toggled
+ *           to quickly settle the filter.
+ *
+ *    On:    The high pass filter will pass signals above the cut off frequency.
+ *
+ *    Hold:  When triggered, the filter holds the present sample. The filter
+ *           output will be the difference between the input sample and the held
+ *           sample.
+ * </pre>
+ *
+ * <pre>
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0         | Reset       | None
+ * 1         | On          | 5Hz
+ * 2         | On          | 2.5Hz
+ * 3         | On          | 1.25Hz
+ * 4         | On          | 0.63Hz
+ * 7         | Hold        | None
+ * </pre>
+ *
+ * @return Current high-pass filter configuration
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+uint8_t MPU6050::getDHPFMode()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set the high-pass filter configuration.
+ * @param bandwidth New high-pass filter configuration
+ * @see setDHPFMode()
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050::setDHPFMode(uint8_t bandwidth)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, bandwidth);
+}
+
+// FF_THR register
+
+/** Get free-fall event acceleration threshold.
+ * This register configures the detection threshold for Free Fall event
+ * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the
+ * absolute value of the accelerometer measurements for the three axes are each
+ * less than the detection threshold. This condition increments the Free Fall
+ * duration counter (Register 30). The Free Fall interrupt is triggered when the
+ * Free Fall duration counter reaches the time specified in FF_DUR.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current free-fall acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_FF_THR
+ */
+uint8_t MPU6050::getFreefallDetectionThreshold()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_FF_THR, buffer);
+    return buffer[0];
+}
+/** Get free-fall event acceleration threshold.
+ * @param threshold New free-fall acceleration threshold value (LSB = 2mg)
+ * @see getFreefallDetectionThreshold()
+ * @see MPU6050_RA_FF_THR
+ */
+void MPU6050::setFreefallDetectionThreshold(uint8_t threshold)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_FF_THR, threshold);
+}
+
+// FF_DUR register
+
+/** Get free-fall event duration threshold.
+ * This register configures the duration counter threshold for Free Fall event
+ * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit
+ * of 1 LSB = 1 ms.
+ *
+ * The Free Fall duration counter increments while the absolute value of the
+ * accelerometer measurements are each less than the detection threshold
+ * (Register 29). The Free Fall interrupt is triggered when the Free Fall
+ * duration counter reaches the time specified in this register.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current free-fall duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_FF_DUR
+ */
+uint8_t MPU6050::getFreefallDetectionDuration()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_FF_DUR, buffer);
+    return buffer[0];
+}
+/** Get free-fall event duration threshold.
+ * @param duration New free-fall duration threshold value (LSB = 1ms)
+ * @see getFreefallDetectionDuration()
+ * @see MPU6050_RA_FF_DUR
+ */
+void MPU6050::setFreefallDetectionDuration(uint8_t duration)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_FF_DUR, duration);
+}
+
+// MOT_THR register
+
+/** Get motion detection event acceleration threshold.
+ * This register configures the detection threshold for Motion interrupt
+ * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the
+ * absolute value of any of the accelerometer measurements exceeds this Motion
+ * detection threshold. This condition increments the Motion detection duration
+ * counter (Register 32). The Motion detection interrupt is triggered when the
+ * Motion Detection counter reaches the time count specified in MOT_DUR
+ * (Register 32).
+ *
+ * The Motion interrupt will indicate the axis and polarity of detected motion
+ * in MOT_DETECT_STATUS (Register 97).
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_MOT_THR
+ */
+uint8_t MPU6050::getMotionDetectionThreshold()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_MOT_THR, buffer);
+    return buffer[0];
+}
+/** Set free-fall event acceleration threshold.
+ * @param threshold New motion detection acceleration threshold value (LSB = 2mg)
+ * @see getMotionDetectionThreshold()
+ * @see MPU6050_RA_MOT_THR
+ */
+void MPU6050::setMotionDetectionThreshold(uint8_t threshold)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_MOT_THR, threshold);
+}
+
+// MOT_DUR register
+
+/** Get motion detection event duration threshold.
+ * This register configures the duration counter threshold for Motion interrupt
+ * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit
+ * of 1LSB = 1ms. The Motion detection duration counter increments when the
+ * absolute value of any of the accelerometer measurements exceeds the Motion
+ * detection threshold (Register 31). The Motion detection interrupt is
+ * triggered when the Motion detection counter reaches the time count specified
+ * in this register.
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current motion detection duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_MOT_DUR
+ */
+uint8_t MPU6050::getMotionDetectionDuration()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_MOT_DUR, buffer);
+    return buffer[0];
+}
+/** Set motion detection event duration threshold.
+ * @param duration New motion detection duration threshold value (LSB = 1ms)
+ * @see getMotionDetectionDuration()
+ * @see MPU6050_RA_MOT_DUR
+ */
+void MPU6050::setMotionDetectionDuration(uint8_t duration)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_MOT_DUR, duration);
+}
+
+// ZRMOT_THR register
+
+/** Get zero motion detection event acceleration threshold.
+ * This register configures the detection threshold for Zero Motion interrupt
+ * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when
+ * the absolute value of the accelerometer measurements for the 3 axes are each
+ * less than the detection threshold. This condition increments the Zero Motion
+ * duration counter (Register 34). The Zero Motion interrupt is triggered when
+ * the Zero Motion duration counter reaches the time count specified in
+ * ZRMOT_DUR (Register 34).
+ *
+ * Unlike Free Fall or Motion detection, Zero Motion detection triggers an
+ * interrupt both when Zero Motion is first detected and when Zero Motion is no
+ * longer detected.
+ *
+ * When a zero motion event is detected, a Zero Motion Status will be indicated
+ * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion
+ * condition is detected, the status bit is set to 1. When a zero-motion-to-
+ * motion condition is detected, the status bit is set to 0.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+uint8_t MPU6050::getZeroMotionDetectionThreshold()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_ZRMOT_THR, buffer);
+    return buffer[0];
+}
+/** Set zero motion detection event acceleration threshold.
+ * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see getZeroMotionDetectionThreshold()
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+void MPU6050::setZeroMotionDetectionThreshold(uint8_t threshold)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_ZRMOT_THR, threshold);
+}
+
+// ZRMOT_DUR register
+
+/** Get zero motion detection event duration threshold.
+ * This register configures the duration counter threshold for Zero Motion
+ * interrupt generation. The duration counter ticks at 16 Hz, therefore
+ * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter
+ * increments while the absolute value of the accelerometer measurements are
+ * each less than the detection threshold (Register 33). The Zero Motion
+ * interrupt is triggered when the Zero Motion duration counter reaches the time
+ * count specified in this register.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document, as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection duration threshold value (LSB = 64ms)
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+uint8_t MPU6050::getZeroMotionDetectionDuration()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_ZRMOT_DUR, buffer);
+    return buffer[0];
+}
+/** Set zero motion detection event duration threshold.
+ * @param duration New zero motion detection duration threshold value (LSB = 1ms)
+ * @see getZeroMotionDetectionDuration()
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+void MPU6050::setZeroMotionDetectionDuration(uint8_t duration)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_ZRMOT_DUR, duration);
+}
+
+// FIFO_EN register
+
+/** Get temperature FIFO enabled value.
+ * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and
+ * 66) to be written into the FIFO buffer.
+ * @return Current temperature FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getTempFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set temperature FIFO enabled value.
+ * @param enabled New temperature FIFO enabled value
+ * @see getTempFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setTempFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope X-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and
+ * 68) to be written into the FIFO buffer.
+ * @return Current gyroscope X-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getXGyroFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set gyroscope X-axis FIFO enabled value.
+ * @param enabled New gyroscope X-axis FIFO enabled value
+ * @see getXGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setXGyroFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Y-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and
+ * 70) to be written into the FIFO buffer.
+ * @return Current gyroscope Y-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getYGyroFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set gyroscope Y-axis FIFO enabled value.
+ * @param enabled New gyroscope Y-axis FIFO enabled value
+ * @see getYGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setYGyroFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Z-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and
+ * 72) to be written into the FIFO buffer.
+ * @return Current gyroscope Z-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getZGyroFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set gyroscope Z-axis FIFO enabled value.
+ * @param enabled New gyroscope Z-axis FIFO enabled value
+ * @see getZGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setZGyroFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, enabled);
+}
+/** Get accelerometer FIFO enabled value.
+ * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H,
+ * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be
+ * written into the FIFO buffer.
+ * @return Current accelerometer FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getAccelFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set accelerometer FIFO enabled value.
+ * @param enabled New accelerometer FIFO enabled value
+ * @see getAccelFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setAccelFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 2 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 2 to be written into the FIFO buffer.
+ * @return Current Slave 2 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getSlave2FIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set Slave 2 FIFO enabled value.
+ * @param enabled New Slave 2 FIFO enabled value
+ * @see getSlave2FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setSlave2FIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 1 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 1 to be written into the FIFO buffer.
+ * @return Current Slave 1 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getSlave1FIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set Slave 1 FIFO enabled value.
+ * @param enabled New Slave 1 FIFO enabled value
+ * @see getSlave1FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setSlave1FIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 0 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 0 to be written into the FIFO buffer.
+ * @return Current Slave 0 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getSlave0FIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set Slave 0 FIFO enabled value.
+ * @param enabled New Slave 0 FIFO enabled value
+ * @see getSlave0FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setSlave0FIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, enabled);
+}
+
+// I2C_MST_CTRL register
+
+/** Get multi-master enabled value.
+ * Multi-master capability allows multiple I2C masters to operate on the same
+ * bus. In circuits where multi-master capability is required, set MULT_MST_EN
+ * to 1. This will increase current drawn by approximately 30uA.
+ *
+ * In circuits where multi-master capability is required, the state of the I2C
+ * bus must always be monitored by each separate I2C Master. Before an I2C
+ * Master can assume arbitration of the bus, it must first confirm that no other
+ * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the
+ * MPU-60X0's bus arbitration detection logic is turned on, enabling it to
+ * detect when the bus is available.
+ *
+ * @return Current multi-master enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050::getMultiMasterEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set multi-master enabled value.
+ * @param enabled New multi-master enabled value
+ * @see getMultiMasterEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050::setMultiMasterEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, enabled);
+}
+/** Get wait-for-external-sensor-data enabled value.
+ * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be
+ * delayed until External Sensor data from the Slave Devices are loaded into the
+ * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor
+ * data (i.e. from gyro and accel) and external sensor data have been loaded to
+ * their respective data registers (i.e. the data is synced) when the Data Ready
+ * interrupt is triggered.
+ *
+ * @return Current wait-for-external-sensor-data enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050::getWaitForExternalSensorEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, buffer);
+    return buffer[0];
+}
+/** Set wait-for-external-sensor-data enabled value.
+ * @param enabled New wait-for-external-sensor-data enabled value
+ * @see getWaitForExternalSensorEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050::setWaitForExternalSensorEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, enabled);
+}
+/** Get Slave 3 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 3 to be written into the FIFO buffer.
+ * @return Current Slave 3 FIFO enabled value
+ * @see MPU6050_RA_MST_CTRL
+ */
+bool MPU6050::getSlave3FIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set Slave 3 FIFO enabled value.
+ * @param enabled New Slave 3 FIFO enabled value
+ * @see getSlave3FIFOEnabled()
+ * @see MPU6050_RA_MST_CTRL
+ */
+void MPU6050::setSlave3FIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, enabled);
+}
+/** Get slave read/write transition enabled value.
+ * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave
+ * read to the next slave read. If the bit equals 0, there will be a restart
+ * between reads. If the bit equals 1, there will be a stop followed by a start
+ * of the following read. When a write transaction follows a read transaction,
+ * the stop followed by a start of the successive write will be always used.
+ *
+ * @return Current slave read/write transition enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050::getSlaveReadWriteTransitionEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, buffer);
+    return buffer[0];
+}
+/** Set slave read/write transition enabled value.
+ * @param enabled New slave read/write transition enabled value
+ * @see getSlaveReadWriteTransitionEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050::setSlaveReadWriteTransitionEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, enabled);
+}
+/** Get I2C master clock speed.
+ * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the
+ * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to
+ * the following table:
+ *
+ * <pre>
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0           | 348kHz                 | 23
+ * 1           | 333kHz                 | 24
+ * 2           | 320kHz                 | 25
+ * 3           | 308kHz                 | 26
+ * 4           | 296kHz                 | 27
+ * 5           | 286kHz                 | 28
+ * 6           | 276kHz                 | 29
+ * 7           | 267kHz                 | 30
+ * 8           | 258kHz                 | 31
+ * 9           | 500kHz                 | 16
+ * 10          | 471kHz                 | 17
+ * 11          | 444kHz                 | 18
+ * 12          | 421kHz                 | 19
+ * 13          | 400kHz                 | 20
+ * 14          | 381kHz                 | 21
+ * 15          | 364kHz                 | 22
+ * </pre>
+ *
+ * @return Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+uint8_t MPU6050::getMasterClockSpeed()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set I2C master clock speed.
+ * @reparam speed Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050::setMasterClockSpeed(uint8_t speed)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, speed);
+}
+
+// I2C_SLV* registers (Slave 0-3)
+
+/** Get the I2C address of the specified slave (0-3).
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * In read mode, the result of the read is placed in the lowest available
+ * EXT_SENS_DATA register. For further information regarding the allocation of
+ * read results, please refer to the EXT_SENS_DATA register description
+ * (Registers 73 - 96).
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions (getSlave4* and setSlave4*).
+ *
+ * I2C data transactions are performed at the Sample Rate, as defined in
+ * Register 25. The user is responsible for ensuring that I2C data transactions
+ * to and from each enabled Slave can be completed within a single period of the
+ * Sample Rate.
+ *
+ * The I2C slave access rate can be reduced relative to the Sample Rate. This
+ * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a
+ * slave's access rate is reduced relative to the Sample Rate is determined by
+ * I2C_MST_DELAY_CTRL (Register 103).
+ *
+ * The processing order for the slaves is fixed. The sequence followed for
+ * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a
+ * particular Slave is disabled it will be skipped.
+ *
+ * Each slave can either be accessed at the sample rate or at a reduced sample
+ * rate. In a case where some slaves are accessed at the Sample Rate and some
+ * slaves are accessed at the reduced rate, the sequence of accessing the slaves
+ * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will
+ * be skipped if their access rate dictates that they should not be accessed
+ * during that particular cycle. For further information regarding the reduced
+ * access rate, please refer to Register 52. Whether a slave is accessed at the
+ * Sample Rate or at the reduced rate is determined by the Delay Enable bits in
+ * Register 103.
+ *
+ * @param num Slave number (0-3)
+ * @return Current address for specified slave
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+uint8_t MPU6050::getSlaveAddress(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, buffer);
+    return buffer[0];
+}
+/** Set the I2C address of the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param address New address for specified slave
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+void MPU6050::setSlaveAddress(uint8_t num, uint8_t address)
+{
+    if (num > 3) return;
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, address);
+}
+/** Get the active internal register for the specified slave (0-3).
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions.
+ *
+ * @param num Slave number (0-3)
+ * @return Current active register for specified slave
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+uint8_t MPU6050::getSlaveRegister(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, buffer);
+    return buffer[0];
+}
+/** Set the active internal register for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param reg New active register for specified slave
+ * @see getSlaveRegister()
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+void MPU6050::setSlaveRegister(uint8_t num, uint8_t reg)
+{
+    if (num > 3) return;
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, reg);
+}
+/** Get the enabled value for the specified slave (0-3).
+ * When set to 1, this bit enables Slave 0 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 0 from data transfer operations.
+ * @param num Slave number (0-3)
+ * @return Current enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050::getSlaveEnabled(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set the enabled value for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New enabled value for specified slave 
+ * @see getSlaveEnabled()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveEnabled(uint8_t num, bool enabled)
+{
+    if (num > 3) return;
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, enabled);
+}
+/** Get word pair byte-swapping enabled for the specified slave (0-3).
+ * When set to 1, this bit enables byte swapping. When byte swapping is enabled,
+ * the high and low bytes of a word pair are swapped. Please refer to
+ * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0,
+ * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA
+ * registers in the order they were transferred.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair byte-swapping enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050::getSlaveWordByteSwap(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, buffer);
+    return buffer[0];
+}
+/** Set word pair byte-swapping enabled for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair byte-swapping enabled value for specified slave
+ * @see getSlaveWordByteSwap()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveWordByteSwap(uint8_t num, bool enabled)
+{
+    if (num > 3) return;
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, enabled);
+}
+/** Get write mode for the specified slave (0-3).
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @param num Slave number (0-3)
+ * @return Current write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050::getSlaveWriteMode(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, buffer);
+    return buffer[0];
+}
+/** Set write mode for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param mode New write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see getSlaveWriteMode()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveWriteMode(uint8_t num, bool mode)
+{
+    if (num > 3) return;
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, mode);
+}
+/** Get word pair grouping order offset for the specified slave (0-3).
+ * This sets specifies the grouping order of word pairs received from registers.
+ * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even,
+ * then odd register addresses) are paired to form a word. When set to 1, bytes
+ * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even
+ * register addresses) are paired to form a word.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair grouping order offset for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050::getSlaveWordGroupOffset(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, buffer);
+    return buffer[0];
+}
+/** Set word pair grouping order offset for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair grouping order offset for specified slave
+ * @see getSlaveWordGroupOffset()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveWordGroupOffset(uint8_t num, bool enabled)
+{
+    if (num > 3) return;
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, enabled);
+}
+/** Get number of bytes to read for the specified slave (0-3).
+ * Specifies the number of bytes transferred to and from Slave 0. Clearing this
+ * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN.
+ * @param num Slave number (0-3)
+ * @return Number of bytes to read for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+uint8_t MPU6050::getSlaveDataLength(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set number of bytes to read for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param length Number of bytes to read for specified slave
+ * @see getSlaveDataLength()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveDataLength(uint8_t num, uint8_t length)
+{
+    if (num > 3) return;
+    i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, length);
+}
+
+// I2C_SLV* registers (Slave 4)
+
+/** Get the I2C address of Slave 4.
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * @return Current address for Slave 4
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+uint8_t MPU6050::getSlave4Address()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, buffer);
+    return buffer[0];
+}
+/** Set the I2C address of Slave 4.
+ * @param address New address for Slave 4
+ * @see getSlave4Address()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+void MPU6050::setSlave4Address(uint8_t address)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, address);
+}
+/** Get the active internal register for the Slave 4.
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * @return Current active register for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+uint8_t MPU6050::getSlave4Register()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_REG, buffer);
+    return buffer[0];
+}
+/** Set the active internal register for Slave 4.
+ * @param reg New active register for Slave 4
+ * @see getSlave4Register()
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+void MPU6050::setSlave4Register(uint8_t reg)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_REG, reg);
+}
+/** Set new byte to write to Slave 4.
+ * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW
+ * is set 1 (set to read), this register has no effect.
+ * @param data New byte to write to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DO
+ */
+void MPU6050::setSlave4OutputByte(uint8_t data)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_DO, data);
+}
+/** Get the enabled value for the Slave 4.
+ * When set to 1, this bit enables Slave 4 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 4 from data transfer operations.
+ * @return Current enabled value for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050::getSlave4Enabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set the enabled value for Slave 4.
+ * @param enabled New enabled value for Slave 4
+ * @see getSlave4Enabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050::setSlave4Enabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, enabled);
+}
+/** Get the enabled value for Slave 4 transaction interrupts.
+ * When set to 1, this bit enables the generation of an interrupt signal upon
+ * completion of a Slave 4 transaction. When cleared to 0, this bit disables the
+ * generation of an interrupt signal upon completion of a Slave 4 transaction.
+ * The interrupt status can be observed in Register 54.
+ *
+ * @return Current enabled value for Slave 4 transaction interrupts.
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050::getSlave4InterruptEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set the enabled value for Slave 4 transaction interrupts.
+ * @param enabled New enabled value for Slave 4 transaction interrupts.
+ * @see getSlave4InterruptEnabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050::setSlave4InterruptEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, enabled);
+}
+/** Get write mode for Slave 4.
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050::getSlave4WriteMode()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, buffer);
+    return buffer[0];
+}
+/** Set write mode for the Slave 4.
+ * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see getSlave4WriteMode()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050::setSlave4WriteMode(bool mode)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mode);
+}
+/** Get Slave 4 master delay value.
+ * This configures the reduced access rate of I2C slaves relative to the Sample
+ * Rate. When a slave's access rate is decreased relative to the Sample Rate,
+ * the slave is accessed every:
+ *
+ *     1 / (1 + I2C_MST_DLY) samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and
+ * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to
+ * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For
+ * further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @return Current Slave 4 master delay value
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+uint8_t MPU6050::getSlave4MasterDelay()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Slave 4 master delay value.
+ * @param delay New Slave 4 master delay value
+ * @see getSlave4MasterDelay()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050::setSlave4MasterDelay(uint8_t delay)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, delay);
+}
+/** Get last available byte read from Slave 4.
+ * This register stores the data read from Slave 4. This field is populated
+ * after a read transaction.
+ * @return Last available byte read from to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DI
+ */
+uint8_t MPU6050::getSlate4InputByte()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_DI, buffer);
+    return buffer[0];
+}
+
+// I2C_MST_STATUS register
+
+/** Get FSYNC interrupt status.
+ * This bit reflects the status of the FSYNC interrupt from an external device
+ * into the MPU-60X0. This is used as a way to pass an external interrupt
+ * through the MPU-60X0 to the host application processor. When set to 1, this
+ * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG
+ * (Register 55).
+ * @return FSYNC interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getPassthroughStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 4 transaction done status.
+ * Automatically sets to 1 when a Slave 4 transaction has completed. This
+ * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register
+ * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the
+ * I2C_SLV4_CTRL register (Register 52).
+ * @return Slave 4 transaction done status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave4IsDone()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, buffer);
+    return buffer[0];
+}
+/** Get master arbitration lost status.
+ * This bit automatically sets to 1 when the I2C Master has lost arbitration of
+ * the auxiliary I2C bus (an error condition). This triggers an interrupt if the
+ * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Master arbitration lost status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getLostArbitration()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 4 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 4 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave4Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 3 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 3 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave3Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 2 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 2 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave2Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 1 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 1 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave1Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 0 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 0 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave0Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, buffer);
+    return buffer[0];
+}
+
+// INT_PIN_CFG register
+
+/** Get interrupt logic level mode.
+ * Will be set 0 for active-high, 1 for active-low.
+ * @return Current interrupt mode (0=active-high, 1=active-low)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+bool MPU6050::getInterruptMode()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, buffer);
+    return buffer[0];
+}
+/** Set interrupt logic level mode.
+ * @param mode New interrupt mode (0=active-high, 1=active-low)
+ * @see getInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+void MPU6050::setInterruptMode(bool mode)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mode);
+}
+/** Get interrupt drive mode.
+ * Will be set 0 for push-pull, 1 for open-drain.
+ * @return Current interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+bool MPU6050::getInterruptDrive()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, buffer);
+    return buffer[0];
+}
+/** Set interrupt drive mode.
+ * @param drive New interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see getInterruptDrive()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+void MPU6050::setInterruptDrive(bool drive)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, drive);
+}
+/** Get interrupt latch mode.
+ * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared.
+ * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+bool MPU6050::getInterruptLatch()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set interrupt latch mode.
+ * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see getInterruptLatch()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+void MPU6050::setInterruptLatch(bool latch)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, latch);
+}
+/** Get interrupt latch clear mode.
+ * Will be set 0 for status-read-only, 1 for any-register-read.
+ * @return Current latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+bool MPU6050::getInterruptLatchClear()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, buffer);
+    return buffer[0];
+}
+/** Set interrupt latch clear mode.
+ * @param clear New latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see getInterruptLatchClear()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+void MPU6050::setInterruptLatchClear(bool clear)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, clear);
+}
+/** Get FSYNC interrupt logic level mode.
+ * @return Current FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+bool MPU6050::getFSyncInterruptLevel()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, buffer);
+    return buffer[0];
+}
+/** Set FSYNC interrupt logic level mode.
+ * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+void MPU6050::setFSyncInterruptLevel(bool level)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, level);
+}
+/** Get FSYNC pin interrupt enabled setting.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled setting
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+bool MPU6050::getFSyncInterruptEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set FSYNC pin interrupt enabled setting.
+ * @param enabled New FSYNC pin interrupt enabled setting
+ * @see getFSyncInterruptEnabled()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+void MPU6050::setFSyncInterruptEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, enabled);
+}
+/** Get I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @return Current I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+bool MPU6050::getI2CBypassEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @param enabled New I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+void MPU6050::setI2CBypassEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, enabled);
+}
+/** Get reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @return Current reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+bool MPU6050::getClockOutputEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @param enabled New reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+void MPU6050::setClockOutputEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, enabled);
+}
+
+// INT_ENABLE register
+
+/** Get full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit will be
+ * set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+uint8_t MPU6050::getIntEnabled()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_INT_ENABLE, buffer);
+    return buffer[0];
+}
+/** Set full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit should be
+ * set 0 for disabled, 1 for enabled.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void MPU6050::setIntEnabled(uint8_t enabled)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_INT_ENABLE, enabled);
+}
+/** Get Free Fall interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+bool MPU6050::getIntFreefallEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, buffer);
+    return buffer[0];
+}
+/** Set Free Fall interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void MPU6050::setIntFreefallEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, enabled);
+}
+/** Get Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+bool MPU6050::getIntMotionEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, buffer);
+    return buffer[0];
+}
+/** Set Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+void MPU6050::setIntMotionEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, enabled);
+}
+/** Get Zero Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+bool MPU6050::getIntZeroMotionEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
+    return buffer[0];
+}
+/** Set Zero Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntZeroMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+void MPU6050::setIntZeroMotionEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, enabled);
+}
+/** Get FIFO Buffer Overflow interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+bool MPU6050::getIntFIFOBufferOverflowEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+    return buffer[0];
+}
+/** Set FIFO Buffer Overflow interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFIFOBufferOverflowEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+void MPU6050::setIntFIFOBufferOverflowEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, enabled);
+}
+/** Get I2C Master interrupt enabled status.
+ * This enables any of the I2C Master interrupt sources to generate an
+ * interrupt. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+bool MPU6050::getIntI2CMasterEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
+    return buffer[0];
+}
+/** Set I2C Master interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntI2CMasterEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+void MPU6050::setIntI2CMasterEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, enabled);
+}
+/** Get Data Ready interrupt enabled setting.
+ * This event occurs each time a write operation to all of the sensor registers
+ * has been completed. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool MPU6050::getIntDataReadyEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
+    return buffer[0];
+}
+/** Set Data Ready interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntDataReadyEnabled()
+ * @see MPU6050_RA_INT_CFG
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+void MPU6050::setIntDataReadyEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, enabled);
+}
+
+// INT_STATUS register
+
+/** Get full set of interrupt status bits.
+ * These bits clear to 0 after the register has been read. Very useful
+ * for getting multiple INT statuses, since each single bit read clears
+ * all of them because it has to read the whole byte.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ */
+uint8_t MPU6050::getIntStatus()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_INT_STATUS, buffer);
+    return buffer[0];
+}
+/** Get Free Fall interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FF_BIT
+ */
+bool MPU6050::getIntFreefallStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, buffer);
+    return buffer[0];
+}
+/** Get Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Motion Detection interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ */
+bool MPU6050::getIntMotionStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, buffer);
+    return buffer[0];
+}
+/** Get Zero Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Zero Motion Detection interrupt has
+ * been generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ */
+bool MPU6050::getIntZeroMotionStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
+    return buffer[0];
+}
+/** Get FIFO Buffer Overflow interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ */
+bool MPU6050::getIntFIFOBufferOverflowStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+    return buffer[0];
+}
+/** Get I2C Master interrupt status.
+ * This bit automatically sets to 1 when an I2C Master interrupt has been
+ * generated. For a list of I2C Master interrupts, please refer to Register 54.
+ * The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ */
+bool MPU6050::getIntI2CMasterStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
+    return buffer[0];
+}
+/** Get Data Ready interrupt status.
+ * This bit automatically sets to 1 when a Data Ready interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool MPU6050::getIntDataReadyStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
+    return buffer[0];
+}
+
+// ACCEL_*OUT_* registers
+
+/** Get raw 9-axis motion sensor readings (accel/gyro/compass).
+ * FUNCTION NOT FULLY IMPLEMENTED YET.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @param mx 16-bit signed integer container for magnetometer X-axis value
+ * @param my 16-bit signed integer container for magnetometer Y-axis value
+ * @param mz 16-bit signed integer container for magnetometer Z-axis value
+ * @see getMotion6()
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void MPU6050::getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz)
+{
+    getMotion6(ax, ay, az, gx, gy, gz);
+    
+    // magnetometer reading
+    i2Cdev.writeByte(devAddr, MPU6050_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer
+    wait_ms(10); // necessary wait >=6ms
+    i2Cdev.writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); // enable the magnetometer
+    wait_ms(10); // necessary wait >=6ms
+    i2Cdev.readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer);
+    *mx = (((int16_t)buffer[0]) << 8) | buffer[1];
+    *my = (((int16_t)buffer[2]) << 8) | buffer[3];
+    *mz = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get raw 6-axis motion sensor readings (accel/gyro).
+ * Retrieves all currently available motion sensor values.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void MPU6050::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, buffer);
+    *ax = (((int16_t)buffer[0]) << 8) | buffer[1];
+    *ay = (((int16_t)buffer[2]) << 8) | buffer[3];
+    *az = (((int16_t)buffer[4]) << 8) | buffer[5];
+    *gx = (((int16_t)buffer[8]) << 8) | buffer[9];
+    *gy = (((int16_t)buffer[10]) << 8) | buffer[11];
+    *gz = (((int16_t)buffer[12]) << 8) | buffer[13];
+}
+/** Get 3-axis accelerometer readings.
+ * These registers store the most recent accelerometer measurements.
+ * Accelerometer measurements are written to these registers at the Sample Rate
+ * as defined in Register 25.
+ *
+ * The accelerometer measurement registers, along with the temperature
+ * measurement registers, gyroscope measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ *
+ * The data within the accelerometer sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS
+ * (Register 28). For each full scale setting, the accelerometers' sensitivity
+ * per LSB in ACCEL_xOUT is shown in the table below:
+ *
+ * <pre>
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0       | +/- 2g           | 8192 LSB/mg
+ * 1       | +/- 4g           | 4096 LSB/mg
+ * 2       | +/- 8g           | 2048 LSB/mg
+ * 3       | +/- 16g          | 1024 LSB/mg
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis acceleration
+ * @param y 16-bit signed integer container for Y-axis acceleration
+ * @param z 16-bit signed integer container for Z-axis acceleration
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void MPU6050::getAcceleration(int16_t* x, int16_t* y, int16_t* z)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, buffer);
+    *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+    *y = (((int16_t)buffer[2]) << 8) | buffer[3];
+    *z = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis accelerometer reading.
+ * @return X-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+int16_t MPU6050::getAccelerationX()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis accelerometer reading.
+ * @return Y-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_YOUT_H
+ */
+int16_t MPU6050::getAccelerationY()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis accelerometer reading.
+ * @return Z-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_ZOUT_H
+ */
+int16_t MPU6050::getAccelerationZ()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// TEMP_OUT_* registers
+
+/** Get current internal temperature.
+ * @return Temperature reading in 16-bit 2's complement format
+ * @see MPU6050_RA_TEMP_OUT_H
+ */
+int16_t MPU6050::getTemperature()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_TEMP_OUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// GYRO_*OUT_* registers
+
+/** Get 3-axis gyroscope readings.
+ * These gyroscope measurement registers, along with the accelerometer
+ * measurement registers, temperature measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ * The data within the gyroscope sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL
+ * (Register 27). For each full scale setting, the gyroscopes' sensitivity per
+ * LSB in GYRO_xOUT is shown in the table below:
+ *
+ * <pre>
+ * FS_SEL | Full Scale Range   | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
+ * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
+ * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis rotation
+ * @param y 16-bit signed integer container for Y-axis rotation
+ * @param z 16-bit signed integer container for Z-axis rotation
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void MPU6050::getRotation(int16_t* x, int16_t* y, int16_t* z)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 6, buffer);
+    *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+    *y = (((int16_t)buffer[2]) << 8) | buffer[3];
+    *z = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis gyroscope reading.
+ * @return X-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+int16_t MPU6050::getRotationX()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis gyroscope reading.
+ * @return Y-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_YOUT_H
+ */
+int16_t MPU6050::getRotationY()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_YOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis gyroscope reading.
+ * @return Z-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_ZOUT_H
+ */
+int16_t MPU6050::getRotationZ()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// EXT_SENS_DATA_* registers
+
+/** Read single byte from external sensor data register.
+ * These registers store data read from external sensors by the Slave 0, 1, 2,
+ * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in
+ * I2C_SLV4_DI (Register 53).
+ *
+ * External sensor data is written to these registers at the Sample Rate as
+ * defined in Register 25. This access rate can be reduced by using the Slave
+ * Delay Enable registers (Register 103).
+ *
+ * External sensor data registers, along with the gyroscope measurement
+ * registers, accelerometer measurement registers, and temperature measurement
+ * registers, are composed of two sets of registers: an internal register set
+ * and a user-facing read register set.
+ *
+ * The data within the external sensors' internal register set is always updated
+ * at the Sample Rate (or the reduced access rate) whenever the serial interface
+ * is idle. This guarantees that a burst read of sensor registers will read
+ * measurements from the same sampling instant. Note that if burst reads are not
+ * used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Data is placed in these external sensor data registers according to
+ * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39,
+ * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from
+ * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as
+ * defined in Register 25) or delayed rate (if specified in Register 52 and
+ * 103). During each Sample cycle, slave reads are performed in order of Slave
+ * number. If all slaves are enabled with more than zero bytes to be read, the
+ * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3.
+ *
+ * Each enabled slave will have EXT_SENS_DATA registers associated with it by
+ * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from
+ * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may
+ * change the higher numbered slaves' associated registers. Furthermore, if
+ * fewer total bytes are being read from the external sensors as a result of
+ * such a change, then the data remaining in the registers which no longer have
+ * an associated slave device (i.e. high numbered registers) will remain in
+ * these previously allocated registers unless reset.
+ *
+ * If the sum of the read lengths of all SLVx transactions exceed the number of
+ * available EXT_SENS_DATA registers, the excess bytes will be dropped. There
+ * are 24 EXT_SENS_DATA registers and hence the total read lengths between all
+ * the slaves cannot be greater than 24 or some bytes will be lost.
+ *
+ * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further
+ * information regarding the characteristics of Slave 4, please refer to
+ * Registers 49 to 53.
+ *
+ * EXAMPLE:
+ * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and
+ * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that
+ * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00
+ * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05
+ * will be associated with Slave 1. If Slave 2 is enabled as well, registers
+ * starting from EXT_SENS_DATA_06 will be allocated to Slave 2.
+ *
+ * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then
+ * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3
+ * instead.
+ *
+ * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE:
+ * If a slave is disabled at any time, the space initially allocated to the
+ * slave in the EXT_SENS_DATA register, will remain associated with that slave.
+ * This is to avoid dynamic adjustment of the register allocation.
+ *
+ * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all
+ * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106).
+ *
+ * This above is also true if one of the slaves gets NACKed and stops
+ * functioning.
+ *
+ * @param position Starting position (0-23)
+ * @return Byte read from register
+ */
+uint8_t MPU6050::getExternalSensorByte(int position)
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, buffer);
+    return buffer[0];
+}
+/** Read word (2 bytes) from external sensor data registers.
+ * @param position Starting position (0-21)
+ * @return Word read from register
+ * @see getExternalSensorByte()
+ */
+uint16_t MPU6050::getExternalSensorWord(int position)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, buffer);
+    return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Read double word (4 bytes) from external sensor data registers.
+ * @param position Starting position (0-20)
+ * @return Double word read from registers
+ * @see getExternalSensorByte()
+ */
+uint32_t MPU6050::getExternalSensorDWord(int position)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, buffer);
+    return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3];
+}
+
+// MOT_DETECT_STATUS register
+
+/** Get X-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XNEG_BIT
+ */
+bool MPU6050::getXNegMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, buffer);
+    return buffer[0];
+}
+/** Get X-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XPOS_BIT
+ */
+bool MPU6050::getXPosMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, buffer);
+    return buffer[0];
+}
+/** Get Y-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YNEG_BIT
+ */
+bool MPU6050::getYNegMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, buffer);
+    return buffer[0];
+}
+/** Get Y-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YPOS_BIT
+ */
+bool MPU6050::getYPosMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, buffer);
+    return buffer[0];
+}
+/** Get Z-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZNEG_BIT
+ */
+bool MPU6050::getZNegMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, buffer);
+    return buffer[0];
+}
+/** Get Z-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZPOS_BIT
+ */
+bool MPU6050::getZPosMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, buffer);
+    return buffer[0];
+}
+/** Get zero motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZRMOT_BIT
+ */
+bool MPU6050::getZeroMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, buffer);
+    return buffer[0];
+}
+
+// I2C_SLV*_DO register
+
+/** Write byte to Data Output container for specified slave.
+ * This register holds the output data written into Slave when Slave is set to
+ * write mode. For further information regarding Slave control, please
+ * refer to Registers 37 to 39 and immediately following.
+ * @param num Slave number (0-3)
+ * @param data Byte to write
+ * @see MPU6050_RA_I2C_SLV0_DO
+ */
+void MPU6050::setSlaveOutputByte(uint8_t num, uint8_t data)
+{
+    if (num > 3) return;
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_DO + num, data);
+}
+
+// I2C_MST_DELAY_CTRL register
+
+/** Get external data shadow delay enabled status.
+ * This register is used to specify the timing of external sensor data
+ * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external
+ * sensor data is delayed until all data has been received.
+ * @return Current external data shadow delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+bool MPU6050::getExternalShadowDelayEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer);
+    return buffer[0];
+}
+/** Set external data shadow delay enabled status.
+ * @param enabled New external data shadow delay enabled status.
+ * @see getExternalShadowDelayEnabled()
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+void MPU6050::setExternalShadowDelayEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled);
+}
+/** Get slave delay enabled status.
+ * When a particular slave delay is enabled, the rate of access for the that
+ * slave device is reduced. When a slave's access rate is decreased relative to
+ * the Sample Rate, the slave is accessed every:
+ *
+ *     1 / (1 + I2C_MST_DLY) Samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register  * 25)
+ * and DLPF_CFG (register 26).
+ *
+ * For further information regarding I2C_MST_DLY, please refer to register 52.
+ * For further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @param num Slave number (0-4)
+ * @return Current slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+bool MPU6050::getSlaveDelayEnabled(uint8_t num)
+{
+    // MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc.
+    if (num > 4) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, buffer);
+    return buffer[0];
+}
+/** Set slave delay enabled status.
+ * @param num Slave number (0-4)
+ * @param enabled New slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+void MPU6050::setSlaveDelayEnabled(uint8_t num, bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, enabled);
+}
+
+// SIGNAL_PATH_RESET register
+
+/** Reset gyroscope signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_GYRO_RESET_BIT
+ */
+void MPU6050::resetGyroscopePath()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_GYRO_RESET_BIT, true);
+}
+/** Reset accelerometer signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_ACCEL_RESET_BIT
+ */
+void MPU6050::resetAccelerometerPath()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_ACCEL_RESET_BIT, true);
+}
+/** Reset temperature sensor signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_TEMP_RESET_BIT
+ */
+void MPU6050::resetTemperaturePath()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_TEMP_RESET_BIT, true);
+}
+
+// MOT_DETECT_CTRL register
+
+/** Get accelerometer power-on delay.
+ * The accelerometer data path provides samples to the sensor registers, Motion
+ * detection, Zero Motion detection, and Free Fall detection modules. The
+ * signal path contains filters which must be flushed on wake-up with new
+ * samples before the detection modules begin operations. The default wake-up
+ * delay, of 4ms can be lengthened by up to 3ms. This additional delay is
+ * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select
+ * any value above zero unless instructed otherwise by InvenSense. Please refer
+ * to Section 8 of the MPU-6000/MPU-6050 Product Specification document for
+ * further information regarding the detection modules.
+ * @return Current accelerometer power-on delay
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+uint8_t MPU6050::getAccelerometerPowerOnDelay()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set accelerometer power-on delay.
+ * @param delay New accelerometer power-on delay (0-3)
+ * @see getAccelerometerPowerOnDelay()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+void MPU6050::setAccelerometerPowerOnDelay(uint8_t delay)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, delay);
+}
+/** Get Free Fall detection counter decrement configuration.
+ * Detection is registered by the Free Fall detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring FF_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * </pre>
+ *
+ * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Free Fall detection,
+ * please refer to Registers 29 to 32.
+ *
+ * @return Current decrement configuration
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+uint8_t MPU6050::getFreefallDetectionCounterDecrement()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Free Fall detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getFreefallDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+void MPU6050::setFreefallDetectionCounterDecrement(uint8_t decrement)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, decrement);
+}
+/** Get Motion detection counter decrement configuration.
+ * Detection is registered by the Motion detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring MOT_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * </pre>
+ *
+ * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Motion detection,
+ * please refer to Registers 29 to 32.
+ *
+ */
+uint8_t MPU6050::getMotionDetectionCounterDecrement()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Motion detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getMotionDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_MOT_COUNT_BIT
+ */
+void MPU6050::setMotionDetectionCounterDecrement(uint8_t decrement)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, decrement);
+}
+
+// USER_CTRL register
+
+/** Get FIFO enabled status.
+ * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer
+ * cannot be written to or read from while disabled. The FIFO buffer's state
+ * does not change unless the MPU-60X0 is power cycled.
+ * @return Current FIFO enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+bool MPU6050::getFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set FIFO enabled status.
+ * @param enabled New FIFO enabled status
+ * @see getFIFOEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+void MPU6050::setFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, enabled);
+}
+/** Get I2C Master Mode enabled status.
+ * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the
+ * external sensor slave devices on the auxiliary I2C bus. When this bit is
+ * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically
+ * driven by the primary I2C bus (SDA and SCL). This is a precondition to
+ * enabling Bypass Mode. For further information regarding Bypass Mode, please
+ * refer to Register 55.
+ * @return Current I2C Master Mode enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+bool MPU6050::getI2CMasterModeEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set I2C Master Mode enabled status.
+ * @param enabled New I2C Master Mode enabled status
+ * @see getI2CMasterModeEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+void MPU6050::setI2CMasterModeEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, enabled);
+}
+/** Switch from I2C to SPI mode (MPU-6000 only)
+ * If this is set, the primary SPI interface will be enabled in place of the
+ * disabled primary I2C interface.
+ */
+void MPU6050::switchSPIEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled);
+}
+/** Reset the FIFO.
+ * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This
+ * bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_RESET_BIT
+ */
+void MPU6050::resetFIFO()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, true);
+}
+/** Reset the I2C Master.
+ * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0.
+ * This bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_RESET_BIT
+ */
+void MPU6050::resetI2CMaster()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, true);
+}
+/** Reset all sensor registers and signal paths.
+ * When set to 1, this bit resets the signal paths for all sensors (gyroscopes,
+ * accelerometers, and temperature sensor). This operation will also clear the
+ * sensor registers. This bit automatically clears to 0 after the reset has been
+ * triggered.
+ *
+ * When resetting only the signal path (and not the sensor registers), please
+ * use Register 104, SIGNAL_PATH_RESET.
+ *
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_SIG_COND_RESET_BIT
+ */
+void MPU6050::resetSensors()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_SIG_COND_RESET_BIT, true);
+}
+
+// PWR_MGMT_1 register
+
+/** Trigger a full device reset.
+ * A small delay of ~50ms may be desirable after triggering a reset.
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_DEVICE_RESET_BIT
+ */
+void MPU6050::reset()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, true);
+}
+/** Get sleep mode status.
+ * Setting the SLEEP bit in the register puts the device into very low power
+ * sleep mode. In this mode, only the serial interface and internal registers
+ * remain active, allowing for a very low standby current. Clearing this bit
+ * puts the device back into normal mode. To save power, the individual standby
+ * selections for each of the gyros should be used if any gyro axis is not used
+ * by the application.
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+bool MPU6050::getSleepEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, buffer);
+    return buffer[0];
+}
+/** Set sleep mode status.
+ * @param enabled New sleep mode enabled status
+ * @see getSleepEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+void MPU6050::setSleepEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, enabled);
+}
+/** Get wake cycle enabled status.
+ * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle
+ * between sleep mode and waking up to take a single sample of data from active
+ * sensors at a rate determined by LP_WAKE_CTRL (register 108).
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+bool MPU6050::getWakeCycleEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, buffer);
+    return buffer[0];
+}
+/** Set wake cycle enabled status.
+ * @param enabled New sleep mode enabled status
+ * @see getWakeCycleEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+void MPU6050::setWakeCycleEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, enabled);
+}
+/** Get temperature sensor enabled status.
+ * Control the usage of the internal temperature sensor.
+ *
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @return Current temperature sensor enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+bool MPU6050::getTempSensorEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, buffer);
+    return buffer[0] == 0; // 1 is actually disabled here
+}
+/** Set temperature sensor enabled status.
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @param enabled New temperature sensor enabled status
+ * @see getTempSensorEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+void MPU6050::setTempSensorEnabled(bool enabled)
+{
+    // 1 is actually disabled here
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, !enabled);
+}
+/** Get clock source setting.
+ * @return Current clock source setting
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+uint8_t MPU6050::getClockSource()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set clock source setting.
+ * An internal 8MHz oscillator, gyroscope based clock, or external sources can
+ * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator
+ * or an external source is chosen as the clock source, the MPU-60X0 can operate
+ * in low power modes with the gyroscopes disabled.
+ *
+ * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator.
+ * However, it is highly recommended that the device be configured to use one of
+ * the gyroscopes (or an external clock source) as the clock reference for
+ * improved stability. The clock source can be selected according to the following table:
+ *
+ * <pre>
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0       | Internal oscillator
+ * 1       | PLL with X Gyro reference
+ * 2       | PLL with Y Gyro reference
+ * 3       | PLL with Z Gyro reference
+ * 4       | PLL with external 32.768kHz reference
+ * 5       | PLL with external 19.2MHz reference
+ * 6       | Reserved
+ * 7       | Stops the clock and keeps the timing generator in reset
+ * </pre>
+ *
+ * @param source New clock source setting
+ * @see getClockSource()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+void MPU6050::setClockSource(uint8_t source)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, source);
+}
+
+// PWR_MGMT_2 register
+
+/** Get wake frequency in Accel-Only Low Power Mode.
+ * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting
+ * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode,
+ * the device will power off all devices except for the primary I2C interface,
+ * waking only the accelerometer at fixed intervals to take a single
+ * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL
+ * as shown below:
+ *
+ * <pre>
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * <pre>
+ *
+ * For further information regarding the MPU-60X0's power modes, please refer to
+ * Register 107.
+ *
+ * @return Current wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+uint8_t MPU6050::getWakeFrequency()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+void MPU6050::setWakeFrequency(uint8_t frequency)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
+}
+
+/** Get X-axis accelerometer standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+bool MPU6050::getStandbyXAccelEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+void MPU6050::setStandbyXAccelEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, enabled);
+}
+/** Get Y-axis accelerometer standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+bool MPU6050::getStandbyYAccelEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+void MPU6050::setStandbyYAccelEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, enabled);
+}
+/** Get Z-axis accelerometer standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+bool MPU6050::getStandbyZAccelEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+void MPU6050::setStandbyZAccelEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, enabled);
+}
+/** Get X-axis gyroscope standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+bool MPU6050::getStandbyXGyroEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+void MPU6050::setStandbyXGyroEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, enabled);
+}
+/** Get Y-axis gyroscope standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+bool MPU6050::getStandbyYGyroEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+void MPU6050::setStandbyYGyroEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, enabled);
+}
+/** Get Z-axis gyroscope standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+bool MPU6050::getStandbyZGyroEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+void MPU6050::setStandbyZGyroEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t MPU6050::getFIFOCount()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_FIFO_COUNTH, 2, buffer);
+    return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t MPU6050::getFIFOByte()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_FIFO_R_W, buffer);
+    return buffer[0];
+}
+void MPU6050::getFIFOBytes(uint8_t *data, uint8_t length)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU6050_RA_FIFO_R_W
+ */
+void MPU6050::setFIFOByte(uint8_t data)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_FIFO_R_W, data);
+}
+
+// WHO_AM_I register
+
+/** Get Device ID.
+ * This register is used to verify the identity of the device (0b110100, 0x34).
+ * @return Device ID (6 bits only! should be 0x34)
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+uint8_t MPU6050::getDeviceID()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+void MPU6050::setDeviceID(uint8_t id)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t MPU6050::getOTPBankValid()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, buffer);
+    return buffer[0];
+}
+void MPU6050::setOTPBankValid(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t MPU6050::getXGyroOffset()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU6050::setXGyroOffset(int8_t offset)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU6050::getYGyroOffset()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU6050::setYGyroOffset(int8_t offset)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU6050::getZGyroOffset()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU6050::setZGyroOffset(int8_t offset)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// X_FINE_GAIN register
+
+int8_t MPU6050::getXFineGain()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_X_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU6050::setXFineGain(int8_t gain)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU6050::getYFineGain()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_Y_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU6050::setYFineGain(int8_t gain)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU6050::getZFineGain()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_Z_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU6050::setZFineGain(int8_t gain)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU6050::getXAccelOffset()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_XA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setXAccelOffset(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU6050::getYAccelOffset()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_YA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setYAccelOffset(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU6050::getZAccelOffset()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ZA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setZAccelOffset(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU6050::getXGyroOffsetUser()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_XG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setXGyroOffsetUser(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU6050::getYGyroOffsetUser()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_YG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setYGyroOffsetUser(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU6050::getZGyroOffsetUser()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setZGyroOffsetUser(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU6050::getIntPLLReadyEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU6050::setIntPLLReadyEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool MPU6050::getIntDMPEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU6050::setIntDMPEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool MPU6050::getDMPInt5Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6050::getDMPInt4Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6050::getDMPInt3Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6050::getDMPInt2Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6050::getDMPInt1Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6050::getDMPInt0Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, buffer);
+    return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU6050::getIntPLLReadyStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6050::getIntDMPStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU6050::getDMPEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, buffer);
+    return buffer[0];
+}
+void MPU6050::setDMPEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled);
+}
+void MPU6050::resetDMP()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, true);
+}
+
+// BANK_SEL register
+
+void MPU6050::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank)
+{
+    bank &= 0x1F;
+    if (userBank) bank |= 0x20;
+    if (prefetchEnabled) bank |= 0x40;
+    i2Cdev.writeByte(devAddr, MPU6050_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void MPU6050::setMemoryStartAddress(uint8_t address)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t MPU6050::readMemoryByte()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_MEM_R_W, buffer);
+    return buffer[0];
+}
+void MPU6050::writeMemoryByte(uint8_t data)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_MEM_R_W, data);
+}
+void MPU6050::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address)
+{
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    for (uint16_t i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+        // read the chunk of data as specified
+        i2Cdev.readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, data + i);
+
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+}
+bool MPU6050::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem)
+{
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    uint8_t *verifyBuffer = NULL;
+    uint8_t *progBuffer = NULL;
+    uint16_t i;
+    uint8_t j;
+    if (verify) verifyBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
+    if (useProgMem) progBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
+    for (i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+        if (useProgMem) {
+            // write the chunk of data as specified
+            for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+        } else {
+            // write the chunk of data as specified
+            progBuffer = (uint8_t *)data + i;
+        }
+
+        i2Cdev.writeBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer);
+
+        // verify data if needed
+        if (verify && verifyBuffer) {
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+            i2Cdev.readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer);
+            if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
+                /*Serial.print("Block write verification error, bank ");
+                Serial.print(bank, DEC);
+                Serial.print(", address ");
+                Serial.print(address, DEC);
+                Serial.print("!\nExpected:");
+                for (j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (progBuffer[j] < 16) Serial.print("0");
+                    Serial.print(progBuffer[j], HEX);
+                }
+                Serial.print("\nReceived:");
+                for (uint8_t j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (verifyBuffer[i + j] < 16) Serial.print("0");
+                    Serial.print(verifyBuffer[i + j], HEX);
+                }
+                Serial.print("\n");*/
+                free(verifyBuffer);
+                if (useProgMem) free(progBuffer);
+                return false; // uh oh.
+            }
+        }
+
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+    if (verify) free(verifyBuffer);
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU6050::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify)
+{
+    return writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU6050::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem)
+{
+    uint8_t success, special;
+    uint8_t *progBuffer = NULL;
+    uint16_t i, j;
+    if (useProgMem) {
+        progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
+    }
+
+    // config set data is a long string of blocks with the following structure:
+    // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+    uint8_t bank, offset, length;
+    for (i = 0; i < dataSize;) {
+        if (useProgMem) {
+            bank = pgm_read_byte(data + i++);
+            offset = pgm_read_byte(data + i++);
+            length = pgm_read_byte(data + i++);
+        } else {
+            bank = data[i++];
+            offset = data[i++];
+            length = data[i++];
+        }
+
+        // write data or perform special action
+        if (length > 0) {
+            // regular block of data to write
+            /*Serial.print("Writing config block to bank ");
+            Serial.print(bank);
+            Serial.print(", offset ");
+            Serial.print(offset);
+            Serial.print(", length=");
+            Serial.println(length);*/
+            if (useProgMem) {
+                if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
+                for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+            } else {
+                progBuffer = (uint8_t *)data + i;
+            }
+            success = writeMemoryBlock(progBuffer, length, bank, offset, true);
+            i += length;
+        } else {
+            // special instruction
+            // NOTE: this kind of behavior (what and when to do certain things)
+            // is totally undocumented. This code is in here based on observed
+            // behavior only, and exactly why (or even whether) it has to be here
+            // is anybody's guess for now.
+            if (useProgMem) {
+                special = pgm_read_byte(data + i++);
+            } else {
+                special = data[i++];
+            }
+            /*Serial.print("Special command code ");
+            Serial.print(special, HEX);
+            Serial.println(" found...");*/
+            if (special == 0x01) {
+                // enable DMP-related interrupts
+
+                //setIntZeroMotionEnabled(true);
+                //setIntFIFOBufferOverflowEnabled(true);
+                //setIntDMPEnabled(true);
+                i2Cdev.writeByte(devAddr, MPU6050_RA_INT_ENABLE, 0x32);  // single operation
+
+                success = true;
+            } else {
+                // unknown special command
+                success = false;
+            }
+        }
+
+        if (!success) {
+            if (useProgMem) free(progBuffer);
+            return false; // uh oh
+        }
+    }
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU6050::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize)
+{
+    return writeDMPConfigurationSet(data, dataSize, false);
+}
+
+// DMP_CFG_1 register
+
+uint8_t MPU6050::getDMPConfig1()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_DMP_CFG_1, buffer);
+    return buffer[0];
+}
+void MPU6050::setDMPConfig1(uint8_t config)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU6050::getDMPConfig2()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_DMP_CFG_2, buffer);
+    return buffer[0];
+}
+void MPU6050::setDMPConfig2(uint8_t config)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_DMP_CFG_2, config);
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/MPU/src/MPU6050_6Axis_MotionApps20.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/MPU/src/MPU6050_6Axis_MotionApps20.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,470 @@
+// I2Cdev library collection - MPU6050 I2C device class, 6-axis MotionApps 2.0 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 5/20/2013 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+ 
+/* ============================================
+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.
+===============================================
+*/
+
+#include "MPU6050_6Axis_MotionApps20.h"
+
+uint8_t MPU6050::dmpInitialize()
+{
+    // reset device
+    wait_ms(50);
+    reset();
+    wait_ms(30);
+
+    // enable sleep mode and wake cycle
+    /*Serial.println(F("Enabling sleep mode..."));
+    setSleepEnabled(true);
+    Serial.println(F("Enabling wake cycle..."));
+    setWakeCycleEnabled(true);*/
+
+    // disable sleep mode
+    //DEBUG_PRINT("Disabling sleep mode...\n");
+    setSleepEnabled(false);
+
+    // get MPU hardware revision
+    //DEBUG_PRINT("Selecting user bank 16...\n");
+    setMemoryBank(0x10, true, true);
+    //DEBUG_PRINT("Selecting memory byte 6...\n");
+    setMemoryStartAddress(0x06);
+    //DEBUG_PRINT("Checking hardware revision...\n");
+    uint8_t hwRevision = readMemoryByte();
+    //DEBUG_PRINT("Revision @ user[16][6] = ");
+    //DEBUG_PRINTF("%x\n",hwRevision);
+    //DEBUG_PRINT("Resetting memory bank selection to 0...\n");
+    setMemoryBank(0, false, false);
+
+    // check OTP bank valid
+    //DEBUG_PRINT("Reading OTP bank valid flag...\n");
+    uint8_t otpValid = getOTPBankValid();
+
+    //DEBUG_PRINT("OTP bank is ");
+    if(otpValid);  //DEBUG_PRINT("valid!\n");
+    else;  //DEBUG_PRINT("invalid!\n");
+
+    // get X/Y/Z gyro offsets
+    /*
+    DEBUG_PRINT("\nReading gyro offset TC values...\n");
+    int8_t xgOffsetTC = mpu.getXGyroOffsetTC();
+    int8_t ygOffsetTC = getYGyroOffsetTC();
+    int8_t zgOffsetTC = getZGyroOffsetTC();
+    DEBUG_PRINTF("X gyro offset = %u\n",xgOffset);
+    DEBUG_PRINTF("Y gyro offset = %u\n",ygOffset);
+    DEBUG_PRINTF("Z gyro offset = %u\n",zgOffset);
+    */
+    // setup weird slave stuff (?)
+    //DEBUG_PRINT("Setting slave 0 address to 0x7F...\n");
+    setSlaveAddress(0, 0x7F);
+
+    //DEBUG_PRINT("Disabling I2C Master mode...");
+    setI2CMasterModeEnabled(false);
+    //DEBUG_PRINT("Setting slave 0 address to 0x68 (self)...");
+    setSlaveAddress(0, 0x68);
+    //DEBUG_PRINT("Resetting I2C Master control...\n");
+    resetI2CMaster();
+
+    wait_ms(20);
+
+    // load DMP code into memory banks
+    //DEBUG_PRINT("Writing DMP code to MPU memory banks (");
+    //DEBUG_PRINTF("%u",MPU6050_DMP_CODE_SIZE);
+    //DEBUG_PRINT(" bytes)\n");
+    if (writeProgMemoryBlock(dmpMemory, MPU6050_DMP_CODE_SIZE)) {
+        //DEBUG_PRINT("Success! DMP code written and verified.\n");
+
+        // write DMP configuration
+        //DEBUG_PRINT("Writing DMP configuration to MPU memory banks (");
+        //DEBUG_PRINTF("%u",MPU6050_DMP_CONFIG_SIZE);
+        //DEBUG_PRINT(" bytes in config def)\n");
+        if (writeProgDMPConfigurationSet(dmpConfig, MPU6050_DMP_CONFIG_SIZE)) {
+            //DEBUG_PRINT("Success! DMP configuration written and verified.\n");
+
+            //DEBUG_PRINT("Setting clock source to Z Gyro...\n");
+            setClockSource(MPU6050_CLOCK_PLL_ZGYRO);
+
+            //DEBUG_PRINT("Setting DMP and FIFO_OFLOW interrupts enabled...\n");
+            setIntEnabled(0x12);
+
+            //DEBUG_PRINT("Setting sample rate to 200Hz...");
+            setRate(4); // 1khz / (1 + 4) = 200 Hz
+
+            //DEBUG_PRINT("Setting external frame sync to TEMP_OUT_L[0]...\n");
+            setExternalFrameSync(MPU6050_EXT_SYNC_TEMP_OUT_L);
+
+            //DEBUG_PRINT("Setting DLPF bandwidth to 42Hz...\n");
+            setDLPFMode(MPU6050_DLPF_BW_42);
+
+            //DEBUG_PRINT("Setting gyro sensitivity to +/- 2000 deg/sec...\n");
+            setFullScaleGyroRange(MPU6050_GYRO_FS_2000);
+
+            //DEBUG_PRINT("Setting DMP configuration bytes (function unknown)...\n");
+            setDMPConfig1(0x03);
+            setDMPConfig2(0x00);
+
+            //DEBUG_PRINT("Clearing OTP Bank flag...");
+            setOTPBankValid(false);
+
+            //DEBUG_PRINT("Setting X/Y/Z gyro offset TCs to previous values...\n");
+            //setXGyroOffsetTC(xgOffsetTC);
+            //setYGyroOffsetTC(ygOffsetTC);
+            //setZGyroOffsetTC(zgOffsetTC);
+
+            //DEBUG_PRINTLN(F("Setting X/Y/Z gyro user offsets to zero..."));
+            //setXGyroOffset(0);
+            //setYGyroOffset(0);
+            //setZGyroOffset(0);
+
+            //DEBUG_PRINT("Writing final memory update 1/7 (function unknown)...\n");
+            uint8_t dmpUpdate[16], j;
+            uint16_t pos = 0;
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Writing final memory update 2/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Resetting FIFO...\n");
+            resetFIFO();
+
+            //DEBUG_PRINT("Reading FIFO count...\n");
+            uint16_t fifoCount = getFIFOCount();
+            uint8_t fifoBuffer[128];
+
+            //DEBUG_PRINT("Current FIFO count=");
+            //DEBUG_PRINTF("%u\n",fifoCount);
+            getFIFOBytes(fifoBuffer, fifoCount);
+
+            //DEBUG_PRINT("Setting motion detection threshold to 2...\n");
+            setMotionDetectionThreshold(2);
+
+            //DEBUG_PRINT("Setting zero-motion detection threshold to 156...\n");
+            setZeroMotionDetectionThreshold(156);
+
+            //DEBUG_PRINT("Setting motion detection duration to 80...");
+            setMotionDetectionDuration(80);
+
+            //DEBUG_PRINT("Setting zero-motion detection duration to 0...");
+            setZeroMotionDetectionDuration(0);
+
+            //DEBUG_PRINT("Resetting FIFO...\n");
+            resetFIFO();
+
+            //DEBUG_PRINT("Enabling FIFO...\n");
+            setFIFOEnabled(true);
+
+            //DEBUG_PRINT("Enabling DMP...\n");
+            setDMPEnabled(true);
+
+            //DEBUG_PRINT("Resetting DMP...\n");
+            resetDMP();
+
+            //DEBUG_PRINT("Writing final memory update 3/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Writing final memory update 4/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Writing final memory update 5/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Waiting for FIFO count > 2...\n");
+            while ((fifoCount = getFIFOCount()) < 3);
+
+            //DEBUG_PRINT("Current FIFO count=");
+            //DEBUG_PRINTF("%u\n",fifoCount);
+            //DEBUG_PRINT("Reading FIFO data...\n");
+            getFIFOBytes(fifoBuffer, fifoCount);
+
+            //DEBUG_PRINT("Reading interrupt status...\n");
+            uint8_t mpuIntStatus = getIntStatus();
+
+            //DEBUG_PRINT("Current interrupt status=");
+            //DEBUG_PRINTF("%x\n",mpuIntStatus);
+
+            //DEBUG_PRINT("Reading final memory update 6/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Waiting for FIFO count > 2...\n");
+            while ((fifoCount = getFIFOCount()) < 3);
+
+            //DEBUG_PRINT("Current FIFO count=");
+            //DEBUG_PRINTF("%u\n",fifoCount);
+
+            //DEBUG_PRINT("Reading FIFO data...\n");
+            getFIFOBytes(fifoBuffer, fifoCount);
+
+            //DEBUG_PRINT("Reading interrupt status...\n");
+            mpuIntStatus = getIntStatus();
+
+            //DEBUG_PRINT("Current interrupt status=");
+            //DEBUG_PRINTF("%x\n",mpuIntStatus);
+
+            //DEBUG_PRINT("Writing final memory update 7/7 (function unknown)...");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("DMP is good to go! Finally.\n");
+
+            //DEBUG_PRINT("Disabling DMP (you turn it on later)...\n");
+            setDMPEnabled(false);
+
+            //DEBUG_PRINT("Setting up internal 42-byte (default) DMP packet buffer...\n");
+            dmpPacketSize = 42;
+            /*if ((dmpPacketBuffer = (uint8_t *)malloc(42)) == 0) {
+                return 3; // TODO: proper error code for no memory
+            }*/
+
+            //DEBUG_PRINT("Resetting FIFO and clearing INT status one last time...\n");
+            resetFIFO();
+            getIntStatus();
+        } else {
+            //DEBUG_PRINT("ERROR! DMP configuration verification failed.\n");
+            return 2; // configuration block loading failed
+        }
+    } else {
+        //DEBUG_PRINT("ERROR! DMP code verification failed.");
+        return 1; // main binary block loading failed
+    }
+    return 0; // success
+}
+
+bool MPU6050::dmpPacketAvailable()
+{
+    return getFIFOCount() >= dmpGetFIFOPacketSize();
+}
+
+// uint8_t MPU6050::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6050::dmpGetFIFORate();
+// uint8_t MPU6050::dmpGetSampleStepSizeMS();
+// uint8_t MPU6050::dmpGetSampleFrequency();
+// int32_t MPU6050::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6050::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6050::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6050::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6050::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+uint8_t MPU6050::dmpGetAccel(int32_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[28] << 24) + (packet[29] << 16) + (packet[30] << 8) + packet[31]);
+    data[1] = ((packet[32] << 24) + (packet[33] << 16) + (packet[34] << 8) + packet[35]);
+    data[2] = ((packet[36] << 24) + (packet[37] << 16) + (packet[38] << 8) + packet[39]);
+    return 0;
+}
+uint8_t MPU6050::dmpGetAccel(int16_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = (packet[28] << 8) + packet[29];
+    data[1] = (packet[32] << 8) + packet[33];
+    data[2] = (packet[36] << 8) + packet[37];
+    return 0;
+}
+uint8_t MPU6050::dmpGetAccel(VectorInt16 *v, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    v -> x = (packet[28] << 8) + packet[29];
+    v -> y = (packet[32] << 8) + packet[33];
+    v -> z = (packet[36] << 8) + packet[37];
+    return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(int32_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[0] << 24) + (packet[1] << 16) + (packet[2] << 8) + packet[3]);
+    data[1] = ((packet[4] << 24) + (packet[5] << 16) + (packet[6] << 8) + packet[7]);
+    data[2] = ((packet[8] << 24) + (packet[9] << 16) + (packet[10] << 8) + packet[11]);
+    data[3] = ((packet[12] << 24) + (packet[13] << 16) + (packet[14] << 8) + packet[15]);
+    return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(int16_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[0] << 8) + packet[1]);
+    data[1] = ((packet[4] << 8) + packet[5]);
+    data[2] = ((packet[8] << 8) + packet[9]);
+    data[3] = ((packet[12] << 8) + packet[13]);
+    return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(Quaternion *q, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    int16_t qI[4];
+    uint8_t status = dmpGetQuaternion(qI, packet);
+    if (status == 0) {
+        q -> w = (float)qI[0] / 16384.0f;
+        q -> x = (float)qI[1] / 16384.0f;
+        q -> y = (float)qI[2] / 16384.0f;
+        q -> z = (float)qI[3] / 16384.0f;
+        return 0;
+    }
+    return status; // int16 return value, indicates error if this line is reached
+}
+// uint8_t MPU6050::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetGyro(int32_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[16] << 24) + (packet[17] << 16) + (packet[18] << 8) + packet[19]);
+    data[1] = ((packet[20] << 24) + (packet[21] << 16) + (packet[22] << 8) + packet[23]);
+    data[2] = ((packet[24] << 24) + (packet[25] << 16) + (packet[26] << 8) + packet[27]);
+    return 0;
+}
+uint8_t MPU6050::dmpGetGyro(int16_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = (packet[16] << 8) + packet[17];
+    data[1] = (packet[20] << 8) + packet[21];
+    data[2] = (packet[24] << 8) + packet[25];
+    return 0;
+}
+// uint8_t MPU6050::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6050::dmpGetLinearAccel(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity)
+{
+    // get rid of the gravity component (+1g = +8192 in standard DMP FIFO packet, sensitivity is 2g)
+    v -> x = vRaw -> x - gravity -> x*8192;
+    v -> y = vRaw -> y - gravity -> y*8192;
+    v -> z = vRaw -> z - gravity -> z*8192;
+    return 0;
+}
+// uint8_t MPU6050::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q)
+{
+    // rotate measured 3D acceleration vector into original state
+    // frame of reference based on orientation quaternion
+    memcpy(v, vReal, sizeof(VectorInt16));
+    v -> rotate(q);
+    return 0;
+}
+// uint8_t MPU6050::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGravity(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetGravity(VectorFloat *v, Quaternion *q)
+{
+    v -> x = 2 * (q -> x*q -> z - q -> w*q -> y);
+    v -> y = 2 * (q -> w*q -> x + q -> y*q -> z);
+    v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z;
+    return 0;
+}
+// uint8_t MPU6050::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetEIS(long *data, const uint8_t* packet);
+
+uint8_t MPU6050::dmpGetEuler(float *data, Quaternion *q)
+{
+    data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);   // psi
+    data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y);                              // theta
+    data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1);   // phi
+    return 0;
+}
+
+uint8_t MPU6050::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity)
+{
+    // yaw: (about Z axis)
+    data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+    // pitch: (nose up/down, about Y axis)
+    data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+    // roll: (tilt left/right, about X axis)
+    data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z));
+    return 0;
+}
+
+// uint8_t MPU6050::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+uint8_t MPU6050::dmpProcessFIFOPacket(const unsigned char *dmpData)
+{
+    /*for (uint8_t k = 0; k < dmpPacketSize; k++) {
+        if (dmpData[k] < 0x10) Serial.print("0");
+        Serial.print(dmpData[k], HEX);
+        Serial.print(" ");
+    }
+    Serial.print("\n");*/
+    //Serial.println((uint16_t)dmpPacketBuffer);
+    return 0;
+}
+uint8_t MPU6050::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed)
+{
+    uint8_t status;
+    uint8_t buf[dmpPacketSize];
+    for (uint8_t i = 0; i < numPackets; i++) {
+        // read packet from FIFO
+        getFIFOBytes(buf, dmpPacketSize);
+
+        // process packet
+        if ((status = dmpProcessFIFOPacket(buf)) > 0) return status;
+
+        // increment external process count variable, if supplied
+        if (processed != 0) *processed++;
+    }
+    return 0;
+}
+
+// uint8_t MPU6050::dmpSetFIFOProcessedCallback(void (*func) (void));
+
+// uint8_t MPU6050::dmpInitFIFOParam();
+// uint8_t MPU6050::dmpCloseFIFO();
+// uint8_t MPU6050::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6050::dmpDecodeQuantizedAccel();
+// uint32_t MPU6050::dmpGetGyroSumOfSquare();
+// uint32_t MPU6050::dmpGetAccelSumOfSquare();
+// void MPU6050::dmpOverrideQuaternion(long *q);
+uint16_t MPU6050::dmpGetFIFOPacketSize()
+{
+    return dmpPacketSize;
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/MPU/src/MPU6051.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/MPU/src/MPU6051.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,3442 @@
+//ported from arduino library: https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
+//written by szymon gaertig (email: szymon@gaertig.com.pl)
+//
+//Changelog:
+//2013-01-08 - first beta release
+
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 8/24/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+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.
+===============================================
+*/
+
+#include "MPU6051.h"
+
+//#define useDebugSerial
+
+//instead of using pgmspace.h
+typedef const unsigned char prog_uchar;
+#define pgm_read_byte_near(x) (*(prog_uchar*)(x))//<- I modified here
+#define pgm_read_byte(x) (*(prog_uchar*)(x))//<- I modified here
+
+/** Default constructor, uses default I2C address.
+ * @see MPU6050_DEFAULT_ADDRESS
+ */
+MPU6051::MPU6051() //: debugSerial(USBTX, USBRX)
+{
+    devAddr = MPU6050_DEFAULT_ADDRESS;
+}
+
+/** Specific address constructor.
+ * @param address I2C address
+ * @see MPU6050_DEFAULT_ADDRESS
+ * @see MPU6050_ADDRESS_AD0_LOW
+ * @see MPU6050_ADDRESS_AD0_HIGH
+ */
+MPU6051::MPU6051(uint8_t address) //: debugSerial(USBTX, USBRX)
+{
+    devAddr = address;
+}
+
+/** Power on and prepare for general usage.
+ * This will activate the device and take it out of sleep mode (which must be done
+ * after start-up). This function also sets both the accelerometer and the gyroscope
+ * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets
+ * the clock source to use the X Gyro for reference, which is slightly better than
+ * the default internal clock source.
+ */
+void MPU6051::initialize()
+{
+
+#ifdef useDebugSerial
+    debugSerial.printf("MPU6050::initialize start\n");
+#endif
+
+    setClockSource(MPU6050_CLOCK_PLL_XGYRO);
+    setFullScaleGyroRange(MPU6050_GYRO_FS_250);
+    setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
+    setSleepEnabled(false); // thanks to Jack Elston for pointing this one out!
+
+#ifdef useDebugSerial
+    debugSerial.printf("MPU6050::initialize end\n");
+#endif
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool MPU6051::testConnection()
+{
+#ifdef useDebugSerial
+    debugSerial.printf("MPU6050::testConnection start\n");
+#endif
+    uint8_t deviceId = getDeviceID();
+#ifdef useDebugSerial
+    debugSerial.printf("DeviceId = %d\n",deviceId);
+#endif
+    return deviceId == 0x34;
+}
+
+// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC)
+
+/** Get the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @return I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+uint8_t MPU6051::getAuxVDDIOLevel()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, buffer);
+    return buffer[0];
+}
+/** Set the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @param level I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+void MPU6051::setAuxVDDIOLevel(uint8_t level)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, level);
+}
+
+// SMPLRT_DIV register
+
+/** Get gyroscope output rate divider.
+ * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero
+ * Motion detection, and Free Fall detection are all based on the Sample Rate.
+ * The Sample Rate is generated by dividing the gyroscope output rate by
+ * SMPLRT_DIV:
+ *
+ * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
+ *
+ * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or
+ * 7), and 1kHz when the DLPF is enabled (see Register 26).
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * For a diagram of the gyroscope and accelerometer signal paths, see Section 8
+ * of the MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current sample rate
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+uint8_t MPU6051::getRate()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_SMPLRT_DIV, buffer);
+    return buffer[0];
+}
+/** Set gyroscope sample rate divider.
+ * @param rate New sample rate divider
+ * @see getRate()
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+void MPU6051::setRate(uint8_t rate)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_SMPLRT_DIV, rate);
+}
+
+// CONFIG register
+
+/** Get external FSYNC configuration.
+ * Configures the external Frame Synchronization (FSYNC) pin sampling. An
+ * external signal connected to the FSYNC pin can be sampled by configuring
+ * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short
+ * strobes may be captured. The latched FSYNC signal will be sampled at the
+ * Sampling Rate, as defined in register 25. After sampling, the latch will
+ * reset to the current FSYNC signal state.
+ *
+ * The sampled value will be reported in place of the least significant bit in
+ * a sensor data register determined by the value of EXT_SYNC_SET according to
+ * the following table.
+ *
+ * <pre>
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0            | Input disabled
+ * 1            | TEMP_OUT_L[0]
+ * 2            | GYRO_XOUT_L[0]
+ * 3            | GYRO_YOUT_L[0]
+ * 4            | GYRO_ZOUT_L[0]
+ * 5            | ACCEL_XOUT_L[0]
+ * 6            | ACCEL_YOUT_L[0]
+ * 7            | ACCEL_ZOUT_L[0]
+ * </pre>
+ *
+ * @return FSYNC configuration value
+ */
+uint8_t MPU6051::getExternalFrameSync()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set external FSYNC configuration.
+ * @see getExternalFrameSync()
+ * @see MPU6050_RA_CONFIG
+ * @param sync New FSYNC configuration value
+ */
+void MPU6051::setExternalFrameSync(uint8_t sync)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, sync);
+}
+/** Get digital low-pass filter configuration.
+ * The DLPF_CFG parameter sets the digital low pass filter configuration. It
+ * also determines the internal sampling rate used by the device as shown in
+ * the table below.
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * <pre>
+ *          |   ACCELEROMETER    |           GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
+ * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
+ * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
+ * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
+ * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
+ * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
+ * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
+ * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
+ * </pre>
+ *
+ * @return DLFP configuration
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+uint8_t MPU6051::getDLPFMode()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set digital low-pass filter configuration.
+ * @param mode New DLFP configuration setting
+ * @see getDLPFBandwidth()
+ * @see MPU6050_DLPF_BW_256
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+void MPU6051::setDLPFMode(uint8_t mode)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, mode);
+}
+
+// GYRO_CONFIG register
+
+/** Get full-scale gyroscope range.
+ * The FS_SEL parameter allows setting the full-scale range of the gyro sensors,
+ * as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * </pre>
+ *
+ * @return Current full-scale gyroscope range setting
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+uint8_t MPU6051::getFullScaleGyroRange()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set full-scale gyroscope range.
+ * @param range New full-scale gyroscope range value
+ * @see getFullScaleRange()
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+void MPU6051::setFullScaleGyroRange(uint8_t range)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, range);
+}
+
+// ACCEL_CONFIG register
+
+/** Get self-test enabled setting for accelerometer X axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6051::getAccelXSelfTest()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, buffer);
+    return buffer[0];
+}
+/** Get self-test enabled setting for accelerometer X axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6051::setAccelXSelfTest(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6051::getAccelYSelfTest()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, buffer);
+    return buffer[0];
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6051::setAccelYSelfTest(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Z axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6051::getAccelZSelfTest()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, buffer);
+    return buffer[0];
+}
+/** Set self-test enabled value for accelerometer Z axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6051::setAccelZSelfTest(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, enabled);
+}
+/** Get full-scale accelerometer range.
+ * The FS_SEL parameter allows setting the full-scale range of the accelerometer
+ * sensors, as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * </pre>
+ *
+ * @return Current full-scale accelerometer range setting
+ * @see MPU6050_ACCEL_FS_2
+ * @see MPU6050_RA_ACCEL_CONFIG
+ * @see MPU6050_ACONFIG_AFS_SEL_BIT
+ * @see MPU6050_ACONFIG_AFS_SEL_LENGTH
+ */
+uint8_t MPU6051::getFullScaleAccelRange()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set full-scale accelerometer range.
+ * @param range New full-scale accelerometer range setting
+ * @see getFullScaleAccelRange()
+ */
+void MPU6051::setFullScaleAccelRange(uint8_t range)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, range);
+}
+/** Get the high-pass filter configuration.
+ * The DHPF is a filter module in the path leading to motion detectors (Free
+ * Fall, Motion threshold, and Zero Motion). The high pass filter output is not
+ * available to the data registers (see Figure in Section 8 of the MPU-6000/
+ * MPU-6050 Product Specification document).
+ *
+ * The high pass filter has three modes:
+ *
+ * <pre>
+ *    Reset: The filter output settles to zero within one sample. This
+ *           effectively disables the high pass filter. This mode may be toggled
+ *           to quickly settle the filter.
+ *
+ *    On:    The high pass filter will pass signals above the cut off frequency.
+ *
+ *    Hold:  When triggered, the filter holds the present sample. The filter
+ *           output will be the difference between the input sample and the held
+ *           sample.
+ * </pre>
+ *
+ * <pre>
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0         | Reset       | None
+ * 1         | On          | 5Hz
+ * 2         | On          | 2.5Hz
+ * 3         | On          | 1.25Hz
+ * 4         | On          | 0.63Hz
+ * 7         | Hold        | None
+ * </pre>
+ *
+ * @return Current high-pass filter configuration
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+uint8_t MPU6051::getDHPFMode()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set the high-pass filter configuration.
+ * @param bandwidth New high-pass filter configuration
+ * @see setDHPFMode()
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6051::setDHPFMode(uint8_t bandwidth)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, bandwidth);
+}
+
+// FF_THR register
+
+/** Get free-fall event acceleration threshold.
+ * This register configures the detection threshold for Free Fall event
+ * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the
+ * absolute value of the accelerometer measurements for the three axes are each
+ * less than the detection threshold. This condition increments the Free Fall
+ * duration counter (Register 30). The Free Fall interrupt is triggered when the
+ * Free Fall duration counter reaches the time specified in FF_DUR.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current free-fall acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_FF_THR
+ */
+uint8_t MPU6051::getFreefallDetectionThreshold()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_FF_THR, buffer);
+    return buffer[0];
+}
+/** Get free-fall event acceleration threshold.
+ * @param threshold New free-fall acceleration threshold value (LSB = 2mg)
+ * @see getFreefallDetectionThreshold()
+ * @see MPU6050_RA_FF_THR
+ */
+void MPU6051::setFreefallDetectionThreshold(uint8_t threshold)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_FF_THR, threshold);
+}
+
+// FF_DUR register
+
+/** Get free-fall event duration threshold.
+ * This register configures the duration counter threshold for Free Fall event
+ * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit
+ * of 1 LSB = 1 ms.
+ *
+ * The Free Fall duration counter increments while the absolute value of the
+ * accelerometer measurements are each less than the detection threshold
+ * (Register 29). The Free Fall interrupt is triggered when the Free Fall
+ * duration counter reaches the time specified in this register.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current free-fall duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_FF_DUR
+ */
+uint8_t MPU6051::getFreefallDetectionDuration()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_FF_DUR, buffer);
+    return buffer[0];
+}
+/** Get free-fall event duration threshold.
+ * @param duration New free-fall duration threshold value (LSB = 1ms)
+ * @see getFreefallDetectionDuration()
+ * @see MPU6050_RA_FF_DUR
+ */
+void MPU6051::setFreefallDetectionDuration(uint8_t duration)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_FF_DUR, duration);
+}
+
+// MOT_THR register
+
+/** Get motion detection event acceleration threshold.
+ * This register configures the detection threshold for Motion interrupt
+ * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the
+ * absolute value of any of the accelerometer measurements exceeds this Motion
+ * detection threshold. This condition increments the Motion detection duration
+ * counter (Register 32). The Motion detection interrupt is triggered when the
+ * Motion Detection counter reaches the time count specified in MOT_DUR
+ * (Register 32).
+ *
+ * The Motion interrupt will indicate the axis and polarity of detected motion
+ * in MOT_DETECT_STATUS (Register 97).
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_MOT_THR
+ */
+uint8_t MPU6051::getMotionDetectionThreshold()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_MOT_THR, buffer);
+    return buffer[0];
+}
+/** Set free-fall event acceleration threshold.
+ * @param threshold New motion detection acceleration threshold value (LSB = 2mg)
+ * @see getMotionDetectionThreshold()
+ * @see MPU6050_RA_MOT_THR
+ */
+void MPU6051::setMotionDetectionThreshold(uint8_t threshold)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_MOT_THR, threshold);
+}
+
+// MOT_DUR register
+
+/** Get motion detection event duration threshold.
+ * This register configures the duration counter threshold for Motion interrupt
+ * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit
+ * of 1LSB = 1ms. The Motion detection duration counter increments when the
+ * absolute value of any of the accelerometer measurements exceeds the Motion
+ * detection threshold (Register 31). The Motion detection interrupt is
+ * triggered when the Motion detection counter reaches the time count specified
+ * in this register.
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current motion detection duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_MOT_DUR
+ */
+uint8_t MPU6051::getMotionDetectionDuration()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_MOT_DUR, buffer);
+    return buffer[0];
+}
+/** Set motion detection event duration threshold.
+ * @param duration New motion detection duration threshold value (LSB = 1ms)
+ * @see getMotionDetectionDuration()
+ * @see MPU6050_RA_MOT_DUR
+ */
+void MPU6051::setMotionDetectionDuration(uint8_t duration)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_MOT_DUR, duration);
+}
+
+// ZRMOT_THR register
+
+/** Get zero motion detection event acceleration threshold.
+ * This register configures the detection threshold for Zero Motion interrupt
+ * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when
+ * the absolute value of the accelerometer measurements for the 3 axes are each
+ * less than the detection threshold. This condition increments the Zero Motion
+ * duration counter (Register 34). The Zero Motion interrupt is triggered when
+ * the Zero Motion duration counter reaches the time count specified in
+ * ZRMOT_DUR (Register 34).
+ *
+ * Unlike Free Fall or Motion detection, Zero Motion detection triggers an
+ * interrupt both when Zero Motion is first detected and when Zero Motion is no
+ * longer detected.
+ *
+ * When a zero motion event is detected, a Zero Motion Status will be indicated
+ * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion
+ * condition is detected, the status bit is set to 1. When a zero-motion-to-
+ * motion condition is detected, the status bit is set to 0.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+uint8_t MPU6051::getZeroMotionDetectionThreshold()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_ZRMOT_THR, buffer);
+    return buffer[0];
+}
+/** Set zero motion detection event acceleration threshold.
+ * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see getZeroMotionDetectionThreshold()
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+void MPU6051::setZeroMotionDetectionThreshold(uint8_t threshold)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_ZRMOT_THR, threshold);
+}
+
+// ZRMOT_DUR register
+
+/** Get zero motion detection event duration threshold.
+ * This register configures the duration counter threshold for Zero Motion
+ * interrupt generation. The duration counter ticks at 16 Hz, therefore
+ * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter
+ * increments while the absolute value of the accelerometer measurements are
+ * each less than the detection threshold (Register 33). The Zero Motion
+ * interrupt is triggered when the Zero Motion duration counter reaches the time
+ * count specified in this register.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document, as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection duration threshold value (LSB = 64ms)
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+uint8_t MPU6051::getZeroMotionDetectionDuration()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_ZRMOT_DUR, buffer);
+    return buffer[0];
+}
+/** Set zero motion detection event duration threshold.
+ * @param duration New zero motion detection duration threshold value (LSB = 1ms)
+ * @see getZeroMotionDetectionDuration()
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+void MPU6051::setZeroMotionDetectionDuration(uint8_t duration)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_ZRMOT_DUR, duration);
+}
+
+// FIFO_EN register
+
+/** Get temperature FIFO enabled value.
+ * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and
+ * 66) to be written into the FIFO buffer.
+ * @return Current temperature FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6051::getTempFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set temperature FIFO enabled value.
+ * @param enabled New temperature FIFO enabled value
+ * @see getTempFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6051::setTempFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope X-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and
+ * 68) to be written into the FIFO buffer.
+ * @return Current gyroscope X-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6051::getXGyroFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set gyroscope X-axis FIFO enabled value.
+ * @param enabled New gyroscope X-axis FIFO enabled value
+ * @see getXGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6051::setXGyroFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Y-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and
+ * 70) to be written into the FIFO buffer.
+ * @return Current gyroscope Y-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6051::getYGyroFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set gyroscope Y-axis FIFO enabled value.
+ * @param enabled New gyroscope Y-axis FIFO enabled value
+ * @see getYGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6051::setYGyroFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Z-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and
+ * 72) to be written into the FIFO buffer.
+ * @return Current gyroscope Z-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6051::getZGyroFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set gyroscope Z-axis FIFO enabled value.
+ * @param enabled New gyroscope Z-axis FIFO enabled value
+ * @see getZGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6051::setZGyroFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, enabled);
+}
+/** Get accelerometer FIFO enabled value.
+ * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H,
+ * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be
+ * written into the FIFO buffer.
+ * @return Current accelerometer FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6051::getAccelFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set accelerometer FIFO enabled value.
+ * @param enabled New accelerometer FIFO enabled value
+ * @see getAccelFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6051::setAccelFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 2 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 2 to be written into the FIFO buffer.
+ * @return Current Slave 2 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6051::getSlave2FIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set Slave 2 FIFO enabled value.
+ * @param enabled New Slave 2 FIFO enabled value
+ * @see getSlave2FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6051::setSlave2FIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 1 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 1 to be written into the FIFO buffer.
+ * @return Current Slave 1 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6051::getSlave1FIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set Slave 1 FIFO enabled value.
+ * @param enabled New Slave 1 FIFO enabled value
+ * @see getSlave1FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6051::setSlave1FIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 0 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 0 to be written into the FIFO buffer.
+ * @return Current Slave 0 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6051::getSlave0FIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set Slave 0 FIFO enabled value.
+ * @param enabled New Slave 0 FIFO enabled value
+ * @see getSlave0FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6051::setSlave0FIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, enabled);
+}
+
+// I2C_MST_CTRL register
+
+/** Get multi-master enabled value.
+ * Multi-master capability allows multiple I2C masters to operate on the same
+ * bus. In circuits where multi-master capability is required, set MULT_MST_EN
+ * to 1. This will increase current drawn by approximately 30uA.
+ *
+ * In circuits where multi-master capability is required, the state of the I2C
+ * bus must always be monitored by each separate I2C Master. Before an I2C
+ * Master can assume arbitration of the bus, it must first confirm that no other
+ * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the
+ * MPU-60X0's bus arbitration detection logic is turned on, enabling it to
+ * detect when the bus is available.
+ *
+ * @return Current multi-master enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6051::getMultiMasterEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set multi-master enabled value.
+ * @param enabled New multi-master enabled value
+ * @see getMultiMasterEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6051::setMultiMasterEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, enabled);
+}
+/** Get wait-for-external-sensor-data enabled value.
+ * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be
+ * delayed until External Sensor data from the Slave Devices are loaded into the
+ * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor
+ * data (i.e. from gyro and accel) and external sensor data have been loaded to
+ * their respective data registers (i.e. the data is synced) when the Data Ready
+ * interrupt is triggered.
+ *
+ * @return Current wait-for-external-sensor-data enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6051::getWaitForExternalSensorEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, buffer);
+    return buffer[0];
+}
+/** Set wait-for-external-sensor-data enabled value.
+ * @param enabled New wait-for-external-sensor-data enabled value
+ * @see getWaitForExternalSensorEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6051::setWaitForExternalSensorEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, enabled);
+}
+/** Get Slave 3 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 3 to be written into the FIFO buffer.
+ * @return Current Slave 3 FIFO enabled value
+ * @see MPU6050_RA_MST_CTRL
+ */
+bool MPU6051::getSlave3FIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set Slave 3 FIFO enabled value.
+ * @param enabled New Slave 3 FIFO enabled value
+ * @see getSlave3FIFOEnabled()
+ * @see MPU6050_RA_MST_CTRL
+ */
+void MPU6051::setSlave3FIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, enabled);
+}
+/** Get slave read/write transition enabled value.
+ * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave
+ * read to the next slave read. If the bit equals 0, there will be a restart
+ * between reads. If the bit equals 1, there will be a stop followed by a start
+ * of the following read. When a write transaction follows a read transaction,
+ * the stop followed by a start of the successive write will be always used.
+ *
+ * @return Current slave read/write transition enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6051::getSlaveReadWriteTransitionEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, buffer);
+    return buffer[0];
+}
+/** Set slave read/write transition enabled value.
+ * @param enabled New slave read/write transition enabled value
+ * @see getSlaveReadWriteTransitionEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6051::setSlaveReadWriteTransitionEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, enabled);
+}
+/** Get I2C master clock speed.
+ * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the
+ * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to
+ * the following table:
+ *
+ * <pre>
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0           | 348kHz                 | 23
+ * 1           | 333kHz                 | 24
+ * 2           | 320kHz                 | 25
+ * 3           | 308kHz                 | 26
+ * 4           | 296kHz                 | 27
+ * 5           | 286kHz                 | 28
+ * 6           | 276kHz                 | 29
+ * 7           | 267kHz                 | 30
+ * 8           | 258kHz                 | 31
+ * 9           | 500kHz                 | 16
+ * 10          | 471kHz                 | 17
+ * 11          | 444kHz                 | 18
+ * 12          | 421kHz                 | 19
+ * 13          | 400kHz                 | 20
+ * 14          | 381kHz                 | 21
+ * 15          | 364kHz                 | 22
+ * </pre>
+ *
+ * @return Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+uint8_t MPU6051::getMasterClockSpeed()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set I2C master clock speed.
+ * @reparam speed Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6051::setMasterClockSpeed(uint8_t speed)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, speed);
+}
+
+// I2C_SLV* registers (Slave 0-3)
+
+/** Get the I2C address of the specified slave (0-3).
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * In read mode, the result of the read is placed in the lowest available
+ * EXT_SENS_DATA register. For further information regarding the allocation of
+ * read results, please refer to the EXT_SENS_DATA register description
+ * (Registers 73 - 96).
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions (getSlave4* and setSlave4*).
+ *
+ * I2C data transactions are performed at the Sample Rate, as defined in
+ * Register 25. The user is responsible for ensuring that I2C data transactions
+ * to and from each enabled Slave can be completed within a single period of the
+ * Sample Rate.
+ *
+ * The I2C slave access rate can be reduced relative to the Sample Rate. This
+ * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a
+ * slave's access rate is reduced relative to the Sample Rate is determined by
+ * I2C_MST_DELAY_CTRL (Register 103).
+ *
+ * The processing order for the slaves is fixed. The sequence followed for
+ * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a
+ * particular Slave is disabled it will be skipped.
+ *
+ * Each slave can either be accessed at the sample rate or at a reduced sample
+ * rate. In a case where some slaves are accessed at the Sample Rate and some
+ * slaves are accessed at the reduced rate, the sequence of accessing the slaves
+ * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will
+ * be skipped if their access rate dictates that they should not be accessed
+ * during that particular cycle. For further information regarding the reduced
+ * access rate, please refer to Register 52. Whether a slave is accessed at the
+ * Sample Rate or at the reduced rate is determined by the Delay Enable bits in
+ * Register 103.
+ *
+ * @param num Slave number (0-3)
+ * @return Current address for specified slave
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+uint8_t MPU6051::getSlaveAddress(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, buffer);
+    return buffer[0];
+}
+/** Set the I2C address of the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param address New address for specified slave
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+void MPU6051::setSlaveAddress(uint8_t num, uint8_t address)
+{
+    if (num > 3) return;
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, address);
+}
+/** Get the active internal register for the specified slave (0-3).
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions.
+ *
+ * @param num Slave number (0-3)
+ * @return Current active register for specified slave
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+uint8_t MPU6051::getSlaveRegister(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, buffer);
+    return buffer[0];
+}
+/** Set the active internal register for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param reg New active register for specified slave
+ * @see getSlaveRegister()
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+void MPU6051::setSlaveRegister(uint8_t num, uint8_t reg)
+{
+    if (num > 3) return;
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, reg);
+}
+/** Get the enabled value for the specified slave (0-3).
+ * When set to 1, this bit enables Slave 0 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 0 from data transfer operations.
+ * @param num Slave number (0-3)
+ * @return Current enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6051::getSlaveEnabled(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set the enabled value for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New enabled value for specified slave 
+ * @see getSlaveEnabled()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6051::setSlaveEnabled(uint8_t num, bool enabled)
+{
+    if (num > 3) return;
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, enabled);
+}
+/** Get word pair byte-swapping enabled for the specified slave (0-3).
+ * When set to 1, this bit enables byte swapping. When byte swapping is enabled,
+ * the high and low bytes of a word pair are swapped. Please refer to
+ * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0,
+ * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA
+ * registers in the order they were transferred.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair byte-swapping enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6051::getSlaveWordByteSwap(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, buffer);
+    return buffer[0];
+}
+/** Set word pair byte-swapping enabled for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair byte-swapping enabled value for specified slave
+ * @see getSlaveWordByteSwap()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6051::setSlaveWordByteSwap(uint8_t num, bool enabled)
+{
+    if (num > 3) return;
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, enabled);
+}
+/** Get write mode for the specified slave (0-3).
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @param num Slave number (0-3)
+ * @return Current write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6051::getSlaveWriteMode(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, buffer);
+    return buffer[0];
+}
+/** Set write mode for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param mode New write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see getSlaveWriteMode()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6051::setSlaveWriteMode(uint8_t num, bool mode)
+{
+    if (num > 3) return;
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, mode);
+}
+/** Get word pair grouping order offset for the specified slave (0-3).
+ * This sets specifies the grouping order of word pairs received from registers.
+ * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even,
+ * then odd register addresses) are paired to form a word. When set to 1, bytes
+ * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even
+ * register addresses) are paired to form a word.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair grouping order offset for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6051::getSlaveWordGroupOffset(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, buffer);
+    return buffer[0];
+}
+/** Set word pair grouping order offset for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair grouping order offset for specified slave
+ * @see getSlaveWordGroupOffset()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6051::setSlaveWordGroupOffset(uint8_t num, bool enabled)
+{
+    if (num > 3) return;
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, enabled);
+}
+/** Get number of bytes to read for the specified slave (0-3).
+ * Specifies the number of bytes transferred to and from Slave 0. Clearing this
+ * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN.
+ * @param num Slave number (0-3)
+ * @return Number of bytes to read for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+uint8_t MPU6051::getSlaveDataLength(uint8_t num)
+{
+    if (num > 3) return 0;
+    i2Cdev.readBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set number of bytes to read for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param length Number of bytes to read for specified slave
+ * @see getSlaveDataLength()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6051::setSlaveDataLength(uint8_t num, uint8_t length)
+{
+    if (num > 3) return;
+    i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, length);
+}
+
+// I2C_SLV* registers (Slave 4)
+
+/** Get the I2C address of Slave 4.
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * @return Current address for Slave 4
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+uint8_t MPU6051::getSlave4Address()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, buffer);
+    return buffer[0];
+}
+/** Set the I2C address of Slave 4.
+ * @param address New address for Slave 4
+ * @see getSlave4Address()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+void MPU6051::setSlave4Address(uint8_t address)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, address);
+}
+/** Get the active internal register for the Slave 4.
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * @return Current active register for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+uint8_t MPU6051::getSlave4Register()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_REG, buffer);
+    return buffer[0];
+}
+/** Set the active internal register for Slave 4.
+ * @param reg New active register for Slave 4
+ * @see getSlave4Register()
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+void MPU6051::setSlave4Register(uint8_t reg)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_REG, reg);
+}
+/** Set new byte to write to Slave 4.
+ * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW
+ * is set 1 (set to read), this register has no effect.
+ * @param data New byte to write to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DO
+ */
+void MPU6051::setSlave4OutputByte(uint8_t data)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_DO, data);
+}
+/** Get the enabled value for the Slave 4.
+ * When set to 1, this bit enables Slave 4 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 4 from data transfer operations.
+ * @return Current enabled value for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6051::getSlave4Enabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set the enabled value for Slave 4.
+ * @param enabled New enabled value for Slave 4
+ * @see getSlave4Enabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6051::setSlave4Enabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, enabled);
+}
+/** Get the enabled value for Slave 4 transaction interrupts.
+ * When set to 1, this bit enables the generation of an interrupt signal upon
+ * completion of a Slave 4 transaction. When cleared to 0, this bit disables the
+ * generation of an interrupt signal upon completion of a Slave 4 transaction.
+ * The interrupt status can be observed in Register 54.
+ *
+ * @return Current enabled value for Slave 4 transaction interrupts.
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6051::getSlave4InterruptEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set the enabled value for Slave 4 transaction interrupts.
+ * @param enabled New enabled value for Slave 4 transaction interrupts.
+ * @see getSlave4InterruptEnabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6051::setSlave4InterruptEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, enabled);
+}
+/** Get write mode for Slave 4.
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6051::getSlave4WriteMode()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, buffer);
+    return buffer[0];
+}
+/** Set write mode for the Slave 4.
+ * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see getSlave4WriteMode()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6051::setSlave4WriteMode(bool mode)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mode);
+}
+/** Get Slave 4 master delay value.
+ * This configures the reduced access rate of I2C slaves relative to the Sample
+ * Rate. When a slave's access rate is decreased relative to the Sample Rate,
+ * the slave is accessed every:
+ *
+ *     1 / (1 + I2C_MST_DLY) samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and
+ * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to
+ * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For
+ * further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @return Current Slave 4 master delay value
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+uint8_t MPU6051::getSlave4MasterDelay()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Slave 4 master delay value.
+ * @param delay New Slave 4 master delay value
+ * @see getSlave4MasterDelay()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6051::setSlave4MasterDelay(uint8_t delay)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, delay);
+}
+/** Get last available byte read from Slave 4.
+ * This register stores the data read from Slave 4. This field is populated
+ * after a read transaction.
+ * @return Last available byte read from to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DI
+ */
+uint8_t MPU6051::getSlate4InputByte()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_DI, buffer);
+    return buffer[0];
+}
+
+// I2C_MST_STATUS register
+
+/** Get FSYNC interrupt status.
+ * This bit reflects the status of the FSYNC interrupt from an external device
+ * into the MPU-60X0. This is used as a way to pass an external interrupt
+ * through the MPU-60X0 to the host application processor. When set to 1, this
+ * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG
+ * (Register 55).
+ * @return FSYNC interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6051::getPassthroughStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 4 transaction done status.
+ * Automatically sets to 1 when a Slave 4 transaction has completed. This
+ * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register
+ * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the
+ * I2C_SLV4_CTRL register (Register 52).
+ * @return Slave 4 transaction done status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6051::getSlave4IsDone()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, buffer);
+    return buffer[0];
+}
+/** Get master arbitration lost status.
+ * This bit automatically sets to 1 when the I2C Master has lost arbitration of
+ * the auxiliary I2C bus (an error condition). This triggers an interrupt if the
+ * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Master arbitration lost status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6051::getLostArbitration()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 4 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 4 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6051::getSlave4Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 3 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 3 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6051::getSlave3Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 2 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 2 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6051::getSlave2Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 1 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 1 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6051::getSlave1Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, buffer);
+    return buffer[0];
+}
+/** Get Slave 0 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 0 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6051::getSlave0Nack()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, buffer);
+    return buffer[0];
+}
+
+// INT_PIN_CFG register
+
+/** Get interrupt logic level mode.
+ * Will be set 0 for active-high, 1 for active-low.
+ * @return Current interrupt mode (0=active-high, 1=active-low)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+bool MPU6051::getInterruptMode()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, buffer);
+    return buffer[0];
+}
+/** Set interrupt logic level mode.
+ * @param mode New interrupt mode (0=active-high, 1=active-low)
+ * @see getInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+void MPU6051::setInterruptMode(bool mode)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mode);
+}
+/** Get interrupt drive mode.
+ * Will be set 0 for push-pull, 1 for open-drain.
+ * @return Current interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+bool MPU6051::getInterruptDrive()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, buffer);
+    return buffer[0];
+}
+/** Set interrupt drive mode.
+ * @param drive New interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see getInterruptDrive()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+void MPU6051::setInterruptDrive(bool drive)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, drive);
+}
+/** Get interrupt latch mode.
+ * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared.
+ * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+bool MPU6051::getInterruptLatch()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set interrupt latch mode.
+ * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see getInterruptLatch()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+void MPU6051::setInterruptLatch(bool latch)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, latch);
+}
+/** Get interrupt latch clear mode.
+ * Will be set 0 for status-read-only, 1 for any-register-read.
+ * @return Current latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+bool MPU6051::getInterruptLatchClear()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, buffer);
+    return buffer[0];
+}
+/** Set interrupt latch clear mode.
+ * @param clear New latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see getInterruptLatchClear()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+void MPU6051::setInterruptLatchClear(bool clear)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, clear);
+}
+/** Get FSYNC interrupt logic level mode.
+ * @return Current FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+bool MPU6051::getFSyncInterruptLevel()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, buffer);
+    return buffer[0];
+}
+/** Set FSYNC interrupt logic level mode.
+ * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+void MPU6051::setFSyncInterruptLevel(bool level)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, level);
+}
+/** Get FSYNC pin interrupt enabled setting.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled setting
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+bool MPU6051::getFSyncInterruptEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set FSYNC pin interrupt enabled setting.
+ * @param enabled New FSYNC pin interrupt enabled setting
+ * @see getFSyncInterruptEnabled()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+void MPU6051::setFSyncInterruptEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, enabled);
+}
+/** Get I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @return Current I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+bool MPU6051::getI2CBypassEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @param enabled New I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+void MPU6051::setI2CBypassEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, enabled);
+}
+/** Get reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @return Current reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+bool MPU6051::getClockOutputEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @param enabled New reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+void MPU6051::setClockOutputEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, enabled);
+}
+
+// INT_ENABLE register
+
+/** Get full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit will be
+ * set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+uint8_t MPU6051::getIntEnabled()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_INT_ENABLE, buffer);
+    return buffer[0];
+}
+/** Set full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit should be
+ * set 0 for disabled, 1 for enabled.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void MPU6051::setIntEnabled(uint8_t enabled)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_INT_ENABLE, enabled);
+}
+/** Get Free Fall interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+bool MPU6051::getIntFreefallEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, buffer);
+    return buffer[0];
+}
+/** Set Free Fall interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void MPU6051::setIntFreefallEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, enabled);
+}
+/** Get Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+bool MPU6051::getIntMotionEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, buffer);
+    return buffer[0];
+}
+/** Set Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+void MPU6051::setIntMotionEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, enabled);
+}
+/** Get Zero Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+bool MPU6051::getIntZeroMotionEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
+    return buffer[0];
+}
+/** Set Zero Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntZeroMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+void MPU6051::setIntZeroMotionEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, enabled);
+}
+/** Get FIFO Buffer Overflow interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+bool MPU6051::getIntFIFOBufferOverflowEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+    return buffer[0];
+}
+/** Set FIFO Buffer Overflow interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFIFOBufferOverflowEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+void MPU6051::setIntFIFOBufferOverflowEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, enabled);
+}
+/** Get I2C Master interrupt enabled status.
+ * This enables any of the I2C Master interrupt sources to generate an
+ * interrupt. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+bool MPU6051::getIntI2CMasterEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
+    return buffer[0];
+}
+/** Set I2C Master interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntI2CMasterEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+void MPU6051::setIntI2CMasterEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, enabled);
+}
+/** Get Data Ready interrupt enabled setting.
+ * This event occurs each time a write operation to all of the sensor registers
+ * has been completed. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool MPU6051::getIntDataReadyEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
+    return buffer[0];
+}
+/** Set Data Ready interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntDataReadyEnabled()
+ * @see MPU6050_RA_INT_CFG
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+void MPU6051::setIntDataReadyEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, enabled);
+}
+
+// INT_STATUS register
+
+/** Get full set of interrupt status bits.
+ * These bits clear to 0 after the register has been read. Very useful
+ * for getting multiple INT statuses, since each single bit read clears
+ * all of them because it has to read the whole byte.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ */
+uint8_t MPU6051::getIntStatus()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_INT_STATUS, buffer);
+    return buffer[0];
+}
+/** Get Free Fall interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FF_BIT
+ */
+bool MPU6051::getIntFreefallStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, buffer);
+    return buffer[0];
+}
+/** Get Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Motion Detection interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ */
+bool MPU6051::getIntMotionStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, buffer);
+    return buffer[0];
+}
+/** Get Zero Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Zero Motion Detection interrupt has
+ * been generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ */
+bool MPU6051::getIntZeroMotionStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
+    return buffer[0];
+}
+/** Get FIFO Buffer Overflow interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ */
+bool MPU6051::getIntFIFOBufferOverflowStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+    return buffer[0];
+}
+/** Get I2C Master interrupt status.
+ * This bit automatically sets to 1 when an I2C Master interrupt has been
+ * generated. For a list of I2C Master interrupts, please refer to Register 54.
+ * The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ */
+bool MPU6051::getIntI2CMasterStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
+    return buffer[0];
+}
+/** Get Data Ready interrupt status.
+ * This bit automatically sets to 1 when a Data Ready interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool MPU6051::getIntDataReadyStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
+    return buffer[0];
+}
+
+// ACCEL_*OUT_* registers
+
+/** Get raw 9-axis motion sensor readings (accel/gyro/compass).
+ * FUNCTION NOT FULLY IMPLEMENTED YET.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @param mx 16-bit signed integer container for magnetometer X-axis value
+ * @param my 16-bit signed integer container for magnetometer Y-axis value
+ * @param mz 16-bit signed integer container for magnetometer Z-axis value
+ * @see getMotion6()
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void MPU6051::getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz)
+{
+    getMotion6(ax, ay, az, gx, gy, gz);
+    
+    // magnetometer reading
+    i2Cdev.writeByte(devAddr, MPU6050_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer
+    wait_ms(10); // necessary wait >=6ms
+    i2Cdev.writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); // enable the magnetometer
+    wait_ms(10); // necessary wait >=6ms
+    i2Cdev.readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer);
+    *mx = (((int16_t)buffer[0]) << 8) | buffer[1];
+    *my = (((int16_t)buffer[2]) << 8) | buffer[3];
+    *mz = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get raw 6-axis motion sensor readings (accel/gyro).
+ * Retrieves all currently available motion sensor values.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void MPU6051::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, buffer);
+    *ax = (((int16_t)buffer[0]) << 8) | buffer[1];
+    *ay = (((int16_t)buffer[2]) << 8) | buffer[3];
+    *az = (((int16_t)buffer[4]) << 8) | buffer[5];
+    *gx = (((int16_t)buffer[8]) << 8) | buffer[9];
+    *gy = (((int16_t)buffer[10]) << 8) | buffer[11];
+    *gz = (((int16_t)buffer[12]) << 8) | buffer[13];
+}
+/** Get 3-axis accelerometer readings.
+ * These registers store the most recent accelerometer measurements.
+ * Accelerometer measurements are written to these registers at the Sample Rate
+ * as defined in Register 25.
+ *
+ * The accelerometer measurement registers, along with the temperature
+ * measurement registers, gyroscope measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ *
+ * The data within the accelerometer sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS
+ * (Register 28). For each full scale setting, the accelerometers' sensitivity
+ * per LSB in ACCEL_xOUT is shown in the table below:
+ *
+ * <pre>
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0       | +/- 2g           | 8192 LSB/mg
+ * 1       | +/- 4g           | 4096 LSB/mg
+ * 2       | +/- 8g           | 2048 LSB/mg
+ * 3       | +/- 16g          | 1024 LSB/mg
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis acceleration
+ * @param y 16-bit signed integer container for Y-axis acceleration
+ * @param z 16-bit signed integer container for Z-axis acceleration
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void MPU6051::getAcceleration(int16_t* x, int16_t* y, int16_t* z)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, buffer);
+    *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+    *y = (((int16_t)buffer[2]) << 8) | buffer[3];
+    *z = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis accelerometer reading.
+ * @return X-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+int16_t MPU6051::getAccelerationX()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis accelerometer reading.
+ * @return Y-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_YOUT_H
+ */
+int16_t MPU6051::getAccelerationY()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis accelerometer reading.
+ * @return Z-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_ZOUT_H
+ */
+int16_t MPU6051::getAccelerationZ()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// TEMP_OUT_* registers
+
+/** Get current internal temperature.
+ * @return Temperature reading in 16-bit 2's complement format
+ * @see MPU6050_RA_TEMP_OUT_H
+ */
+int16_t MPU6051::getTemperature()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_TEMP_OUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// GYRO_*OUT_* registers
+
+/** Get 3-axis gyroscope readings.
+ * These gyroscope measurement registers, along with the accelerometer
+ * measurement registers, temperature measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ * The data within the gyroscope sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL
+ * (Register 27). For each full scale setting, the gyroscopes' sensitivity per
+ * LSB in GYRO_xOUT is shown in the table below:
+ *
+ * <pre>
+ * FS_SEL | Full Scale Range   | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
+ * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
+ * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis rotation
+ * @param y 16-bit signed integer container for Y-axis rotation
+ * @param z 16-bit signed integer container for Z-axis rotation
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void MPU6051::getRotation(int16_t* x, int16_t* y, int16_t* z)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 6, buffer);
+    *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+    *y = (((int16_t)buffer[2]) << 8) | buffer[3];
+    *z = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis gyroscope reading.
+ * @return X-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+int16_t MPU6051::getRotationX()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis gyroscope reading.
+ * @return Y-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_YOUT_H
+ */
+int16_t MPU6051::getRotationY()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_YOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis gyroscope reading.
+ * @return Z-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_ZOUT_H
+ */
+int16_t MPU6051::getRotationZ()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// EXT_SENS_DATA_* registers
+
+/** Read single byte from external sensor data register.
+ * These registers store data read from external sensors by the Slave 0, 1, 2,
+ * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in
+ * I2C_SLV4_DI (Register 53).
+ *
+ * External sensor data is written to these registers at the Sample Rate as
+ * defined in Register 25. This access rate can be reduced by using the Slave
+ * Delay Enable registers (Register 103).
+ *
+ * External sensor data registers, along with the gyroscope measurement
+ * registers, accelerometer measurement registers, and temperature measurement
+ * registers, are composed of two sets of registers: an internal register set
+ * and a user-facing read register set.
+ *
+ * The data within the external sensors' internal register set is always updated
+ * at the Sample Rate (or the reduced access rate) whenever the serial interface
+ * is idle. This guarantees that a burst read of sensor registers will read
+ * measurements from the same sampling instant. Note that if burst reads are not
+ * used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Data is placed in these external sensor data registers according to
+ * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39,
+ * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from
+ * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as
+ * defined in Register 25) or delayed rate (if specified in Register 52 and
+ * 103). During each Sample cycle, slave reads are performed in order of Slave
+ * number. If all slaves are enabled with more than zero bytes to be read, the
+ * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3.
+ *
+ * Each enabled slave will have EXT_SENS_DATA registers associated with it by
+ * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from
+ * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may
+ * change the higher numbered slaves' associated registers. Furthermore, if
+ * fewer total bytes are being read from the external sensors as a result of
+ * such a change, then the data remaining in the registers which no longer have
+ * an associated slave device (i.e. high numbered registers) will remain in
+ * these previously allocated registers unless reset.
+ *
+ * If the sum of the read lengths of all SLVx transactions exceed the number of
+ * available EXT_SENS_DATA registers, the excess bytes will be dropped. There
+ * are 24 EXT_SENS_DATA registers and hence the total read lengths between all
+ * the slaves cannot be greater than 24 or some bytes will be lost.
+ *
+ * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further
+ * information regarding the characteristics of Slave 4, please refer to
+ * Registers 49 to 53.
+ *
+ * EXAMPLE:
+ * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and
+ * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that
+ * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00
+ * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05
+ * will be associated with Slave 1. If Slave 2 is enabled as well, registers
+ * starting from EXT_SENS_DATA_06 will be allocated to Slave 2.
+ *
+ * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then
+ * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3
+ * instead.
+ *
+ * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE:
+ * If a slave is disabled at any time, the space initially allocated to the
+ * slave in the EXT_SENS_DATA register, will remain associated with that slave.
+ * This is to avoid dynamic adjustment of the register allocation.
+ *
+ * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all
+ * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106).
+ *
+ * This above is also true if one of the slaves gets NACKed and stops
+ * functioning.
+ *
+ * @param position Starting position (0-23)
+ * @return Byte read from register
+ */
+uint8_t MPU6051::getExternalSensorByte(int position)
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, buffer);
+    return buffer[0];
+}
+/** Read word (2 bytes) from external sensor data registers.
+ * @param position Starting position (0-21)
+ * @return Word read from register
+ * @see getExternalSensorByte()
+ */
+uint16_t MPU6051::getExternalSensorWord(int position)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, buffer);
+    return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Read double word (4 bytes) from external sensor data registers.
+ * @param position Starting position (0-20)
+ * @return Double word read from registers
+ * @see getExternalSensorByte()
+ */
+uint32_t MPU6051::getExternalSensorDWord(int position)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, buffer);
+    return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3];
+}
+
+// MOT_DETECT_STATUS register
+
+/** Get X-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XNEG_BIT
+ */
+bool MPU6051::getXNegMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, buffer);
+    return buffer[0];
+}
+/** Get X-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XPOS_BIT
+ */
+bool MPU6051::getXPosMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, buffer);
+    return buffer[0];
+}
+/** Get Y-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YNEG_BIT
+ */
+bool MPU6051::getYNegMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, buffer);
+    return buffer[0];
+}
+/** Get Y-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YPOS_BIT
+ */
+bool MPU6051::getYPosMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, buffer);
+    return buffer[0];
+}
+/** Get Z-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZNEG_BIT
+ */
+bool MPU6051::getZNegMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, buffer);
+    return buffer[0];
+}
+/** Get Z-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZPOS_BIT
+ */
+bool MPU6051::getZPosMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, buffer);
+    return buffer[0];
+}
+/** Get zero motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZRMOT_BIT
+ */
+bool MPU6051::getZeroMotionDetected()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, buffer);
+    return buffer[0];
+}
+
+// I2C_SLV*_DO register
+
+/** Write byte to Data Output container for specified slave.
+ * This register holds the output data written into Slave when Slave is set to
+ * write mode. For further information regarding Slave control, please
+ * refer to Registers 37 to 39 and immediately following.
+ * @param num Slave number (0-3)
+ * @param data Byte to write
+ * @see MPU6050_RA_I2C_SLV0_DO
+ */
+void MPU6051::setSlaveOutputByte(uint8_t num, uint8_t data)
+{
+    if (num > 3) return;
+    i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_DO + num, data);
+}
+
+// I2C_MST_DELAY_CTRL register
+
+/** Get external data shadow delay enabled status.
+ * This register is used to specify the timing of external sensor data
+ * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external
+ * sensor data is delayed until all data has been received.
+ * @return Current external data shadow delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+bool MPU6051::getExternalShadowDelayEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer);
+    return buffer[0];
+}
+/** Set external data shadow delay enabled status.
+ * @param enabled New external data shadow delay enabled status.
+ * @see getExternalShadowDelayEnabled()
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+void MPU6051::setExternalShadowDelayEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled);
+}
+/** Get slave delay enabled status.
+ * When a particular slave delay is enabled, the rate of access for the that
+ * slave device is reduced. When a slave's access rate is decreased relative to
+ * the Sample Rate, the slave is accessed every:
+ *
+ *     1 / (1 + I2C_MST_DLY) Samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register  * 25)
+ * and DLPF_CFG (register 26).
+ *
+ * For further information regarding I2C_MST_DLY, please refer to register 52.
+ * For further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @param num Slave number (0-4)
+ * @return Current slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+bool MPU6051::getSlaveDelayEnabled(uint8_t num)
+{
+    // MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc.
+    if (num > 4) return 0;
+    i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, buffer);
+    return buffer[0];
+}
+/** Set slave delay enabled status.
+ * @param num Slave number (0-4)
+ * @param enabled New slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+void MPU6051::setSlaveDelayEnabled(uint8_t num, bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, enabled);
+}
+
+// SIGNAL_PATH_RESET register
+
+/** Reset gyroscope signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_GYRO_RESET_BIT
+ */
+void MPU6051::resetGyroscopePath()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_GYRO_RESET_BIT, true);
+}
+/** Reset accelerometer signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_ACCEL_RESET_BIT
+ */
+void MPU6051::resetAccelerometerPath()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_ACCEL_RESET_BIT, true);
+}
+/** Reset temperature sensor signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_TEMP_RESET_BIT
+ */
+void MPU6051::resetTemperaturePath()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_TEMP_RESET_BIT, true);
+}
+
+// MOT_DETECT_CTRL register
+
+/** Get accelerometer power-on delay.
+ * The accelerometer data path provides samples to the sensor registers, Motion
+ * detection, Zero Motion detection, and Free Fall detection modules. The
+ * signal path contains filters which must be flushed on wake-up with new
+ * samples before the detection modules begin operations. The default wake-up
+ * delay, of 4ms can be lengthened by up to 3ms. This additional delay is
+ * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select
+ * any value above zero unless instructed otherwise by InvenSense. Please refer
+ * to Section 8 of the MPU-6000/MPU-6050 Product Specification document for
+ * further information regarding the detection modules.
+ * @return Current accelerometer power-on delay
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+uint8_t MPU6051::getAccelerometerPowerOnDelay()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set accelerometer power-on delay.
+ * @param delay New accelerometer power-on delay (0-3)
+ * @see getAccelerometerPowerOnDelay()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+void MPU6051::setAccelerometerPowerOnDelay(uint8_t delay)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, delay);
+}
+/** Get Free Fall detection counter decrement configuration.
+ * Detection is registered by the Free Fall detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring FF_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * </pre>
+ *
+ * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Free Fall detection,
+ * please refer to Registers 29 to 32.
+ *
+ * @return Current decrement configuration
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+uint8_t MPU6051::getFreefallDetectionCounterDecrement()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Free Fall detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getFreefallDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+void MPU6051::setFreefallDetectionCounterDecrement(uint8_t decrement)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, decrement);
+}
+/** Get Motion detection counter decrement configuration.
+ * Detection is registered by the Motion detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring MOT_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * </pre>
+ *
+ * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Motion detection,
+ * please refer to Registers 29 to 32.
+ *
+ */
+uint8_t MPU6051::getMotionDetectionCounterDecrement()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Motion detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getMotionDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_MOT_COUNT_BIT
+ */
+void MPU6051::setMotionDetectionCounterDecrement(uint8_t decrement)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, decrement);
+}
+
+// USER_CTRL register
+
+/** Get FIFO enabled status.
+ * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer
+ * cannot be written to or read from while disabled. The FIFO buffer's state
+ * does not change unless the MPU-60X0 is power cycled.
+ * @return Current FIFO enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+bool MPU6051::getFIFOEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set FIFO enabled status.
+ * @param enabled New FIFO enabled status
+ * @see getFIFOEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+void MPU6051::setFIFOEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, enabled);
+}
+/** Get I2C Master Mode enabled status.
+ * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the
+ * external sensor slave devices on the auxiliary I2C bus. When this bit is
+ * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically
+ * driven by the primary I2C bus (SDA and SCL). This is a precondition to
+ * enabling Bypass Mode. For further information regarding Bypass Mode, please
+ * refer to Register 55.
+ * @return Current I2C Master Mode enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+bool MPU6051::getI2CMasterModeEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, buffer);
+    return buffer[0];
+}
+/** Set I2C Master Mode enabled status.
+ * @param enabled New I2C Master Mode enabled status
+ * @see getI2CMasterModeEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+void MPU6051::setI2CMasterModeEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, enabled);
+}
+/** Switch from I2C to SPI mode (MPU-6000 only)
+ * If this is set, the primary SPI interface will be enabled in place of the
+ * disabled primary I2C interface.
+ */
+void MPU6051::switchSPIEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled);
+}
+/** Reset the FIFO.
+ * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This
+ * bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_RESET_BIT
+ */
+void MPU6051::resetFIFO()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, true);
+}
+/** Reset the I2C Master.
+ * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0.
+ * This bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_RESET_BIT
+ */
+void MPU6051::resetI2CMaster()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, true);
+}
+/** Reset all sensor registers and signal paths.
+ * When set to 1, this bit resets the signal paths for all sensors (gyroscopes,
+ * accelerometers, and temperature sensor). This operation will also clear the
+ * sensor registers. This bit automatically clears to 0 after the reset has been
+ * triggered.
+ *
+ * When resetting only the signal path (and not the sensor registers), please
+ * use Register 104, SIGNAL_PATH_RESET.
+ *
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_SIG_COND_RESET_BIT
+ */
+void MPU6051::resetSensors()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_SIG_COND_RESET_BIT, true);
+}
+
+// PWR_MGMT_1 register
+
+/** Trigger a full device reset.
+ * A small delay of ~50ms may be desirable after triggering a reset.
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_DEVICE_RESET_BIT
+ */
+void MPU6051::reset()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, true);
+}
+/** Get sleep mode status.
+ * Setting the SLEEP bit in the register puts the device into very low power
+ * sleep mode. In this mode, only the serial interface and internal registers
+ * remain active, allowing for a very low standby current. Clearing this bit
+ * puts the device back into normal mode. To save power, the individual standby
+ * selections for each of the gyros should be used if any gyro axis is not used
+ * by the application.
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+bool MPU6051::getSleepEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, buffer);
+    return buffer[0];
+}
+/** Set sleep mode status.
+ * @param enabled New sleep mode enabled status
+ * @see getSleepEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+void MPU6051::setSleepEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, enabled);
+}
+/** Get wake cycle enabled status.
+ * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle
+ * between sleep mode and waking up to take a single sample of data from active
+ * sensors at a rate determined by LP_WAKE_CTRL (register 108).
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+bool MPU6051::getWakeCycleEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, buffer);
+    return buffer[0];
+}
+/** Set wake cycle enabled status.
+ * @param enabled New sleep mode enabled status
+ * @see getWakeCycleEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+void MPU6051::setWakeCycleEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, enabled);
+}
+/** Get temperature sensor enabled status.
+ * Control the usage of the internal temperature sensor.
+ *
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @return Current temperature sensor enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+bool MPU6051::getTempSensorEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, buffer);
+    return buffer[0] == 0; // 1 is actually disabled here
+}
+/** Set temperature sensor enabled status.
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @param enabled New temperature sensor enabled status
+ * @see getTempSensorEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+void MPU6051::setTempSensorEnabled(bool enabled)
+{
+    // 1 is actually disabled here
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, !enabled);
+}
+/** Get clock source setting.
+ * @return Current clock source setting
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+uint8_t MPU6051::getClockSource()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set clock source setting.
+ * An internal 8MHz oscillator, gyroscope based clock, or external sources can
+ * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator
+ * or an external source is chosen as the clock source, the MPU-60X0 can operate
+ * in low power modes with the gyroscopes disabled.
+ *
+ * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator.
+ * However, it is highly recommended that the device be configured to use one of
+ * the gyroscopes (or an external clock source) as the clock reference for
+ * improved stability. The clock source can be selected according to the following table:
+ *
+ * <pre>
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0       | Internal oscillator
+ * 1       | PLL with X Gyro reference
+ * 2       | PLL with Y Gyro reference
+ * 3       | PLL with Z Gyro reference
+ * 4       | PLL with external 32.768kHz reference
+ * 5       | PLL with external 19.2MHz reference
+ * 6       | Reserved
+ * 7       | Stops the clock and keeps the timing generator in reset
+ * </pre>
+ *
+ * @param source New clock source setting
+ * @see getClockSource()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+void MPU6051::setClockSource(uint8_t source)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, source);
+}
+
+// PWR_MGMT_2 register
+
+/** Get wake frequency in Accel-Only Low Power Mode.
+ * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting
+ * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode,
+ * the device will power off all devices except for the primary I2C interface,
+ * waking only the accelerometer at fixed intervals to take a single
+ * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL
+ * as shown below:
+ *
+ * <pre>
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * <pre>
+ *
+ * For further information regarding the MPU-60X0's power modes, please refer to
+ * Register 107.
+ *
+ * @return Current wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+uint8_t MPU6051::getWakeFrequency()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+void MPU6051::setWakeFrequency(uint8_t frequency)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
+}
+
+/** Get X-axis accelerometer standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+bool MPU6051::getStandbyXAccelEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+void MPU6051::setStandbyXAccelEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, enabled);
+}
+/** Get Y-axis accelerometer standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+bool MPU6051::getStandbyYAccelEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+void MPU6051::setStandbyYAccelEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, enabled);
+}
+/** Get Z-axis accelerometer standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+bool MPU6051::getStandbyZAccelEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+void MPU6051::setStandbyZAccelEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, enabled);
+}
+/** Get X-axis gyroscope standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+bool MPU6051::getStandbyXGyroEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+void MPU6051::setStandbyXGyroEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, enabled);
+}
+/** Get Y-axis gyroscope standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+bool MPU6051::getStandbyYGyroEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+void MPU6051::setStandbyYGyroEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, enabled);
+}
+/** Get Z-axis gyroscope standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+bool MPU6051::getStandbyZGyroEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+void MPU6051::setStandbyZGyroEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t MPU6051::getFIFOCount()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_FIFO_COUNTH, 2, buffer);
+    return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t MPU6051::getFIFOByte()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_FIFO_R_W, buffer);
+    return buffer[0];
+}
+void MPU6051::getFIFOBytes(uint8_t *data, uint8_t length)
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU6050_RA_FIFO_R_W
+ */
+void MPU6051::setFIFOByte(uint8_t data)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_FIFO_R_W, data);
+}
+
+// WHO_AM_I register
+
+/** Get Device ID.
+ * This register is used to verify the identity of the device (0b110100, 0x34).
+ * @return Device ID (6 bits only! should be 0x34)
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+uint8_t MPU6051::getDeviceID()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+void MPU6051::setDeviceID(uint8_t id)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t MPU6051::getOTPBankValid()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, buffer);
+    return buffer[0];
+}
+void MPU6051::setOTPBankValid(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t MPU6051::getXGyroOffset()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU6051::setXGyroOffset(int8_t offset)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU6051::getYGyroOffset()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU6051::setYGyroOffset(int8_t offset)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU6051::getZGyroOffset()
+{
+    i2Cdev.readBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU6051::setZGyroOffset(int8_t offset)
+{
+    i2Cdev.writeBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// X_FINE_GAIN register
+
+int8_t MPU6051::getXFineGain()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_X_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU6051::setXFineGain(int8_t gain)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU6051::getYFineGain()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_Y_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU6051::setYFineGain(int8_t gain)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU6051::getZFineGain()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_Z_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU6051::setZFineGain(int8_t gain)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU6051::getXAccelOffset()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_XA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6051::setXAccelOffset(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU6051::getYAccelOffset()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_YA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6051::setYAccelOffset(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU6051::getZAccelOffset()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ZA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6051::setZAccelOffset(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU6051::getXGyroOffsetUser()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_XG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6051::setXGyroOffsetUser(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU6051::getYGyroOffsetUser()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_YG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6051::setYGyroOffsetUser(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU6051::getZGyroOffsetUser()
+{
+    i2Cdev.readBytes(devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6051::setZGyroOffsetUser(int16_t offset)
+{
+    i2Cdev.writeWord(devAddr, MPU6050_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU6051::getIntPLLReadyEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU6051::setIntPLLReadyEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool MPU6051::getIntDMPEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU6051::setIntDMPEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool MPU6051::getDMPInt5Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6051::getDMPInt4Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6051::getDMPInt3Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6051::getDMPInt2Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6051::getDMPInt1Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6051::getDMPInt0Status()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, buffer);
+    return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU6051::getIntPLLReadyStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+bool MPU6051::getIntDMPStatus()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU6051::getDMPEnabled()
+{
+    i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, buffer);
+    return buffer[0];
+}
+void MPU6051::setDMPEnabled(bool enabled)
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled);
+}
+void MPU6051::resetDMP()
+{
+    i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, true);
+}
+
+// BANK_SEL register
+
+void MPU6051::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank)
+{
+    bank &= 0x1F;
+    if (userBank) bank |= 0x20;
+    if (prefetchEnabled) bank |= 0x40;
+    i2Cdev.writeByte(devAddr, MPU6050_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void MPU6051::setMemoryStartAddress(uint8_t address)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t MPU6051::readMemoryByte()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_MEM_R_W, buffer);
+    return buffer[0];
+}
+void MPU6051::writeMemoryByte(uint8_t data)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_MEM_R_W, data);
+}
+void MPU6051::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address)
+{
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    for (uint16_t i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+        // read the chunk of data as specified
+        i2Cdev.readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, data + i);
+
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+}
+bool MPU6051::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem)
+{
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    uint8_t *verifyBuffer = NULL;
+    uint8_t *progBuffer = NULL;
+    uint16_t i;
+    uint8_t j;
+    if (verify) verifyBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
+    if (useProgMem) progBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
+    for (i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+        if (useProgMem) {
+            // write the chunk of data as specified
+            for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+        } else {
+            // write the chunk of data as specified
+            progBuffer = (uint8_t *)data + i;
+        }
+
+        i2Cdev.writeBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer);
+
+        // verify data if needed
+        if (verify && verifyBuffer) {
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+            i2Cdev.readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer);
+            if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
+                /*Serial.print("Block write verification error, bank ");
+                Serial.print(bank, DEC);
+                Serial.print(", address ");
+                Serial.print(address, DEC);
+                Serial.print("!\nExpected:");
+                for (j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (progBuffer[j] < 16) Serial.print("0");
+                    Serial.print(progBuffer[j], HEX);
+                }
+                Serial.print("\nReceived:");
+                for (uint8_t j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (verifyBuffer[i + j] < 16) Serial.print("0");
+                    Serial.print(verifyBuffer[i + j], HEX);
+                }
+                Serial.print("\n");*/
+                free(verifyBuffer);
+                if (useProgMem) free(progBuffer);
+                return false; // uh oh.
+            }
+        }
+
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+    if (verify) free(verifyBuffer);
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU6051::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify)
+{
+    return writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU6051::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem)
+{
+    uint8_t success, special;
+    uint8_t *progBuffer = NULL;
+    uint16_t i, j;
+    if (useProgMem) {
+        progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
+    }
+
+    // config set data is a long string of blocks with the following structure:
+    // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+    uint8_t bank, offset, length;
+    for (i = 0; i < dataSize;) {
+        if (useProgMem) {
+            bank = pgm_read_byte(data + i++);
+            offset = pgm_read_byte(data + i++);
+            length = pgm_read_byte(data + i++);
+        } else {
+            bank = data[i++];
+            offset = data[i++];
+            length = data[i++];
+        }
+
+        // write data or perform special action
+        if (length > 0) {
+            // regular block of data to write
+            /*Serial.print("Writing config block to bank ");
+            Serial.print(bank);
+            Serial.print(", offset ");
+            Serial.print(offset);
+            Serial.print(", length=");
+            Serial.println(length);*/
+            if (useProgMem) {
+                if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
+                for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+            } else {
+                progBuffer = (uint8_t *)data + i;
+            }
+            success = writeMemoryBlock(progBuffer, length, bank, offset, true);
+            i += length;
+        } else {
+            // special instruction
+            // NOTE: this kind of behavior (what and when to do certain things)
+            // is totally undocumented. This code is in here based on observed
+            // behavior only, and exactly why (or even whether) it has to be here
+            // is anybody's guess for now.
+            if (useProgMem) {
+                special = pgm_read_byte(data + i++);
+            } else {
+                special = data[i++];
+            }
+            /*Serial.print("Special command code ");
+            Serial.print(special, HEX);
+            Serial.println(" found...");*/
+            if (special == 0x01) {
+                // enable DMP-related interrupts
+
+                //setIntZeroMotionEnabled(true);
+                //setIntFIFOBufferOverflowEnabled(true);
+                //setIntDMPEnabled(true);
+                i2Cdev.writeByte(devAddr, MPU6050_RA_INT_ENABLE, 0x32);  // single operation
+
+                success = true;
+            } else {
+                // unknown special command
+                success = false;
+            }
+        }
+
+        if (!success) {
+            if (useProgMem) free(progBuffer);
+            return false; // uh oh
+        }
+    }
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU6051::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize)
+{
+    return writeDMPConfigurationSet(data, dataSize, false);
+}
+
+// DMP_CFG_1 register
+
+uint8_t MPU6051::getDMPConfig1()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_DMP_CFG_1, buffer);
+    return buffer[0];
+}
+void MPU6051::setDMPConfig1(uint8_t config)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU6051::getDMPConfig2()
+{
+    i2Cdev.readByte(devAddr, MPU6050_RA_DMP_CFG_2, buffer);
+    return buffer[0];
+}
+void MPU6051::setDMPConfig2(uint8_t config)
+{
+    i2Cdev.writeByte(devAddr, MPU6050_RA_DMP_CFG_2, config);
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/MPU/src/MPU6051_6Axis_MotionApps20.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/MPU/src/MPU6051_6Axis_MotionApps20.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,470 @@
+// I2Cdev library collection - MPU6050 I2C device class, 6-axis MotionApps 2.0 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 5/20/2013 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+ 
+/* ============================================
+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.
+===============================================
+*/
+
+#include "MPU6051_6Axis_MotionApps20.h"
+
+uint8_t MPU6051::dmpInitialize()
+{
+    // reset device
+    wait_ms(50);
+    reset();
+    wait_ms(30);
+
+    // enable sleep mode and wake cycle
+    /*Serial.println(F("Enabling sleep mode..."));
+    setSleepEnabled(true);
+    Serial.println(F("Enabling wake cycle..."));
+    setWakeCycleEnabled(true);*/
+
+    // disable sleep mode
+    //DEBUG_PRINT("Disabling sleep mode...\n");
+    setSleepEnabled(false);
+
+    // get MPU hardware revision
+    //DEBUG_PRINT("Selecting user bank 16...\n");
+    setMemoryBank(0x10, true, true);
+    //DEBUG_PRINT("Selecting memory byte 6...\n");
+    setMemoryStartAddress(0x06);
+    //DEBUG_PRINT("Checking hardware revision...\n");
+    uint8_t hwRevision = readMemoryByte();
+    //DEBUG_PRINT("Revision @ user[16][6] = ");
+    //DEBUG_PRINTF("%x\n",hwRevision);
+    //DEBUG_PRINT("Resetting memory bank selection to 0...\n");
+    setMemoryBank(0, false, false);
+
+    // check OTP bank valid
+    //DEBUG_PRINT("Reading OTP bank valid flag...\n");
+    uint8_t otpValid = getOTPBankValid();
+
+    //DEBUG_PRINT("OTP bank is ");
+    if(otpValid);  //DEBUG_PRINT("valid!\n");
+    else;  //DEBUG_PRINT("invalid!\n");
+
+    // get X/Y/Z gyro offsets
+    /*
+    DEBUG_PRINT("\nReading gyro offset TC values...\n");
+    int8_t xgOffsetTC = mpu.getXGyroOffsetTC();
+    int8_t ygOffsetTC = getYGyroOffsetTC();
+    int8_t zgOffsetTC = getZGyroOffsetTC();
+    DEBUG_PRINTF("X gyro offset = %u\n",xgOffset);
+    DEBUG_PRINTF("Y gyro offset = %u\n",ygOffset);
+    DEBUG_PRINTF("Z gyro offset = %u\n",zgOffset);
+    */
+    // setup weird slave stuff (?)
+    //DEBUG_PRINT("Setting slave 0 address to 0x7F...\n");
+    setSlaveAddress(0, 0x7F);
+
+    //DEBUG_PRINT("Disabling I2C Master mode...");
+    setI2CMasterModeEnabled(false);
+    //DEBUG_PRINT("Setting slave 0 address to 0x68 (self)...");
+    setSlaveAddress(0, 0x68);
+    //DEBUG_PRINT("Resetting I2C Master control...\n");
+    resetI2CMaster();
+
+    wait_ms(20);
+
+    // load DMP code into memory banks
+    //DEBUG_PRINT("Writing DMP code to MPU memory banks (");
+    //DEBUG_PRINTF("%u",MPU6050_DMP_CODE_SIZE);
+    //DEBUG_PRINT(" bytes)\n");
+    if (writeProgMemoryBlock(dmpMemory2, MPU6050_DMP_CODE_SIZE)) {
+        //DEBUG_PRINT("Success! DMP code written and verified.\n");
+
+        // write DMP configuration
+        //DEBUG_PRINT("Writing DMP configuration to MPU memory banks (");
+        //DEBUG_PRINTF("%u",MPU6050_DMP_CONFIG_SIZE);
+        //DEBUG_PRINT(" bytes in config def)\n");
+        if (writeProgDMPConfigurationSet(dmpConfig2, MPU6050_DMP_CONFIG_SIZE)) {
+            //DEBUG_PRINT("Success! DMP configuration written and verified.\n");
+
+            //DEBUG_PRINT("Setting clock source to Z Gyro...\n");
+            setClockSource(MPU6050_CLOCK_PLL_ZGYRO);
+
+            //DEBUG_PRINT("Setting DMP and FIFO_OFLOW interrupts enabled...\n");
+            setIntEnabled(0x12);
+
+            //DEBUG_PRINT("Setting sample rate to 200Hz...");
+            setRate(4); // 1khz / (1 + 4) = 200 Hz
+
+            //DEBUG_PRINT("Setting external frame sync to TEMP_OUT_L[0]...\n");
+            setExternalFrameSync(MPU6050_EXT_SYNC_TEMP_OUT_L);
+
+            //DEBUG_PRINT("Setting DLPF bandwidth to 42Hz...\n");
+            setDLPFMode(MPU6050_DLPF_BW_42);
+
+            //DEBUG_PRINT("Setting gyro sensitivity to +/- 2000 deg/sec...\n");
+            setFullScaleGyroRange(MPU6050_GYRO_FS_2000);
+
+            //DEBUG_PRINT("Setting DMP configuration bytes (function unknown)...\n");
+            setDMPConfig1(0x03);
+            setDMPConfig2(0x00);
+
+            //DEBUG_PRINT("Clearing OTP Bank flag...");
+            setOTPBankValid(false);
+
+            //DEBUG_PRINT("Setting X/Y/Z gyro offset TCs to previous values...\n");
+            //setXGyroOffsetTC(xgOffsetTC);
+            //setYGyroOffsetTC(ygOffsetTC);
+            //setZGyroOffsetTC(zgOffsetTC);
+
+            //DEBUG_PRINTLN(F("Setting X/Y/Z gyro user offsets to zero..."));
+            //setXGyroOffset(0);
+            //setYGyroOffset(0);
+            //setZGyroOffset(0);
+
+            //DEBUG_PRINT("Writing final memory update 1/7 (function unknown)...\n");
+            uint8_t dmpUpdate[16], j;
+            uint16_t pos = 0;
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates2[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Writing final memory update 2/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates2[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Resetting FIFO...\n");
+            resetFIFO();
+
+            //DEBUG_PRINT("Reading FIFO count...\n");
+            uint16_t fifoCount = getFIFOCount();
+            uint8_t fifoBuffer[128];
+
+            //DEBUG_PRINT("Current FIFO count=");
+            //DEBUG_PRINTF("%u\n",fifoCount);
+            getFIFOBytes(fifoBuffer, fifoCount);
+
+            //DEBUG_PRINT("Setting motion detection threshold to 2...\n");
+            setMotionDetectionThreshold(2);
+
+            //DEBUG_PRINT("Setting zero-motion detection threshold to 156...\n");
+            setZeroMotionDetectionThreshold(156);
+
+            //DEBUG_PRINT("Setting motion detection duration to 80...");
+            setMotionDetectionDuration(80);
+
+            //DEBUG_PRINT("Setting zero-motion detection duration to 0...");
+            setZeroMotionDetectionDuration(0);
+
+            //DEBUG_PRINT("Resetting FIFO...\n");
+            resetFIFO();
+
+            //DEBUG_PRINT("Enabling FIFO...\n");
+            setFIFOEnabled(true);
+
+            //DEBUG_PRINT("Enabling DMP...\n");
+            setDMPEnabled(true);
+
+            //DEBUG_PRINT("Resetting DMP...\n");
+            resetDMP();
+
+            //DEBUG_PRINT("Writing final memory update 3/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates2[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Writing final memory update 4/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates2[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Writing final memory update 5/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates2[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Waiting for FIFO count > 2...\n");
+            while ((fifoCount = getFIFOCount()) < 3);
+
+            //DEBUG_PRINT("Current FIFO count=");
+            //DEBUG_PRINTF("%u\n",fifoCount);
+            //DEBUG_PRINT("Reading FIFO data...\n");
+            getFIFOBytes(fifoBuffer, fifoCount);
+
+            //DEBUG_PRINT("Reading interrupt status...\n");
+            uint8_t mpuIntStatus = getIntStatus();
+
+            //DEBUG_PRINT("Current interrupt status=");
+            //DEBUG_PRINTF("%x\n",mpuIntStatus);
+
+            //DEBUG_PRINT("Reading final memory update 6/7 (function unknown)...\n");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates2[pos]);
+            readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("Waiting for FIFO count > 2...\n");
+            while ((fifoCount = getFIFOCount()) < 3);
+
+            //DEBUG_PRINT("Current FIFO count=");
+            //DEBUG_PRINTF("%u\n",fifoCount);
+
+            //DEBUG_PRINT("Reading FIFO data...\n");
+            getFIFOBytes(fifoBuffer, fifoCount);
+
+            //DEBUG_PRINT("Reading interrupt status...\n");
+            mpuIntStatus = getIntStatus();
+
+            //DEBUG_PRINT("Current interrupt status=");
+            //DEBUG_PRINTF("%x\n",mpuIntStatus);
+
+            //DEBUG_PRINT("Writing final memory update 7/7 (function unknown)...");
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates2[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            //DEBUG_PRINT("DMP is good to go! Finally.\n");
+
+            //DEBUG_PRINT("Disabling DMP (you turn it on later)...\n");
+            setDMPEnabled(false);
+
+            //DEBUG_PRINT("Setting up internal 42-byte (default) DMP packet buffer...\n");
+            dmpPacketSize = 42;
+            /*if ((dmpPacketBuffer = (uint8_t *)malloc(42)) == 0) {
+                return 3; // TODO: proper error code for no memory
+            }*/
+
+            //DEBUG_PRINT("Resetting FIFO and clearing INT status one last time...\n");
+            resetFIFO();
+            getIntStatus();
+        } else {
+            //DEBUG_PRINT("ERROR! DMP configuration verification failed.\n");
+            return 2; // configuration block loading failed
+        }
+    } else {
+        //DEBUG_PRINT("ERROR! DMP code verification failed.");
+        return 1; // main binary block loading failed
+    }
+    return 0; // success
+}
+
+bool MPU6051::dmpPacketAvailable()
+{
+    return getFIFOCount() >= dmpGetFIFOPacketSize();
+}
+
+// uint8_t MPU6051::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6051::dmpGetFIFORate();
+// uint8_t MPU6051::dmpGetSampleStepSizeMS();
+// uint8_t MPU6051::dmpGetSampleFrequency();
+// int32_t MPU6051::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6051::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6051::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6051::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6051::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6051::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+uint8_t MPU6051::dmpGetAccel(int32_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[28] << 24) + (packet[29] << 16) + (packet[30] << 8) + packet[31]);
+    data[1] = ((packet[32] << 24) + (packet[33] << 16) + (packet[34] << 8) + packet[35]);
+    data[2] = ((packet[36] << 24) + (packet[37] << 16) + (packet[38] << 8) + packet[39]);
+    return 0;
+}
+uint8_t MPU6051::dmpGetAccel(int16_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = (packet[28] << 8) + packet[29];
+    data[1] = (packet[32] << 8) + packet[33];
+    data[2] = (packet[36] << 8) + packet[37];
+    return 0;
+}
+uint8_t MPU6051::dmpGetAccel(VectorInt16 *v, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    v -> x = (packet[28] << 8) + packet[29];
+    v -> y = (packet[32] << 8) + packet[33];
+    v -> z = (packet[36] << 8) + packet[37];
+    return 0;
+}
+uint8_t MPU6051::dmpGetQuaternion(int32_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[0] << 24) + (packet[1] << 16) + (packet[2] << 8) + packet[3]);
+    data[1] = ((packet[4] << 24) + (packet[5] << 16) + (packet[6] << 8) + packet[7]);
+    data[2] = ((packet[8] << 24) + (packet[9] << 16) + (packet[10] << 8) + packet[11]);
+    data[3] = ((packet[12] << 24) + (packet[13] << 16) + (packet[14] << 8) + packet[15]);
+    return 0;
+}
+uint8_t MPU6051::dmpGetQuaternion(int16_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[0] << 8) + packet[1]);
+    data[1] = ((packet[4] << 8) + packet[5]);
+    data[2] = ((packet[8] << 8) + packet[9]);
+    data[3] = ((packet[12] << 8) + packet[13]);
+    return 0;
+}
+uint8_t MPU6051::dmpGetQuaternion(Quaternion *q, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    int16_t qI[4];
+    uint8_t status = dmpGetQuaternion(qI, packet);
+    if (status == 0) {
+        q -> w = (float)qI[0] / 16384.0f;
+        q -> x = (float)qI[1] / 16384.0f;
+        q -> y = (float)qI[2] / 16384.0f;
+        q -> z = (float)qI[3] / 16384.0f;
+        return 0;
+    }
+    return status; // int16 return value, indicates error if this line is reached
+}
+// uint8_t MPU6051::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+uint8_t MPU6051::dmpGetGyro(int32_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[16] << 24) + (packet[17] << 16) + (packet[18] << 8) + packet[19]);
+    data[1] = ((packet[20] << 24) + (packet[21] << 16) + (packet[22] << 8) + packet[23]);
+    data[2] = ((packet[24] << 24) + (packet[25] << 16) + (packet[26] << 8) + packet[27]);
+    return 0;
+}
+uint8_t MPU6051::dmpGetGyro(int16_t *data, const uint8_t* packet)
+{
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = (packet[16] << 8) + packet[17];
+    data[1] = (packet[20] << 8) + packet[21];
+    data[2] = (packet[24] << 8) + packet[25];
+    return 0;
+}
+// uint8_t MPU6051::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6051::dmpGetLinearAccel(long *data, const uint8_t* packet);
+uint8_t MPU6051::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity)
+{
+    // get rid of the gravity component (+1g = +8192 in standard DMP FIFO packet, sensitivity is 2g)
+    v -> x = vRaw -> x - gravity -> x*8192;
+    v -> y = vRaw -> y - gravity -> y*8192;
+    v -> z = vRaw -> z - gravity -> z*8192;
+    return 0;
+}
+// uint8_t MPU6051::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+uint8_t MPU6051::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q)
+{
+    // rotate measured 3D acceleration vector into original state
+    // frame of reference based on orientation quaternion
+    memcpy(v, vReal, sizeof(VectorInt16));
+    v -> rotate(q);
+    return 0;
+}
+// uint8_t MPU6051::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetGravity(long *data, const uint8_t* packet);
+uint8_t MPU6051::dmpGetGravity(VectorFloat *v, Quaternion *q)
+{
+    v -> x = 2 * (q -> x*q -> z - q -> w*q -> y);
+    v -> y = 2 * (q -> w*q -> x + q -> y*q -> z);
+    v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z;
+    return 0;
+}
+// uint8_t MPU6051::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetEIS(long *data, const uint8_t* packet);
+
+uint8_t MPU6051::dmpGetEuler(float *data, Quaternion *q)
+{
+    data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);   // psi
+    data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y);                              // theta
+    data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1);   // phi
+    return 0;
+}
+
+uint8_t MPU6051::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity)
+{
+    // yaw: (about Z axis)
+    data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+    // pitch: (nose up/down, about Y axis)
+    data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+    // roll: (tilt left/right, about X axis)
+    data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z));
+    return 0;
+}
+
+// uint8_t MPU6051::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6051::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+uint8_t MPU6051::dmpProcessFIFOPacket(const unsigned char *dmpData)
+{
+    /*for (uint8_t k = 0; k < dmpPacketSize; k++) {
+        if (dmpData[k] < 0x10) Serial.print("0");
+        Serial.print(dmpData[k], HEX);
+        Serial.print(" ");
+    }
+    Serial.print("\n");*/
+    //Serial.println((uint16_t)dmpPacketBuffer);
+    return 0;
+}
+uint8_t MPU6051::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed)
+{
+    uint8_t status;
+    uint8_t buf[dmpPacketSize];
+    for (uint8_t i = 0; i < numPackets; i++) {
+        // read packet from FIFO
+        getFIFOBytes(buf, dmpPacketSize);
+
+        // process packet
+        if ((status = dmpProcessFIFOPacket(buf)) > 0) return status;
+
+        // increment external process count variable, if supplied
+        if (processed != 0) *processed++;
+    }
+    return 0;
+}
+
+// uint8_t MPU6051::dmpSetFIFOProcessedCallback(void (*func) (void));
+
+// uint8_t MPU6051::dmpInitFIFOParam();
+// uint8_t MPU6051::dmpCloseFIFO();
+// uint8_t MPU6051::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6051::dmpDecodeQuantizedAccel();
+// uint32_t MPU6051::dmpGetGyroSumOfSquare();
+// uint32_t MPU6051::dmpGetAccelSumOfSquare();
+// void MPU6051::dmpOverrideQuaternion(long *q);
+uint16_t MPU6051::dmpGetFIFOPacketSize()
+{
+    return dmpPacketSize;
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/MPU6050-DMP-Ian/Math/helper_3dmath.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/MPU6050-DMP-Ian/Math/helper_3dmath.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,216 @@
+// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class, 3D math helper
+// 6/5/2012 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     2012-06-05 - add 3D math helper file to DMP6 example sketch
+
+/* ============================================
+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.
+===============================================
+*/
+
+#ifndef _HELPER_3DMATH_H_
+#define _HELPER_3DMATH_H_
+
+class Quaternion {
+    public:
+        float w;
+        float x;
+        float y;
+        float z;
+        
+        Quaternion() {
+            w = 1.0f;
+            x = 0.0f;
+            y = 0.0f;
+            z = 0.0f;
+        }
+        
+        Quaternion(float nw, float nx, float ny, float nz) {
+            w = nw;
+            x = nx;
+            y = ny;
+            z = nz;
+        }
+
+        Quaternion getProduct(Quaternion q) {
+            // Quaternion multiplication is defined by:
+            //     (Q1 * Q2).w = (w1w2 - x1x2 - y1y2 - z1z2)
+            //     (Q1 * Q2).x = (w1x2 + x1w2 + y1z2 - z1y2)
+            //     (Q1 * Q2).y = (w1y2 - x1z2 + y1w2 + z1x2)
+            //     (Q1 * Q2).z = (w1z2 + x1y2 - y1x2 + z1w2
+            return Quaternion(
+                w*q.w - x*q.x - y*q.y - z*q.z,  // new w
+                w*q.x + x*q.w + y*q.z - z*q.y,  // new x
+                w*q.y - x*q.z + y*q.w + z*q.x,  // new y
+                w*q.z + x*q.y - y*q.x + z*q.w); // new z
+        }
+
+        Quaternion getConjugate() {
+            return Quaternion(w, -x, -y, -z);
+        }
+        
+        float getMagnitude() {
+            return sqrt(w*w + x*x + y*y + z*z);
+        }
+        
+        void normalize() {
+            float m = getMagnitude();
+            w /= m;
+            x /= m;
+            y /= m;
+            z /= m;
+        }
+        
+        Quaternion getNormalized() {
+            Quaternion r(w, x, y, z);
+            r.normalize();
+            return r;
+        }
+};
+
+class VectorInt16 {
+    public:
+        int16_t x;
+        int16_t y;
+        int16_t z;
+
+        VectorInt16() {
+            x = 0;
+            y = 0;
+            z = 0;
+        }
+        
+        VectorInt16(int16_t nx, int16_t ny, int16_t nz) {
+            x = nx;
+            y = ny;
+            z = nz;
+        }
+
+        float getMagnitude() {
+            return sqrt((float)(x*x + y*y + z*z));
+        }
+
+        void normalize() {
+            float m = getMagnitude();
+            x /= m;
+            y /= m;
+            z /= m;
+        }
+        
+        VectorInt16 getNormalized() {
+            VectorInt16 r(x, y, z);
+            r.normalize();
+            return r;
+        }
+        
+        void rotate(Quaternion *q) {
+            // http://www.cprogramming.com/tutorial/3d/quaternions.html
+            // http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/transforms/index.htm
+            // http://content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation
+            // ^ or: http://webcache.googleusercontent.com/search?q=cache:xgJAp3bDNhQJ:content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation&hl=en&gl=us&strip=1
+        
+            // P_out = q * P_in * conj(q)
+            // - P_out is the output vector
+            // - q is the orientation quaternion
+            // - P_in is the input vector (a*aReal)
+            // - conj(q) is the conjugate of the orientation quaternion (q=[w,x,y,z], q*=[w,-x,-y,-z])
+            Quaternion p(0, x, y, z);
+
+            // quaternion multiplication: q * p, stored back in p
+            p = q -> getProduct(p);
+
+            // quaternion multiplication: p * conj(q), stored back in p
+            p = p.getProduct(q -> getConjugate());
+
+            // p quaternion is now [0, x', y', z']
+            x = p.x;
+            y = p.y;
+            z = p.z;
+        }
+
+        VectorInt16 getRotated(Quaternion *q) {
+            VectorInt16 r(x, y, z);
+            r.rotate(q);
+            return r;
+        }
+};
+
+class VectorFloat {
+    public:
+        float x;
+        float y;
+        float z;
+
+        VectorFloat() {
+            x = 0;
+            y = 0;
+            z = 0;
+        }
+        
+        VectorFloat(float nx, float ny, float nz) {
+            x = nx;
+            y = ny;
+            z = nz;
+        }
+
+        float getMagnitude() {
+            return sqrt(x*x + y*y + z*z);
+        }
+
+        void normalize() {
+            float m = getMagnitude();
+            x /= m;
+            y /= m;
+            z /= m;
+        }
+        
+        VectorFloat getNormalized() {
+            VectorFloat r(x, y, z);
+            r.normalize();
+            return r;
+        }
+        
+        void rotate(Quaternion *q) {
+            Quaternion p(0, x, y, z);
+
+            // quaternion multiplication: q * p, stored back in p
+            p = q -> getProduct(p);
+
+            // quaternion multiplication: p * conj(q), stored back in p
+            p = p.getProduct(q -> getConjugate());
+
+            // p quaternion is now [0, x', y', z']
+            x = p.x;
+            y = p.y;
+            z = p.z;
+        }
+
+        VectorFloat getRotated(Quaternion *q) {
+            VectorFloat r(x, y, z);
+            r.rotate(q);
+            return r;
+        }
+};
+
+#endif /* _HELPER_3DMATH_H_ */
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 drivers/RF_Network/RF_node.cpp
diff -r 000000000000 -r 964eb6a2ef00 drivers/RF_Network/RF_node.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/RF_Network/RF_node.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,12 @@
+#ifndef RF_node_H
+#define RF_node_H
+
+//The following are used for the RF communication devices
+#define ROBOT_ADDRESS      ((unsigned long long) 0xE7E7E7E7E7 )//in pipe 0     //use this as the general receive address for ALL robots
+#define ROBOT1_ADDRESS      ((unsigned long long) 0xC2C2C2C2C2 )//in pipe 1
+#define ROBOT2_ADDRESS      ((unsigned long long) 0xC2C2C2C2C3)//in pipe 2
+#define ADDRESS_WIDTH       4
+
+
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 drivers/TB6612FNG2/TB6612.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/TB6612FNG2/TB6612.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,46 @@
+/**
+ * Motor Driver TB6612 Control Library
+ *
+ * -- TB6612 is a device of the TOSHIBA. 
+ *
+ * Copyright (C) 2012 Junichi Katsu (JKSOFT) 
+ */
+
+
+#include "TB6612.h"
+
+// TB6612 Class Constructor
+TB6612::TB6612(PinName pwm, PinName fwd, PinName rev):
+        scale(1), _pwm(pwm), _fwd(fwd), _rev(rev) {
+
+    _fwd = 0;
+    _rev = 0;
+    _pwm = 0.0;
+    _pwm.period(0.001);
+}
+
+// Speed Control
+//  arg
+//   int speed -100 -- 0 -- 100
+void TB6612::speed(int speed_) {
+    
+    float speed = scale*(float)speed_;
+    
+    if( speed > 0 )
+    {
+        _pwm = ((float)speed)/ 100.0;
+        _fwd = 1;
+        _rev = 0;
+    }
+    else if( speed < 0 )
+    {
+        _pwm = -((float)speed)/ 100.0;
+        _fwd = 0;
+        _rev = 1;
+    }
+    else
+    {
+        _fwd = 1;
+        _rev = 1;
+    }
+}
diff -r 000000000000 -r 964eb6a2ef00 drivers/TB6612FNG2/TB6612.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/TB6612FNG2/TB6612.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,33 @@
+/**
+ * Motor Driver TB6612 Control Library
+ *
+ * -- TB6612 is a device of the rohm. 
+ *
+ * Copyright (C) 2012 Junichi Katsu (JKSOFT) 
+ */
+
+#ifndef MBED_TB6612_H
+#define MBED_TB6612_H
+
+#include "mbed.h"
+
+class TB6612 {
+public:
+
+    float scale;
+
+    TB6612(PinName pwm, PinName fwd, PinName rev);
+    
+    void speed(int speed);
+    void operator= ( int value )
+    {
+        speed(value);
+    }
+    
+protected:
+    PwmOut _pwm;
+    DigitalOut _fwd;
+    DigitalOut _rev;
+};
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 drivers/nRF24L01P/nRF24L01P.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/nRF24L01P/nRF24L01P.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,1029 @@
+/**
+ * @file nRF24L01P.cpp
+ *
+ * @author Owen Edwards
+ * 
+ * @section LICENSE
+ *
+ * Copyright (c) 2010 Owen Edwards
+ *
+ *    This program is free software: you can redistribute it and/or modify
+ *    it under the terms of the GNU General Public License as published by
+ *    the Free Software Foundation, either version 3 of the License, or
+ *    (at your option) any later version.
+ *
+ *    This program is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ *    GNU General Public License for more details.
+ *
+ *    You should have received a copy of the GNU General Public License
+ *    along with this program.  If not, see <http://www.gnu.org/licenses/>.
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * @section DESCRIPTION
+ *
+ * nRF24L01+ Single Chip 2.4GHz Transceiver from Nordic Semiconductor.
+ *
+ * Datasheet:
+ *
+ * http://www.nordicsemi.no/files/Product/data_sheet/nRF24L01P_Product_Specification_1_0.pdf
+ */
+
+/**
+ * Includes
+ */
+#include "nRF24L01P.h"
+
+/**
+ * Defines
+ *
+ * (Note that all defines here start with an underscore, e.g. '_NRF24L01P_MODE_UNKNOWN',
+ *  and are local to this library.  The defines in the nRF24L01P.h file do not start
+ *  with the underscore, and can be used by code to access this library.)
+ */
+
+typedef enum {
+    _NRF24L01P_MODE_UNKNOWN,
+    _NRF24L01P_MODE_POWER_DOWN,
+    _NRF24L01P_MODE_STANDBY,
+    _NRF24L01P_MODE_RX,
+    _NRF24L01P_MODE_TX,
+} nRF24L01P_Mode_Type;
+
+/*
+ * The following FIFOs are present in nRF24L01+:
+ *   TX three level, 32 byte FIFO
+ *   RX three level, 32 byte FIFO
+ */
+#define _NRF24L01P_TX_FIFO_COUNT   3
+#define _NRF24L01P_RX_FIFO_COUNT   3
+
+#define _NRF24L01P_TX_FIFO_SIZE   32
+#define _NRF24L01P_RX_FIFO_SIZE   32
+
+#define _NRF24L01P_SPI_MAX_DATA_RATE     10000000
+
+#define _NRF24L01P_SPI_CMD_RD_REG            0x00
+#define _NRF24L01P_SPI_CMD_WR_REG            0x20
+#define _NRF24L01P_SPI_CMD_RD_RX_PAYLOAD     0x61   
+#define _NRF24L01P_SPI_CMD_WR_TX_PAYLOAD     0xa0
+#define _NRF24L01P_SPI_CMD_FLUSH_TX          0xe1
+#define _NRF24L01P_SPI_CMD_FLUSH_RX          0xe2
+#define _NRF24L01P_SPI_CMD_REUSE_TX_PL       0xe3
+#define _NRF24L01P_SPI_CMD_R_RX_PL_WID       0x60
+#define _NRF24L01P_SPI_CMD_W_ACK_PAYLOAD     0xa8
+#define _NRF24L01P_SPI_CMD_W_TX_PYLD_NO_ACK  0xb0
+#define _NRF24L01P_SPI_CMD_NOP               0xff
+
+
+#define _NRF24L01P_REG_CONFIG                0x00
+#define _NRF24L01P_REG_EN_AA                 0x01
+#define _NRF24L01P_REG_EN_RXADDR             0x02
+#define _NRF24L01P_REG_SETUP_AW              0x03
+#define _NRF24L01P_REG_SETUP_RETR            0x04
+#define _NRF24L01P_REG_RF_CH                 0x05
+#define _NRF24L01P_REG_RF_SETUP              0x06
+#define _NRF24L01P_REG_STATUS                0x07
+#define _NRF24L01P_REG_OBSERVE_TX            0x08
+#define _NRF24L01P_REG_RPD                   0x09
+#define _NRF24L01P_REG_RX_ADDR_P0            0x0a
+#define _NRF24L01P_REG_RX_ADDR_P1            0x0b
+#define _NRF24L01P_REG_RX_ADDR_P2            0x0c
+#define _NRF24L01P_REG_RX_ADDR_P3            0x0d
+#define _NRF24L01P_REG_RX_ADDR_P4            0x0e
+#define _NRF24L01P_REG_RX_ADDR_P5            0x0f
+#define _NRF24L01P_REG_TX_ADDR               0x10
+#define _NRF24L01P_REG_RX_PW_P0              0x11
+#define _NRF24L01P_REG_RX_PW_P1              0x12
+#define _NRF24L01P_REG_RX_PW_P2              0x13
+#define _NRF24L01P_REG_RX_PW_P3              0x14
+#define _NRF24L01P_REG_RX_PW_P4              0x15
+#define _NRF24L01P_REG_RX_PW_P5              0x16
+#define _NRF24L01P_REG_FIFO_STATUS           0x17
+#define _NRF24L01P_REG_DYNPD                 0x1c
+#define _NRF24L01P_REG_FEATURE               0x1d
+
+#define _NRF24L01P_REG_ADDRESS_MASK          0x1f
+
+// CONFIG register:
+#define _NRF24L01P_CONFIG_PRIM_RX        (1<<0)
+#define _NRF24L01P_CONFIG_PWR_UP         (1<<1)
+#define _NRF24L01P_CONFIG_CRC0           (1<<2)
+#define _NRF24L01P_CONFIG_EN_CRC         (1<<3)
+#define _NRF24L01P_CONFIG_MASK_MAX_RT    (1<<4)
+#define _NRF24L01P_CONFIG_MASK_TX_DS     (1<<5)
+#define _NRF24L01P_CONFIG_MASK_RX_DR     (1<<6)
+
+#define _NRF24L01P_CONFIG_CRC_MASK       (_NRF24L01P_CONFIG_EN_CRC|_NRF24L01P_CONFIG_CRC0)
+#define _NRF24L01P_CONFIG_CRC_NONE       (0)
+#define _NRF24L01P_CONFIG_CRC_8BIT       (_NRF24L01P_CONFIG_EN_CRC)
+#define _NRF24L01P_CONFIG_CRC_16BIT      (_NRF24L01P_CONFIG_EN_CRC|_NRF24L01P_CONFIG_CRC0)
+
+// EN_AA register:
+#define _NRF24L01P_EN_AA_NONE            0
+
+// EN_RXADDR register:
+#define _NRF24L01P_EN_RXADDR_NONE        0
+
+// SETUP_AW register:
+#define _NRF24L01P_SETUP_AW_AW_MASK      (0x3<<0)
+#define _NRF24L01P_SETUP_AW_AW_3BYTE     (0x1<<0)
+#define _NRF24L01P_SETUP_AW_AW_4BYTE     (0x2<<0)
+#define _NRF24L01P_SETUP_AW_AW_5BYTE     (0x3<<0)
+
+// SETUP_RETR register:
+#define _NRF24L01P_SETUP_RETR_NONE       0
+
+// RF_SETUP register:
+#define _NRF24L01P_RF_SETUP_RF_PWR_MASK          (0x3<<1)
+#define _NRF24L01P_RF_SETUP_RF_PWR_0DBM          (0x3<<1)
+#define _NRF24L01P_RF_SETUP_RF_PWR_MINUS_6DBM    (0x2<<1)
+#define _NRF24L01P_RF_SETUP_RF_PWR_MINUS_12DBM   (0x1<<1)
+#define _NRF24L01P_RF_SETUP_RF_PWR_MINUS_18DBM   (0x0<<1)
+
+#define _NRF24L01P_RF_SETUP_RF_DR_HIGH_BIT       (1 << 3)
+#define _NRF24L01P_RF_SETUP_RF_DR_LOW_BIT        (1 << 5)
+#define _NRF24L01P_RF_SETUP_RF_DR_MASK           (_NRF24L01P_RF_SETUP_RF_DR_LOW_BIT|_NRF24L01P_RF_SETUP_RF_DR_HIGH_BIT)
+#define _NRF24L01P_RF_SETUP_RF_DR_250KBPS        (_NRF24L01P_RF_SETUP_RF_DR_LOW_BIT)
+#define _NRF24L01P_RF_SETUP_RF_DR_1MBPS          (0)
+#define _NRF24L01P_RF_SETUP_RF_DR_2MBPS          (_NRF24L01P_RF_SETUP_RF_DR_HIGH_BIT)
+
+// STATUS register:
+#define _NRF24L01P_STATUS_TX_FULL        (1<<0)
+#define _NRF24L01P_STATUS_RX_P_NO        (0x7<<1)
+#define _NRF24L01P_STATUS_MAX_RT         (1<<4)
+#define _NRF24L01P_STATUS_TX_DS          (1<<5)
+#define _NRF24L01P_STATUS_RX_DR          (1<<6)
+
+// RX_PW_P0..RX_PW_P5 registers:
+#define _NRF24L01P_RX_PW_Px_MASK         0x3F
+
+#define _NRF24L01P_TIMING_Tundef2pd_us     100000   // 100mS
+#define _NRF24L01P_TIMING_Tstby2a_us          130   // 130uS
+#define _NRF24L01P_TIMING_Thce_us              10   //  10uS
+#define _NRF24L01P_TIMING_Tpd2stby_us        4500   // 4.5mS worst case
+#define _NRF24L01P_TIMING_Tpece2csn_us          4   //   4uS
+
+/**
+ * Methods
+ */
+
+nRF24L01P::nRF24L01P(PinName mosi, 
+                     PinName miso, 
+                     PinName sck, 
+                     PinName csn,
+                     PinName ce,
+                     PinName irq) : spi_(mosi, miso, sck), nCS_(csn), ce_(ce), nIRQ_(irq) {
+
+    mode = _NRF24L01P_MODE_UNKNOWN;
+
+    disable();
+
+    nCS_ = 1;
+
+    spi_.frequency(_NRF24L01P_SPI_MAX_DATA_RATE/5);     // 2Mbit, 1/5th the maximum transfer rate for the SPI bus
+    spi_.format(8,0);                                   // 8-bit, ClockPhase = 0, ClockPolarity = 0
+
+    wait_us(_NRF24L01P_TIMING_Tundef2pd_us);    // Wait for Power-on reset
+
+    setRegister(_NRF24L01P_REG_CONFIG, 0); // Power Down
+
+    setRegister(_NRF24L01P_REG_STATUS, _NRF24L01P_STATUS_MAX_RT|_NRF24L01P_STATUS_TX_DS|_NRF24L01P_STATUS_RX_DR);   // Clear any pending interrupts
+
+    //
+    // Setup default configuration
+    //
+    disableAllRxPipes();
+    setRfFrequency();
+    setRfOutputPower();
+    setAirDataRate();
+    setCrcWidth();
+    setTxAddress();
+    setRxAddress();
+    disableAutoAcknowledge();
+    disableAutoRetransmit();
+    setTransferSize();
+
+    mode = _NRF24L01P_MODE_POWER_DOWN;
+
+}
+
+
+void nRF24L01P::powerUp(void) {
+
+    int config = getRegister(_NRF24L01P_REG_CONFIG);
+
+    config |= _NRF24L01P_CONFIG_PWR_UP;
+
+    setRegister(_NRF24L01P_REG_CONFIG, config);
+
+    // Wait until the nRF24L01+ powers up
+    wait_us( _NRF24L01P_TIMING_Tpd2stby_us );
+
+    mode = _NRF24L01P_MODE_STANDBY;
+
+}
+
+
+void nRF24L01P::powerDown(void) {
+
+    int config = getRegister(_NRF24L01P_REG_CONFIG);
+
+    config &= ~_NRF24L01P_CONFIG_PWR_UP;
+
+    setRegister(_NRF24L01P_REG_CONFIG, config);
+
+    // Wait until the nRF24L01+ powers down
+    wait_us( _NRF24L01P_TIMING_Tpd2stby_us );    // This *may* not be necessary (no timing is shown in the Datasheet), but just to be safe
+
+    mode = _NRF24L01P_MODE_POWER_DOWN;
+
+}
+
+
+void nRF24L01P::setReceiveMode(void) {
+
+    if ( _NRF24L01P_MODE_POWER_DOWN == mode ) powerUp();
+
+    int config = getRegister(_NRF24L01P_REG_CONFIG);
+
+    config |= _NRF24L01P_CONFIG_PRIM_RX;
+
+    setRegister(_NRF24L01P_REG_CONFIG, config);
+
+    mode = _NRF24L01P_MODE_RX;
+
+}
+
+
+void nRF24L01P::setTransmitMode(void) {
+
+    if ( _NRF24L01P_MODE_POWER_DOWN == mode ) powerUp();
+
+    int config = getRegister(_NRF24L01P_REG_CONFIG);
+
+    config &= ~_NRF24L01P_CONFIG_PRIM_RX;
+
+    setRegister(_NRF24L01P_REG_CONFIG, config);
+
+    mode = _NRF24L01P_MODE_TX;
+
+}
+
+
+void nRF24L01P::enable(void) {
+
+    ce_ = 1;
+    wait_us( _NRF24L01P_TIMING_Tpece2csn_us );
+
+}
+
+
+void nRF24L01P::disable(void) {
+
+    ce_ = 0;
+
+}
+
+void nRF24L01P::setRfFrequency(int frequency) {
+
+    if ( ( frequency < NRF24L01P_MIN_RF_FREQUENCY ) || ( frequency > NRF24L01P_MAX_RF_FREQUENCY ) ) {
+
+        error( "nRF24L01P: Invalid RF Frequency setting %d\r\n", frequency );
+        return;
+
+    }
+
+    int channel = ( frequency - NRF24L01P_MIN_RF_FREQUENCY ) & 0x7F;
+
+    setRegister(_NRF24L01P_REG_RF_CH, channel);
+
+}
+
+
+int nRF24L01P::getRfFrequency(void) {
+
+    int channel = getRegister(_NRF24L01P_REG_RF_CH) & 0x7F;
+
+    return ( channel + NRF24L01P_MIN_RF_FREQUENCY );
+
+}
+
+
+void nRF24L01P::setRfOutputPower(int power) {
+
+    int rfSetup = getRegister(_NRF24L01P_REG_RF_SETUP) & ~_NRF24L01P_RF_SETUP_RF_PWR_MASK;
+
+    switch ( power ) {
+
+        case NRF24L01P_TX_PWR_ZERO_DB:
+            rfSetup |= _NRF24L01P_RF_SETUP_RF_PWR_0DBM;
+            break;
+
+        case NRF24L01P_TX_PWR_MINUS_6_DB:
+            rfSetup |= _NRF24L01P_RF_SETUP_RF_PWR_MINUS_6DBM;
+            break;
+
+        case NRF24L01P_TX_PWR_MINUS_12_DB:
+            rfSetup |= _NRF24L01P_RF_SETUP_RF_PWR_MINUS_12DBM;
+            break;
+
+        case NRF24L01P_TX_PWR_MINUS_18_DB:
+            rfSetup |= _NRF24L01P_RF_SETUP_RF_PWR_MINUS_18DBM;
+            break;
+
+        default:
+            error( "nRF24L01P: Invalid RF Output Power setting %d\r\n", power );
+            return;
+
+    }
+
+    setRegister(_NRF24L01P_REG_RF_SETUP, rfSetup);
+
+}
+
+
+int nRF24L01P::getRfOutputPower(void) {
+
+    int rfPwr = getRegister(_NRF24L01P_REG_RF_SETUP) & _NRF24L01P_RF_SETUP_RF_PWR_MASK;
+
+    switch ( rfPwr ) {
+
+        case _NRF24L01P_RF_SETUP_RF_PWR_0DBM:
+            return NRF24L01P_TX_PWR_ZERO_DB;
+
+        case _NRF24L01P_RF_SETUP_RF_PWR_MINUS_6DBM:
+            return NRF24L01P_TX_PWR_MINUS_6_DB;
+
+        case _NRF24L01P_RF_SETUP_RF_PWR_MINUS_12DBM:
+            return NRF24L01P_TX_PWR_MINUS_12_DB;
+
+        case _NRF24L01P_RF_SETUP_RF_PWR_MINUS_18DBM:
+            return NRF24L01P_TX_PWR_MINUS_18_DB;
+
+        default:
+            error( "nRF24L01P: Unknown RF Output Power value %d\r\n", rfPwr );
+            return 0;
+
+    }
+}
+
+
+void nRF24L01P::setAirDataRate(int rate) {
+
+    int rfSetup = getRegister(_NRF24L01P_REG_RF_SETUP) & ~_NRF24L01P_RF_SETUP_RF_DR_MASK;
+
+    switch ( rate ) {
+
+        case NRF24L01P_DATARATE_250_KBPS:
+            rfSetup |= _NRF24L01P_RF_SETUP_RF_DR_250KBPS;
+            break;
+
+        case NRF24L01P_DATARATE_1_MBPS:
+            rfSetup |= _NRF24L01P_RF_SETUP_RF_DR_1MBPS;
+            break;
+
+        case NRF24L01P_DATARATE_2_MBPS:
+            rfSetup |= _NRF24L01P_RF_SETUP_RF_DR_2MBPS;
+            break;
+
+        default:
+            error( "nRF24L01P: Invalid Air Data Rate setting %d\r\n", rate );
+            return;
+
+    }
+
+    setRegister(_NRF24L01P_REG_RF_SETUP, rfSetup);
+
+}
+
+
+int nRF24L01P::getAirDataRate(void) {
+
+    int rfDataRate = getRegister(_NRF24L01P_REG_RF_SETUP) & _NRF24L01P_RF_SETUP_RF_DR_MASK;
+
+    switch ( rfDataRate ) {
+
+        case _NRF24L01P_RF_SETUP_RF_DR_250KBPS:
+            return NRF24L01P_DATARATE_250_KBPS;
+
+        case _NRF24L01P_RF_SETUP_RF_DR_1MBPS:
+            return NRF24L01P_DATARATE_1_MBPS;
+
+        case _NRF24L01P_RF_SETUP_RF_DR_2MBPS:
+            return NRF24L01P_DATARATE_2_MBPS;
+
+        default:
+            error( "nRF24L01P: Unknown Air Data Rate value %d\r\n", rfDataRate );
+            return 0;
+
+    }
+}
+
+
+void nRF24L01P::setCrcWidth(int width) {
+
+    int config = getRegister(_NRF24L01P_REG_CONFIG) & ~_NRF24L01P_CONFIG_CRC_MASK;
+
+    switch ( width ) {
+
+        case NRF24L01P_CRC_NONE:
+            config |= _NRF24L01P_CONFIG_CRC_NONE;
+            break;
+
+        case NRF24L01P_CRC_8_BIT:
+            config |= _NRF24L01P_CONFIG_CRC_8BIT;
+            break;
+
+        case NRF24L01P_CRC_16_BIT:
+            config |= _NRF24L01P_CONFIG_CRC_16BIT;
+            break;
+
+        default:
+            error( "nRF24L01P: Invalid CRC Width setting %d\r\n", width );
+            return;
+
+    }
+
+    setRegister(_NRF24L01P_REG_CONFIG, config);
+
+}
+
+
+int nRF24L01P::getCrcWidth(void) {
+
+    int crcWidth = getRegister(_NRF24L01P_REG_CONFIG) & _NRF24L01P_CONFIG_CRC_MASK;
+
+    switch ( crcWidth ) {
+
+        case _NRF24L01P_CONFIG_CRC_NONE:
+            return NRF24L01P_CRC_NONE;
+
+        case _NRF24L01P_CONFIG_CRC_8BIT:
+            return NRF24L01P_CRC_8_BIT;
+
+        case _NRF24L01P_CONFIG_CRC_16BIT:
+            return NRF24L01P_CRC_16_BIT;
+
+        default:
+            error( "nRF24L01P: Unknown CRC Width value %d\r\n", crcWidth );
+            return 0;
+
+    }
+}
+
+
+void nRF24L01P::setTransferSize(int size, int pipe) {
+
+    if ( ( pipe < NRF24L01P_PIPE_P0 ) || ( pipe > NRF24L01P_PIPE_P5 ) ) {
+
+        error( "nRF24L01P: Invalid Transfer Size pipe number %d\r\n", pipe );
+        return;
+
+    }
+
+    if ( ( size < 0 ) || ( size > _NRF24L01P_RX_FIFO_SIZE ) ) {
+
+        error( "nRF24L01P: Invalid Transfer Size setting %d\r\n", size );
+        return;
+
+    }
+
+    int rxPwPxRegister = _NRF24L01P_REG_RX_PW_P0 + ( pipe - NRF24L01P_PIPE_P0 );
+
+    setRegister(rxPwPxRegister, ( size & _NRF24L01P_RX_PW_Px_MASK ) );
+
+}
+
+
+int nRF24L01P::getTransferSize(int pipe) {
+
+    if ( ( pipe < NRF24L01P_PIPE_P0 ) || ( pipe > NRF24L01P_PIPE_P5 ) ) {
+
+        error( "nRF24L01P: Invalid Transfer Size pipe number %d\r\n", pipe );
+        return 0;
+
+    }
+
+    int rxPwPxRegister = _NRF24L01P_REG_RX_PW_P0 + ( pipe - NRF24L01P_PIPE_P0 );
+
+    int size = getRegister(rxPwPxRegister);
+    
+    return ( size & _NRF24L01P_RX_PW_Px_MASK );
+
+}
+
+
+void nRF24L01P::disableAllRxPipes(void) {
+
+    setRegister(_NRF24L01P_REG_EN_RXADDR, _NRF24L01P_EN_RXADDR_NONE);
+
+}
+
+
+void nRF24L01P::disableAutoAcknowledge(void) {
+
+    setRegister(_NRF24L01P_REG_EN_AA, _NRF24L01P_EN_AA_NONE);
+
+}
+
+
+void nRF24L01P::enableAutoAcknowledge(int pipe) {
+
+    if ( ( pipe < NRF24L01P_PIPE_P0 ) || ( pipe > NRF24L01P_PIPE_P5 ) ) {
+
+        error( "nRF24L01P: Invalid Enable AutoAcknowledge pipe number %d\r\n", pipe );
+        return;
+
+    }
+
+    int enAA = getRegister(_NRF24L01P_REG_EN_AA);
+
+    enAA |= ( 1 << (pipe - NRF24L01P_PIPE_P0) );
+
+    setRegister(_NRF24L01P_REG_EN_AA, enAA);
+
+}
+
+
+void nRF24L01P::disableAutoRetransmit(void) {
+
+    setRegister(_NRF24L01P_REG_SETUP_RETR, _NRF24L01P_SETUP_RETR_NONE);
+
+}
+
+void nRF24L01P::setRxAddress(unsigned long long address, int width, int pipe) {
+
+    if ( ( pipe < NRF24L01P_PIPE_P0 ) || ( pipe > NRF24L01P_PIPE_P5 ) ) {
+
+        error( "nRF24L01P: Invalid setRxAddress pipe number %d\r\n", pipe );
+        return;
+
+    }
+
+    if ( ( pipe == NRF24L01P_PIPE_P0 ) || ( pipe == NRF24L01P_PIPE_P1 ) ) {
+
+        int setupAw = getRegister(_NRF24L01P_REG_SETUP_AW) & ~_NRF24L01P_SETUP_AW_AW_MASK;
+    
+        switch ( width ) {
+    
+            case 3:
+                setupAw |= _NRF24L01P_SETUP_AW_AW_3BYTE;
+                break;
+    
+            case 4:
+                setupAw |= _NRF24L01P_SETUP_AW_AW_4BYTE;
+                break;
+    
+            case 5:
+                setupAw |= _NRF24L01P_SETUP_AW_AW_5BYTE;
+                break;
+    
+            default:
+                error( "nRF24L01P: Invalid setRxAddress width setting %d\r\n", width );
+                return;
+    
+        }
+    
+        setRegister(_NRF24L01P_REG_SETUP_AW, setupAw);
+
+    } else {
+    
+        width = 1;
+    
+    }
+
+    int rxAddrPxRegister = _NRF24L01P_REG_RX_ADDR_P0 + ( pipe - NRF24L01P_PIPE_P0 );
+
+    int cn = (_NRF24L01P_SPI_CMD_WR_REG | (rxAddrPxRegister & _NRF24L01P_REG_ADDRESS_MASK));
+
+    nCS_ = 0;
+
+    int status = spi_.write(cn);
+
+    while ( width-- > 0 ) {
+
+        //
+        // LSByte first
+        //
+        spi_.write((int) (address & 0xFF));
+        address >>= 8;
+
+    }
+
+    nCS_ = 1;
+
+    int enRxAddr = getRegister(_NRF24L01P_REG_EN_RXADDR);
+
+    enRxAddr |= (1 << ( pipe - NRF24L01P_PIPE_P0 ) );
+
+    setRegister(_NRF24L01P_REG_EN_RXADDR, enRxAddr);
+}
+
+/*
+ * This version of setRxAddress is just a wrapper for the version that takes 'long long's,
+ *  in case the main code doesn't want to deal with long long's.
+ */
+void nRF24L01P::setRxAddress(unsigned long msb_address, unsigned long lsb_address, int width, int pipe) {
+
+    unsigned long long address = ( ( (unsigned long long) msb_address ) << 32 ) | ( ( (unsigned long long) lsb_address ) << 0 );
+
+    setRxAddress(address, width, pipe);
+
+}
+
+
+/*
+ * This version of setTxAddress is just a wrapper for the version that takes 'long long's,
+ *  in case the main code doesn't want to deal with long long's.
+ */
+void nRF24L01P::setTxAddress(unsigned long msb_address, unsigned long lsb_address, int width) {
+
+    unsigned long long address = ( ( (unsigned long long) msb_address ) << 32 ) | ( ( (unsigned long long) lsb_address ) << 0 );
+
+    setTxAddress(address, width);
+
+}
+
+
+void nRF24L01P::setTxAddress(unsigned long long address, int width) {
+
+    int setupAw = getRegister(_NRF24L01P_REG_SETUP_AW) & ~_NRF24L01P_SETUP_AW_AW_MASK;
+
+    switch ( width ) {
+
+        case 3:
+            setupAw |= _NRF24L01P_SETUP_AW_AW_3BYTE;
+            break;
+
+        case 4:
+            setupAw |= _NRF24L01P_SETUP_AW_AW_4BYTE;
+            break;
+
+        case 5:
+            setupAw |= _NRF24L01P_SETUP_AW_AW_5BYTE;
+            break;
+
+        default:
+            error( "nRF24L01P: Invalid setTxAddress width setting %d\r\n", width );
+            return;
+
+    }
+
+    setRegister(_NRF24L01P_REG_SETUP_AW, setupAw);
+
+    int cn = (_NRF24L01P_SPI_CMD_WR_REG | (_NRF24L01P_REG_TX_ADDR & _NRF24L01P_REG_ADDRESS_MASK));
+
+    nCS_ = 0;
+
+    int status = spi_.write(cn);
+
+    while ( width-- > 0 ) {
+
+        //
+        // LSByte first
+        //
+        spi_.write((int) (address & 0xFF));
+        address >>= 8;
+
+    }
+
+    nCS_ = 1;
+
+}
+
+
+unsigned long long nRF24L01P::getRxAddress(int pipe) {
+
+    if ( ( pipe < NRF24L01P_PIPE_P0 ) || ( pipe > NRF24L01P_PIPE_P5 ) ) {
+
+        error( "nRF24L01P: Invalid setRxAddress pipe number %d\r\n", pipe );
+        return 0;
+
+    }
+
+    int width;
+
+    if ( ( pipe == NRF24L01P_PIPE_P0 ) || ( pipe == NRF24L01P_PIPE_P1 ) ) {
+
+        int setupAw = getRegister(_NRF24L01P_REG_SETUP_AW) & _NRF24L01P_SETUP_AW_AW_MASK;
+
+        switch ( setupAw ) {
+
+            case _NRF24L01P_SETUP_AW_AW_3BYTE:
+                width = 3;
+                break;
+
+            case _NRF24L01P_SETUP_AW_AW_4BYTE:
+                width = 4;
+                break;
+
+            case _NRF24L01P_SETUP_AW_AW_5BYTE:
+                width = 5;
+                break;
+
+            default:
+                error( "nRF24L01P: Unknown getRxAddress width value %d\r\n", setupAw );
+                return 0;
+
+        }
+
+    } else {
+
+        width = 1;
+
+    }
+
+    int rxAddrPxRegister = _NRF24L01P_REG_RX_ADDR_P0 + ( pipe - NRF24L01P_PIPE_P0 );
+
+    int cn = (_NRF24L01P_SPI_CMD_RD_REG | (rxAddrPxRegister & _NRF24L01P_REG_ADDRESS_MASK));
+
+    unsigned long long address = 0;
+
+    nCS_ = 0;
+
+    int status = spi_.write(cn);
+
+    for ( int i=0; i<width; i++ ) {
+
+        //
+        // LSByte first
+        //
+        address |= ( ( (unsigned long long)( spi_.write(_NRF24L01P_SPI_CMD_NOP) & 0xFF ) ) << (i*8) );
+
+    }
+
+    nCS_ = 1;
+
+    if ( !( ( pipe == NRF24L01P_PIPE_P0 ) || ( pipe == NRF24L01P_PIPE_P1 ) ) ) {
+
+        address |= ( getRxAddress(NRF24L01P_PIPE_P1) & ~((unsigned long long) 0xFF) );
+
+    }
+
+    return address;
+
+}
+
+    
+unsigned long long nRF24L01P::getTxAddress(void) {
+
+    int setupAw = getRegister(_NRF24L01P_REG_SETUP_AW) & _NRF24L01P_SETUP_AW_AW_MASK;
+
+    int width;
+
+    switch ( setupAw ) {
+
+        case _NRF24L01P_SETUP_AW_AW_3BYTE:
+            width = 3;
+            break;
+
+        case _NRF24L01P_SETUP_AW_AW_4BYTE:
+            width = 4;
+            break;
+
+        case _NRF24L01P_SETUP_AW_AW_5BYTE:
+            width = 5;
+            break;
+
+        default:
+            error( "nRF24L01P: Unknown getTxAddress width value %d\r\n", setupAw );
+            return 0;
+
+    }
+
+    int cn = (_NRF24L01P_SPI_CMD_RD_REG | (_NRF24L01P_REG_TX_ADDR & _NRF24L01P_REG_ADDRESS_MASK));
+
+    unsigned long long address = 0;
+
+    nCS_ = 0;
+
+    int status = spi_.write(cn);
+
+    for ( int i=0; i<width; i++ ) {
+
+        //
+        // LSByte first
+        //
+        address |= ( ( (unsigned long long)( spi_.write(_NRF24L01P_SPI_CMD_NOP) & 0xFF ) ) << (i*8) );
+
+    }
+
+    nCS_ = 1;
+
+    return address;
+}
+
+
+bool nRF24L01P::readable(int pipe) {
+
+    if ( ( pipe < NRF24L01P_PIPE_P0 ) || ( pipe > NRF24L01P_PIPE_P5 ) ) {
+
+        error( "nRF24L01P: Invalid readable pipe number %d\r\n", pipe );
+        return false;
+
+    }
+
+    int status = getStatusRegister();
+
+    return ( ( status & _NRF24L01P_STATUS_RX_DR ) && ( ( ( status & _NRF24L01P_STATUS_RX_P_NO ) >> 1 ) == ( pipe & 0x7 ) ) );
+
+}
+
+
+int nRF24L01P::write(int pipe, char *data, int count) {
+
+    // Note: the pipe number is ignored in a Transmit / write
+
+    //
+    // Save the CE state
+    //
+    int originalCe = ce_;
+    disable();
+
+    if ( count <= 0 ) return 0;
+
+    if ( count > _NRF24L01P_TX_FIFO_SIZE ) count = _NRF24L01P_TX_FIFO_SIZE;
+
+    // Clear the Status bit
+    setRegister(_NRF24L01P_REG_STATUS, _NRF24L01P_STATUS_TX_DS);
+	
+    nCS_ = 0;
+
+    int status = spi_.write(_NRF24L01P_SPI_CMD_WR_TX_PAYLOAD);
+
+    for ( int i = 0; i < count; i++ ) {
+
+        spi_.write(*data++);
+
+    }
+
+    nCS_ = 1;
+
+    int originalMode = mode;
+    setTransmitMode();
+
+    enable();
+    wait_us(_NRF24L01P_TIMING_Thce_us);
+    disable();
+
+    while ( !( getStatusRegister() & _NRF24L01P_STATUS_TX_DS ) ) {
+
+        // Wait for the transfer to complete
+
+    }
+
+    // Clear the Status bit
+    setRegister(_NRF24L01P_REG_STATUS, _NRF24L01P_STATUS_TX_DS);
+
+    if ( originalMode == _NRF24L01P_MODE_RX ) {
+
+        setReceiveMode();
+
+    }
+
+    ce_ = originalCe;
+    wait_us( _NRF24L01P_TIMING_Tpece2csn_us );
+
+    return count;
+
+}
+
+
+int nRF24L01P::read(int pipe, char *data, int count) {
+
+    if ( ( pipe < NRF24L01P_PIPE_P0 ) || ( pipe > NRF24L01P_PIPE_P5 ) ) {
+
+        error( "nRF24L01P: Invalid read pipe number %d\r\n", pipe );
+        return -1;
+
+    }
+
+    if ( count <= 0 ) return 0;
+
+    if ( count > _NRF24L01P_RX_FIFO_SIZE ) count = _NRF24L01P_RX_FIFO_SIZE;
+
+    if ( readable(pipe) ) {
+
+        nCS_ = 0;
+
+        int status = spi_.write(_NRF24L01P_SPI_CMD_R_RX_PL_WID);
+
+        int rxPayloadWidth = spi_.write(_NRF24L01P_SPI_CMD_NOP);
+        
+        nCS_ = 1;
+
+        if ( ( rxPayloadWidth < 0 ) || ( rxPayloadWidth > _NRF24L01P_RX_FIFO_SIZE ) ) {
+    
+            // Received payload error: need to flush the FIFO
+
+            nCS_ = 0;
+    
+            int status = spi_.write(_NRF24L01P_SPI_CMD_FLUSH_RX);
+    
+            int rxPayloadWidth = spi_.write(_NRF24L01P_SPI_CMD_NOP);
+            
+            nCS_ = 1;
+            
+            //
+            // At this point, we should retry the reception,
+            //  but for now we'll just fall through...
+            //
+
+        } else {
+
+            if ( rxPayloadWidth < count ) count = rxPayloadWidth;
+
+            nCS_ = 0;
+        
+            int status = spi_.write(_NRF24L01P_SPI_CMD_RD_RX_PAYLOAD);
+        
+            for ( int i = 0; i < count; i++ ) {
+        
+                *data++ = spi_.write(_NRF24L01P_SPI_CMD_NOP);
+        
+            }
+
+            nCS_ = 1;
+
+            // Clear the Status bit
+            setRegister(_NRF24L01P_REG_STATUS, _NRF24L01P_STATUS_RX_DR);
+
+            return count;
+
+        }
+
+    } else {
+
+        //
+        // What should we do if there is no 'readable' data?
+        //  We could wait for data to arrive, but for now, we'll
+        //  just return with no data.
+        //
+        return 0;
+
+    }
+
+    //
+    // We get here because an error condition occured;
+    //  We could wait for data to arrive, but for now, we'll
+    //  just return with no data.
+    //
+    return -1;
+
+}
+
+void nRF24L01P::setRegister(int regAddress, int regData) {
+
+    //
+    // Save the CE state
+    //
+    int originalCe = ce_;
+    disable();
+
+    int cn = (_NRF24L01P_SPI_CMD_WR_REG | (regAddress & _NRF24L01P_REG_ADDRESS_MASK));
+
+    nCS_ = 0;
+
+    int status = spi_.write(cn);
+
+    spi_.write(regData & 0xFF);
+
+    nCS_ = 1;
+
+    ce_ = originalCe;
+    wait_us( _NRF24L01P_TIMING_Tpece2csn_us );
+
+}
+
+
+int nRF24L01P::getRegister(int regAddress) {
+
+    int cn = (_NRF24L01P_SPI_CMD_RD_REG | (regAddress & _NRF24L01P_REG_ADDRESS_MASK));
+
+    nCS_ = 0;
+
+    int status = spi_.write(cn);
+
+    int dn = spi_.write(_NRF24L01P_SPI_CMD_NOP);
+
+    nCS_ = 1;
+
+    return dn;
+
+}
+
+int nRF24L01P::getStatusRegister(void) {
+
+    nCS_ = 0;
+
+    int status = spi_.write(_NRF24L01P_SPI_CMD_NOP);
+
+    nCS_ = 1;
+
+    return status;
+
+}
diff -r 000000000000 -r 964eb6a2ef00 drivers/nRF24L01P/nRF24L01P.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/drivers/nRF24L01P/nRF24L01P.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,347 @@
+/**
+ * @file nRF24L01P.h
+ *
+ * @author Owen Edwards
+ * 
+ * @section LICENSE
+ *
+ * Copyright (c) 2010 Owen Edwards
+ *
+ *    This program is free software: you can redistribute it and/or modify
+ *    it under the terms of the GNU General Public License as published by
+ *    the Free Software Foundation, either version 3 of the License, or
+ *    (at your option) any later version.
+ *
+ *    This program is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ *    GNU General Public License for more details.
+ *
+ *    You should have received a copy of the GNU General Public License
+ *    along with this program.  If not, see <http://www.gnu.org/licenses/>.
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * @section DESCRIPTION
+ *
+ * nRF24L01+ Single Chip 2.4GHz Transceiver from Nordic Semiconductor.
+ *
+ * Datasheet:
+ *
+ * http://www.nordicsemi.no/files/Product/data_sheet/nRF24L01P_Product_Specification_1_0.pdf
+ */
+
+#ifndef __NRF24L01P_H__
+#define __NRF24L01P_H__
+
+/**
+ * Includes
+ */
+#include "mbed.h"
+
+/**
+ * Defines
+ */
+#define NRF24L01P_TX_PWR_ZERO_DB         0
+#define NRF24L01P_TX_PWR_MINUS_6_DB     -6
+#define NRF24L01P_TX_PWR_MINUS_12_DB   -12
+#define NRF24L01P_TX_PWR_MINUS_18_DB   -18
+
+#define NRF24L01P_DATARATE_250_KBPS    250
+#define NRF24L01P_DATARATE_1_MBPS     1000
+#define NRF24L01P_DATARATE_2_MBPS     2000
+
+#define NRF24L01P_CRC_NONE               0
+#define NRF24L01P_CRC_8_BIT              8
+#define NRF24L01P_CRC_16_BIT            16
+
+#define NRF24L01P_MIN_RF_FREQUENCY    2400
+#define NRF24L01P_MAX_RF_FREQUENCY    2525
+
+#define NRF24L01P_PIPE_P0                0
+#define NRF24L01P_PIPE_P1                1
+#define NRF24L01P_PIPE_P2                2
+#define NRF24L01P_PIPE_P3                3
+#define NRF24L01P_PIPE_P4                4
+#define NRF24L01P_PIPE_P5                5
+
+/**
+* Default setup for the nRF24L01+, based on the Sparkfun "Nordic Serial Interface Board"
+*  for evaluation (http://www.sparkfun.com/products/9019)
+*/
+#define DEFAULT_NRF24L01P_ADDRESS       ((unsigned long long) 0xE7E7E7E7E7 )
+#define DEFAULT_NRF24L01P_ADDRESS_WIDTH  5
+#define DEFAULT_NRF24L01P_CRC            NRF24L01P_CRC_8_BIT
+#define DEFAULT_NRF24L01P_RF_FREQUENCY  (NRF24L01P_MIN_RF_FREQUENCY + 2)
+#define DEFAULT_NRF24L01P_DATARATE       NRF24L01P_DATARATE_1_MBPS
+#define DEFAULT_NRF24L01P_TX_PWR         NRF24L01P_TX_PWR_ZERO_DB
+#define DEFAULT_NRF24L01P_TRANSFER_SIZE  4
+
+/**
+ * nRF24L01+ Single Chip 2.4GHz Transceiver from Nordic Semiconductor.
+ */
+class nRF24L01P {
+
+public:
+
+    /**
+     * Constructor.
+     *
+     * @param mosi mbed pin to use for MOSI line of SPI interface.
+     * @param miso mbed pin to use for MISO line of SPI interface.
+     * @param sck mbed pin to use for SCK line of SPI interface.
+     * @param csn mbed pin to use for not chip select line of SPI interface.
+     * @param ce mbed pin to use for the chip enable line.
+     * @param irq mbed pin to use for the interrupt request line.
+     */
+    nRF24L01P(PinName mosi, PinName miso, PinName sck, PinName csn, PinName ce, PinName irq = NC);
+
+    /**
+     * Set the RF frequency.
+     *
+     * @param frequency the frequency of RF transmission in MHz (2400..2525).
+     */
+    void setRfFrequency(int frequency = DEFAULT_NRF24L01P_RF_FREQUENCY);
+
+    /**
+     * Get the RF frequency.
+     *
+     * @return the frequency of RF transmission in MHz (2400..2525).
+     */
+    int getRfFrequency(void);
+
+    /**
+     * Set the RF output power.
+     *
+     * @param power the RF output power in dBm (0, -6, -12 or -18).
+     */
+    void setRfOutputPower(int power = DEFAULT_NRF24L01P_TX_PWR);
+
+    /**
+     * Get the RF output power.
+     *
+     * @return the RF output power in dBm (0, -6, -12 or -18).
+     */
+    int getRfOutputPower(void);
+
+    /**
+     * Set the Air data rate.
+     *
+     * @param rate the air data rate in kbps (250, 1M or 2M).
+     */
+    void setAirDataRate(int rate = DEFAULT_NRF24L01P_DATARATE);
+
+    /**
+     * Get the Air data rate.
+     *
+     * @return the air data rate in kbps (250, 1M or 2M).
+     */
+    int getAirDataRate(void);
+
+    /**
+     * Set the CRC width.
+     *
+     * @param width the number of bits for the CRC (0, 8 or 16).
+     */
+    void setCrcWidth(int width = DEFAULT_NRF24L01P_CRC);
+
+    /**
+     * Get the CRC width.
+     *
+     * @return the number of bits for the CRC (0, 8 or 16).
+     */
+    int getCrcWidth(void);
+
+    /**
+     * Set the Receive address.
+     *
+     * @param address address associated with the particular pipe
+     * @param width width of the address in bytes (3..5)
+     * @param pipe pipe to associate the address with (0..5, default 0)
+     *
+     * Note that Pipes 0 & 1 have 3, 4 or 5 byte addresses,
+     *  while Pipes 2..5 only use the lowest byte (bits 7..0) of the
+     *  address provided here, and use 2, 3 or 4 bytes from Pipe 1's address.
+     *  The width parameter is ignored for Pipes 2..5.
+     */
+    void setRxAddress(unsigned long long address = DEFAULT_NRF24L01P_ADDRESS, int width = DEFAULT_NRF24L01P_ADDRESS_WIDTH, int pipe = NRF24L01P_PIPE_P0);
+
+    void setRxAddress(unsigned long msb_address, unsigned long lsb_address, int width, int pipe = NRF24L01P_PIPE_P0);
+
+    /**
+     * Set the Transmit address.
+     *
+     * @param address address for transmission
+     * @param width width of the address in bytes (3..5)
+     *
+     * Note that the address width is shared with the Receive pipes,
+     *  so a change to that address width affect transmissions.
+     */
+    void setTxAddress(unsigned long long address = DEFAULT_NRF24L01P_ADDRESS, int width = DEFAULT_NRF24L01P_ADDRESS_WIDTH);
+
+    void setTxAddress(unsigned long msb_address, unsigned long lsb_address, int width);
+
+    /**
+     * Get the Receive address.
+     *
+     * @param pipe pipe to get the address from (0..5, default 0)
+     * @return the address associated with the particular pipe
+     */
+    unsigned long long getRxAddress(int pipe = NRF24L01P_PIPE_P0);
+
+    /**
+     * Get the Transmit address.
+     *
+     * @return address address for transmission
+     */
+    unsigned long long getTxAddress(void);
+
+    /**
+     * Set the transfer size.
+     *
+     * @param size the size of the transfer, in bytes (1..32)
+     * @param pipe pipe for the transfer (0..5, default 0)
+     */
+    void setTransferSize(int size = DEFAULT_NRF24L01P_TRANSFER_SIZE, int pipe = NRF24L01P_PIPE_P0);
+
+    /**
+     * Get the transfer size.
+     *
+     * @return the size of the transfer, in bytes (1..32).
+     */
+    int getTransferSize(int pipe = NRF24L01P_PIPE_P0);
+
+
+    /**
+     * Get the RPD (Received Power Detector) state.
+     *
+     * @return true if the received power exceeded -64dBm
+     */
+    bool getRPD(void);
+
+    /**
+     * Put the nRF24L01+ into Receive mode
+     */
+    void setReceiveMode(void);
+
+    /**
+     * Put the nRF24L01+ into Transmit mode
+     */
+    void setTransmitMode(void);
+
+    /**
+     * Power up the nRF24L01+ into Standby mode
+     */
+    void powerUp(void);
+
+    /**
+     * Power down the nRF24L01+ into Power Down mode
+     */
+    void powerDown(void);
+
+    /**
+     * Enable the nRF24L01+ to Receive or Transmit (using the CE pin)
+     */
+    void enable(void);
+
+    /**
+     * Disable the nRF24L01+ to Receive or Transmit (using the CE pin)
+     */
+    void disable(void);
+
+    /**
+     * Transmit data
+     *
+     * @param pipe is ignored (included for consistency with file write routine)
+     * @param data pointer to an array of bytes to write
+     * @param count the number of bytes to send (1..32)
+     * @return the number of bytes actually written, or -1 for an error
+     */
+    int write(int pipe, char *data, int count);
+    
+    /**
+     * Receive data
+     *
+     * @param pipe the receive pipe to get data from
+     * @param data pointer to an array of bytes to store the received data
+     * @param count the number of bytes to receive (1..32)
+     * @return the number of bytes actually received, 0 if none are received, or -1 for an error
+     */
+    int read(int pipe, char *data, int count);
+
+    /**
+     * Determine if there is data available to read
+     *
+     * @param pipe the receive pipe to check for data
+     * @return true if the is data waiting in the given pipe
+     */
+    bool readable(int pipe = NRF24L01P_PIPE_P0);
+
+    /**
+     * Disable all receive pipes
+     *
+     * Note: receive pipes are enabled when their address is set.
+     */
+    void disableAllRxPipes(void);
+    
+    /**
+     * Disable AutoAcknowledge function
+     */
+    void disableAutoAcknowledge(void);
+    
+    /**
+     * Enable AutoAcknowledge function
+     *
+     * @param pipe the receive pipe
+     */
+    void enableAutoAcknowledge(int pipe = NRF24L01P_PIPE_P0);
+    
+    /**
+     * Disable AutoRetransmit function
+     */
+    void disableAutoRetransmit(void);
+    
+    /**
+     * Enable AutoRetransmit function
+     *
+     * @param delay the delay between restransmits, in uS (250uS..4000uS)
+     * @param count number of retransmits before generating an error (1..15)
+     */
+    void enableAutoRetransmit(int delay, int count);
+
+private:
+
+    /**
+     * Get the contents of an addressable register.
+     *
+     * @param regAddress address of the register
+     * @return the contents of the register
+     */
+    int getRegister(int regAddress);
+
+    /**
+     * Set the contents of an addressable register.
+     *
+     * @param regAddress address of the register
+     * @param regData data to write to the register
+     */
+    void setRegister(int regAddress, int regData);
+
+    /**
+     * Get the contents of the status register.
+     *
+     * @return the contents of the status register
+     */
+    int getStatusRegister(void);
+
+    SPI         spi_;
+    DigitalOut  nCS_;
+    DigitalOut  ce_;
+    InterruptIn nIRQ_;
+
+    int mode;
+
+};
+
+#endif /* __NRF24L01P_H__ */
diff -r 000000000000 -r 964eb6a2ef00 main.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,134 @@
+/* This is the current working code for the FYDP Autowalk
+-only IMU1 works. I don't know why IMU2 works. I'll fix that later
+*/
+
+#include "robot.h"
+#include "bt_shell.h"
+
+RtosTimer *MotorStopTimer;
+RtosTimer *HalfHourTimer;
+
+void HalfHourUpdate(void const *args)
+{
+        long_time += t.read_us();
+        t.reset();
+}
+
+/*
+RtosTimer *OpticalFlowTimer;
+
+void update_opt(void const *args)
+{
+    reckon.updateOpticalFlow();   
+}
+
+void RF_mesh_thread(void const *args)   //this thread handles the mesh network
+{
+    while(1){
+        Thread::wait(10);
+    }
+}
+
+*/
+
+void moveMotors(int Lspeed, int Rspeed, int ms)
+{   
+    *motors.Left = Lspeed;
+    *motors.Right = Rspeed;
+    
+    if(ms > 0)
+        MotorStopTimer->start(ms); 
+}
+
+void stopMotors(void const *args)
+{   
+    *motors.Left = 0;
+    *motors.Right = 0;    
+    send_flag = 0;
+}
+
+void CURRENT_thread(void const *args)
+{
+    float current;
+    while(1){
+        current = current_sensor.get_current();
+        bt.lock();
+        bt.printf("\n\rCurrent: %f mA",current);
+        bt.unlock();
+        Thread::wait(50);
+    }
+}
+
+void optflow_thread(void const *args)
+{    
+    while(true) {
+        reckon.updateOpticalFlow();                   
+        Thread::wait(3);
+    }    
+}
+
+void IMU_thread(void const *args)
+{
+     bt.baud(BT_BAUD_RATE);   //you have to do this for some reason
+    //test_dmp(); 
+    test_dmp2();
+    bt.baud(BT_BAUD_RATE);   //you have to do this for some reason
+    //start_dmp(mpu);
+    start_dmp2(mpu2);
+    //calibrate_1();
+
+    while(1) {
+        /*if(calibrate_flag)
+        {
+            calibrate_1();
+            calibrate_flag = 0;
+        }*/
+        
+        //if(!mpuInterrupt && fifoCount < packetSize);    //interrupt not ready
+        //else {  //mpu interrupt is ready
+        //    update_dmp();
+          update_dmp2();
+            //mpuInterrupt = false;   //this resets the interrupt flag
+            //mpuInterrupt2 = false;
+        //}
+        
+         Thread::yield();
+    }
+}
+
+void bt_shell(void const *args)
+{
+    bt_shell_init();
+    bt.printf("BT shell initialized\r\n");
+    
+    while(true) {
+        bt_shell_run();
+        Thread::yield();
+    }    
+}
+
+int main()
+{
+    initRobot();
+    
+    MotorStopTimer = new RtosTimer(&stopMotors, osTimerOnce, NULL);    
+    HalfHourTimer = new RtosTimer(&HalfHourUpdate, osTimerPeriodic, NULL);
+    
+    HalfHourTimer->start(1800000);  //doesn't work because the timer takes over (high priority)
+    
+    //OpticalFlowTimer = new RtosTimer(&update_opt, osTimerPeriodic, NULL);
+    //OpticalFlowTimer->start(10);  //doesn't work because the timer takes over (high priority)
+        
+
+    Thread bt_shell_th(bt_shell, NULL, osPriorityNormal, 2048, NULL);    //if you get a hard fault, increase memory size of this thread (second last value)
+    
+    Thread IMU_th(IMU_thread,NULL,osPriorityNormal, 2048,NULL);
+    
+//    Thread current_sense(CURRENT_thread,NULL,osPriorityNormal,300,NULL);  //this thread for monitoring current is unnecessary. Thread use lotsa rams. Kill it.
+    
+    //Thread optflow_th(optflow_thread, NULL, osPriorityNormal, 500, NULL); 
+    
+    //Thread RF_mesh_th(RF_mesh_thread,NULL,osPriorityNormal,500,NULL);
+    
+    Thread::wait(osWaitForever);
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/ChangeLog.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/ChangeLog.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,192 @@
+/* $Id:$
+1.32    12th October 2013
+    * Improved claim documentation: http://mbed.org/questions/1817/Redirect-stdout-via-MODSERIAL-is-this-po/ by http://mbed.org/users/WiredHome/
+
+1.31    11th October 2013
+    * Added claim function to redirect for example stdout
+
+1.30    1st September 2013
+    * Removed all DMA related code (not supported in this version currently)
+    * Minor bug fix
+
+1.29    12th July 2013
+    * Added KL25Z support + split code in device dependent and independent part
+
+1.26    10th June 2013
+    * _uidx reference in DMA code replaced by _serial.index
+
+1.25    8th January 2013
+    
+    * Bring back into line with MBed libraries.
+    * Credits: 
+        Erik Olieman : http://mbed.org/users/Sissors/code/MODSERIAL/rev/3ba4341d74d6
+        Erik Olieman : http://mbed.org/users/Sissors/code/MODSERIAL/rev/a469aa702bab
+    
+
+1.24    6th Dec 2012
+        
+    * Beta release for new Mbed library.
+
+1.23    25th July 2012
+
+    * LPC1768 code as was. This release includes "alpha" support for the LPC11U24
+
+1.22    19th April 2012
+
+    * http://mbed.org/forum/bugs-suggestions/topic/2936/
+    * Bug fix, protect important buffer pointers from IRQ corruption.
+    * Credits: 
+        Anthony Wieser  http://mbed.org/users/WieserSoftwareLtd/ for the fix.
+        BlazeX http://mbed.org/users/BlazeX/ for the alert that a fix was needed!
+
+1.21    10 May 2011
+    
+    * http://mbed.org/forum/mbed/topic/2264
+    
+1.20    26 April 2011
+
+    * Bug fix, not blocking on transmit
+      by Erik Petrich, http://mbed.org/forum/bugs-suggestions/topic/2200
+      
+1.19    20 April 2011
+
+    * Fixed some doxygen comment bugs.
+    
+1.18    20 April 2011
+
+    * All callbacks now use MODSERIAL_callback (rather than Mbed's FunctionPointer[1] type)
+      to store and invoke it's callbacks. This allows MODSERIAL to pass a parameter
+      to callbacks. The function prototype is now void func(MODSERIAL_IRQ_INFO *q).
+    * Callbacks now pass a pointer to a MODSERIAL_IRQ_INFO class type.
+      This class holds a pointer to the MODSERIAL object that invoked the callback
+      thus freeing callbacks need to use the global variable of the original 
+      MODSERIAL instance.
+    * MODSERIAL_IRQ_INFO also declares public functions that are protected within MODSERIAL
+      thus allowing certain functions to be restricted to callback context only.
+    * New function MODSERIAL_IRQ_INFO::rxDiscardLastChar() allows an rxCallback function
+      to remove the character that was just placed into the RX buffer.
+    
+    [1] http://mbed.org/users/AjK/libraries/FPointer/latest/docs/
+
+1.17   08/Mar/2011
+       Fixed a memory leak in the DMA code.
+       
+1.16 - 12 Feb 2011
+    
+    * Missed one, doh!
+
+1.15 - 12 Feb 2011
+    
+    * Fixed some typos.
+    
+1.14 - 7 Feb 2011
+
+    * Fixed a bug in __putc() that caused the output buffer pointer to 
+      become corrupted.
+
+1.13 - 20/01/2011
+
+    * Added extra documentation.
+    * Fixed some typos.
+    
+1.12 - 20/01/2011
+
+    * Added new "autoDetectChar()" function. To use:-
+      1st: Add a callback to invoke when the char is detected:-        
+        .attach(&detectedChar, MODSERIAL::RxAutoDetect);
+      2nd: Send the char to detect.
+        .autoDectectChar('\n');
+      Whenever that char goes into the RX buffer your callback will be invoked.
+      Added example2.cpp to demo a simple messaging system using this auto feature.
+
+
+1.11 - 23/11/2010
+
+    * Fixed a minor issue with 1.10 missed an alteration of name change.
+    
+1.10 - 23/11/2010
+
+    * Rename the DMA callback from attach_dma_complete() to attach_dmaSendComplete()
+    
+1.9 - 23/11/2010
+
+    * Added support for DMA sending of characters. Required is
+      the MODDMA library module:-
+      http://mbed.org/users/AjK/libraries/MODDMA/latest
+      See example_dma.cpp for more information.
+      
+1.8 - 22/11/2010
+
+    * Added code so that if a buffer is set to zero length then
+      MODSERIAL defaults to just using the FIFO for that stream
+      thus making the library "fall back" to teh same operation
+      that the Mbed Serial library performs.
+    * Removed dmaSend() function that should have been removed 
+      at 1.7
+    
+1.7 - 21/11/2010
+
+    * Remove the DMA enum from MODSERIAL.h as it's not currently 
+      ready for release.
+    * Added page doxygen comments.
+
+1.6 - 21/11/2010
+
+   * Version 1.5 solved a blocking problem on putc() when called 
+     from another ISR. However, isr_tx() invokes a callback of it's
+     own when a byte is tranferred from TX buffer to TX FIFO. User
+     programs may interpret that as an IRQ callback. That's an ISR
+     call from within an existing ISR which is not good. So the 
+     TxIrq callback from isr_tx is now conditional. It will only
+     be called when isr_tx() is actually within it's own ISR and
+     not when called from alternate ISR handlers.
+     
+1.5 - 21/11/2010
+
+    * Calling putc() (or any derived function that uses it like
+      printf()) while inside an interrupt service routine can
+      cause the system to lock up if the TX buffer is full. This
+      is because bytes are only transferred from the TX buffer to
+      the TX FIFO via the TX ISR. If we are, say in an RX ISR already,
+      then the TX ISR will never trigger. The TX buffer stays full and
+      there is never space to putc() the byte. So, while putc() blocks
+      waiting for space it calls isr_tx() to ensure if TX FIFO space
+      becomes available it will move bytes from the TX buffer to TX
+      FIFO thus removing the blocking condition within putc().
+
+1.4 - 21/11/2010
+
+    * Removed all the new DMA code. I wish mbed.org had proper SVN
+      versioning, I'm use to working in HEAD and BRANCHES after I've
+      released a project. Getting bug reports in current releases
+      while trying to dev new code is hard to manage without source
+      control of some type!
+
+1.3 - 21/11/2010
+
+    * Fixed a macro problem with txIsBusy()
+    * Started adding code to use "block data" sending using DMA
+    * Removed #include "IOMACROS.h"
+    
+1.2 - 21/11/2010
+
+    * Removed unsed variables from flushBuffer()
+    * Fixed a bug where both RX AND TX fifos are cleared/reset 
+      when just TX OR RX should be cleared.
+    * Fixed a bug that cleared IIR when in fact it should be left
+      alone so that any pending interrupt after flush is handled.
+    * Merged setBase() into init() as it wasn't required anywhere else.
+    * Changed init() to enforce _uidx is set by Serial to define the _base
+      address of the Uart in use.
+        
+1.1 - 20/11/2010
+
+    * Added this file
+    * Removed cruft from GETC.cpp
+    * "teh" should be "the", why do my fingers do that?
+
+1.0 - 20/11/2010
+
+    * First release.
+
+*/
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/AddingDevice.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/AddingDevice.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,34 @@
+/*
+
+To add another device some functions/macros need to be defined.
+The Device folder shows examples of other devices.
+
+1. In MACROS.h the include to the macro file need to be added.
+
+2. A <NameOfYourFile.h> file needs to be added, it needs to include the ifdef(target) statement, and definitions for:
+MODSERIAL_IRQ_REG    ---   register which enables/disables serial IRQs
+DISABLE_TX_IRQ       ---   macro that disables TX IRQs
+DISABLE_RX_IRQ       ---   macro that disables RX IRQs
+ENABLE_TX_IRQ        ---   macro that enables TX IRQs
+ENABLE_RX_IRQ        ---   macro that enables RX IRQs
+
+RESET_TX_FIFO        ---   macro that resets TX FIFO buffer, if applicable. If not, something like while(1==0) won't do anything and doesn't generate compiler warnings
+RESET_RX_FIFO        ---   macro that resets RX FIFO buffer, if no hardware options, you can also read data until no more data is available
+
+MODSERIAL_READ_REG   ---   register where RX data is in
+MODSERIAL_WRITE_REG  ---   register where TX data is in (can be same as previous)
+MODSERIAL_READABLE   ---   returns true if new data is available in read_reg
+MODSERIAL_WRITABLE   ---   returns true if we may write new data in write_reg
+
+RX_IRQ_ENABLED       ---   checks if RX IRQs are enabled by MODSERIAL. Only required if the device has no registers that tell which IRQ fired. If those registers are available (LPCs have then), may just be 'true'
+TX_IRQ_ENABLED       ---   checks if TX IRQs are enabled by MODSERIAL. See previous
+
+3. A <NameOfYourFile.cpp> file needs to be added, it needs to include the ifdef(target) statement, and functions for:
+void setBase(void)   ---   function that sets _base pointer to point to correct UART, and _IRQ pointer to point to correct IRQ.
+
+void initDevice(void)---   function that allows for setting registers after everything else is initialized, if required
+
+bool txIsBusy(void)  ---   function that returns true as long as long as device isn't done with transmitting
+
+*/
+ 
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_K64F.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_K64F.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,21 @@
+#ifdef TARGET_K64F
+#include "MODSERIAL.h"
+
+void MODSERIAL::setBase(void ) {
+switch( _serial.index ) {
+        case 0: _base = UART0; _IRQ = UART0_RX_TX_IRQn; break;
+        case 1: _base = UART1; _IRQ = UART1_RX_TX_IRQn; break;
+        case 2: _base = UART2; _IRQ = UART2_RX_TX_IRQn; break;
+        case 3: _base = UART3; _IRQ = UART3_RX_TX_IRQn; break;
+        case 4: _base = UART4; _IRQ = UART4_RX_TX_IRQn; break;
+        default: _base = NULL; _IRQ = (IRQn_Type)NULL; break;
+    }
+}
+
+void MODSERIAL::initDevice(void) {};
+
+bool MODSERIAL::txIsBusy( void ) 
+{ 
+    return ( ((UART_Type*)_base)->S1 & ( 1UL << 6 ) == 0 ) ? true : false; 
+} 
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_K64F.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_K64F.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,20 @@
+#if defined (TARGET_K64F)
+
+#define MODSERIAL_IRQ_REG ((UART_Type*)_base)->C2
+#define DISABLE_TX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << UART_C2_TIE_SHIFT)
+#define DISABLE_RX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << UART_C2_RIE_SHIFT)
+#define ENABLE_TX_IRQ MODSERIAL_IRQ_REG |= (1UL << UART_C2_TIE_SHIFT)
+#define ENABLE_RX_IRQ MODSERIAL_IRQ_REG |= (1UL << UART_C2_RIE_SHIFT)
+
+#define MODSERIAL_READ_REG ((UART_Type*)_base)->D
+#define MODSERIAL_WRITE_REG ((UART_Type*)_base)->D
+#define MODSERIAL_READABLE ((((UART_Type*)_base)->S1 & (1UL<<5)) != 0)
+#define MODSERIAL_WRITABLE ((((UART_Type*)_base)->S1 & (1UL<<7)) != 0)
+
+#define RESET_TX_FIFO while(0 == 1)
+#define RESET_RX_FIFO while(MODSERIAL_READABLE) char dummy = MODSERIAL_READ_REG
+
+#define RX_IRQ_ENABLED ((MODSERIAL_IRQ_REG & (1UL << UART_C2_RIE_SHIFT)) != 0 )
+#define TX_IRQ_ENABLED ((MODSERIAL_IRQ_REG & (1UL << UART_C2_TIE_SHIFT)) != 0 )
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_KL05Z.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_KL05Z.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,16 @@
+#ifdef TARGET_KL05Z
+#include "MODSERIAL.h"
+
+void MODSERIAL::setBase(void ) {
+    _base = UART0;
+    _IRQ  = UART0_IRQn;
+}
+
+void MODSERIAL::initDevice(void) {};
+
+bool MODSERIAL::txIsBusy( void ) 
+{ 
+    return ( ((UARTLP_Type*)_base)->S1 & ( 1UL << 6 ) == 0 ) ? true : false; 
+} 
+#endif
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_KL05Z.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_KL05Z.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,20 @@
+#if defined(TARGET_KL05Z)
+
+#define MODSERIAL_IRQ_REG ((UARTLP_Type*)_base)->C2
+#define DISABLE_TX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << UARTLP_C2_TIE_SHIFT)
+#define DISABLE_RX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << UARTLP_C2_RIE_SHIFT)
+#define ENABLE_TX_IRQ MODSERIAL_IRQ_REG |= (1UL << UARTLP_C2_TIE_SHIFT)
+#define ENABLE_RX_IRQ MODSERIAL_IRQ_REG |= (1UL << UARTLP_C2_RIE_SHIFT)
+
+#define MODSERIAL_READ_REG ((UARTLP_Type*)_base)->D
+#define MODSERIAL_WRITE_REG ((UARTLP_Type*)_base)->D
+#define MODSERIAL_READABLE ((((UARTLP_Type*)_base)->S1 & (1UL<<5)) != 0)
+#define MODSERIAL_WRITABLE ((((UARTLP_Type*)_base)->S1 & (1UL<<7)) != 0)
+
+#define RESET_TX_FIFO while(0 == 1)
+#define RESET_RX_FIFO while(MODSERIAL_READABLE) char dummy = MODSERIAL_READ_REG
+
+#define RX_IRQ_ENABLED ((MODSERIAL_IRQ_REG & (1UL << UARTLP_C2_RIE_SHIFT)) != 0 )
+#define TX_IRQ_ENABLED ((MODSERIAL_IRQ_REG & (1UL << UARTLP_C2_TIE_SHIFT)) != 0 )
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_KL25Z.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_KL25Z.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,20 @@
+#ifdef TARGET_KL25Z
+#include "MODSERIAL.h"
+
+void MODSERIAL::setBase(void ) {
+switch( _serial.index ) {
+        case 0: _base = UART0; _IRQ = UART0_IRQn; break;
+        case 1: _base = UART1; _IRQ = UART1_IRQn; break;
+        case 2: _base = UART2; _IRQ = UART2_IRQn; break;
+        default: _base = NULL; _IRQ = (IRQn_Type)NULL; break;
+    }
+}
+
+void MODSERIAL::initDevice(void) {};
+
+bool MODSERIAL::txIsBusy( void ) 
+{ 
+    return ( ((UART_Type*)_base)->S1 & ( 1UL << 6 ) == 0 ) ? true : false; 
+} 
+#endif
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_KL25Z.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_KL25Z.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,20 @@
+#if defined(TARGET_KL25Z)
+
+#define MODSERIAL_IRQ_REG ((UART_Type*)_base)->C2
+#define DISABLE_TX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << UART_C2_TIE_SHIFT)
+#define DISABLE_RX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << UART_C2_RIE_SHIFT)
+#define ENABLE_TX_IRQ MODSERIAL_IRQ_REG |= (1UL << UART_C2_TIE_SHIFT)
+#define ENABLE_RX_IRQ MODSERIAL_IRQ_REG |= (1UL << UART_C2_RIE_SHIFT)
+
+#define MODSERIAL_READ_REG ((UART_Type*)_base)->D
+#define MODSERIAL_WRITE_REG ((UART_Type*)_base)->D
+#define MODSERIAL_READABLE ((((UART_Type*)_base)->S1 & (1UL<<5)) != 0)
+#define MODSERIAL_WRITABLE ((((UART_Type*)_base)->S1 & (1UL<<7)) != 0)
+
+#define RESET_TX_FIFO while(0 == 1)
+#define RESET_RX_FIFO while(MODSERIAL_READABLE) char dummy = MODSERIAL_READ_REG
+
+#define RX_IRQ_ENABLED ((MODSERIAL_IRQ_REG & (1UL << UART_C2_RIE_SHIFT)) != 0 )
+#define TX_IRQ_ENABLED ((MODSERIAL_IRQ_REG & (1UL << UART_C2_TIE_SHIFT)) != 0 )
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_LPC11U24.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_LPC11U24.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,17 @@
+#ifdef TARGET_LPC11U24
+#include "MODSERIAL.h"
+
+void MODSERIAL::setBase(void ) {
+    _base = LPC_USART;
+    _IRQ = UART_IRQn;
+}
+
+void MODSERIAL::initDevice(void) {
+    ((LPC_USART_Type*)_base)->FCR = (1UL<<0) + (1UL<<1) + (1UL<<2);
+    }
+
+bool MODSERIAL::txIsBusy( void ) 
+{ 
+    return ( (((LPC_USART_Type*)_base)->LSR & ( 1UL << 6 )) == 0 ) ? true : false; 
+} 
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_LPC11U24.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_LPC11U24.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,20 @@
+#if defined(TARGET_LPC11U24)
+
+#define MODSERIAL_IRQ_REG ((LPC_USART_Type*)_base)->IER
+#define DISABLE_TX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << 1)
+#define DISABLE_RX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << 0)
+#define ENABLE_TX_IRQ MODSERIAL_IRQ_REG |= (1UL << 1)
+#define ENABLE_RX_IRQ MODSERIAL_IRQ_REG |= (1UL << 0)
+
+#define RESET_TX_FIFO ((LPC_USART_Type*)_base)->FCR |= (1UL<<2)
+#define RESET_RX_FIFO ((LPC_USART_Type*)_base)->FCR |= (1UL<<1)
+
+#define MODSERIAL_READ_REG ((LPC_USART_Type*)_base)->RBR
+#define MODSERIAL_WRITE_REG ((LPC_USART_Type*)_base)->THR
+#define MODSERIAL_READABLE ((((LPC_USART_Type*)_base)->LSR & (1UL<<0)) != 0)
+#define MODSERIAL_WRITABLE ((((LPC_USART_Type*)_base)->LSR & (1UL<<5)) != 0)
+
+#define RX_IRQ_ENABLED true
+#define TX_IRQ_ENABLED true
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_LPC1768.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_LPC1768.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,24 @@
+#ifdef TARGET_LPC1768
+#include "MODSERIAL.h"
+
+
+void MODSERIAL::setBase(void ) {
+switch( _serial.index ) {
+        case 0: _base = LPC_UART0; _IRQ = UART0_IRQn; break;
+        case 1: _base = LPC_UART1; _IRQ = UART1_IRQn; break;
+        case 2: _base = LPC_UART2; _IRQ = UART2_IRQn; break;
+        case 3: _base = LPC_UART3; _IRQ = UART3_IRQn; break;
+        default: _base = NULL; _IRQ = (IRQn_Type)NULL; break;
+    }
+}
+
+void MODSERIAL::initDevice(void) {
+    ((LPC_UART_TypeDef*)_base)->FCR = (1UL<<0) + (1UL<<1) + (1UL<<2);
+    }
+
+bool MODSERIAL::txIsBusy( void ) 
+{ 
+    return ( (((LPC_UART_TypeDef*)_base)->LSR & ( 1UL << 6 )) == 0 ) ? true : false; 
+} 
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/Device/MODSERIAL_LPC1768.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/Device/MODSERIAL_LPC1768.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,20 @@
+#if defined(TARGET_LPC1768)
+
+#define MODSERIAL_IRQ_REG ((LPC_UART_TypeDef*)_base)->IER
+#define DISABLE_TX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << 1)
+#define DISABLE_RX_IRQ MODSERIAL_IRQ_REG &= ~(1UL << 0)
+#define ENABLE_TX_IRQ MODSERIAL_IRQ_REG |= (1UL << 1)
+#define ENABLE_RX_IRQ MODSERIAL_IRQ_REG |= (1UL << 0)
+
+#define RESET_TX_FIFO ((LPC_UART_TypeDef*)_base)->FCR |= (1UL<<2)
+#define RESET_RX_FIFO ((LPC_UART_TypeDef*)_base)->FCR |= (1UL<<1)
+
+#define MODSERIAL_READ_REG ((LPC_UART_TypeDef*)_base)->RBR
+#define MODSERIAL_WRITE_REG ((LPC_UART_TypeDef*)_base)->THR
+#define MODSERIAL_READABLE ((((LPC_UART_TypeDef*)_base)->LSR & (1UL<<0)) != 0)
+#define MODSERIAL_WRITABLE ((((LPC_UART_TypeDef*)_base)->LSR & (1UL<<5)) != 0)
+
+#define RX_IRQ_ENABLED true
+#define TX_IRQ_ENABLED true
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/FLUSH.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/FLUSH.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,47 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+*/
+
+#include "MODSERIAL.h"
+#include "MACROS.h"
+
+namespace AjK {
+
+void
+MODSERIAL::flushBuffer(IrqType type)
+{
+    uint32_t irq_req = MODSERIAL_IRQ_REG;
+    switch(type) {
+        case TxIrq: DISABLE_TX_IRQ; break;
+        case RxIrq: DISABLE_RX_IRQ; break;
+    }
+    buffer_in[type]       = 0;
+    buffer_out[type]      = 0;
+    buffer_count[type]    = 0;
+    buffer_overflow[type] = 0;  
+    switch(type) {
+        case TxIrq: RESET_TX_FIFO; break;
+        case RxIrq: RESET_RX_FIFO; break;
+    }
+    MODSERIAL_IRQ_REG = irq_req;
+}
+
+}; // namespace AjK ends
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/GETC.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/GETC.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,65 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+*/
+
+#include "MODSERIAL.h"
+#include "MACROS.h"
+
+namespace AjK {
+
+int 
+MODSERIAL::__getc(bool block)
+{
+    // If no buffer is in use fall back to standard RX FIFO usage.
+    // Note, we must block in this case and ignore bool "block" 
+    // so as to maintain compat with Mbed Serial.
+    if (buffer_size[RxIrq] == 0 || buffer[RxIrq] == (char *)NULL) {
+        while(! MODSERIAL_READABLE ) ;
+        return (int)(MODSERIAL_READ_REG & 0xFF);
+    }
+
+    if (block) { while ( MODSERIAL_RX_BUFFER_EMPTY ) ; } // Blocks.
+    else if ( MODSERIAL_RX_BUFFER_EMPTY ) return -1;
+    
+    int c = buffer[RxIrq][buffer_out[RxIrq]];
+    buffer_out[RxIrq]++;
+    if (buffer_out[RxIrq] >= buffer_size[RxIrq]) {
+        buffer_out[RxIrq] = 0;
+    }
+    
+    // If we have made space in the RX Buffer then copy over
+    // any characters in the RX FIFO that my reside there.
+    // Temporarily disable the RX IRQ so that we do not re-enter 
+    // it under interrupts.
+    if ( ! MODSERIAL_RX_BUFFER_FULL ) {
+        uint32_t irq_reg = MODSERIAL_IRQ_REG;
+        DISABLE_RX_IRQ;
+        isr_rx();    
+        MODSERIAL_IRQ_REG = irq_reg;
+    }
+    
+    __disable_irq();
+    buffer_count[RxIrq]--;   
+    __enable_irq();
+    return c;
+}
+
+}; // namespace AjK ends
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/INIT.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/INIT.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,78 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+*/
+
+#include "MODSERIAL.h"
+#include "MACROS.h"
+
+    #define MODSERIAL_FCR  0x08
+    #define _FCR    *((char *)_base+MODSERIAL_FCR)
+    
+    #define MODSERIAL_FIFO_ENABLE   1
+#define MODSERIAL_FIFO_RX_RESET 2
+#define MODSERIAL_FIFO_TX_RESET 4
+
+
+namespace AjK {
+
+void
+MODSERIAL::init( int txSize, int rxSize, PinName rx )
+{
+    
+    NVIC_DisableIRQ(_IRQ);
+    setBase();
+
+    callbackInfo.setSerial(this);
+
+    
+    if ( _base != NULL ) {
+        buffer_size[RxIrq]     = rxSize;
+        buffer[RxIrq]          = rxSize > 0 ? (char *)malloc(buffer_size[RxIrq]) : (char *)NULL;
+        buffer_in[RxIrq]       = 0;
+        buffer_out[RxIrq]      = 0;
+        buffer_count[RxIrq]    = 0;
+        buffer_overflow[RxIrq] = 0;
+        Serial::attach( this, &MODSERIAL::isr_rx, Serial::RxIrq );        
+        
+        buffer_size[TxIrq]     = txSize;
+        buffer[TxIrq]          = txSize > 0 ? (char *)malloc(buffer_size[TxIrq]) : (char *)NULL;
+        buffer_in[TxIrq]       = 0;
+        buffer_out[TxIrq]      = 0;
+        buffer_count[TxIrq]    = 0;
+        buffer_overflow[TxIrq] = 0;
+        Serial::attach( this, &MODSERIAL::isr_tx, Serial::TxIrq );
+    }
+    else {
+        error("MODSERIAL must have a defined UART to function.");
+    }
+    
+
+    initDevice();
+
+    //_FCR = MODSERIAL_FIFO_ENABLE | MODSERIAL_FIFO_RX_RESET | MODSERIAL_FIFO_TX_RESET;
+    
+    auto_detect_char = 0;
+    
+    NVIC_EnableIRQ(_IRQ);
+}
+
+}; // namespace AjK ends
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/ISR_RX.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/ISR_RX.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,64 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+*/
+
+#include "MODSERIAL.h"
+#include "MACROS.h"
+
+namespace AjK {
+        
+void 
+MODSERIAL::isr_rx(void)
+{
+    if (RX_IRQ_ENABLED) {
+    DigitalOut led(LED2);
+    led = 1;
+    if (! _base || buffer_size[RxIrq] == 0 || buffer[RxIrq] == (char *)NULL) {
+        _isr[RxIrq].call(&this->callbackInfo); 
+        return;
+    } 
+    
+    while( MODSERIAL_READABLE ) {
+        rxc = (char)(MODSERIAL_READ_REG & 0xFF); 
+        if ( MODSERIAL_RX_BUFFER_FULL ) {
+            buffer_overflow[RxIrq] = rxc; // Oh dear, no room in buffer.
+            _isr[RxOvIrq].call(&this->callbackInfo);
+        }
+        else {
+            if (buffer[RxIrq] != (char *)NULL) {
+                buffer[RxIrq][buffer_in[RxIrq]] = rxc;
+                buffer_count[RxIrq]++; 
+                buffer_in[RxIrq]++;
+                if (buffer_in[RxIrq] >= buffer_size[RxIrq]) {
+                    buffer_in[RxIrq] = 0;
+                }
+            }  
+            _isr[RxIrq].call(&this->callbackInfo); 
+        }
+        if (auto_detect_char == rxc) {
+            _isr[RxAutoDetect].call(&this->callbackInfo);
+        }
+    }  
+    }  
+}
+
+}; // namespace AjK ends
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/ISR_TX.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/ISR_TX.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,55 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+
+    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.
+*/
+
+#include "MODSERIAL.h"
+#include "MACROS.h"
+
+namespace AjK
+{
+
+void MODSERIAL::isr_tx(bool doCallback)
+{ 
+    if (TX_IRQ_ENABLED || MODSERIAL_TX_BUFFER_FULL ) {
+        if (! _base || buffer_size[TxIrq] == 0 || buffer[TxIrq] == (char *)NULL) {
+            _isr[TxIrq].call(&this->callbackInfo);
+            return;
+        }
+
+        while (! MODSERIAL_TX_BUFFER_EMPTY && MODSERIAL_WRITABLE ) {
+            MODSERIAL_WRITE_REG = txc = (uint8_t)(buffer[TxIrq][buffer_out[TxIrq]]);
+            buffer_count[TxIrq]--;
+            buffer_out[TxIrq]++;
+            if (buffer_out[TxIrq] >= buffer_size[TxIrq]) {
+                buffer_out[TxIrq] = 0;
+            }
+            if (doCallback) _isr[TxIrq].call(&this->callbackInfo);
+        }
+
+        if ( MODSERIAL_TX_BUFFER_EMPTY ) {
+            DISABLE_TX_IRQ;
+            _isr[TxEmpty].call(&this->callbackInfo);
+        }
+}
+}
+}; // namespace AjK ends
+
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/MACROS.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/MACROS.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,37 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+*/
+
+#ifndef MODSERIAL_MACROS_H
+#define MODSERIAL_MACROS_H
+
+#include "MODSERIAL_LPC1768.h"
+#include "MODSERIAL_LPC11U24.h"
+#include "MODSERIAL_KL25Z.h"
+#include "MODSERIAL_KL05Z.h"
+#include "MODSERIAL_K64F.h"
+
+#define MODSERIAL_TX_BUFFER_EMPTY (buffer_count[TxIrq]==0)
+#define MODSERIAL_RX_BUFFER_EMPTY (buffer_count[RxIrq]==0)
+#define MODSERIAL_TX_BUFFER_FULL  (buffer_count[TxIrq]==buffer_size[TxIrq])
+#define MODSERIAL_RX_BUFFER_FULL  (buffer_count[RxIrq]==buffer_size[RxIrq])
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/MODSERIAL.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/MODSERIAL.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,119 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+    
+    @file          MODSERIAL.h 
+    @purpose       Extends Serial to provide fully buffered IO
+    @version       1.6
+    @date          Nov 2010
+    @author        Andy Kirkham    
+*/
+
+#include "MODSERIAL.h"
+#include "MACROS.h"
+
+namespace AjK {
+
+MODSERIAL::MODSERIAL( PinName tx, PinName rx, const char* name ) : Serial( tx, rx, name )
+{
+    init( MODSERIAL_DEFAULT_TX_BUFFER_SIZE, MODSERIAL_DEFAULT_RX_BUFFER_SIZE, rx );
+}
+
+MODSERIAL::MODSERIAL( PinName tx, PinName rx, int bufferSize, const char* name ) : Serial( tx, rx, name )
+{
+    init( bufferSize, bufferSize, rx );
+}
+
+MODSERIAL::MODSERIAL( PinName tx, PinName rx, int txSize, int rxSize, const char* name ) : Serial( tx, rx, name )
+{
+    init( txSize, rxSize, rx );
+}
+
+MODSERIAL::~MODSERIAL()
+{
+    NVIC_DisableIRQ(_IRQ);
+    if ( buffer[0] != NULL) free((char *)buffer[0] );
+    if ( buffer[1] != NULL) free((char *)buffer[1] );    
+}
+
+bool MODSERIAL::txBufferFull( void ) 
+{ 
+    return MODSERIAL_TX_BUFFER_FULL; 
+}
+
+bool MODSERIAL::rxBufferFull( void ) 
+{ 
+    return MODSERIAL_RX_BUFFER_FULL; 
+}
+
+bool MODSERIAL::txBufferEmpty( void ) 
+{ 
+    return MODSERIAL_TX_BUFFER_EMPTY; 
+}
+
+bool MODSERIAL::rxBufferEmpty( void ) 
+{ 
+    return MODSERIAL_RX_BUFFER_EMPTY; 
+}
+
+
+int MODSERIAL::rxDiscardLastChar( void )
+{
+    // This function can only be called indirectly from
+    // an rxCallback function. Therefore, we know we 
+    // just placed a char into the buffer.
+    char c = buffer[RxIrq][buffer_in[RxIrq]];
+    
+    if (buffer_count[RxIrq]) {        
+        buffer_count[RxIrq]--;
+        buffer_in[RxIrq]--;
+        if (buffer_in[RxIrq] < 0) {
+            buffer_in[RxIrq] = buffer_size[RxIrq] - 1;
+        }
+    }
+    
+    return (int)c;
+}
+
+
+bool MODSERIAL::claim (FILE *stream) {
+    if ( _name == NULL) {
+        error("claim requires a name to be given in the instantiator of the MODSERIAL instance!\r\n");
+    }
+    
+    //Add '/' before name:
+    char *path = new char[strlen(_name) + 2];
+    sprintf(path, "/%s", _name);
+    
+    if (freopen(path, "w", stream) == NULL) {
+        // Failed, should not happen
+        return false;
+    }
+    
+    delete(path);
+    
+    //No buffering
+    setvbuf(stdout, NULL, _IONBF, buffer_size[TxIrq]);
+    return true;
+} 
+
+
+
+}; // namespace AjK ends
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/MODSERIAL.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/MODSERIAL.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,1001 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+    
+    @file          MODSERIAL.h 
+    @purpose       Extends Serial to provide fully buffered IO
+    @version       see ChangeLog.c
+    @date          Nov 2010
+    @author        Andy Kirkham
+*/
+
+#ifndef MODSERIAL_H
+#define MODSERIAL_H
+
+/** @defgroup API The MODSERIAL API */
+/** @defgroup MISC Misc MODSERIAL functions */
+/** @defgroup INTERNALS MODSERIAL Internals */
+
+#ifndef MODSERIAL_DEFAULT_RX_BUFFER_SIZE
+#define MODSERIAL_DEFAULT_RX_BUFFER_SIZE    256
+#endif
+
+#ifndef MODSERIAL_DEFAULT_TX_BUFFER_SIZE
+#define MODSERIAL_DEFAULT_TX_BUFFER_SIZE    256
+#endif
+
+#include "mbed.h"
+#include "serial_api.h"
+
+namespace AjK {
+
+// Forward reference.
+class MODSERIAL;
+
+/**
+ * @author Andy Kirkham
+ * @see http://mbed.org/cookbook/MODSERIAL
+ * @see example3a.cpp
+ * @see example3b.cpp
+ * @see API 
+ *
+ * <b>MODSERIAL_IRQ_INFO</b> is a class used to pass information (and access to protected
+ * MODSERIAL functions) to IRQ callbacks. 
+ */
+class MODSERIAL_IRQ_INFO
+{
+public:
+    friend class MODSERIAL;
+    
+    MODSERIAL *serial;
+    
+    MODSERIAL_IRQ_INFO() { serial = 0; }
+    
+    /** rxDiscardLastChar()
+     *
+     * Remove the last char placed into the rx buffer.
+     * This is an operation that can only be performed
+     * by an rxCallback function. 
+     * @ingroup API
+     * @return The byte removed from the buffer.
+     */
+    int rxDiscardLastChar(void);
+
+protected:
+
+    /** setSerial()
+     *
+     * Used internally by MODSERIAL to set the "this" pointer
+     * of the MODSERIAL that created this object.
+     * @ingroup INTERNAL
+     * @param A pointer to a MODSERIAL object instance.
+     */
+    void setSerial(MODSERIAL *s) { serial = s; }    
+};
+
+// Forward reference dummy class.
+class MODSERIAL_callback_dummy;
+
+/**
+ * @author Andy Kirkham
+ * @see http://mbed.org/cookbook/MODSERIAL
+ * @see example3a.cpp
+ * @see example3b.cpp
+ * @see API 
+ *
+ * <b>MODSERIAL_callback</b> is a class used to hold application callbacks that
+ * MODSERIAL can invoke on certain events.
+ */
+class MODSERIAL_callback 
+{
+protected:
+
+    //! C callback function pointer.
+    void (*c_callback)(MODSERIAL_IRQ_INFO *); 
+    
+    //! C++ callback object/method pointer (the object part).
+    MODSERIAL_callback_dummy *obj_callback;
+    
+    //! C++ callback object/method pointer (the method part).
+    void (MODSERIAL_callback_dummy::*method_callback)(MODSERIAL_IRQ_INFO *);
+
+public:
+    
+    /** Constructor
+     */
+    MODSERIAL_callback() {
+        c_callback      = 0;
+        obj_callback    = 0;
+        method_callback = 0;
+    }
+    
+    /** attach - Overloaded attachment function.
+     *
+     * Attach a C type function pointer as the callback.
+     *
+     * Note, the callback function prototype must be:-
+     * @code
+     * void myCallbackFunction(MODSERIAL_IRQ_INFO *);
+     * @endcode
+     * @param A C function pointer to call.
+     */
+    void attach(void (*function)(MODSERIAL_IRQ_INFO *) = 0) { c_callback = function; }
+    
+    /** attach - Overloaded attachment function.
+     *
+     * Attach a C++ type object/method pointer as the callback.
+     *
+     * Note, the callback method prototype must be:-
+     * @code
+     *     public:
+     *         void myCallbackFunction(MODSERIAL_IRQ_INFO *);
+     * @endcode
+     * @param A C++ object pointer.
+     * @param A C++ method within the object to call.
+     */
+    template<class T> 
+    void attach(T* item, void (T::*method)(MODSERIAL_IRQ_INFO *)) { 
+        obj_callback    = (MODSERIAL_callback_dummy *)item; 
+        method_callback = (void (MODSERIAL_callback_dummy::*)(MODSERIAL_IRQ_INFO *))method; 
+    }
+
+    /** call - Overloaded callback initiator.
+     *
+     * call the callback function.
+     *
+     * @param A pointer to a MODSERIAL_IRQ_INFO object.
+     */
+    void call(MODSERIAL_IRQ_INFO *arg) {
+        if (c_callback != 0) {
+            (*c_callback)(arg);
+        }
+        else {
+            if (obj_callback  != 0 && method_callback != 0) {
+                (obj_callback->*method_callback)(arg);
+            }
+        }       
+    }    
+};
+
+/**
+ * @author Andy Kirkham
+ * @see http://mbed.org/cookbook/MODSERIAL
+ * @see http://mbed.org/handbook/Serial
+ * @see example1.cpp
+ * @see example2.cpp
+ * @see example3a.cpp
+ * @see example3b.cpp
+ * @see example_dma.cpp
+ * @see API 
+ *
+ * <b>MODSERIAL</b> extends the Mbed library <a href="/handbook/Serial">Serial</a> to provide fully buffered
+ * TX and RX streams. Buffer length is fully customisable. 
+ *
+ * Before using MODSERIAL users should be familar with Mbed's standard <a href="/handbook/Serial">Serial</a>
+ * library object. MODSERIAL is a direct "drop in" replacement for <a href="/handbook/Serial">Serial</a>. Where
+ * previously Serial was used, MODSERIAL can be used as adirect replacement instantly offering standard
+ * TX and RX buffering. By default, both TX and RX buffers are 256 bytes in length.
+ *
+ * @image html /media/uploads/mbedofficial/serial_interfaces.png
+ *
+ * Standard example:
+ * @code
+ * #include "mbed.h"
+ * #include "MODSERIAL.h"
+ *
+ * MODSERIAL pc(USBTX, USBRX); // tx, rx
+ *
+ * int main() {
+ *     pc.printf("Hello World!");
+ *     while(1) {
+ *         pc.putc(pc.getc() + 1);
+ *     }
+ * }
+ * @endcode
+ *
+ * Example with alternate buffer length:
+ * @code
+ * #include "mbed.h"
+ * #include "MODSERIAL.h"
+ *
+ * // Make TX and RX buffers 512byes in length
+ * MODSERIAL pc(USBTX, USBRX, 512); // tx, rx
+ *
+ * int main() {
+ *     pc.printf("Hello World!");
+ *     while(1) {
+ *         pc.putc(pc.getc() + 1);
+ *     }
+ * }
+ * @endcode
+ *
+ * Example with alternate buffer length:
+ * @code
+ * #include "mbed.h"
+ * #include "MODSERIAL.h"
+ *
+ * // Make TX 1024bytes and RX 512byes in length
+ * MODSERIAL pc(USBTX, USBRX, 1024, 512); // tx, rx
+ *
+ * int main() {
+ *     pc.printf("Hello World!");
+ *     while(1) {
+ *         pc.putc(pc.getc() + 1);
+ *     }
+ * }
+ * @endcode
+ */
+class MODSERIAL : public Serial 
+{
+public:
+
+    // Allow instances of MODSERIAL_IRQ_INFO to use protected properties and methods.
+    friend class MODSERIAL_IRQ_INFO;
+
+    //! A copy of the Serial parity enum
+    /** @see http://mbed.org/projects/libraries/api/mbed/trunk/Serial#Serial.format */
+    enum Parity {
+          None = 0
+        , Odd
+        , Even
+        , Forced1   
+        , Forced0
+    };
+    
+    //! A copy of the Serial IrqType enum
+    enum IrqType {
+          RxIrq = 0
+        , TxIrq
+        , RxOvIrq
+        , TxOvIrq
+        , TxEmpty
+        , RxAutoDetect
+        , NumOfIrqTypes
+    };
+    
+    //! Non-blocking functions return code.
+    enum Result {
+          Ok = 0                /*!< Ok. */
+        , NoMemory       = -1   /*!< Memory allocation failed. */
+        , NoChar         = -1   /*!< No character in buffer. */
+        , BufferOversize = -2   /*!< Oversized buffer. */
+    };
+    
+    /**
+     * The MODSERIAL constructor is used to initialise the serial object.
+     *
+     * @param tx PinName of the TX pin.
+     * @param rx PinName of the TX pin.
+     */    
+    MODSERIAL(PinName tx, PinName rx, const char* name = NULL);
+    
+    /**
+     * The MODSERIAL constructor is used to initialise the serial object.
+     *
+     * @param tx PinName of the TX pin.
+     * @param rx PinName of the TX pin.
+     * @param bufferSize Integer of the TX and RX buffer sizes.
+     */    
+    MODSERIAL(PinName tx, PinName rx, int bufferSize, const char* name = NULL);
+    
+    /**
+     * The MODSERIAL constructor is used to initialise the serial object.
+     *
+     * @param tx PinName of the TX pin.
+     * @param rx PinName of the TX pin.
+     * @param txBufferSize Integer of the TX buffer sizes.
+     * @param rxBufferSize Integer of the RX buffer sizes.
+     */    
+    MODSERIAL(PinName tx, PinName rx, int txBufferSize, int rxBufferSize, const char* name = NULL);
+    
+    virtual ~MODSERIAL();
+
+    /**
+     * Function: attach
+     *  
+     * The Mbed standard <a href="/handbook/Serial">Serial</a> library object allows an interrupt callback
+     * to be made when a byte is received by the TX or RX UART hardware. MODSERIAL traps these interrupts
+     * to enable it's buffering system. However, after the byte has been received/sent under interrupt control, 
+     * MODSERIAL can callback a user function as a notification of the interrupt. Note, user code should not
+     * directly interact with the Uart hardware, MODSERIAL does that, instead, MODSERIAL API functions should
+     * be used.
+     *
+     * <b>Note</b>, a character is written out then, if there is room in the TX FIFO and the TX buffer is empty,
+     * putc() will put the character directly into THR (the output holding register). If the TX FIFO is full and 
+     * cannot accept the character, it is placed into the TX output buffer. The TX interrupts are then enabled
+     * so that when the TX FIFO empties, the TX buffer is then transferred to the THR FIFO. The TxIrq will ONLY 
+     * be activated when this transfer of a character from BUFFER to THR FIFO takes place. If your character 
+     * throughput is not high bandwidth, then the 16 byte TX FIFO may be enough and the TX output buffer may 
+     * never come into play.
+     *
+     * @code
+     * #include "mbed.h"
+     * #include "MODSERIAL.h"
+     *
+     * DigitalOut led1(LED1);
+     * DigitalOut led2(LED2);
+     * DigitalOut led3(LED3);
+     *
+     * // To test, connect p9 to p10 as a loopback.
+     * MODSERIAL pc(p9, p10);
+     *
+     * // This function is called when a character goes into the TX buffer.
+     * void txCallback(void) {
+     *     led2 = !led2;
+     * }
+     *
+     * // This function is called when a character goes into the RX buffer.
+     * void rxCallback(void) {
+     *     led3 = !led3;
+     * }
+     *
+     * int main() {
+     *     pc.baud(115200);
+     *     pc.attach(&txCallback, MODSERIAL::TxIrq);
+     *     pc.attach(&rxCallback, MODSERIAL::RxIrq);
+     *
+     *     while(1) {
+     *         led1 = !led1;
+     *         wait(0.5);
+     *         pc.putc('A');
+     *         wait(0.5);
+     *     }
+     * ]
+     * @endcode
+     *
+     * @ingroup API
+     * @param fptr A pointer to a void function, or 0 to set as none
+     * @param type Which serial interrupt to attach the member function to (Seriall::RxIrq for receive, TxIrq for transmit buffer empty)
+     */  
+    void attach(void (*fptr)(MODSERIAL_IRQ_INFO *), IrqType type = RxIrq) { _isr[type].attach(fptr); }
+    
+    /**
+     * Function: attach
+     *  
+     * The Mbed standard <a href="/handbook/Serial">Serial</a> library object allows an interrupt callback
+     * to be made when a byte is received by the TX or RX UART hardware. MODSERIAL traps these interrupts
+     * to enable it's buffering system. However, after the byte has been received/sent under interrupt control, 
+     * MODSERIAL can callback a user function as a notification of the interrupt. Note, user code should not
+     * directly interact with the Uart hardware, MODSERIAL does that, instead, MODSERIAL API functions should
+     * be used.
+     *
+     * <b>Note</b>, a character is written out then, if there is room in the TX FIFO and the TX buffer is empty,
+     * putc() will put the character directly into THR (the output holding register). If the TX FIFO is full and 
+     * cannot accept the character, it is placed into the TX output buffer. The TX interrupts are then enabled
+     * so that when the TX FIFO empties, the TX buffer is then transferred to the THR FIFO. The TxIrq will ONLY 
+     * be activated when this transfer of a character from BUFFER to THR FIFO takes place. If your character 
+     * throughput is not high bandwidth, then the 16 byte TX FIFO may be enough and the TX output buffer may 
+     * never come into play.
+     *
+     * @code
+     * #include "mbed.h"
+     * #include "MODSERIAL.h"
+     *
+     * DigitalOut led1(LED1);
+     * DigitalOut led2(LED2);
+     * DigitalOut led3(LED3);
+     *
+     * // To test, connect p9 to p10 as a loopback.
+     * MODSERIAL pc(p9, p10);
+     *
+     * class Foo {
+     * public:
+     *     // This method is called when a character goes into the TX buffer.
+     *     void txCallback(void) { led2 = !led2; }
+     *
+     *     // This method is called when a character goes into the RX buffer.
+     *     void rxCallback(void) { led3 = !led3; }
+     * };
+     *
+     * Foo foo;
+     *
+     * int main() {
+     *     pc.baud(115200);
+     *     pc.attach(&foo, &Foo::txCallback, MODSERIAL::TxIrq);
+     *     pc.attach(&foo, &Foo::rxCallback, MODSERIAL::RxIrq);
+     *
+     *     while(1) {
+     *         led1 = !led1;
+     *         wait(0.5);
+     *         pc.putc('A');
+     *         wait(0.5);
+     *     }
+     * ]
+     * @endcode
+     *     
+     * @ingroup API
+     * @param  tptr A pointer to the object to call the member function on
+     * @param  mptr A pointer to the member function to be called
+     * @param  type Which serial interrupt to attach the member function to (Seriall::RxIrq for receive, TxIrq for transmit buffer empty)
+     */
+    template<typename T>
+    void attach(T* tptr, void (T::*mptr)(MODSERIAL_IRQ_INFO *), IrqType type = RxIrq) {
+        if((mptr != 0) && (tptr != 0)) {
+            _isr[type].attach(tptr, mptr);            
+        }
+    }
+
+    /**
+     * @see attach
+     * @ingroup API
+     */
+    void connect(void (*fptr)(MODSERIAL_IRQ_INFO *), IrqType type = RxIrq) { _isr[RxIrq].attach(fptr); }
+    
+    /**
+     * @see attach
+     * @ingroup API
+     */
+    template<typename T>
+    void connect(T* tptr, void (T::*mptr)(MODSERIAL_IRQ_INFO *), IrqType type = RxIrq) {
+        if((mptr != 0) && (tptr != 0)) {
+            _isr[type].attach(tptr, mptr);            
+        }
+    }
+    
+    /**
+     * Function: writeable
+     *  
+     * Determine if there is space available to write a byte
+     *
+     * @ingroup API
+     * @return 1 if there is space to write a character, else 0
+     */
+    int writeable() { return txBufferFull() ? 0 : 1; }
+    
+    /**
+     * Function: readable
+     *  
+     * Determine if there is a byte available to read
+     *
+     * @ingroup API
+     * @return 1 if there is a character available to read, else 0
+     */
+    int readable() { return rxBufferEmpty() ? 0 : 1; } 
+    
+    /**
+     * Function: txBufferSane
+     *  
+     * Determine if the TX buffer has been initialized.
+     *
+     * @ingroup API
+     * @return true if the buffer is initialized, else false
+     */
+    bool txBufferSane(void) { return buffer[TxIrq] != (char *)NULL ? true : false; }
+    
+    /**
+     * Function: rxBufferSane
+     *  
+     * Determine if the RX buffer has been initialized.
+     *
+     * @ingroup API
+     * @return true if the buffer is initialized, else false
+     */
+    bool rxBufferSane(void) { return buffer[TxIrq] != (char *)NULL ? true : false; }
+    
+    /**
+     * Function: txBufferGetCount
+     *  
+     * Returns how many bytes are in the TX buffer
+     *
+     * @ingroup API
+     * @return The number of bytes in the TX buffer
+     */
+    int txBufferGetCount(void)    { return buffer_count[TxIrq]; }
+    
+    /**
+     * Function: rxBufferGetCount
+     *  
+     * Returns how many bytes are in the RX buffer
+     *
+     * @ingroup API
+     * @return The number of bytes in the RX buffer
+     */
+    int rxBufferGetCount(void)    { return buffer_count[RxIrq]; }
+    
+    /**
+     * Function: txBufferGetSize
+     *  
+     * Returns the current size of the TX buffer
+     *
+     * @ingroup API
+     * @return The length iof the TX buffer in bytes
+     */
+    int txBufferGetSize(int size) { return buffer_size[TxIrq]; } 
+    
+    /**
+     * Function: rxBufferGetSize
+     *  
+     * Returns the current size of the RX buffer
+     *
+     * @ingroup API
+     * @return The length iof the RX buffer in bytes
+     */
+    int rxBufferGetSize(int size) { return buffer_size[RxIrq]; } 
+    
+    /**
+     * Function: txBufferFull
+     *  
+     * Is the TX buffer full?
+     *
+     * @ingroup API
+     * @return true if the TX buffer is full, otherwise false
+     */
+    bool txBufferFull(void);
+    
+    /**
+     * Function: rxBufferFull
+     *  
+     * Is the RX buffer full?
+     *
+     * @ingroup API
+     * @return true if the RX buffer is full, otherwise false
+     */
+    bool rxBufferFull(void);
+    
+    /**
+     * Function: txBufferEmpty
+     *  
+     * Is the TX buffer empty?
+     *
+     * @ingroup API
+     * @return true if the TX buffer is empty, otherwise false
+     */
+    bool txBufferEmpty(void);
+    
+    /**
+     * Function: rxBufferEmpty
+     *  
+     * Is the RX buffer empty?
+     *
+     * @ingroup API
+     * @return true if the RX buffer is empty, otherwise false
+     */
+    bool rxBufferEmpty(void);
+    
+    /**
+     * Function: txBufferSetSize
+     *  
+     * Change the TX buffer size.
+     *
+     * @see Result
+     * @ingroup API
+     * @param size The new TX buffer size in bytes.
+     * @param m Perform a memory sanity check. Errs the Mbed if memory alloc fails.
+     * @return Result Ok on success.
+     */
+    int txBufferSetSize(int size, bool m) { return resizeBuffer(size, TxIrq, m); } 
+    
+    /**
+     * Function: rxBufferSetSize
+     *  
+     * Change the RX buffer size.
+     *
+     * @see Result
+     * @ingroup API
+     * @param size The new RX buffer size in bytes.
+     * @param m Perform a memory sanity check. Errs the Mbed if memory alloc fails.
+     * @return Result Ok on success.
+     */
+    int rxBufferSetSize(int size, bool m) { return resizeBuffer(size, RxIrq, m); } 
+    
+    /**
+     * Function: txBufferSetSize
+     *  
+     * Change the TX buffer size.
+     * Always performs a memory sanity check, halting the Mbed on failure.
+     *
+     * @see Result
+     * @ingroup API
+     * @param size The new TX buffer size in bytes.
+     * @return Result Ok on success.
+     */
+    int txBufferSetSize(int size) { return resizeBuffer(size, TxIrq, true); } 
+    
+    /**
+     * Function: rxBufferSetSize
+     *  
+     * Change the RX buffer size.
+     * Always performs a memory sanity check, halting the Mbed on failure.
+     *
+     * @see Result
+     * @ingroup API
+     * @param size The new RX buffer size in bytes.
+     * @return Result Ok on success.
+     */
+    int rxBufferSetSize(int size) { return resizeBuffer(size, RxIrq, true); } 
+    
+    /**
+     * Function: txBufferFlush
+     *  
+     * Remove all bytes from the TX buffer.
+     * @ingroup API
+     */
+    void txBufferFlush(void) { flushBuffer(TxIrq); }
+    
+    /**
+     * Function: rxBufferFlush
+     *  
+     * Remove all bytes from the RX buffer.
+     * @ingroup API
+     */
+    void rxBufferFlush(void) { flushBuffer(RxIrq); }
+        
+    /**
+     * Function: getcNb
+     *
+     * Like getc() but is non-blocking. If no bytes are in the RX buffer this
+     * function returns Result::NoChar (-1)
+     *
+     * @ingroup API
+     * @return A byte from the RX buffer or Result::NoChar (-1) if bufer empty.
+     */
+    int getcNb() { return __getc(false); }
+    
+    /**
+     * Function: getc
+     *
+     * Overloaded version of Serial::getc()
+     * 
+     * This function blocks (if the RX buffer is empty the function will wait for a
+     * character to arrive and then return that character).
+     *
+     * @ingroup API
+     * @return A byte from the RX buffer
+     */
+    int getc()   { return __getc(true);  }
+    
+    /**
+     * Function: txGetLastChar
+     *
+     * Rteurn the last byte to pass through the TX interrupt handler.
+     *
+     * @ingroup MISC
+     * @return The byte
+     */
+    char txGetLastChar(void) { return txc; }
+    
+    /**
+     * Function: rxGetLastChar
+     *
+     * Return the last byte to pass through the RX interrupt handler.
+     *
+     * @ingroup MISC
+     * @return The byte
+     */
+    char rxGetLastChar(void) { return rxc; }
+    
+
+    
+    /**
+     * Function: autoDetectChar
+     *
+     * Set the char that, if seen incoming, invokes the AutoDetectChar callback.
+     *
+     * @ingroup API
+     * @param int c The character to detect.
+     */
+    void autoDetectChar(char c) { auto_detect_char = c; }
+    
+    /**
+     * Function: move
+     *
+     * Move contents of RX buffer to external buffer. Stops if "end" detected.
+     *
+     * @ingroup API
+     * @param char *s The destination buffer address
+     * @param int max The maximum number of chars to move.
+     * @param char end If this char is detected stop moving.
+     */
+    int move(char *s, int max, char end) {
+        int counter = 0;
+        char c;
+        while(readable()) {
+            c = getc();
+            if (c == end) break;
+            *(s++) = c;
+            counter++;
+            if (counter == max) break;
+        }
+        return counter;
+    }
+    
+    /**
+     * Function: move (overloaded)
+     *
+     * Move contents of RX buffer to external buffer. Stops if auto_detect_char detected.
+     *
+     * @ingroup API
+     * @param int max The maximum number of chars to move.
+     * @param char *s The destination buffer address
+     */
+    int move(char *s, int max) {
+        return move(s, max, auto_detect_char);
+    }
+    
+    /**
+    * Function: claim
+    *
+    * Redirect a stream to this MODSERIAL object
+    *
+    * Important: A name parameter must have been added when creating the MODSERIAL object:
+    *
+    * @code
+    * #include "MODSERIAL.h"
+    * ...
+    * MODSERIAL pc(USBTX, USBRX, "modser");
+    * 
+    * int main() {
+    *   pc.claim()            // capture <stdout>
+    *   pc.printf("Uses the MODSERIAL library\r\n");
+    *   printf("So does this!\r\n");
+    * }
+    * @endcode
+    *
+    * @ingroup API
+    * @param FILE *stream The stream to redirect (default = stdout)
+    * @return true if succeeded, else false
+    */    
+    bool claim(FILE *stream = stdout);
+    
+    #if 0 // Inhereted from Serial/Stream, for documentation only
+    /**
+     * Function: putc
+     * 
+     * Write a character
+     * Inhereted from Serial/Stream
+     *
+     * @see http://mbed.org/projects/libraries/api/mbed/trunk/Serial#Serial.putc
+     * @ingroup API
+     * @param c The character to write to the serial port
+     */
+    int putc(int c);
+    #endif
+    
+    #if 0 // Inhereted from Serial/Stream, for documentation only
+    /**
+     * Function: printf
+     *  
+     * Write a formated string
+     * Inhereted from Serial/Stream
+     *
+     * @see http://mbed.org/projects/libraries/api/mbed/trunk/Serial#Serial.printf
+     * @ingroup API
+     * @param format A printf-style format string, followed by the variables to use in formating the string.
+     */
+    int printf(const char* format, ...);
+    #endif
+    
+    #if 0 // Inhereted from Serial/Stream, for documentation only
+    /**
+     * Function: scanf
+     *  
+     * Read a formated string
+     * Inhereted from Serial/Stream
+     *
+     * @see http://mbed.org/projects/libraries/api/mbed/trunk/Serial#Serial.scanf
+     * @ingroup API
+     * @param format - A scanf-style format string, followed by the pointers to variables to store the results.
+     */
+    int scanf(const char* format, ...);
+    #endif
+
+protected:    
+    /**
+     * Used to pass information to callbacks.
+     * @ingroup INTERNALS
+     */
+    MODSERIAL_IRQ_INFO callbackInfo;
+
+    /**
+     * Remove the last char placed into the rx buffer.
+     * This is an operation that can only be performed
+     * by an rxCallback function. To protect the buffers
+     * this function is defined protected so that a 
+     * regular application cannot call it directly. It 
+     * can only be called by the public version within a
+     * MODSERIAL_IRQ_INFO class.
+     * @ingroup INTERNALS
+     * @return The byte removed from the buffer.
+     */
+    int rxDiscardLastChar(void);    
+            
+private:
+
+    /**
+     * A pointer to the UART peripheral base address being used.
+     * @ingroup INTERNALS
+     */
+    void *_base;
+    
+    /**
+     * The last byte to pass through the TX IRQ handler.
+     * @ingroup INTERNALS
+     */
+    volatile char txc;
+    
+    /**
+     * The last byte to pass through the RX IRQ handler.
+     * @ingroup INTERNALS
+     */
+    volatile char rxc;
+    
+    /**
+     * Pointers to the TX and RX buffers.
+     * @ingroup INTERNALS
+     */
+    volatile char *buffer[2];
+    
+    /**
+     * Buffer in pointers.
+     * @ingroup INTERNALS
+     */
+    volatile int   buffer_in[2];
+    
+    /**
+     * Buffer out pointers.
+     * @ingroup INTERNALS
+     */
+    volatile int   buffer_out[2];
+    
+    /**
+     * Buffer lengths.
+     * @ingroup INTERNALS
+     */
+    volatile int   buffer_size[2];
+    
+    /**
+     * Buffer content counters.
+     * @ingroup INTERNALS
+     */
+    volatile int   buffer_count[2];
+    
+    /**
+     * Buffer overflow.
+     * @ingroup INTERNALS
+     */
+    volatile int   buffer_overflow[2];
+    
+    /**
+     * Auto-detect character.
+     * @ingroup INTERNALS
+     */
+    volatile char auto_detect_char;
+    
+    /**
+     * Callback system.
+     * @ingroup INTERNALS
+     */
+    MODSERIAL_callback _isr[NumOfIrqTypes];
+    
+    /**
+     * TX Interrupt Service Routine.
+     * @ingroup INTERNALS
+     */
+    void isr_tx(bool doCallback);
+    
+    /**
+     * TX Interrupt Service Routine stub version.
+     * @ingroup INTERNALS
+     */ 
+    void isr_tx(void) { isr_tx(true); }
+    
+    
+    /**
+     * RX Interrupt Service Routine.
+     * @ingroup INTERNALS
+     */
+    void isr_rx(void);
+    
+        /**
+     * Get a character from the RX buffer
+     * @ingroup INTERNALS
+     * @param bool True to block (wait for input)
+     * @return A byte from the buffer.
+     */
+    int __getc(bool);
+    
+    /**
+     * Put a character from the TX buffer
+     * @ingroup INTERNALS
+     * @param bool True to block (wait for space in the TX buffer if full)
+     * @return 0 on success
+     */
+    int __putc(int c, bool);
+    
+    /**
+     * Function: _putc 
+     * Overloaded virtual function.
+     */
+    virtual int _putc(int c) { return __putc(c, true); }
+    
+    /**
+     * Function: _getc 
+     * Overloaded virtual function.
+     */
+    virtual int _getc()      { return __getc(true); }
+        
+    /** 
+     * Function: init
+     * Initialize the MODSERIAL object
+     * @ingroup INTERNALS
+     */
+    void init(int txSize, int rxSize, PinName rx);
+    
+    /** 
+     * Function: flushBuffer
+     * @ingroup INTERNALS
+     */
+    void flushBuffer(IrqType type);
+
+    /** 
+     * Function: resizeBuffer
+     * @ingroup INTERNALS
+     */
+    int resizeBuffer(int size, IrqType type = RxIrq, bool memory_check = true);   
+    
+    /** 
+     * Function: downSizeBuffer
+     * @ingroup INTERNALS
+     */
+    int downSizeBuffer(int size, IrqType type, bool memory_check); 
+    
+    /** 
+     * Function: upSizeBuffer
+     * @ingroup INTERNALS
+     */
+    int upSizeBuffer(int size, IrqType type, bool memory_check); 
+
+    
+
+
+//DEVICE SPECIFIC FUNCTIONS:
+    private:
+    /**
+    * Set pointers to UART and IRQ
+    */
+    void setBase( void );
+    
+    /**
+    * If required, allows for adding specific settings
+    */
+    void initDevice( void );
+    
+    IRQn_Type _IRQ;
+    
+    public:
+     /**
+     * Function: txIsBusy
+     *
+     * If the Uart is still actively sending characters this
+     * function will return true.
+     *
+     * @ingroup API
+     * @return bool
+     */
+    bool txIsBusy(void);
+    
+
+};
+
+}; // namespace AjK ends
+
+using namespace AjK;
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/MODSERIAL_IRQ_INFO.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/MODSERIAL_IRQ_INFO.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,38 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+    
+    @file          MODSERIAL_IRQ_INFO.cpp 
+    @author        Andy Kirkham    
+*/
+
+#include "MODSERIAL.h"
+
+namespace AjK {
+
+int 
+MODSERIAL_IRQ_INFO::rxDiscardLastChar(void) 
+{ 
+    if (!serial) return -1;
+    
+    return serial->rxDiscardLastChar(); 
+}
+
+}; // namespace AjK ends
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/PUTC.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/PUTC.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,81 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+*/
+
+#include "MODSERIAL.h"
+#include "MACROS.h"
+
+namespace AjK {
+
+int
+MODSERIAL::__putc(int c, bool block) {
+    
+    // If no buffer is in use fall back to standard TX FIFO usage.
+    // Note, we must block in this case and ignore bool "block" 
+    // so as to maintain compat with Mbed Serial.
+    if (buffer[TxIrq] == (char *)NULL || buffer_size[TxIrq] == 0) {
+        while (! MODSERIAL_WRITABLE) ; // Wait for space in the TX FIFO.
+        MODSERIAL_WRITE_REG = (uint32_t)c;
+        return 0;
+    }
+        
+    if ( MODSERIAL_WRITABLE && MODSERIAL_TX_BUFFER_EMPTY ) {
+        MODSERIAL_WRITE_REG = (uint32_t)c;
+    }
+    else {
+        if (block) {
+            uint32_t irq_reg = MODSERIAL_IRQ_REG; DISABLE_TX_IRQ;
+            while ( MODSERIAL_TX_BUFFER_FULL ) {  // Blocks!
+                // If putc() is called from an ISR then we are stuffed
+                // because in an ISR no bytes from the TX buffer will 
+                // get transferred to teh TX FIFOs while we block here.
+                // So, to work around this, instead of sitting in a 
+                // loop waiting for space in the TX buffer (which will
+                // never happen in IRQ context), check to see if the
+                // TX FIFO has space available to move bytes from the
+                // TX buffer to TX FIFO to make space. The easiest way
+                // to do this is to poll the isr_tx() function while we
+                // are blocking.
+                isr_tx(false);
+            }
+            MODSERIAL_IRQ_REG = irq_reg;
+        }
+        else if( MODSERIAL_TX_BUFFER_FULL ) {
+            buffer_overflow[TxIrq] = c; // Oh dear, no room in buffer.
+            _isr[TxOvIrq].call(&this->callbackInfo);
+            return -1;
+        }
+        DISABLE_TX_IRQ;
+        buffer[TxIrq][buffer_in[TxIrq]] = c;
+        __disable_irq();
+        buffer_count[TxIrq]++;
+        __enable_irq();
+        buffer_in[TxIrq]++;
+        if (buffer_in[TxIrq] >= buffer_size[TxIrq]) {
+            buffer_in[TxIrq] = 0;
+        }            
+        ENABLE_TX_IRQ;        
+    }
+      
+    return 0;
+}
+
+}; // namespace AjK ends
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/RESIZE.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/RESIZE.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,123 @@
+/*
+    Copyright (c) 2010 Andy Kirkham
+ 
+    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.
+*/
+
+#include "MODSERIAL.h"
+#include "MACROS.h"
+
+namespace AjK {
+
+int
+MODSERIAL::resizeBuffer(int size, IrqType type, bool memory_check)
+{
+    int rval = Ok;
+    
+    // If the requested size is the same as the current size there's nothing to do,
+    // just continue to use the same buffer as it's fine as it is.
+    if (buffer_size[type] == size) return rval;
+    
+    // Make sure the ISR cannot use the buffers while we are manipulating them.
+    NVIC_DisableIRQ(_IRQ);
+    
+    // If the requested buffer size is larger than the current size, 
+    // attempt to create a new buffer and use it.
+    if (buffer_size[type] < size) {
+        rval = upSizeBuffer(size, type, memory_check);
+    }
+    else if (buffer_size[type] > size) {
+        rval = downSizeBuffer(size, type, memory_check);
+    }
+    
+    // Start the ISR system again with the new buffers.
+    NVIC_EnableIRQ(_IRQ);
+    
+    return rval;
+}
+
+int 
+MODSERIAL::downSizeBuffer(int size, IrqType type, bool memory_check)
+{
+    if (size >= buffer_count[type]) {
+        return BufferOversize;
+    }
+    
+    char *s = (char *)malloc(size);
+    
+    if (s == (char *)NULL) {
+        if (memory_check) {
+            error("Failed to allocate memory for %s buffer", type == TxIrq ? "TX" : "RX");
+        }
+        return NoMemory;
+    }
+    
+    int c, new_in = 0;
+    
+    do {
+        c = __getc(false);
+        if (c != -1) s[new_in++] = (char)c;
+        if (new_in >= size) new_in = 0;
+    }
+    while (c != -1);
+    
+    free((char *)buffer[type]);
+    buffer[type]      = s;
+    buffer_in[type]   = new_in;
+    buffer_out[type]  = 0;
+    return Ok;        
+}
+
+int 
+MODSERIAL::upSizeBuffer(int size, IrqType type, bool memory_check)
+{
+    char *s = (char *)malloc(size);
+    
+    if (s == (char *)NULL) {
+        if (memory_check) {
+            error("Failed to allocate memory for %s buffer", type == TxIrq ? "TX" : "RX");
+        }
+        return NoMemory;
+    }
+    
+    if (buffer_count[type] == 0) { // Current buffer empty?
+        free((char *)buffer[type]);
+        buffer[type]      = s;
+        buffer_in[type]   = 0;
+        buffer_out[type]  = 0;
+    }        
+    else { // Copy the current contents into the new buffer.
+        int c, new_in = 0;
+        do {
+            c = __getc(false);
+            if (c != -1) s[new_in++] = (char)c;
+            if (new_in >= size) new_in = 0; // Shouldn't happen, but be sure.
+        }
+        while (c != -1);
+        free((char *)buffer[type]);
+        buffer[type]      = s;
+        buffer_in[type]   = new_in;
+        buffer_out[type]  = 0;
+    }
+    
+    buffer_size[type] = size;
+    return Ok;
+}
+
+}; // namespace AjK ends
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/example1.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/example1.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,120 @@
+#ifdef COMPILE_EXAMPLE1_CODE_MODSERIAL
+
+/*
+ * To run this test program, link p9 to p10 so the Serial loops
+ * back and receives characters it sends.
+ */
+ 
+#include "mbed.h"
+#include "MODSERIAL.h"
+
+DigitalOut led1(LED1);
+DigitalOut led2(LED2);
+DigitalOut led3(LED3);
+DigitalOut led4(LED4);
+
+MODSERIAL pc(USBTX, USBRX);
+
+/*
+ * As experiement, you can define MODSERIAL as show here and see what
+ * effects it has on the LEDs.
+ *
+ * MODSERIAL uart(TX_PIN, RX_PIN, 512);
+ *   With this, the 512 characters sent can straight into the buffer
+ *   vary quickly. This means LED1 is only on briefly as the TX buffer
+ *   fills.
+ *
+ * MODSERIAL uart(TX_PIN, RX_PIN, 32);
+ *   With this, the buffer is smaller than the default 256 bytes and
+ *   therefore LED1 stays on much longer while the system waits for
+ *   room in the TX buffer.
+ */
+MODSERIAL uart(TX_PIN, RX_PIN);
+
+// This function is called when a character goes from the TX buffer
+// to the Uart THR FIFO register.
+void txCallback(MODSERIAL_IRQ_INFO *q) {
+    led2 = !led2;
+}
+
+// This function is called when TX buffer goes empty
+void txEmpty(MODSERIAL_IRQ_INFO *q) {
+    led2 = 0;
+    pc.puts(" Done. ");
+}
+
+// This function is called when a character goes into the RX buffer.
+void rxCallback(MODSERIAL_IRQ_INFO *q) {
+    led3 = !led3;
+    pc.putc(uart.getc());
+}
+
+int main() {
+    int c = 'A';
+    
+    // Ensure the baud rate for the PC "USB" serial is much
+    // higher than "uart" baud rate below.
+    pc.baud(PC_BAUD);
+    
+    // Use a deliberatly slow baud to fill up the TX buffer
+    uart.baud(1200);
+    
+    uart.attach(&txCallback, MODSERIAL::TxIrq);
+    uart.attach(&rxCallback, MODSERIAL::RxIrq);
+    uart.attach(&txEmpty,    MODSERIAL::TxEmpty);
+    
+    // Loop sending characters. We send 512
+    // which is twice the default TX/RX buffer size.
+    
+    led1 = 1; // Show start of sending with LED1.
+    
+    for (int loop = 0; loop < 512; loop++) {
+        uart.printf("%c", c);        
+        c++;
+        if (c > 'Z') c = 'A';
+    }
+    
+    led1 = 0; // Show the end of sending by switching off LED1.
+    
+    // End program. Flash LED4. Notice how LED 2 and 3 continue
+    // to flash for a short period while the interrupt system 
+    // continues to send the characters left in the TX buffer.
+    
+    while(1) {
+        led4 = !led4;
+        wait(0.25);
+    }
+}
+
+/*
+ * Notes. Here is the sort of output you can expect on your PC/Mac/Linux host
+ * machine that is connected to the "pc" USB serial port.
+ *
+ * ABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUV
+ * WXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQR
+ * STUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMN
+ * OPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJ
+ * KLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEF
+ * GHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZAB
+ * CDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ Done. R
+ *
+ * Of interest is that last "R" character after the system has said "Done."
+ * This comes from the fact that the TxEmpty callback is made when the TX buffer
+ * becomes empty. MODSERIAL makes use of the fact that the Uarts built into the 
+ * LPC17xx device use a 16 byte FIFO on both RX and TX channels. This means that
+ * when the TxEmpty callback is made, the TX buffer is empty, but that just means
+ * the "last few characters" were written to the TX FIFO. So although the TX
+ * buffer has gone empty, the Uart's transmit system is still sending any remaining
+ * characters from it's TX FIFO. If you want to be truely sure all the characters
+ * you have sent have left the Mbed then call txIsBusy(); This function will
+ * return true if characters are still being sent. If it returns false after
+ * the Tx buffer is empty then all your characters have been sent.
+ *
+ * In a similar way, when characters are received into the RX FIFO, the entire
+ * FIFO contents is moved to the RX buffer, assuming there is room left in the
+ * RX buffer. If there is not, any remaining characters are left in the RX FIFO
+ * and will be moved to the RX buffer on the next interrupt or when the running 
+ * program removes a character(s) from the RX buffer with the getc() method.
+ */
+ 
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/example2.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/example2.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,167 @@
+/*
+    Copyright (c) 2011 Andy Kirkham
+ 
+    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.
+    
+    @file          example2.cpp 
+    @purpose       Demos a simple messaging system.
+    @version       see ChangeLog.c
+    @date          Jan 2011
+    @author        Andy Kirkham
+*/
+
+/*
+    This example demostrates a simple "messaging" system. You can use it with
+    a terminal program to test it out or write a cusom C#/C++/VB/etc program
+    to read and write messages to or from the Mbed. The default baud rate in
+    this example is 115200.
+    
+    In this example, the LEDs are controlled and pins p21 to p24 are set as
+    InterruptIn and send messages out when their value changes.
+    
+    To use, hook up the MBed USB and open your fav terminal. All messages
+    end with the \n character, don't forget to hit carriage return!. 
+    As an example:-
+        
+        to switch on LED1 send LED1:1\n, off is LED1:0\n and toggle is LED1:2\n
+        to switch on LED2 send LED2:1\n, off is LED2:0\n and toggle is LED2:2\n
+        to switch on LED3 send LED3:1\n, off is LED3:0\n and toggle is LED3:2\n
+        to switch on LED4 send LED4:1\n, off is LED4:0\n and toggle is LED4:2\n
+        
+    When a pin change on p21 to p24 happens, a message is sent. As an example
+    when p21 goes low PIN21:0\n is sent, when goes high PIN21:1\n is sent.
+    
+    Note, the InterruptIn pins p21 to p24 are setup to have pullups. This means
+    they are high. To activate them use a wire to short the pin to 0volts.
+    
+    If you find that p21 to p24 sent a lot of on/off/on/off then it's probably
+    due to "bounce". If you are connecting a mechanical switch to a pin you
+    may prefer to use the PinDetect library rather than using InterruptIn.
+    @see http://mbed.org/users/AjK/libraries/PinDetect/latest
+    
+    One point you may notice. Incoming messages are processed via main()'s
+    while(1) loop whereas pin changes have their messages directly sent.
+    The reason for this is when MODSERIAL makes callbacks to your application
+    it is in "interrupt context". And one thing you want to avoid is spending
+    lots of CPU time in that context. So, the callback moves the message from
+    the input buffer to a local holding buffer and it then sets a bool flag
+    which tells main()'s while(1) loop to process that buffer. This means the 
+    time spent doing the real incoming message handing is within your program
+    and not within MODSERIAL's interrupt context. So you may ask, why not do
+    the same for out going messages? Well, because MODSERIAL output buffers
+    all your sent content then sending chars is very fast. MODSERIAL handles
+    all the nitty gritty bits for you. You can just send. This example uses
+    puts() to send the message. If you can, always try and use sprintf()+puts()
+    rathe than printf(), printf() is known to often screw things up when used
+    within an interrupt context. Better still, just use puts() and do away
+    with any of the crappy ?printf() calls if possible. But I found the code
+    below to work fine even at 115200baud.
+    
+*/
+
+
+#ifdef COMPILE_EXAMPLE1_CODE_MODSERIAL
+
+#include "mbed.h"
+#include "MODSERIAL.h"
+
+#define MESSAGE_BUFFER_SIZE 32
+
+DigitalOut led1(LED1);
+DigitalOut led2(LED2);
+DigitalOut led3(LED3);
+DigitalOut led4(LED4);
+
+InterruptIn P21(p21);
+InterruptIn P22(p22);
+InterruptIn P23(p23);
+InterruptIn P24(p24);
+
+MODSERIAL messageSystem(USBTX, USBRX);
+
+char messageBufferIncoming[MESSAGE_BUFFER_SIZE];
+char messageBufferOutgoing[MESSAGE_BUFFER_SIZE];
+bool messageReceived;
+
+void messageReceive(MODSERIAL_IRQ_INFO *q) {
+    MODSERIAL *sys = q->serial;
+    sys->move(messageBufferIncoming, MESSAGE_BUFFER_SIZE);
+    messageReceived = true;
+    return 0;
+}
+
+void messageProcess(void) {
+         if (!strncmp(messageBufferIncoming, "LED1:1", sizeof("LED1:1")-1)) led1 = 1;
+    else if (!strncmp(messageBufferIncoming, "LED1:0", sizeof("LED1:0")-1)) led1 = 0;
+    else if (!strncmp(messageBufferIncoming, "LED1:2", sizeof("LED1:2")-1)) led1 = !led1;
+    
+    else if (!strncmp(messageBufferIncoming, "LED2:1", sizeof("LED2:1")-1)) led2 = 1;
+    else if (!strncmp(messageBufferIncoming, "LED2:0", sizeof("LED2:0")-1)) led2 = 0;
+    else if (!strncmp(messageBufferIncoming, "LED2:2", sizeof("LED2:2")-1)) led2 = !led2;
+    
+    else if (!strncmp(messageBufferIncoming, "LED3:1", sizeof("LED3:1")-1)) led3 = 1;
+    else if (!strncmp(messageBufferIncoming, "LED3:0", sizeof("LED3:0")-1)) led3 = 0;
+    else if (!strncmp(messageBufferIncoming, "LED3:2", sizeof("LED3:2")-1)) led3 = !led3;
+    
+    else if (!strncmp(messageBufferIncoming, "LED4:1", sizeof("LED4:1")-1)) led4 = 1;
+    else if (!strncmp(messageBufferIncoming, "LED4:0", sizeof("LED4:0")-1)) led4 = 0;
+    else if (!strncmp(messageBufferIncoming, "LED4:2", sizeof("LED4:2")-1)) led4 = !led4;
+    
+    messageReceived = false;
+}
+
+#define PIN_MESSAGE_SEND(x,y) \
+    sprintf(messageBufferOutgoing,"PIN%02d:%d\n",x,y);\
+    messageSystem.puts(messageBufferOutgoing);
+
+void pin21Rise(void) { PIN_MESSAGE_SEND(21, 1); }
+void pin21Fall(void) { PIN_MESSAGE_SEND(21, 0); }
+void pin22Rise(void) { PIN_MESSAGE_SEND(22, 1); }
+void pin22Fall(void) { PIN_MESSAGE_SEND(22, 0); }
+void pin23Rise(void) { PIN_MESSAGE_SEND(23, 1); }
+void pin23Fall(void) { PIN_MESSAGE_SEND(23, 0); }
+void pin24Rise(void) { PIN_MESSAGE_SEND(24, 1); }
+void pin24Fall(void) { PIN_MESSAGE_SEND(24, 0); }
+
+int main() {
+
+    messageReceived = false;
+    messageSystem.baud(115200);
+    messageSystem.attach(&messageReceive, MODSERIAL::RxAutoDetect);
+    messageSystem.autoDetectChar('\n'); 
+
+    // Enable pullup resistors on pins.
+    P21.mode(PullUp); P22.mode(PullUp); P23.mode(PullUp); P24.mode(PullUp);
+    
+    // Fix Mbed library bug, see http://mbed.org/forum/bugs-suggestions/topic/1498
+    LPC_GPIOINT->IO2IntClr = (1UL << 5) | (1UL << 4) | (1UL << 3) | (1UL << 2); 
+    
+    // Attach InterruptIn pin callbacks.
+    P21.rise(&pin21Rise); P21.fall(&pin21Fall);
+    P22.rise(&pin22Rise); P22.fall(&pin22Fall);
+    P23.rise(&pin23Rise); P23.fall(&pin23Fall);
+    P24.rise(&pin24Rise); P24.fall(&pin24Fall);
+    
+    while(1) {
+        // Process incoming messages.
+        if (messageReceived) messageProcess();
+    }
+}
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/example3a.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/example3a.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,83 @@
+/*
+    Copyright (c) 2011 Andy Kirkham
+ 
+    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.
+    
+    @file          example3.cpp 
+    @purpose       Demos a simple filter.
+    @version       see ChangeLog.c
+    @author        Andy Kirkham
+*/
+
+/*
+    This example shows how to use the new callback system. In the old system
+    Mbed's FunctionPointer[1] type was used to store abd make calls to callbacks.
+    However, that limits the callback function prototype to void func(void);
+    which means we cannot pass parameters.
+    
+    This latest version of MODSERIAL now uses its own callback object. This allows
+    the passing of a pointer to a class that holds information about the MODSERIAL
+    object making the callback. As of version 1.18 one critcal piece of information
+    is passed, a pointer to the MODSERIAL object. This allows callbacks to use the
+    MODSERIAL functions and data.
+        
+    Additionally, since MODSERIAL and the callback parameter class MODSERIAL_IRQ_INFO
+    are friends, MODSERIAL_IRQ_INFO can access the protected functions of MODSERIAL.
+    This is used to ensure functions that can only be called during a callback
+    can be invoked from a callback. 
+    
+    [1] http://mbed.org/projects/libraries/svn/mbed/trunk/FunctionPointer.h    
+*/
+
+#ifdef COMPILE_EXAMPLE3_CODE_MODSERIAL
+
+#include "mbed.h"
+#include "MODSERIAL.h"
+
+DigitalOut led1(LED1);
+
+MODSERIAL pc(USBTX, USBRX);
+
+// The following callback is defined in example3b.cpp
+//! @see example3b.cpp
+void rxCallback(MODSERIAL_IRQ_INFO *info);
+
+int main() {
+    
+    int life_counter = 0;
+    
+    pc.baud(115200);
+    
+    pc.attach(&rxCallback, MODSERIAL::RxIrq);
+
+    while(1) {
+        // Echo back any chars we get except 'A' which is filtered by the rxCallback.
+        if (pc.readable()) {
+            pc.putc(pc.getc());
+        }
+        
+        // Toggle LED1 every so often to show we are alive.
+        if (life_counter++ == 1000000) {
+            life_counter = 0;
+            led1 = !led1;
+        }
+    }
+}
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/MODSERIAL/example3b.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/MODSERIAL/example3b.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,78 @@
+/*
+    Copyright (c) 2011 Andy Kirkham
+ 
+    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.
+    
+    @file          example3b.cpp 
+    @purpose       Demos a simple filter.
+    @version       see ChangeLog.c
+    @author        Andy Kirkham
+*/
+
+/*
+    This example shows how to use the new callback system. In the old system
+    Mbed's FunctionPointer[1] type was used to store abd make calls to callbacks.
+    However, that limits the callback function prototype to void func(void);
+    which means we cannot pass parameters.
+    
+    This latest version of MODSERIAL now uses its own callback object. This allows
+    the passing of a pointer to a class that holds information about the MODSERIAL
+    object making the callback. As of version 1.18 one critcal piece of information
+    is passed, a pointer to the MODSERIAL object. This allows callbacks to use the
+    MODSERIAL functions and data.
+        
+    Additionally, since MODSERIAL and the callback parameter class MODSERIAL_IRQ_INFO
+    are friends, MODSERIAL_IRQ_INFO can access the protected functions of MODSERIAL.
+    This is used to ensure functions that can only be called during a callback
+    can be invoked from a callback. 
+    
+    [1] http://mbed.org/projects/libraries/svn/mbed/trunk/FunctionPointer.h    
+*/
+
+
+#ifdef COMPILE_EXAMPLE3_CODE_MODSERIAL
+
+#include "mbed.h"
+#include "MODSERIAL.h"
+
+void rxCallback(MODSERIAL_IRQ_INFO *info) {
+
+    // Get the pointer to our MODSERIAL object that invoked this callback.
+    MODSERIAL *pc = info->serial;
+    
+    // info->serial points at the MODSERIAL instance so we can use it to call
+    // any of the public MODSERIAL functions that are normally available. So
+    // there's now no need to use the global version (pc in our case) inside
+    // callback functions.    
+    char c = pc->rxGetLastChar(); // Where local pc variable is a pointer to the global MODSERIAL pc object.
+    
+    // The following is rather daft but demos the point.
+    // Don't allow the letter "A" go into the RX buffer.
+    // Basically acts as a filter to remove the letter "A" 
+    // if it goes into the RX buffer.
+    if (c == 'A') {
+        // Note, we call the MODSERIAL_IRQ_INFO::rxDiscardLastChar() public function which
+        // is permitted access to the protected version of MODSERIAL::rxDiscardLastChar()
+        // within MODSERIAL (because they are friends). This ensures rxDiscardLastChar()
+        // can only be called within an rxCallback function. 
+        info->rxDiscardLastChar(); 
+    }
+}
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/SWSPI/SWSPI.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/SWSPI/SWSPI.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,86 @@
+/* SWSPI, Software SPI library
+ * Copyright (c) 2012-2014, David R. Van Wagner, http://techwithdave.blogspot.com
+ *
+ * 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.
+ */
+
+#include <mbed.h>
+#include "SWSPI.h"
+
+SWSPI::SWSPI(PinName mosi_pin, PinName miso_pin, PinName sclk_pin)
+{
+    mosi = new DigitalOut(mosi_pin);
+    miso = new DigitalIn(miso_pin);
+    sclk = new DigitalOut(sclk_pin);
+    format(8);
+    frequency();
+}
+
+SWSPI::~SWSPI()
+{
+    delete mosi;
+    delete miso;
+    delete sclk;
+}
+
+void SWSPI::format(int bits, int mode)
+{
+    this->bits = bits;
+    this->mode = mode;
+    polarity = (mode >> 1) & 1;
+    phase = mode & 1;
+    sclk->write(polarity);
+}
+
+void SWSPI::frequency(int hz)
+{
+    this->freq = hz;
+}
+
+int SWSPI::write(int value)
+{
+    int read = 0;
+    for (int bit = bits-1; bit >= 0; --bit)
+    {
+        mosi->write(((value >> bit) & 0x01) != 0);
+
+        if (phase == 0)
+        {
+            if (miso->read())
+                read |= (1 << bit);
+        }
+
+        sclk->write(!polarity);
+
+        wait(1.0/freq/2);
+
+        if (phase == 1)
+        {
+            if (miso->read())
+                read |= (1 << bit);
+        }
+
+        sclk->write(polarity);
+
+        wait(1.0/freq/2);
+    }
+    
+    return read;
+}
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/SWSPI/SWSPI.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/SWSPI/SWSPI.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,95 @@
+/* SWSPI, Software SPI library
+ * Copyright (c) 2012-2014, David R. Van Wagner, http://techwithdave.blogspot.com
+ *
+ * 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.
+ */
+
+#ifndef SWSPI_H
+#define SWSPI_H
+
+/** A software implemented SPI that can use any digital pins
+ *
+ * Useful when don't want to share a single SPI hardware among attached devices
+ * or when pinout doesn't match exactly to the target's SPI pins
+ *
+ * @code
+ * #include "mbed.h"
+ * #include "SWSPI.h"
+ * 
+ * SWSPI spi(p5, p6, p7); // mosi, miso, sclk
+ * 
+ * int main() 
+ * {
+ *     DigitalOut cs(p8);
+ *     spi.format(8, 0);
+ *     spi.frequency(10000000);
+ *     cs.write(0);
+ *     spi.write(0x9f);
+ *     int jedecid = (spi.write(0) << 16) | (spi.write(0) << 8) | spi.write(0);
+ *     cs.write(1);
+ * }
+ * @endcode
+ */
+class SWSPI
+{
+private:
+    DigitalOut* mosi;
+    DigitalIn* miso;
+    DigitalOut* sclk;
+    int port;
+    int bits;
+    int mode;
+    int polarity; // idle clock value
+    int phase; // 0=sample on leading (first) clock edge, 1=trailing (second)
+    int freq;
+    
+public:
+    /** Create SWSPI object
+     *
+     *  @param mosi_pin
+     *  @param miso_pin
+     *  @param sclk_pin
+     */
+    SWSPI(PinName mosi_pin, PinName miso_pin, PinName sclk_pin);
+    
+    /** Destructor */
+    ~SWSPI();
+    
+    /** Specify SPI format
+     *
+     *  @param bits  8 or 16 are typical values
+     *  @param mode  0, 1, 2, or 3 phase (bit1) and idle clock (bit0)
+     */
+    void format(int bits, int mode = 0);
+    
+    /** Specify SPI clock frequency
+     *
+     *  @param hz  frequency (optional, defaults to 10000000)
+     */
+    void frequency(int hz = 10000000);
+    
+    /** Write data and read result
+     *
+     *  @param value  data to write (see format for bit size)
+     *  returns value read from device
+     */
+    int write(int value);
+};
+
+#endif // SWSPI_H
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/Mail.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/Mail.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,109 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#ifndef MAIL_H
+#define MAIL_H
+
+#include <stdint.h>
+#include <string.h>
+
+#include "cmsis_os.h"
+
+namespace rtos {
+
+/** The Mail class allow to control, send, receive, or wait for mail.
+ A mail is a memory block that is send to a thread or interrupt service routine.
+  @tparam  T         data type of a single message element.
+  @tparam  queue_sz  maximum number of messages in queue.
+*/
+template<typename T, uint32_t queue_sz>
+class Mail {
+public:
+    /** Create and Initialise Mail queue. */
+    Mail() {
+    #ifdef CMSIS_OS_RTX
+        memset(_mail_q, 0, sizeof(_mail_q));
+        _mail_p[0] = _mail_q;
+        
+        memset(_mail_m, 0, sizeof(_mail_m));
+        _mail_p[1] = _mail_m;
+        
+        _mail_def.pool = _mail_p;
+        _mail_def.queue_sz = queue_sz;
+        _mail_def.item_sz = sizeof(T);
+    #endif
+        _mail_id = osMailCreate(&_mail_def, NULL);
+    }
+    
+    /** Allocate a memory block of type T
+      @param   millisec  timeout value or 0 in case of no time-out. (default: 0).
+      @return  pointer to memory block that can be filled with mail or NULL in case error.
+    */
+    T* alloc(uint32_t millisec=0) {
+        return (T*)osMailAlloc(_mail_id, millisec);
+    }
+    
+    /** Allocate a memory block of type T and set memory block to zero. 
+      @param   millisec  timeout value or 0 in case of no time-out.  (default: 0).
+      @return  pointer to memory block that can be filled with mail or NULL in case error.
+    */
+    T* calloc(uint32_t millisec=0) {
+        return (T*)osMailCAlloc(_mail_id, millisec);
+    }
+    
+    /** Put a mail in the queue.
+      @param   mptr  memory block previously allocated with Mail::alloc or Mail::calloc.
+      @return  status code that indicates the execution status of the function. 
+    */
+    osStatus put(T *mptr) {
+        return osMailPut(_mail_id, (void*)mptr);
+    }
+    
+    /** Get a mail from a queue.
+      @param   millisec  timeout value or 0 in case of no time-out. (default: osWaitForever).
+      @return  event that contains mail information or error code.
+    */
+    osEvent get(uint32_t millisec=osWaitForever) {
+        return osMailGet(_mail_id, millisec);
+    }
+    
+    /** Free a memory block from a mail.
+      @param   mptr  pointer to the memory block that was obtained with Mail::get. 
+      @return  status code that indicates the execution status of the function.
+    */
+    osStatus free(T *mptr) {
+        return osMailFree(_mail_id, (void*)mptr);
+    }
+
+private:
+    osMailQId    _mail_id;
+    osMailQDef_t _mail_def;
+#ifdef CMSIS_OS_RTX
+    uint32_t     _mail_q[4+(queue_sz)];
+    uint32_t     _mail_m[3+((sizeof(T)+3)/4)*(queue_sz)];
+    void        *_mail_p[2];
+#endif
+};
+
+}
+
+#endif
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/MemoryPool.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/MemoryPool.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,82 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#ifndef MEMORYPOOL_H
+#define MEMORYPOOL_H
+
+#include <stdint.h>
+#include <string.h>
+
+#include "cmsis_os.h"
+
+namespace rtos {
+
+/** Define and manage fixed-size memory pools of objects of a given type.
+  @tparam  T         data type of a single object (element).
+  @tparam  queue_sz  maximum number of objects (elements) in the memory pool.
+*/
+template<typename T, uint32_t pool_sz>
+class MemoryPool {
+public:
+    /** Create and Initialize a memory pool. */
+    MemoryPool() {
+    #ifdef CMSIS_OS_RTX
+        memset(_pool_m, 0, sizeof(_pool_m));
+        _pool_def.pool = _pool_m;
+        
+        _pool_def.pool_sz = pool_sz;
+        _pool_def.item_sz =  sizeof(T);
+    #endif
+        _pool_id = osPoolCreate(&_pool_def);
+    }
+    
+    /** Allocate a memory block of type T from a memory pool.
+      @return  address of the allocated memory block or NULL in case of no memory available.
+    */
+    T* alloc(void) {
+        return (T*)osPoolAlloc(_pool_id);
+    }
+    
+    /** Allocate a memory block of type T from a memory pool and set memory block to zero.
+      @return  address of the allocated memory block or NULL in case of no memory available. 
+    */
+    T* calloc(void) {
+        return (T*)osPoolCAlloc(_pool_id);
+    }
+    
+    /** Return an allocated memory block back to a specific memory pool.
+      @param   address of the allocated memory block that is returned to the memory pool.
+      @return  status code that indicates the execution status of the function. 
+    */
+    osStatus free(T *block) {
+        return osPoolFree(_pool_id, (void*)block);
+    }
+
+private:
+    osPoolId    _pool_id;
+    osPoolDef_t _pool_def;
+#ifdef CMSIS_OS_RTX
+    uint32_t    _pool_m[3+((sizeof(T)+3)/4)*(pool_sz)];
+#endif
+};
+
+}
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/Mutex.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/Mutex.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,56 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#include "Mutex.h"
+
+#include <string.h>
+#include "error.h"
+
+namespace rtos {
+
+Mutex::Mutex() {
+#ifdef CMSIS_OS_RTX
+    memset(_mutex_data, 0, sizeof(_mutex_data));
+    _osMutexDef.mutex = _mutex_data;
+#endif
+    _osMutexId = osMutexCreate(&_osMutexDef);
+    if (_osMutexId == NULL) {
+        error("Error initializing the mutex object\n");
+    }
+}
+
+osStatus Mutex::lock(uint32_t millisec) {
+    return osMutexWait(_osMutexId, millisec);
+}
+
+bool Mutex::trylock() {
+    return (osMutexWait(_osMutexId, 0) == osOK);
+}
+
+osStatus Mutex::unlock() {
+    return osMutexRelease(_osMutexId);
+}
+
+Mutex::~Mutex() {
+    osMutexDelete(_osMutexId);
+}
+
+}
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/Mutex.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/Mutex.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,65 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#ifndef MUTEX_H
+#define MUTEX_H
+
+#include <stdint.h>
+#include "cmsis_os.h"
+
+namespace rtos {
+
+/** The Mutex class is used to synchronise the execution of threads.
+ This is for example used to protect access to a shared resource.
+*/
+class Mutex {
+public:
+    /** Create and Initialize a Mutex object */
+    Mutex();
+    
+    /** Wait until a Mutex becomes available.
+      @param   millisec  timeout value or 0 in case of no time-out. (default: osWaitForever)
+      @return  status code that indicates the execution status of the function.
+     */ 
+    osStatus lock(uint32_t millisec=osWaitForever);
+    
+    /** Try to lock the mutex, and return immediately
+      @return  true if the mutex was acquired, false otherwise.
+     */
+    bool trylock();
+    
+    /** Unlock the mutex that has previously been locked by the same thread
+      @return  status code that indicates the execution status of the function. 
+     */
+    osStatus unlock();
+    
+    ~Mutex();
+
+private:
+    osMutexId _osMutexId;
+    osMutexDef_t _osMutexDef;
+#ifdef CMSIS_OS_RTX
+    int32_t _mutex_data[3];
+#endif
+};
+
+}
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/Queue.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/Queue.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,81 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#ifndef QUEUE_H
+#define QUEUE_H
+
+#include <stdint.h>
+#include <string.h>
+
+#include "cmsis_os.h"
+#include "error.h"
+
+namespace rtos {
+
+/** The Queue class allow to control, send, receive, or wait for messages.
+ A message can be a integer or pointer value  to a certain type T that is send
+ to a thread or interrupt service routine.
+  @tparam  T         data type of a single message element.
+  @tparam  queue_sz  maximum number of messages in queue.
+*/
+template<typename T, uint32_t queue_sz>
+class Queue {
+public:
+    /** Create and initialise a message Queue. */
+    Queue() {
+    #ifdef CMSIS_OS_RTX
+        memset(_queue_q, 0, sizeof(_queue_q));
+        _queue_def.pool = _queue_q;
+        _queue_def.queue_sz = queue_sz;
+    #endif
+        _queue_id = osMessageCreate(&_queue_def, NULL);
+        if (_queue_id == NULL) {
+            error("Error initialising the queue object\n");
+        }
+    }
+    
+    /** Put a message in a Queue.
+      @param   data      message pointer.
+      @param   millisec  timeout value or 0 in case of no time-out. (default: 0)
+      @return  status code that indicates the execution status of the function. 
+    */
+    osStatus put(T* data, uint32_t millisec=0) {
+        return osMessagePut(_queue_id, (uint32_t)data, millisec);
+    }
+    
+    /** Get a message or Wait for a message from a Queue.
+      @param   millisec  timeout value or 0 in case of no time-out. (default: osWaitForever).
+      @return  event information that includes the message and the status code.
+    */
+    osEvent get(uint32_t millisec=osWaitForever) {
+        return osMessageGet(_queue_id, millisec);
+    }
+
+private:
+    osMessageQId    _queue_id;
+    osMessageQDef_t _queue_def;
+#ifdef CMSIS_OS_RTX
+    uint32_t        _queue_q[4+(queue_sz)];
+#endif
+};
+
+}
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/RtosTimer.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/RtosTimer.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,53 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#include "RtosTimer.h"
+
+#include <string.h>
+
+#include "cmsis_os.h"
+#include "error.h"
+
+namespace rtos {
+
+RtosTimer::RtosTimer(void (*periodic_task)(void const *argument), os_timer_type type, void *argument) {
+#ifdef CMSIS_OS_RTX
+    _timer.ptimer = periodic_task;
+    
+    memset(_timer_data, 0, sizeof(_timer_data));
+    _timer.timer = _timer_data;
+#endif
+    _timer_id = osTimerCreate(&_timer, type, argument);
+}
+
+osStatus RtosTimer::start(uint32_t millisec) {
+    return osTimerStart(_timer_id, millisec);
+}
+
+osStatus RtosTimer::stop(void) {
+    return osTimerStop(_timer_id);
+}
+
+RtosTimer::~RtosTimer() {
+    osTimerDelete(_timer_id);
+}
+
+}
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/RtosTimer.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/RtosTimer.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,71 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#ifndef RTOS_TIMER_H
+#define RTOS_TIMER_H
+
+#include <stdint.h>
+#include "cmsis_os.h"
+
+namespace rtos {
+
+/** The RtosTimer class allow creating and and controlling of timer functions in the system.
+ A timer function is called when a time period expires whereby both on-shot and
+ periodic timers are possible. A timer can be started, restarted, or stopped.
+
+ Timers are handled in the thread osTimerThread.
+ Callback functions run under control of this thread and may use CMSIS-RTOS API calls. 
+*/
+class RtosTimer {
+public:
+    /** Create and Start timer.
+      @param   task      name of the timer call back function.
+      @param   type      osTimerOnce for one-shot or osTimerPeriodic for periodic behaviour. (default: osTimerPeriodic)
+      @param   argument  argument to the timer call back function. (default: NULL)
+    */
+    RtosTimer(void (*task)(void const *argument),
+          os_timer_type type=osTimerPeriodic,
+          void *argument=NULL);
+    
+    /** Stop the timer.
+      @return  status code that indicates the execution status of the function. 
+    */
+    osStatus stop(void);
+    
+    /** start a timer.
+      @param   millisec  time delay value of the timer.
+      @return  status code that indicates the execution status of the function. 
+    */
+    osStatus start(uint32_t millisec);
+    
+    ~RtosTimer();
+
+private:
+    osTimerId _timer_id;
+    osTimerDef_t _timer;
+#ifdef CMSIS_OS_RTX
+    uint32_t _timer_data[5];
+#endif
+};
+
+}
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/Semaphore.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/Semaphore.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,49 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#include "Semaphore.h"
+
+#include <string.h>
+#include "error.h"
+
+namespace rtos {
+
+Semaphore::Semaphore(int32_t count) {
+#ifdef CMSIS_OS_RTX
+    memset(_semaphore_data, 0, sizeof(_semaphore_data));
+    _osSemaphoreDef.semaphore = _semaphore_data;
+#endif
+    _osSemaphoreId = osSemaphoreCreate(&_osSemaphoreDef, count);
+}
+
+int32_t Semaphore::wait(uint32_t millisec) {
+    return osSemaphoreWait(_osSemaphoreId, millisec);
+}
+
+osStatus Semaphore::release(void) {
+    return osSemaphoreRelease(_osSemaphoreId);
+}
+
+Semaphore::~Semaphore() {
+    osSemaphoreDelete(_osSemaphoreId);
+}
+
+}
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/Semaphore.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/Semaphore.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,60 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#ifndef SEMAPHORE_H
+#define SEMAPHORE_H
+
+#include <stdint.h>
+#include "cmsis_os.h"
+
+namespace rtos {
+
+/** The Semaphore class is used to manage and protect access to a set of shared resources. */
+class Semaphore {
+public:
+    /** Create and Initialize a Semaphore object used for managing resources. 
+      @param number of available resources; maximum index value is (count-1).
+    */
+    Semaphore(int32_t count);
+    
+    /** Wait until a Semaphore resource becomes available. 
+      @param   millisec  timeout value or 0 in case of no time-out. (default: osWaitForever).
+      @return  number of available tokens, or -1 in case of incorrect parameters
+    */
+    int32_t wait(uint32_t millisec=osWaitForever);
+    
+    /** Release a Semaphore resource that was obtain with Semaphore::wait.
+      @return  status code that indicates the execution status of the function. 
+    */
+    osStatus release(void);
+    
+    ~Semaphore();
+
+private:
+    osSemaphoreId _osSemaphoreId;
+    osSemaphoreDef_t _osSemaphoreDef;
+#ifdef CMSIS_OS_RTX
+    uint32_t _semaphore_data[2];
+#endif
+};
+
+}
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/Thread.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/Thread.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,90 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#include "Thread.h"
+
+#include "error.h"
+
+namespace rtos {
+
+Thread::Thread(void (*task)(void const *argument), void *argument,
+        osPriority priority, uint32_t stack_size, unsigned char *stack_pointer) {
+#ifdef CMSIS_OS_RTX
+    _thread_def.pthread = task;
+    _thread_def.tpriority = priority;
+    _thread_def.stacksize = stack_size;
+    if (stack_pointer != NULL) {
+        _thread_def.stack_pointer = stack_pointer;
+        _dynamic_stack = false;
+    } else {
+        _thread_def.stack_pointer = new unsigned char[stack_size];
+        if (_thread_def.stack_pointer == NULL)
+            error("Error allocating the stack memory\n");
+        _dynamic_stack = true;
+    }
+#endif
+    _tid = osThreadCreate(&_thread_def, argument);
+}
+
+osStatus Thread::terminate() {
+    return osThreadTerminate(_tid);
+}
+
+osStatus Thread::set_priority(osPriority priority) {
+    return osThreadSetPriority(_tid, priority);
+}
+
+osPriority Thread::get_priority() {
+    return osThreadGetPriority(_tid);
+}
+
+int32_t Thread::signal_set(int32_t signals) {
+    return osSignalSet(_tid, signals);
+}
+
+Thread::State Thread::get_state() {
+    return ((State)_thread_def.tcb.state);
+}
+
+osEvent Thread::signal_wait(int32_t signals, uint32_t millisec) {
+    return osSignalWait(signals, millisec);
+}
+
+osStatus Thread::wait(uint32_t millisec) {
+    return osDelay(millisec);
+}
+
+osStatus Thread::yield() {
+    return osThreadYield();
+}
+
+osThreadId Thread::gettid() {
+    return osThreadGetId();
+}
+
+Thread::~Thread() {
+    terminate();
+    if (_dynamic_stack) {
+        delete[] (_thread_def.stack_pointer);
+    }
+}
+
+}
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/Thread.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/Thread.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,118 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#ifndef THREAD_H
+#define THREAD_H
+
+#include <stdint.h>
+#include "cmsis_os.h"
+
+namespace rtos {
+
+/** The Thread class allow defining, creating, and controlling thread functions in the system. */
+class Thread {
+public:
+    /** Create a new thread, and start it executing the specified function.
+      @param   task           function to be executed by this thread.
+      @param   argument       pointer that is passed to the thread function as start argument. (default: NULL).
+      @param   priority       initial priority of the thread function. (default: osPriorityNormal).
+      @param   stack_size      stack size (in bytes) requirements for the thread function. (default: DEFAULT_STACK_SIZE).
+      @param   stack_pointer  pointer to the stack area to be used by this thread (default: NULL).
+    */
+    Thread(void (*task)(void const *argument), void *argument=NULL,
+           osPriority priority=osPriorityNormal,
+           uint32_t stack_size=DEFAULT_STACK_SIZE,
+           unsigned char *stack_pointer=NULL);
+    
+    /** Terminate execution of a thread and remove it from Active Threads
+      @return  status code that indicates the execution status of the function.
+    */
+    osStatus terminate();
+    
+    /** Set priority of an active thread
+      @param   priority  new priority value for the thread function.
+      @return  status code that indicates the execution status of the function.
+    */
+    osStatus set_priority(osPriority priority);
+    
+    /** Get priority of an active thread
+      @return  current priority value of the thread function.
+    */
+    osPriority get_priority();
+    
+    /** Set the specified Signal Flags of an active thread.
+      @param   signals  specifies the signal flags of the thread that should be set.
+      @return  previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters.
+    */
+    int32_t signal_set(int32_t signals);
+    
+    /** State of the Thread */
+    enum State {
+        Inactive,           /**< Not created or terminated */
+        Ready,              /**< Ready to run */
+        Running,            /**< Running */
+        WaitingDelay,       /**< Waiting for a delay to occur */
+        WaitingInterval,    /**< Waiting for an interval to occur */
+        WaitingOr,          /**< Waiting for one event in a set to occur */
+        WaitingAnd,         /**< Waiting for multiple events in a set to occur */
+        WaitingSemaphore,   /**< Waiting for a semaphore event to occur */
+        WaitingMailbox,     /**< Waiting for a mailbox event to occur */
+        WaitingMutex,       /**< Waiting for a mutex event to occur */
+    };
+    
+    /** State of this Thread
+      @return  the State of this Thread
+    */
+    State get_state();
+    
+    /** Wait for one or more Signal Flags to become signaled for the current RUNNING thread. 
+      @param   signals   wait until all specified signal flags set or 0 for any single signal flag.
+      @param   millisec  timeout value or 0 in case of no time-out. (default: osWaitForever).
+      @return  event flag information or error code.
+    */
+    static osEvent signal_wait(int32_t signals, uint32_t millisec=osWaitForever);
+    
+    /** Wait for a specified time period in millisec:
+      @param   millisec  time delay value
+      @return  status code that indicates the execution status of the function. 
+    */
+    static osStatus wait(uint32_t millisec);
+    
+    /** Pass control to next thread that is in state READY.
+      @return  status code that indicates the execution status of the function.
+    */
+    static osStatus yield();
+    
+    /** Get the thread id of the current running thread.
+      @return  thread ID for reference by other functions or NULL in case of error.
+    */
+    static osThreadId gettid();
+    
+    virtual ~Thread();
+
+private:
+    osThreadId _tid;
+    osThreadDef_t _thread_def;
+    bool _dynamic_stack;
+};
+
+}
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtos/rtos.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtos/rtos.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,35 @@
+/* mbed Microcontroller Library
+ * Copyright (c) 2006-2012 ARM Limited
+ *
+ * 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.
+ */
+#ifndef RTOS_H
+#define RTOS_H
+
+#include "Thread.h"
+#include "Mutex.h"
+#include "RtosTimer.h"
+#include "Semaphore.h"
+#include "Mail.h"
+#include "MemoryPool.h"
+#include "Queue.h"
+
+using namespace rtos;
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/HAL_CM.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/HAL_CM.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,170 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM.C
+ *      Purpose: Hardware Abstraction Layer for Cortex-M
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_HAL_CM.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Global Variables
+ *---------------------------------------------------------------------------*/
+
+#ifdef DBG_MSG
+BIT dbg_msg;
+#endif
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_init_stack ---------------------------------*/
+
+void rt_init_stack (P_TCB p_TCB, FUNCP task_body) {
+  /* Prepare TCB and saved context for a first time start of a task. */
+  U32 *stk,i,size;
+
+  /* Prepare a complete interrupt frame for first task start */
+  size = p_TCB->priv_stack >> 2;
+  
+  /* Write to the top of stack. */
+  stk = &p_TCB->stack[size];
+
+  /* Auto correct to 8-byte ARM stack alignment. */
+  if ((U32)stk & 0x04) {
+    stk--;
+  }
+
+  stk -= 16;
+
+  /* Default xPSR and initial PC */
+  stk[15] = INITIAL_xPSR;
+  stk[14] = (U32)task_body;
+
+  /* Clear R4-R11,R0-R3,R12,LR registers. */
+  for (i = 0; i < 14; i++) {
+    stk[i] = 0;
+  }
+
+  /* Assign a void pointer to R0. */
+  stk[8] = (U32)p_TCB->msg;
+
+  /* Initial Task stack pointer. */
+  p_TCB->tsk_stack = (U32)stk;
+
+  /* Task entry point. */
+  p_TCB->ptask = task_body;
+
+  /* Set a magic word for checking of stack overflow.
+   For the main thread (ID: 0x01) the stack is in a memory area shared with the
+   heap, therefore the last word of the stack is a moving target.
+   We want to do stack/heap collision detection instead.
+  */
+  if (p_TCB->task_id != 0x01)
+      p_TCB->stack[0] = MAGIC_WORD;
+}
+
+
+/*--------------------------- rt_ret_val ----------------------------------*/
+
+static __inline U32 *rt_ret_regs (P_TCB p_TCB) {
+  /* Get pointer to task return value registers (R0..R3) in Stack */
+#if (__TARGET_FPU_VFP)
+  if (p_TCB->stack_frame) {
+    /* Extended Stack Frame: R4-R11,S16-S31,R0-R3,R12,LR,PC,xPSR,S0-S15,FPSCR */
+    return (U32 *)(p_TCB->tsk_stack + 8*4 + 16*4);
+  } else {
+    /* Basic Stack Frame: R4-R11,R0-R3,R12,LR,PC,xPSR */
+    return (U32 *)(p_TCB->tsk_stack + 8*4);
+  }
+#else
+  /* Stack Frame: R4-R11,R0-R3,R12,LR,PC,xPSR */
+  return (U32 *)(p_TCB->tsk_stack + 8*4);
+#endif
+}
+
+void rt_ret_val (P_TCB p_TCB, U32 v0) {
+  U32 *ret;
+
+  ret = rt_ret_regs(p_TCB);
+  ret[0] = v0;
+}
+
+void rt_ret_val2(P_TCB p_TCB, U32 v0, U32 v1) {
+  U32 *ret;
+
+  ret = rt_ret_regs(p_TCB);
+  ret[0] = v0;
+  ret[1] = v1;
+}
+
+
+/*--------------------------- dbg_init --------------------------------------*/
+
+#ifdef DBG_MSG
+void dbg_init (void) {
+  if ((DEMCR & DEMCR_TRCENA)     && 
+      (ITM_CONTROL & ITM_ITMENA) &&
+      (ITM_ENABLE & (1UL << 31))) {
+    dbg_msg = __TRUE;
+  }
+}
+#endif
+
+/*--------------------------- dbg_task_notify -------------------------------*/
+
+#ifdef DBG_MSG
+void dbg_task_notify (P_TCB p_tcb, BOOL create) {
+  while (ITM_PORT31_U32 == 0);
+  ITM_PORT31_U32 = (U32)p_tcb->ptask;
+  while (ITM_PORT31_U32 == 0);
+  ITM_PORT31_U16 = (create << 8) | p_tcb->task_id;
+}
+#endif
+
+/*--------------------------- dbg_task_switch -------------------------------*/
+
+#ifdef DBG_MSG
+void dbg_task_switch (U32 task_id) {
+  while (ITM_PORT31_U32 == 0);
+  ITM_PORT31_U8 = task_id;
+}
+#endif
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/RTX_CM_lib.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/RTX_CM_lib.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,422 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RTX_CM_LIB.H
+ *      Purpose: RTX Kernel System Configuration
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used
+ *    to endorse or promote products derived from this software without
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+#include "error.h"
+
+#if   defined (__CC_ARM)
+#pragma O3
+#define __USED __attribute__((used))
+#elif defined (__GNUC__)
+#pragma GCC optimize ("O3")
+#define __USED __attribute__((used))
+#elif defined (__ICCARM__)
+#define __USED __root
+#endif
+
+
+/*----------------------------------------------------------------------------
+ *      Definitions
+ *---------------------------------------------------------------------------*/
+
+#define _declare_box(pool,size,cnt)  uint32_t pool[(((size)+3)/4)*(cnt) + 3]
+#define _declare_box8(pool,size,cnt) uint64_t pool[(((size)+7)/8)*(cnt) + 2]
+
+#define OS_TCB_SIZE     48
+#define OS_TMR_SIZE     8
+
+#if defined (__CC_ARM) && !defined (__MICROLIB)
+
+typedef void    *OS_ID;
+typedef uint32_t OS_TID;
+typedef uint32_t OS_MUT[3];
+typedef uint32_t OS_RESULT;
+
+#define runtask_id()    rt_tsk_self()
+#define mutex_init(m)   rt_mut_init(m)
+#define mutex_wait(m)   os_mut_wait(m,0xFFFF)
+#define mutex_rel(m)    os_mut_release(m)
+
+extern OS_TID    rt_tsk_self    (void);
+extern void      rt_mut_init    (OS_ID mutex);
+extern OS_RESULT rt_mut_release (OS_ID mutex);
+extern OS_RESULT rt_mut_wait    (OS_ID mutex, uint16_t timeout);
+
+#define os_mut_wait(mutex,timeout) _os_mut_wait((uint32_t)rt_mut_wait,mutex,timeout)
+#define os_mut_release(mutex)      _os_mut_release((uint32_t)rt_mut_release,mutex)
+
+OS_RESULT _os_mut_release (uint32_t p, OS_ID mutex)                   __svc_indirect(0);
+OS_RESULT _os_mut_wait    (uint32_t p, OS_ID mutex, uint16_t timeout) __svc_indirect(0);
+
+#endif
+
+
+/*----------------------------------------------------------------------------
+ *      Global Variables
+ *---------------------------------------------------------------------------*/
+
+#if (OS_TIMERS != 0)
+#define OS_TASK_CNT (OS_TASKCNT + 1)
+#else
+#define OS_TASK_CNT  OS_TASKCNT
+#endif
+
+uint16_t const os_maxtaskrun = OS_TASK_CNT;
+uint32_t const os_rrobin     = (OS_ROBIN << 16) | OS_ROBINTOUT;
+uint32_t const os_trv        = OS_TRV;
+uint8_t  const os_flags      = OS_RUNPRIV;
+
+/* Export following defines to uVision debugger. */
+__USED uint32_t const os_clockrate = OS_TICK;
+__USED uint32_t const os_timernum  = 0;
+
+/* Stack for the os_idle_demon */
+unsigned int idle_task_stack[OS_IDLESTKSIZE];
+unsigned short const idle_task_stack_size = OS_IDLESTKSIZE;
+
+#ifndef OS_FIFOSZ
+ #define OS_FIFOSZ      16
+#endif
+
+/* Fifo Queue buffer for ISR requests.*/
+uint32_t       os_fifo[OS_FIFOSZ*2+1];
+uint8_t  const os_fifo_size = OS_FIFOSZ;
+
+/* An array of Active task pointers. */
+void *os_active_TCB[OS_TASK_CNT];
+
+/* User Timers Resources */
+#if (OS_TIMERS != 0)
+extern void osTimerThread (void const *argument);
+osThreadDef(osTimerThread, (osPriority)(OS_TIMERPRIO-3), 4*OS_TIMERSTKSZ);
+osThreadId osThreadId_osTimerThread;
+osMessageQDef(osTimerMessageQ, OS_TIMERCBQS, void *);
+osMessageQId osMessageQId_osTimerMessageQ;
+#else
+osThreadDef_t os_thread_def_osTimerThread = { NULL };
+osThreadId osThreadId_osTimerThread;
+osMessageQDef(osTimerMessageQ, 0, void *);
+osMessageQId osMessageQId_osTimerMessageQ;
+#endif
+
+
+/*----------------------------------------------------------------------------
+ *      RTX Optimizations (empty functions)
+ *---------------------------------------------------------------------------*/
+
+#if OS_ROBIN == 0
+ void rt_init_robin (void) {;}
+ void rt_chk_robin  (void) {;}
+#endif
+
+#if OS_STKCHECK == 0
+ void rt_stk_check  (void) {;}
+#endif
+
+
+/*----------------------------------------------------------------------------
+ *      Standard Library multithreading interface
+ *---------------------------------------------------------------------------*/
+
+#if defined (__CC_ARM) && !defined (__MICROLIB)
+ static OS_MUT   std_libmutex[OS_MUTEXCNT];
+ static uint32_t nr_mutex;
+
+ /*--------------------------- _mutex_initialize -----------------------------*/
+ 
+int _mutex_initialize (OS_ID *mutex) {
+  /* Allocate and initialize a system mutex. */
+
+  if (nr_mutex >= OS_MUTEXCNT) {
+    /* If you are here, you need to increase the number OS_MUTEXCNT. */
+    error("Not enough stdlib mutexes\n");
+  }
+  *mutex = &std_libmutex[nr_mutex++];
+  mutex_init (*mutex);
+  return (1);
+}
+
+
+/*--------------------------- _mutex_acquire --------------------------------*/
+
+__attribute__((used)) void _mutex_acquire (OS_ID *mutex) {
+  /* Acquire a system mutex, lock stdlib resources. */
+  if (runtask_id ()) {
+    /* RTX running, acquire a mutex. */
+    mutex_wait (*mutex);
+  }
+}
+
+
+/*--------------------------- _mutex_release --------------------------------*/
+
+__attribute__((used)) void _mutex_release (OS_ID *mutex) {
+  /* Release a system mutex, unlock stdlib resources. */
+  if (runtask_id ()) {
+    /* RTX running, release a mutex. */
+    mutex_rel (*mutex);
+  }
+}
+
+#endif
+
+
+/*----------------------------------------------------------------------------
+ *      RTX Startup
+ *---------------------------------------------------------------------------*/
+
+/* Main Thread definition */
+extern int main (void);
+osThreadDef_t os_thread_def_main = {(os_pthread)main, osPriorityNormal, 0, NULL};
+
+// This define should be probably moved to the CMSIS layer
+#if   defined(TARGET_LPC1768)
+#define INITIAL_SP            (0x10008000UL)
+
+#elif defined(TARGET_LPC11U24)
+#define INITIAL_SP            (0x10002000UL)
+
+#elif defined(TARGET_LPC11U35_401) || defined(TARGET_LPC11U35_501)
+#define INITIAL_SP            (0x10002000UL)
+
+#elif defined(TARGET_LPC1114)
+#define INITIAL_SP            (0x10001000UL)
+
+#elif defined(TARGET_LPC812)
+#define INITIAL_SP            (0x10001000UL)
+
+#elif defined(TARGET_KL25Z)
+#define INITIAL_SP            (0x20003000UL)
+
+#elif defined(TARGET_K64F)
+#define INITIAL_SP            (0x20030000UL)
+
+#elif defined(TARGET_KL46Z)
+#define INITIAL_SP            (0x20006000UL)
+
+#elif defined(TARGET_KL05Z)
+#define INITIAL_SP            (0x20000C00UL)
+
+#elif defined(TARGET_LPC4088)
+#define INITIAL_SP            (0x10010000UL)
+
+#elif defined(TARGET_LPC1347)
+#define INITIAL_SP            (0x10002000UL)
+
+#elif defined(TARGET_STM32F100RB) || defined(TARGET_STM32F051R8)
+#define INITIAL_SP            (0x20002000UL)
+
+#elif defined(TARGET_DISCO_F303VC)
+#define INITIAL_SP            (0x2000A000UL)
+
+#elif defined(TARGET_STM32F407) || defined(TARGET_F407VG)
+#define INITIAL_SP            (0x20020000UL)
+
+#elif defined(TARGET_LPC1549)
+#define INITIAL_SP            (0x02009000UL)
+
+#elif defined(TARGET_LPC11U68)
+#define INITIAL_SP            (0x10004000UL)
+
+#else
+#error "no target defined"
+
+#endif
+
+#ifdef __CC_ARM
+extern unsigned char     Image$$RW_IRAM1$$ZI$$Limit[];
+#define HEAP_START      (Image$$RW_IRAM1$$ZI$$Limit)
+#elif defined(__GNUC__)
+extern unsigned char     __end__[];
+#define HEAP_START      (__end__)
+#endif
+
+void set_main_stack(void) {
+    // That is the bottom of the main stack block: no collision detection
+    os_thread_def_main.stack_pointer = HEAP_START;
+    
+    // Leave OS_SCHEDULERSTKSIZE words for the scheduler and interrupts
+    os_thread_def_main.stacksize = (INITIAL_SP - (unsigned int)HEAP_START) - (OS_SCHEDULERSTKSIZE * 4);
+}
+
+#if defined (__CC_ARM)
+#ifdef __MICROLIB
+void _main_init (void) __attribute__((section(".ARM.Collect$$$$000000FF")));
+void _main_init (void) {
+  osKernelInitialize();
+  set_main_stack();
+  osThreadCreate(&os_thread_def_main, NULL);
+  osKernelStart();
+  for (;;);
+}
+#else
+
+/* The single memory model is checking for stack collision at run time, verifing
+   that the heap pointer is underneath the stack pointer.
+   
+   With the RTOS there is not only one stack above the heap, there are multiple
+   stacks and some of them are underneath the heap pointer.
+*/
+#pragma import(__use_two_region_memory)
+
+__asm void __rt_entry (void) {
+
+  IMPORT  __user_setup_stackheap
+  IMPORT  __rt_lib_init
+  IMPORT  os_thread_def_main
+  IMPORT  osKernelInitialize
+  IMPORT  set_main_stack
+  IMPORT  osKernelStart
+  IMPORT  osThreadCreate
+  IMPORT  exit
+
+  BL      __user_setup_stackheap
+  MOV     R1,R2
+  BL      __rt_lib_init
+  BL      osKernelInitialize
+  BL      set_main_stack
+  LDR     R0,=os_thread_def_main
+  MOVS    R1,#0
+  BL      osThreadCreate
+  BL      osKernelStart
+  BL      exit
+
+  ALIGN
+}
+#endif
+
+#elif defined (__GNUC__)
+
+#ifdef __CS3__
+
+/* CS3 start_c routine.
+ *
+ * Copyright (c) 2006, 2007 CodeSourcery Inc
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply.
+ */
+
+#include "cs3.h"
+
+extern void __libc_init_array (void);
+
+__attribute ((noreturn)) void __cs3_start_c (void){
+  unsigned regions = __cs3_region_num;
+  const struct __cs3_region *rptr = __cs3_regions;
+
+  /* Initialize memory */
+  for (regions = __cs3_region_num, rptr = __cs3_regions; regions--; rptr++) {
+    long long *src = (long long *)rptr->init;
+    long long *dst = (long long *)rptr->data;
+    unsigned limit = rptr->init_size;
+    unsigned count;
+
+    if (src != dst)
+      for (count = 0; count != limit; count += sizeof (long long))
+        *dst++ = *src++;
+    else
+      dst = (long long *)((char *)dst + limit);
+    limit = rptr->zero_size;
+    for (count = 0; count != limit; count += sizeof (long long))
+      *dst++ = 0;
+  }
+
+  /* Run initializers.  */
+  __libc_init_array ();
+
+  osKernelInitialize();
+  set_main_stack();
+  osThreadCreate(&os_thread_def_main, NULL);
+  osKernelStart();
+  for (;;);
+}
+
+#else
+
+__attribute__((naked)) void software_init_hook (void) {
+  __asm (
+    ".syntax unified\n"
+    ".thumb\n"
+    "movs r0,#0\n"
+    "movs r1,#0\n"
+    "mov  r4,r0\n"
+    "mov  r5,r1\n"
+    "ldr  r0,= __libc_fini_array\n"
+    "bl   atexit\n"
+    "bl   __libc_init_array\n"
+    "mov  r0,r4\n"
+    "mov  r1,r5\n"
+    "bl   osKernelInitialize\n"
+    "bl   set_main_stack\n"
+    "ldr  r0,=os_thread_def_main\n"
+    "movs r1,#0\n"
+    "bl   osThreadCreate\n"
+    "bl   osKernelStart\n"
+    "bl   exit\n"
+  );
+}
+
+#endif
+
+#elif defined (__ICCARM__)
+
+extern int  __low_level_init(void);
+extern void __iar_data_init3(void);
+extern void exit(int arg);
+
+__noreturn __stackless void __cmain(void) {
+  int a;
+  
+  if (__low_level_init() != 0) {
+    __iar_data_init3();
+  }
+  osKernelInitialize();
+  osThreadCreate(&os_thread_def_main, NULL);
+  a = osKernelStart();
+  exit(a);
+}
+
+#endif
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/RTX_Conf.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/RTX_Conf.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RTX_CONFIG.H
+ *      Purpose: Exported functions of RTX_Config.c
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+
+/* Error Codes */
+#define OS_ERR_STK_OVF          1
+#define OS_ERR_FIFO_OVF         2
+#define OS_ERR_MBX_OVF          3
+
+/* Definitions */
+#define BOX_ALIGN_8                   0x80000000
+#define _declare_box(pool,size,cnt)   U32 pool[(((size)+3)/4)*(cnt) + 3]
+#define _declare_box8(pool,size,cnt)  U64 pool[(((size)+7)/8)*(cnt) + 2]
+#define _init_box8(pool,size,bsize)   _init_box (pool,size,(bsize) | BOX_ALIGN_8)
+
+/* Variables */
+extern U32 idle_task_stack[];
+extern U32 os_fifo[];
+extern void *os_active_TCB[];
+
+/* Constants */
+extern U16 const os_maxtaskrun;
+extern U32 const os_trv;
+extern U8  const os_flags;
+extern U32 const os_rrobin;
+extern U32 const os_clockrate;
+extern U32 const os_timernum;
+extern U16 const idle_task_stack_size;
+
+extern U8  const os_fifo_size;
+
+/* Functions */
+extern void os_idle_demon   (void);
+extern int  os_tick_init    (void);
+extern void os_tick_irqack  (void);
+extern void os_tmr_call     (U16  info);
+extern void os_error        (U32 err_code);
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/RTX_Conf_CM.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/RTX_Conf_CM.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,268 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RTX_Conf_CM.C
+ *      Purpose: Configuration of CMSIS RTX Kernel for Cortex-M
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "cmsis_os.h"
+
+
+/*----------------------------------------------------------------------------
+ *      RTX User configuration part BEGIN
+ *---------------------------------------------------------------------------*/
+
+//-------- <<< Use Configuration Wizard in Context Menu >>> -----------------
+//
+// <h>Thread Configuration
+// =======================
+//
+//   <o>Number of concurrent running threads <0-250>
+//   <i> Defines max. number of threads that will run at the same time.
+//       counting "main", but not counting "osTimerThread"
+//   <i> Default: 6
+#ifndef OS_TASKCNT
+#  if   defined(TARGET_LPC1768) || defined(TARGET_LPC2368)   || defined(TARGET_LPC4088) || defined(TARGET_LPC1347) || defined(TARGET_K64F) \
+	 || defined(TARGET_KL46Z)   || defined(TARGET_STM32F407) || defined(TARGET_F407VG)  || defined(TARGET_STM32F303VC) || defined(TARGET_LPC1549) || defined(TARGET_LPC11U68)
+#    define OS_TASKCNT         14
+#  elif defined(TARGET_LPC11U24) || defined(TARGET_LPC11U35_401)  || defined(TARGET_LPC11U35_501) || defined(TARGET_LPC1114) \
+	 || defined(TARGET_LPC812)   || defined(TARGET_KL25Z)         || defined(TARGET_KL05Z)        || defined(TARGET_STM32F100RB)  || defined(TARGET_STM32F051R8)
+#    define OS_TASKCNT         6
+#  else
+#    error "no target defined"
+#  endif
+#endif
+
+//   <o>Scheduler (+ interrupts) stack size [bytes] <64-4096:8><#/4>
+#ifndef OS_SCHEDULERSTKSIZE
+#  if   defined(TARGET_LPC1768) || defined(TARGET_LPC2368)   || defined(TARGET_LPC4088) || defined(TARGET_LPC1347)  || defined(TARGET_K64F) \
+	 || defined(TARGET_KL46Z)   || defined(TARGET_STM32F407) || defined(TARGET_F407VG)  || defined(TARGET_STM32F303VC) || defined(TARGET_LPC1549) || defined(TARGET_LPC11U68)
+#      define OS_SCHEDULERSTKSIZE    256
+#  elif defined(TARGET_LPC11U24) || defined(TARGET_LPC11U35_401)  || defined(TARGET_LPC11U35_501) || defined(TARGET_LPC1114) \
+	 || defined(TARGET_LPC812)   || defined(TARGET_KL25Z)         || defined(TARGET_KL05Z)        || defined(TARGET_STM32F100RB)  || defined(TARGET_STM32F051R8)
+#      define OS_SCHEDULERSTKSIZE    128
+#  else
+#    error "no target defined"
+#  endif
+#endif
+
+//   <o>Idle stack size [bytes] <64-4096:8><#/4>
+//   <i> Defines default stack size for the Idle thread.
+#ifndef OS_IDLESTKSIZE
+ #define OS_IDLESTKSIZE         128
+#endif
+
+//   <o>Timer Thread stack size [bytes] <64-4096:8><#/4>
+//   <i> Defines stack size for Timer thread.
+//   <i> Default: 200
+#ifndef OS_TIMERSTKSZ
+ #define OS_TIMERSTKSZ  WORDS_STACK_SIZE
+#endif
+
+// <q>Check for stack overflow
+// <i> Includes the stack checking code for stack overflow.
+// <i> Note that additional code reduces the Kernel performance.
+#ifndef OS_STKCHECK
+ #define OS_STKCHECK    1
+#endif
+
+// <o>Processor mode for thread execution 
+//   <0=> Unprivileged mode 
+//   <1=> Privileged mode
+// <i> Default: Privileged mode
+#ifndef OS_RUNPRIV
+ #define OS_RUNPRIV     1
+#endif
+
+// </h>
+// <h>SysTick Timer Configuration
+// ==============================
+//
+//   <o>Timer clock value [Hz] <1-1000000000>
+//   <i> Defines the timer clock value.
+//   <i> Default: 6000000  (6MHz)
+#ifndef OS_CLOCK
+#  if defined(TARGET_LPC1768) || defined(TARGET_LPC2368)
+#    define OS_CLOCK       96000000
+
+#  elif defined(TARGET_LPC1347) || defined(TARGET_STM32F303VC) || defined(TARGET_LPC1549)
+#    define OS_CLOCK       72000000
+
+#  elif defined(TARGET_LPC11U24) || defined(TARGET_LPC11U35_401)  || defined(TARGET_LPC11U35_501) || defined(TARGET_LPC1114) || defined(TARGET_KL25Z) || defined(TARGET_KL05Z) || defined(TARGET_KL46Z) || defined(TARGET_STM32F051R8) || defined(TARGET_LPC11U68)
+#    define OS_CLOCK       48000000
+
+#  elif defined(TARGET_LPC812)
+#    define OS_CLOCK       36000000
+
+#  elif  defined(TARGET_STM32F100RB)
+#    define OS_CLOCK       24000000
+
+#  elif defined(TARGET_LPC4088) || defined(TARGET_K64F)
+#    define OS_CLOCK       120000000
+
+#  elif defined(TARGET_STM32F407) || defined(TARGET_F407VG)
+#    define OS_CLOCK       168000000
+
+#  else
+#    error "no target defined"
+#  endif
+#endif
+
+//   <o>Timer tick value [us] <1-1000000>
+//   <i> Defines the timer tick value.
+//   <i> Default: 1000  (1ms)
+#ifndef OS_TICK
+ #define OS_TICK        1000
+#endif
+
+// </h>
+
+// <h>System Configuration
+// =======================
+//
+// <e>Round-Robin Thread switching
+// ===============================
+//
+// <i> Enables Round-Robin Thread switching.
+#ifndef OS_ROBIN
+ #define OS_ROBIN       1
+#endif
+
+//   <o>Round-Robin Timeout [ticks] <1-1000>
+//   <i> Defines how long a thread will execute before a thread switch.
+//   <i> Default: 5
+#ifndef OS_ROBINTOUT
+ #define OS_ROBINTOUT   5
+#endif
+
+// </e>
+
+// <e>User Timers
+// ==============
+//   <i> Enables user Timers
+#ifndef OS_TIMERS
+ #define OS_TIMERS      1
+#endif
+
+//   <o>Timer Thread Priority
+//                        <1=> Low
+//                        <2=> Below Normal
+//                        <3=> Normal
+//                        <4=> Above Normal
+//                        <5=> High
+//                        <6=> Realtime (highest)
+//   <i> Defines priority for Timer Thread
+//   <i> Default: High
+#ifndef OS_TIMERPRIO
+ #define OS_TIMERPRIO   5
+#endif
+
+//   <o>Timer Callback Queue size <1-32>
+//   <i> Number of concurrent active timer callback functions.
+//   <i> Default: 4
+#ifndef OS_TIMERCBQSZ
+ #define OS_TIMERCBQS   4
+#endif
+
+// </e>
+
+//   <o>ISR FIFO Queue size<4=>   4 entries  <8=>   8 entries
+//                         <12=> 12 entries  <16=> 16 entries
+//                         <24=> 24 entries  <32=> 32 entries
+//                         <48=> 48 entries  <64=> 64 entries
+//                         <96=> 96 entries
+//   <i> ISR functions store requests to this buffer,
+//   <i> when they are called from the interrupt handler.
+//   <i> Default: 16 entries
+#ifndef OS_FIFOSZ
+ #define OS_FIFOSZ      16
+#endif
+
+// </h>
+
+//------------- <<< end of configuration section >>> -----------------------
+
+// Standard library system mutexes
+// ===============================
+//  Define max. number system mutexes that are used to protect 
+//  the arm standard runtime library. For microlib they are not used.
+#ifndef OS_MUTEXCNT
+ #define OS_MUTEXCNT    12
+#endif
+
+/*----------------------------------------------------------------------------
+ *      RTX User configuration part END
+ *---------------------------------------------------------------------------*/
+
+#define OS_TRV          ((uint32_t)(((double)OS_CLOCK*(double)OS_TICK)/1E6)-1)
+
+
+/*----------------------------------------------------------------------------
+ *      OS Idle daemon
+ *---------------------------------------------------------------------------*/
+void os_idle_demon (void) {
+  /* The idle demon is a system thread, running when no other thread is      */
+  /* ready to run.                                                           */
+  
+  /* Sleep: ideally, we should put the chip to sleep.
+     Unfortunately, this usually requires disconnecting the interface chip (debugger).
+     This can be done, but it would break the local file system.
+  */
+  for (;;) {
+      // sleep();
+  }
+}
+
+/*----------------------------------------------------------------------------
+ *      RTX Errors
+ *---------------------------------------------------------------------------*/
+extern void mbed_die(void);
+
+void os_error (uint32_t err_code) {
+    /* This function is called when a runtime error is detected. Parameter     */
+    /* 'err_code' holds the runtime error code (defined in RTX_Conf.h).      */
+    mbed_die();
+}
+
+void sysThreadError(osStatus status) {
+    if (status != osOK) {
+        mbed_die();
+    }
+}
+
+/*----------------------------------------------------------------------------
+ *      RTX Configuration Functions
+ *---------------------------------------------------------------------------*/
+
+#include "RTX_CM_lib.h"
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_ARM/HAL_CM0.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_ARM/HAL_CM0.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,301 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM0.C
+ *      Purpose: Hardware Abstraction Layer for Cortex-M0
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_HAL_CM.h"
+#include "rt_Task.h"
+#include "rt_MemBox.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_set_PSP ------------------------------------*/
+
+__asm void rt_set_PSP (U32 stack) {
+        MSR     PSP,R0
+        BX      LR
+}
+
+
+/*--------------------------- rt_get_PSP ------------------------------------*/
+
+__asm U32 rt_get_PSP (void) {
+        MRS     R0,PSP
+        BX      LR
+}
+
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+__asm void os_set_env (void) {
+   /* Switch to Unprivileged/Privileged Thread mode, use PSP. */
+        MOV     R0,SP                   ; PSP = MSP
+        MSR     PSP,R0
+        LDR     R0,=__cpp(&os_flags)
+        LDRB    R0,[R0]
+        LSLS    R0,#31
+        BNE     PrivilegedE
+        MOVS    R0,#0x03                ; Unprivileged Thread mode, use PSP
+        MSR     CONTROL,R0
+        BX      LR
+PrivilegedE
+        MOVS    R0,#0x02                ; Privileged Thread mode, use PSP
+        MSR     CONTROL,R0
+        BX      LR
+
+        ALIGN
+}
+
+
+/*--------------------------- _alloc_box ------------------------------------*/
+
+__asm void *_alloc_box (void *box_mem) {
+   /* Function wrapper for Unprivileged/Privileged mode. */
+        LDR     R3,=__cpp(rt_alloc_box)
+        MOV     R12,R3
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BNE     PrivilegedA
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BEQ     PrivilegedA
+        SVC     0
+        BX      LR
+PrivilegedA
+        BX      R12
+
+        ALIGN
+}
+
+
+/*--------------------------- _free_box -------------------------------------*/
+
+__asm int _free_box (void *box_mem, void *box) {
+   /* Function wrapper for Unprivileged/Privileged mode. */
+        LDR     R3,=__cpp(rt_free_box)
+        MOV     R12,R3
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BNE     PrivilegedF
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BEQ     PrivilegedF
+        SVC     0
+        BX      LR
+PrivilegedF
+        BX      R12
+
+        ALIGN
+}
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+__asm void SVC_Handler (void) {
+        PRESERVE8
+
+        IMPORT  SVC_Count
+        IMPORT  SVC_Table
+        IMPORT  rt_stk_check
+
+        MRS     R0,PSP                  ; Read PSP
+        LDR     R1,[R0,#24]             ; Read Saved PC from Stack
+        SUBS    R1,R1,#2                ; Point to SVC Instruction
+        LDRB    R1,[R1]                 ; Load SVC Number
+        CMP     R1,#0
+        BNE     SVC_User                ; User SVC Number > 0
+
+        MOV     LR,R4
+        LDMIA   R0,{R0-R3,R4}           ; Read R0-R3,R12 from stack
+        MOV     R12,R4
+        MOV     R4,LR
+        BLX     R12                     ; Call SVC Function 
+
+        MRS     R3,PSP                  ; Read PSP
+        STMIA   R3!,{R0-R2}             ; Store return values
+
+        LDR     R3,=__cpp(&os_tsk)
+        LDMIA   R3!,{R1,R2}             ; os_tsk.run, os_tsk.new
+        CMP     R1,R2
+        BEQ     SVC_Exit                ; no task switch
+
+        SUBS    R3,#8
+        CMP     R1,#0                   ; Runtask deleted?
+        BEQ     SVC_Next
+
+        MRS     R0,PSP                  ; Read PSP
+        SUBS    R0,R0,#32               ; Adjust Start Address
+        STR     R0,[R1,#TCB_TSTACK]     ; Update os_tsk.run->tsk_stack       
+        STMIA   R0!,{R4-R7}             ; Save old context (R4-R7)
+        MOV     R4,R8
+        MOV     R5,R9
+        MOV     R6,R10
+        MOV     R7,R11
+        STMIA   R0!,{R4-R7}             ; Save old context (R8-R11)
+        
+        PUSH    {R2,R3}
+        BL      rt_stk_check            ; Check for Stack overflow
+        POP     {R2,R3}
+
+SVC_Next
+        STR     R2,[R3]                 ; os_tsk.run = os_tsk.new
+
+        LDR     R0,[R2,#TCB_TSTACK]     ; os_tsk.new->tsk_stack
+        ADDS    R0,R0,#16               ; Adjust Start Address
+        LDMIA   R0!,{R4-R7}             ; Restore new Context (R8-R11)
+        MOV     R8,R4
+        MOV     R9,R5
+        MOV     R10,R6
+        MOV     R11,R7
+        MSR     PSP,R0                  ; Write PSP
+        SUBS    R0,R0,#32               ; Adjust Start Address
+        LDMIA   R0!,{R4-R7}             ; Restore new Context (R4-R7)
+
+SVC_Exit
+        MOVS    R0,#:NOT:0xFFFFFFFD     ; Set EXC_RETURN value
+        MVNS    R0,R0
+        BX      R0                      ; RETI to Thread Mode, use PSP
+
+        /*------------------- User SVC ------------------------------*/
+
+SVC_User
+        PUSH    {R4,LR}                 ; Save Registers
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                ; Overflow
+
+        LDR     R4,=SVC_Table-4
+        LSLS    R1,R1,#2
+        LDR     R4,[R4,R1]              ; Load SVC Function Address
+        MOV     LR,R4
+
+        LDMIA   R0,{R0-R3,R4}           ; Read R0-R3,R12 from stack
+        MOV     R12,R4
+        BLX     LR                      ; Call SVC Function
+
+        MRS     R4,PSP                  ; Read PSP
+        STMIA   R4!,{R0-R3}             ; Function return values
+SVC_Done
+        POP     {R4,PC}                 ; RETI
+
+        ALIGN
+}
+
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+__asm void PendSV_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(rt_pop_req)
+
+Sys_Switch
+        LDR     R3,=__cpp(&os_tsk)
+        LDMIA   R3!,{R1,R2}             ; os_tsk.run, os_tsk.new
+        CMP     R1,R2
+        BEQ     Sys_Exit                ; no task switch
+
+        SUBS    R3,#8
+
+        MRS     R0,PSP                  ; Read PSP
+        SUBS    R0,R0,#32               ; Adjust Start Address
+        STR     R0,[R1,#TCB_TSTACK]     ; Update os_tsk.run->tsk_stack
+        STMIA   R0!,{R4-R7}             ; Save old context (R4-R7)
+        MOV     R4,R8
+        MOV     R5,R9
+        MOV     R6,R10
+        MOV     R7,R11
+        STMIA   R0!,{R4-R7}             ; Save old context (R8-R11)
+        
+        PUSH    {R2,R3}
+        BL      rt_stk_check            ; Check for Stack overflow
+        POP     {R2,R3}
+
+        STR     R2,[R3]                 ; os_tsk.run = os_tsk.new
+
+        LDR     R0,[R2,#TCB_TSTACK]     ; os_tsk.new->tsk_stack
+        ADDS    R0,R0,#16               ; Adjust Start Address
+        LDMIA   R0!,{R4-R7}             ; Restore new Context (R8-R11)
+        MOV     R8,R4
+        MOV     R9,R5
+        MOV     R10,R6
+        MOV     R11,R7
+        MSR     PSP,R0                  ; Write PSP
+        SUBS    R0,R0,#32               ; Adjust Start Address
+        LDMIA   R0!,{R4-R7}             ; Restore new Context (R4-R7)
+
+Sys_Exit
+        MOVS    R0,#:NOT:0xFFFFFFFD     ; Set EXC_RETURN value
+        MVNS    R0,R0
+        BX      R0                      ; RETI to Thread Mode, use PSP
+
+        ALIGN
+}
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+__asm void SysTick_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(rt_systick)
+        B       Sys_Switch
+
+        ALIGN
+}
+
+
+/*-------------------------- OS_Tick_Handler --------------------------------*/
+
+__asm void OS_Tick_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(os_tick_irqack)
+        BL      __cpp(rt_systick)
+        B       Sys_Switch
+
+        ALIGN
+}
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_ARM/SVC_Table.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_ARM/SVC_Table.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,57 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.60
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+; * All rights reserved.
+; * Redistribution and use in source and binary forms, with or without
+; * modification, are permitted provided that the following conditions are met:
+; *  - Redistributions of source code must retain the above copyright
+; *    notice, this list of conditions and the following disclaimer.
+; *  - Redistributions in binary form must reproduce the above copyright
+; *    notice, this list of conditions and the following disclaimer in the
+; *    documentation and/or other materials provided with the distribution.
+; *  - Neither the name of ARM  nor the names of its contributors may be used 
+; *    to endorse or promote products derived from this software without 
+; *    specific prior written permission.
+; *
+; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+; * POSSIBILITY OF SUCH DAMAGE.
+; *---------------------------------------------------------------------------*/
+
+
+                AREA    SVC_TABLE, CODE, READONLY
+
+                EXPORT  SVC_Count
+
+SVC_Cnt         EQU    (SVC_End-SVC_Table)/4
+SVC_Count       DCD     SVC_Cnt
+
+; Import user SVC functions here.
+;               IMPORT  __SVC_1
+
+                EXPORT  SVC_Table
+SVC_Table
+; Insert user SVC functions here. SVC 0 used by RTL Kernel.
+;               DCD     __SVC_1                 ; user SVC function
+
+SVC_End
+
+                END
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_GCC/HAL_CM0.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_GCC/HAL_CM0.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,370 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM0.S
+ *      Purpose: Hardware Abstraction Layer for Cortex-M0
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+        .file   "HAL_CM0.S"
+        .syntax unified
+
+        .equ    TCB_TSTACK, 36
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+        .thumb
+
+        .section ".text"
+        .align  2
+
+
+/*--------------------------- rt_set_PSP ------------------------------------*/
+
+#       void rt_set_PSP (U32 stack);
+
+        .thumb_func
+        .type   rt_set_PSP, %function
+        .global rt_set_PSP
+rt_set_PSP:
+        .fnstart
+        .cantunwind
+
+        MSR     PSP,R0
+        BX      LR
+
+        .fnend
+        .size   rt_set_PSP, .-rt_set_PSP
+
+
+/*--------------------------- rt_get_PSP ------------------------------------*/
+
+#       U32 rt_get_PSP (void);
+
+        .thumb_func
+        .type   rt_get_PSP, %function
+        .global rt_get_PSP
+rt_get_PSP:
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP
+        BX      LR
+
+        .fnend
+        .size   rt_get_PSP, .-rt_get_PSP
+
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+#       void os_set_env (void);
+        /* Switch to Unprivileged/Privileged Thread mode, use PSP. */
+
+        .thumb_func
+        .type   os_set_env, %function
+        .global os_set_env
+os_set_env:
+        .fnstart
+        .cantunwind
+
+        MOV     R0,SP                   /* PSP = MSP */
+        MSR     PSP,R0
+        LDR     R0,=os_flags
+        LDRB    R0,[R0]
+        LSLS    R0,#31
+        BNE     PrivilegedE
+        MOVS    R0,#0x03                /* Unprivileged Thread mode, use PSP */
+        MSR     CONTROL,R0
+        BX      LR
+PrivilegedE:
+        MOVS    R0,#0x02                /* Privileged Thread mode, use PSP */
+        MSR     CONTROL,R0
+        BX      LR
+
+        .fnend
+        .size   os_set_env, .-os_set_env
+
+
+/*--------------------------- _alloc_box ------------------------------------*/
+
+#      void *_alloc_box (void *box_mem);
+       /* Function wrapper for Unprivileged/Privileged mode. */
+
+        .thumb_func
+        .type   _alloc_box, %function
+        .global _alloc_box
+_alloc_box:
+        .fnstart
+        .cantunwind
+
+        LDR     R3,=rt_alloc_box
+        MOV     R12,R3
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BNE     PrivilegedA
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BEQ     PrivilegedA
+        SVC     0
+        BX      LR
+PrivilegedA:
+        BX      R12
+
+        .fnend
+        .size   _alloc_box, .-_alloc_box
+
+
+/*--------------------------- _free_box -------------------------------------*/
+
+#       int _free_box (void *box_mem, void *box);
+        /* Function wrapper for Unprivileged/Privileged mode. */
+
+        .thumb_func
+        .type   _free_box, %function
+        .global _free_box
+_free_box:
+        .fnstart
+        .cantunwind
+
+        LDR     R3,=rt_free_box
+        MOV     R12,R3
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BNE     PrivilegedF
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BEQ     PrivilegedF
+        SVC     0
+        BX      LR
+PrivilegedF:
+        BX      R12
+
+        .fnend
+        .size   _free_box, .-_free_box
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+#       void SVC_Handler (void);
+
+        .thumb_func
+        .type   SVC_Handler, %function
+        .global SVC_Handler
+SVC_Handler:
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP                  /* Read PSP */
+        LDR     R1,[R0,#24]             /* Read Saved PC from Stack */
+        SUBS    R1,R1,#2                /* Point to SVC Instruction */
+        LDRB    R1,[R1]                 /* Load SVC Number */
+        CMP     R1,#0
+        BNE     SVC_User                /* User SVC Number > 0 */
+
+        MOV     LR,R4
+        LDMIA   R0,{R0-R3,R4}           /* Read R0-R3,R12 from stack */
+        MOV     R12,R4
+        MOV     R4,LR
+        BLX     R12                     /* Call SVC Function */
+
+        MRS     R3,PSP                  /* Read PSP */
+        STMIA   R3!,{R0-R2}             /* Store return values */
+
+        LDR     R3,=os_tsk
+        LDMIA   R3!,{R1,R2}             /* os_tsk.run, os_tsk.new */
+        CMP     R1,R2
+        BEQ     SVC_Exit                /* no task switch */
+
+        SUBS    R3,#8
+        CMP     R1,#0                   /* Runtask deleted? */
+        BEQ     SVC_Next
+
+        MRS     R0,PSP                  /* Read PSP */
+        SUBS    R0,R0,#32               /* Adjust Start Address */
+        STR     R0,[R1,#TCB_TSTACK]     /* Update os_tsk.run->tsk_stack */       
+        STMIA   R0!,{R4-R7}             /* Save old context (R4-R7) */
+        MOV     R4,R8
+        MOV     R5,R9
+        MOV     R6,R10
+        MOV     R7,R11
+        STMIA   R0!,{R4-R7}             /* Save old context (R8-R11) */
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            /* Check for Stack overflow */
+        POP     {R2,R3}
+
+SVC_Next:
+        STR     R2,[R3]                 /* os_tsk.run = os_tsk.new */
+
+        LDR     R0,[R2,#TCB_TSTACK]     /* os_tsk.new->tsk_stack */
+        ADDS    R0,R0,#16               /* Adjust Start Address */
+        LDMIA   R0!,{R4-R7}             /* Restore new Context (R8-R11) */
+        MOV     R8,R4
+        MOV     R9,R5
+        MOV     R10,R6
+        MOV     R11,R7
+        MSR     PSP,R0                  /* Write PSP */
+        SUBS    R0,R0,#32               /* Adjust Start Address */
+        LDMIA   R0!,{R4-R7}             /* Restore new Context (R4-R7) */
+
+SVC_Exit:
+        MOVS    R0,#~0xFFFFFFFD         /* Set EXC_RETURN value */
+        MVNS    R0,R0
+        BX      R0                      /* RETI to Thread Mode, use PSP */
+
+        /*------------------- User SVC ------------------------------*/
+
+SVC_User:
+        PUSH    {R4,LR}                 /* Save Registers */
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                /* Overflow */
+
+        LDR     R4,=SVC_Table-4
+        LSLS    R1,R1,#2
+        LDR     R4,[R4,R1]              /* Load SVC Function Address */
+        MOV     LR,R4
+
+        LDMIA   R0,{R0-R3,R4}           /* Read R0-R3,R12 from stack */
+        MOV     R12,R4
+        BLX     LR                      /* Call SVC Function */
+
+        MRS     R4,PSP                  /* Read PSP */
+        STMIA   R4!,{R0-R3}             /* Function return values */
+SVC_Done:
+        POP     {R4,PC}                 /* RETI */
+
+        .fnend
+        .size   SVC_Handler, .-SVC_Handler
+        
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+#       void PendSV_Handler (void);
+
+        .thumb_func
+        .type   PendSV_Handler, %function
+        .global PendSV_Handler
+        .global Sys_Switch
+PendSV_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      rt_pop_req
+
+Sys_Switch:
+        LDR     R3,=os_tsk
+        LDMIA   R3!,{R1,R2}             /* os_tsk.run, os_tsk.new */
+        CMP     R1,R2
+        BEQ     Sys_Exit                /* no task switch */
+
+        SUBS    R3,#8
+
+        MRS     R0,PSP                  /* Read PSP */
+        SUBS    R0,R0,#32               /* Adjust Start Address */
+        STR     R0,[R1,#TCB_TSTACK]     /* Update os_tsk.run->tsk_stack */
+        STMIA   R0!,{R4-R7}             /* Save old context (R4-R7) */
+        MOV     R4,R8
+        MOV     R5,R9
+        MOV     R6,R10
+        MOV     R7,R11
+        STMIA   R0!,{R4-R7}             /* Save old context (R8-R11) */
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            /* Check for Stack overflow */
+        POP     {R2,R3}
+
+        STR     R2,[R3]                 /* os_tsk.run = os_tsk.new */
+
+        LDR     R0,[R2,#TCB_TSTACK]     /* os_tsk.new->tsk_stack */
+        ADDS    R0,R0,#16               /* Adjust Start Address */
+        LDMIA   R0!,{R4-R7}             /* Restore new Context (R8-R11) */
+        MOV     R8,R4
+        MOV     R9,R5
+        MOV     R10,R6
+        MOV     R11,R7
+        MSR     PSP,R0                  /* Write PSP */
+        SUBS    R0,R0,#32               /* Adjust Start Address */
+        LDMIA   R0!,{R4-R7}             /* Restore new Context (R4-R7) */
+
+Sys_Exit:
+        MOVS    R0,#~0xFFFFFFFD         /* Set EXC_RETURN value */
+        MVNS    R0,R0
+        BX      R0                      /* RETI to Thread Mode, use PSP */
+
+        .fnend
+        .size   PendSV_Handler, .-PendSV_Handler
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+#       void SysTick_Handler (void);
+
+        .thumb_func
+        .type   SysTick_Handler, %function
+        .global SysTick_Handler
+SysTick_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      rt_systick
+        B       Sys_Switch
+
+        .fnend
+        .size   SysTick_Handler, .-SysTick_Handler
+
+
+/*-------------------------- OS_Tick_Handler --------------------------------*/
+
+#       void OS_Tick_Handler (void);
+
+        .thumb_func
+        .type   OS_Tick_Handler, %function
+        .global OS_Tick_Handler
+OS_Tick_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      os_tick_irqack
+        BL      rt_systick
+        B       Sys_Switch
+
+        .fnend
+        .size   OS_Tick_Handler, .-OS_Tick_Handler
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_GCC/SVC_Table.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M0/TOOLCHAIN_GCC/SVC_Table.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,56 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.60
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+; * All rights reserved.
+; * Redistribution and use in source and binary forms, with or without
+; * modification, are permitted provided that the following conditions are met:
+; *  - Redistributions of source code must retain the above copyright
+; *    notice, this list of conditions and the following disclaimer.
+; *  - Redistributions in binary form must reproduce the above copyright
+; *    notice, this list of conditions and the following disclaimer in the
+; *    documentation and/or other materials provided with the distribution.
+; *  - Neither the name of ARM  nor the names of its contributors may be used 
+; *    to endorse or promote products derived from this software without 
+; *    specific prior written permission.
+; *
+; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+; * POSSIBILITY OF SUCH DAMAGE.
+; *---------------------------------------------------------------------------*/
+
+
+        .file   "SVC_Table.S"
+
+
+        .section ".svc_table"
+
+        .global  SVC_Table
+SVC_Table:
+/* Insert user SVC functions here. SVC 0 used by RTL Kernel. */
+#       .long   __SVC_1                 /* user SVC function */
+SVC_End:
+
+        .global  SVC_Count
+SVC_Count:
+        .long   (SVC_End-SVC_Table)/4
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_ARM/HAL_CM0.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_ARM/HAL_CM0.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,301 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM0.C
+ *      Purpose: Hardware Abstraction Layer for Cortex-M0
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_HAL_CM.h"
+#include "rt_Task.h"
+#include "rt_MemBox.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_set_PSP ------------------------------------*/
+
+__asm void rt_set_PSP (U32 stack) {
+        MSR     PSP,R0
+        BX      LR
+}
+
+
+/*--------------------------- rt_get_PSP ------------------------------------*/
+
+__asm U32 rt_get_PSP (void) {
+        MRS     R0,PSP
+        BX      LR
+}
+
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+__asm void os_set_env (void) {
+   /* Switch to Unprivileged/Privileged Thread mode, use PSP. */
+        MOV     R0,SP                   ; PSP = MSP
+        MSR     PSP,R0
+        LDR     R0,=__cpp(&os_flags)
+        LDRB    R0,[R0]
+        LSLS    R0,#31
+        BNE     PrivilegedE
+        MOVS    R0,#0x03                ; Unprivileged Thread mode, use PSP
+        MSR     CONTROL,R0
+        BX      LR
+PrivilegedE
+        MOVS    R0,#0x02                ; Privileged Thread mode, use PSP
+        MSR     CONTROL,R0
+        BX      LR
+
+        ALIGN
+}
+
+
+/*--------------------------- _alloc_box ------------------------------------*/
+
+__asm void *_alloc_box (void *box_mem) {
+   /* Function wrapper for Unprivileged/Privileged mode. */
+        LDR     R3,=__cpp(rt_alloc_box)
+        MOV     R12,R3
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BNE     PrivilegedA
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BEQ     PrivilegedA
+        SVC     0
+        BX      LR
+PrivilegedA
+        BX      R12
+
+        ALIGN
+}
+
+
+/*--------------------------- _free_box -------------------------------------*/
+
+__asm int _free_box (void *box_mem, void *box) {
+   /* Function wrapper for Unprivileged/Privileged mode. */
+        LDR     R3,=__cpp(rt_free_box)
+        MOV     R12,R3
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BNE     PrivilegedF
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BEQ     PrivilegedF
+        SVC     0
+        BX      LR
+PrivilegedF
+        BX      R12
+
+        ALIGN
+}
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+__asm void SVC_Handler (void) {
+        PRESERVE8
+
+        IMPORT  SVC_Count
+        IMPORT  SVC_Table
+        IMPORT  rt_stk_check
+
+        MRS     R0,PSP                  ; Read PSP
+        LDR     R1,[R0,#24]             ; Read Saved PC from Stack
+        SUBS    R1,R1,#2                ; Point to SVC Instruction
+        LDRB    R1,[R1]                 ; Load SVC Number
+        CMP     R1,#0
+        BNE     SVC_User                ; User SVC Number > 0
+
+        MOV     LR,R4
+        LDMIA   R0,{R0-R3,R4}           ; Read R0-R3,R12 from stack
+        MOV     R12,R4
+        MOV     R4,LR
+        BLX     R12                     ; Call SVC Function 
+
+        MRS     R3,PSP                  ; Read PSP
+        STMIA   R3!,{R0-R2}             ; Store return values
+
+        LDR     R3,=__cpp(&os_tsk)
+        LDMIA   R3!,{R1,R2}             ; os_tsk.run, os_tsk.new
+        CMP     R1,R2
+        BEQ     SVC_Exit                ; no task switch
+
+        SUBS    R3,#8
+        CMP     R1,#0                   ; Runtask deleted?
+        BEQ     SVC_Next
+
+        MRS     R0,PSP                  ; Read PSP
+        SUBS    R0,R0,#32               ; Adjust Start Address
+        STR     R0,[R1,#TCB_TSTACK]     ; Update os_tsk.run->tsk_stack       
+        STMIA   R0!,{R4-R7}             ; Save old context (R4-R7)
+        MOV     R4,R8
+        MOV     R5,R9
+        MOV     R6,R10
+        MOV     R7,R11
+        STMIA   R0!,{R4-R7}             ; Save old context (R8-R11)
+        
+        PUSH    {R2,R3}
+        BL      rt_stk_check            ; Check for Stack overflow
+        POP     {R2,R3}
+
+SVC_Next
+        STR     R2,[R3]                 ; os_tsk.run = os_tsk.new
+
+        LDR     R0,[R2,#TCB_TSTACK]     ; os_tsk.new->tsk_stack
+        ADDS    R0,R0,#16               ; Adjust Start Address
+        LDMIA   R0!,{R4-R7}             ; Restore new Context (R8-R11)
+        MOV     R8,R4
+        MOV     R9,R5
+        MOV     R10,R6
+        MOV     R11,R7
+        MSR     PSP,R0                  ; Write PSP
+        SUBS    R0,R0,#32               ; Adjust Start Address
+        LDMIA   R0!,{R4-R7}             ; Restore new Context (R4-R7)
+
+SVC_Exit
+        MOVS    R0,#:NOT:0xFFFFFFFD     ; Set EXC_RETURN value
+        MVNS    R0,R0
+        BX      R0                      ; RETI to Thread Mode, use PSP
+
+        /*------------------- User SVC ------------------------------*/
+
+SVC_User
+        PUSH    {R4,LR}                 ; Save Registers
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                ; Overflow
+
+        LDR     R4,=SVC_Table-4
+        LSLS    R1,R1,#2
+        LDR     R4,[R4,R1]              ; Load SVC Function Address
+        MOV     LR,R4
+
+        LDMIA   R0,{R0-R3,R4}           ; Read R0-R3,R12 from stack
+        MOV     R12,R4
+        BLX     LR                      ; Call SVC Function
+
+        MRS     R4,PSP                  ; Read PSP
+        STMIA   R4!,{R0-R3}             ; Function return values
+SVC_Done
+        POP     {R4,PC}                 ; RETI
+
+        ALIGN
+}
+
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+__asm void PendSV_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(rt_pop_req)
+
+Sys_Switch
+        LDR     R3,=__cpp(&os_tsk)
+        LDMIA   R3!,{R1,R2}             ; os_tsk.run, os_tsk.new
+        CMP     R1,R2
+        BEQ     Sys_Exit                ; no task switch
+
+        SUBS    R3,#8
+
+        MRS     R0,PSP                  ; Read PSP
+        SUBS    R0,R0,#32               ; Adjust Start Address
+        STR     R0,[R1,#TCB_TSTACK]     ; Update os_tsk.run->tsk_stack
+        STMIA   R0!,{R4-R7}             ; Save old context (R4-R7)
+        MOV     R4,R8
+        MOV     R5,R9
+        MOV     R6,R10
+        MOV     R7,R11
+        STMIA   R0!,{R4-R7}             ; Save old context (R8-R11)
+        
+        PUSH    {R2,R3}
+        BL      rt_stk_check            ; Check for Stack overflow
+        POP     {R2,R3}
+
+        STR     R2,[R3]                 ; os_tsk.run = os_tsk.new
+
+        LDR     R0,[R2,#TCB_TSTACK]     ; os_tsk.new->tsk_stack
+        ADDS    R0,R0,#16               ; Adjust Start Address
+        LDMIA   R0!,{R4-R7}             ; Restore new Context (R8-R11)
+        MOV     R8,R4
+        MOV     R9,R5
+        MOV     R10,R6
+        MOV     R11,R7
+        MSR     PSP,R0                  ; Write PSP
+        SUBS    R0,R0,#32               ; Adjust Start Address
+        LDMIA   R0!,{R4-R7}             ; Restore new Context (R4-R7)
+
+Sys_Exit
+        MOVS    R0,#:NOT:0xFFFFFFFD     ; Set EXC_RETURN value
+        MVNS    R0,R0
+        BX      R0                      ; RETI to Thread Mode, use PSP
+
+        ALIGN
+}
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+__asm void SysTick_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(rt_systick)
+        B       Sys_Switch
+
+        ALIGN
+}
+
+
+/*-------------------------- OS_Tick_Handler --------------------------------*/
+
+__asm void OS_Tick_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(os_tick_irqack)
+        BL      __cpp(rt_systick)
+        B       Sys_Switch
+
+        ALIGN
+}
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_ARM/SVC_Table.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_ARM/SVC_Table.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,57 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.60
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+; * All rights reserved.
+; * Redistribution and use in source and binary forms, with or without
+; * modification, are permitted provided that the following conditions are met:
+; *  - Redistributions of source code must retain the above copyright
+; *    notice, this list of conditions and the following disclaimer.
+; *  - Redistributions in binary form must reproduce the above copyright
+; *    notice, this list of conditions and the following disclaimer in the
+; *    documentation and/or other materials provided with the distribution.
+; *  - Neither the name of ARM  nor the names of its contributors may be used 
+; *    to endorse or promote products derived from this software without 
+; *    specific prior written permission.
+; *
+; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+; * POSSIBILITY OF SUCH DAMAGE.
+; *---------------------------------------------------------------------------*/
+
+
+                AREA    SVC_TABLE, CODE, READONLY
+
+                EXPORT  SVC_Count
+
+SVC_Cnt         EQU    (SVC_End-SVC_Table)/4
+SVC_Count       DCD     SVC_Cnt
+
+; Import user SVC functions here.
+;               IMPORT  __SVC_1
+
+                EXPORT  SVC_Table
+SVC_Table
+; Insert user SVC functions here. SVC 0 used by RTL Kernel.
+;               DCD     __SVC_1                 ; user SVC function
+
+SVC_End
+
+                END
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_GCC/HAL_CM0.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_GCC/HAL_CM0.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,370 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM0.S
+ *      Purpose: Hardware Abstraction Layer for Cortex-M0
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+        .file   "HAL_CM0.S"
+        .syntax unified
+
+        .equ    TCB_TSTACK, 36
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+        .thumb
+
+        .section ".text"
+        .align  2
+
+
+/*--------------------------- rt_set_PSP ------------------------------------*/
+
+#       void rt_set_PSP (U32 stack);
+
+        .thumb_func
+        .type   rt_set_PSP, %function
+        .global rt_set_PSP
+rt_set_PSP:
+        .fnstart
+        .cantunwind
+
+        MSR     PSP,R0
+        BX      LR
+
+        .fnend
+        .size   rt_set_PSP, .-rt_set_PSP
+
+
+/*--------------------------- rt_get_PSP ------------------------------------*/
+
+#       U32 rt_get_PSP (void);
+
+        .thumb_func
+        .type   rt_get_PSP, %function
+        .global rt_get_PSP
+rt_get_PSP:
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP
+        BX      LR
+
+        .fnend
+        .size   rt_get_PSP, .-rt_get_PSP
+
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+#       void os_set_env (void);
+        /* Switch to Unprivileged/Privileged Thread mode, use PSP. */
+
+        .thumb_func
+        .type   os_set_env, %function
+        .global os_set_env
+os_set_env:
+        .fnstart
+        .cantunwind
+
+        MOV     R0,SP                   /* PSP = MSP */
+        MSR     PSP,R0
+        LDR     R0,=os_flags
+        LDRB    R0,[R0]
+        LSLS    R0,#31
+        BNE     PrivilegedE
+        MOVS    R0,#0x03                /* Unprivileged Thread mode, use PSP */
+        MSR     CONTROL,R0
+        BX      LR
+PrivilegedE:
+        MOVS    R0,#0x02                /* Privileged Thread mode, use PSP */
+        MSR     CONTROL,R0
+        BX      LR
+
+        .fnend
+        .size   os_set_env, .-os_set_env
+
+
+/*--------------------------- _alloc_box ------------------------------------*/
+
+#      void *_alloc_box (void *box_mem);
+       /* Function wrapper for Unprivileged/Privileged mode. */
+
+        .thumb_func
+        .type   _alloc_box, %function
+        .global _alloc_box
+_alloc_box:
+        .fnstart
+        .cantunwind
+
+        LDR     R3,=rt_alloc_box
+        MOV     R12,R3
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BNE     PrivilegedA
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BEQ     PrivilegedA
+        SVC     0
+        BX      LR
+PrivilegedA:
+        BX      R12
+
+        .fnend
+        .size   _alloc_box, .-_alloc_box
+
+
+/*--------------------------- _free_box -------------------------------------*/
+
+#       int _free_box (void *box_mem, void *box);
+        /* Function wrapper for Unprivileged/Privileged mode. */
+
+        .thumb_func
+        .type   _free_box, %function
+        .global _free_box
+_free_box:
+        .fnstart
+        .cantunwind
+
+        LDR     R3,=rt_free_box
+        MOV     R12,R3
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BNE     PrivilegedF
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BEQ     PrivilegedF
+        SVC     0
+        BX      LR
+PrivilegedF:
+        BX      R12
+
+        .fnend
+        .size   _free_box, .-_free_box
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+#       void SVC_Handler (void);
+
+        .thumb_func
+        .type   SVC_Handler, %function
+        .global SVC_Handler
+SVC_Handler:
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP                  /* Read PSP */
+        LDR     R1,[R0,#24]             /* Read Saved PC from Stack */
+        SUBS    R1,R1,#2                /* Point to SVC Instruction */
+        LDRB    R1,[R1]                 /* Load SVC Number */
+        CMP     R1,#0
+        BNE     SVC_User                /* User SVC Number > 0 */
+
+        MOV     LR,R4
+        LDMIA   R0,{R0-R3,R4}           /* Read R0-R3,R12 from stack */
+        MOV     R12,R4
+        MOV     R4,LR
+        BLX     R12                     /* Call SVC Function */
+
+        MRS     R3,PSP                  /* Read PSP */
+        STMIA   R3!,{R0-R2}             /* Store return values */
+
+        LDR     R3,=os_tsk
+        LDMIA   R3!,{R1,R2}             /* os_tsk.run, os_tsk.new */
+        CMP     R1,R2
+        BEQ     SVC_Exit                /* no task switch */
+
+        SUBS    R3,#8
+        CMP     R1,#0                   /* Runtask deleted? */
+        BEQ     SVC_Next
+
+        MRS     R0,PSP                  /* Read PSP */
+        SUBS    R0,R0,#32               /* Adjust Start Address */
+        STR     R0,[R1,#TCB_TSTACK]     /* Update os_tsk.run->tsk_stack */       
+        STMIA   R0!,{R4-R7}             /* Save old context (R4-R7) */
+        MOV     R4,R8
+        MOV     R5,R9
+        MOV     R6,R10
+        MOV     R7,R11
+        STMIA   R0!,{R4-R7}             /* Save old context (R8-R11) */
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            /* Check for Stack overflow */
+        POP     {R2,R3}
+
+SVC_Next:
+        STR     R2,[R3]                 /* os_tsk.run = os_tsk.new */
+
+        LDR     R0,[R2,#TCB_TSTACK]     /* os_tsk.new->tsk_stack */
+        ADDS    R0,R0,#16               /* Adjust Start Address */
+        LDMIA   R0!,{R4-R7}             /* Restore new Context (R8-R11) */
+        MOV     R8,R4
+        MOV     R9,R5
+        MOV     R10,R6
+        MOV     R11,R7
+        MSR     PSP,R0                  /* Write PSP */
+        SUBS    R0,R0,#32               /* Adjust Start Address */
+        LDMIA   R0!,{R4-R7}             /* Restore new Context (R4-R7) */
+
+SVC_Exit:
+        MOVS    R0,#~0xFFFFFFFD         /* Set EXC_RETURN value */
+        MVNS    R0,R0
+        BX      R0                      /* RETI to Thread Mode, use PSP */
+
+        /*------------------- User SVC ------------------------------*/
+
+SVC_User:
+        PUSH    {R4,LR}                 /* Save Registers */
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                /* Overflow */
+
+        LDR     R4,=SVC_Table-4
+        LSLS    R1,R1,#2
+        LDR     R4,[R4,R1]              /* Load SVC Function Address */
+        MOV     LR,R4
+
+        LDMIA   R0,{R0-R3,R4}           /* Read R0-R3,R12 from stack */
+        MOV     R12,R4
+        BLX     LR                      /* Call SVC Function */
+
+        MRS     R4,PSP                  /* Read PSP */
+        STMIA   R4!,{R0-R3}             /* Function return values */
+SVC_Done:
+        POP     {R4,PC}                 /* RETI */
+
+        .fnend
+        .size   SVC_Handler, .-SVC_Handler
+        
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+#       void PendSV_Handler (void);
+
+        .thumb_func
+        .type   PendSV_Handler, %function
+        .global PendSV_Handler
+        .global Sys_Switch
+PendSV_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      rt_pop_req
+
+Sys_Switch:
+        LDR     R3,=os_tsk
+        LDMIA   R3!,{R1,R2}             /* os_tsk.run, os_tsk.new */
+        CMP     R1,R2
+        BEQ     Sys_Exit                /* no task switch */
+
+        SUBS    R3,#8
+
+        MRS     R0,PSP                  /* Read PSP */
+        SUBS    R0,R0,#32               /* Adjust Start Address */
+        STR     R0,[R1,#TCB_TSTACK]     /* Update os_tsk.run->tsk_stack */
+        STMIA   R0!,{R4-R7}             /* Save old context (R4-R7) */
+        MOV     R4,R8
+        MOV     R5,R9
+        MOV     R6,R10
+        MOV     R7,R11
+        STMIA   R0!,{R4-R7}             /* Save old context (R8-R11) */
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            /* Check for Stack overflow */
+        POP     {R2,R3}
+
+        STR     R2,[R3]                 /* os_tsk.run = os_tsk.new */
+
+        LDR     R0,[R2,#TCB_TSTACK]     /* os_tsk.new->tsk_stack */
+        ADDS    R0,R0,#16               /* Adjust Start Address */
+        LDMIA   R0!,{R4-R7}             /* Restore new Context (R8-R11) */
+        MOV     R8,R4
+        MOV     R9,R5
+        MOV     R10,R6
+        MOV     R11,R7
+        MSR     PSP,R0                  /* Write PSP */
+        SUBS    R0,R0,#32               /* Adjust Start Address */
+        LDMIA   R0!,{R4-R7}             /* Restore new Context (R4-R7) */
+
+Sys_Exit:
+        MOVS    R0,#~0xFFFFFFFD         /* Set EXC_RETURN value */
+        MVNS    R0,R0
+        BX      R0                      /* RETI to Thread Mode, use PSP */
+
+        .fnend
+        .size   PendSV_Handler, .-PendSV_Handler
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+#       void SysTick_Handler (void);
+
+        .thumb_func
+        .type   SysTick_Handler, %function
+        .global SysTick_Handler
+SysTick_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      rt_systick
+        B       Sys_Switch
+
+        .fnend
+        .size   SysTick_Handler, .-SysTick_Handler
+
+
+/*-------------------------- OS_Tick_Handler --------------------------------*/
+
+#       void OS_Tick_Handler (void);
+
+        .thumb_func
+        .type   OS_Tick_Handler, %function
+        .global OS_Tick_Handler
+OS_Tick_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      os_tick_irqack
+        BL      rt_systick
+        B       Sys_Switch
+
+        .fnend
+        .size   OS_Tick_Handler, .-OS_Tick_Handler
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_GCC/SVC_Table.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M0P/TOOLCHAIN_GCC/SVC_Table.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,56 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.60
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+; * All rights reserved.
+; * Redistribution and use in source and binary forms, with or without
+; * modification, are permitted provided that the following conditions are met:
+; *  - Redistributions of source code must retain the above copyright
+; *    notice, this list of conditions and the following disclaimer.
+; *  - Redistributions in binary form must reproduce the above copyright
+; *    notice, this list of conditions and the following disclaimer in the
+; *    documentation and/or other materials provided with the distribution.
+; *  - Neither the name of ARM  nor the names of its contributors may be used 
+; *    to endorse or promote products derived from this software without 
+; *    specific prior written permission.
+; *
+; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+; * POSSIBILITY OF SUCH DAMAGE.
+; *---------------------------------------------------------------------------*/
+
+
+        .file   "SVC_Table.S"
+
+
+        .section ".svc_table"
+
+        .global  SVC_Table
+SVC_Table:
+/* Insert user SVC functions here. SVC 0 used by RTL Kernel. */
+#       .long   __SVC_1                 /* user SVC function */
+SVC_End:
+
+        .global  SVC_Count
+SVC_Count:
+        .long   (SVC_End-SVC_Table)/4
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_ARM/HAL_CM3.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_ARM/HAL_CM3.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,249 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM3.C
+ *      Purpose: Hardware Abstraction Layer for Cortex-M3
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_HAL_CM.h"
+#include "rt_Task.h"
+#include "rt_MemBox.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_set_PSP ------------------------------------*/
+
+__asm void rt_set_PSP (U32 stack) {
+        MSR     PSP,R0
+        BX      LR
+}
+
+
+/*--------------------------- rt_get_PSP ------------------------------------*/
+
+__asm U32 rt_get_PSP (void) {
+        MRS     R0,PSP
+        BX      LR
+}
+
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+__asm void os_set_env (void) {
+   /* Switch to Unprivileged/Privileged Thread mode, use PSP. */
+        MOV     R0,SP                   ; PSP = MSP
+        MSR     PSP,R0
+        LDR     R0,=__cpp(&os_flags)
+        LDRB    R0,[R0]
+        LSLS    R0,#31
+        MOVNE   R0,#0x02                ; Privileged Thread mode, use PSP
+        MOVEQ   R0,#0x03                ; Unprivileged Thread mode, use PSP
+        MSR     CONTROL,R0
+        BX      LR
+
+        ALIGN
+}
+
+
+/*--------------------------- _alloc_box ------------------------------------*/
+
+__asm void *_alloc_box (void *box_mem) {
+   /* Function wrapper for Unprivileged/Privileged mode. */
+        LDR     R12,=__cpp(rt_alloc_box)
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BXNE    R12
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BXEQ    R12
+        SVC     0
+        BX      LR
+
+        ALIGN
+}
+
+
+/*--------------------------- _free_box -------------------------------------*/
+
+__asm int _free_box (void *box_mem, void *box) {
+   /* Function wrapper for Unprivileged/Privileged mode. */
+        LDR     R12,=__cpp(rt_free_box)
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BXNE    R12
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BXEQ    R12
+        SVC     0
+        BX      LR
+
+        ALIGN
+}
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+__asm void SVC_Handler (void) {
+        PRESERVE8
+
+        IMPORT  SVC_Count
+        IMPORT  SVC_Table
+        IMPORT  rt_stk_check
+
+        MRS     R0,PSP                  ; Read PSP
+        LDR     R1,[R0,#24]             ; Read Saved PC from Stack
+        LDRB    R1,[R1,#-2]             ; Load SVC Number
+        CBNZ    R1,SVC_User
+
+        LDM     R0,{R0-R3,R12}          ; Read R0-R3,R12 from stack
+        BLX     R12                     ; Call SVC Function 
+
+        MRS     R12,PSP                 ; Read PSP
+        STM     R12,{R0-R2}             ; Store return values
+
+        LDR     R3,=__cpp(&os_tsk)
+        LDM     R3,{R1,R2}              ; os_tsk.run, os_tsk.new
+        CMP     R1,R2
+        BEQ     SVC_Exit                ; no task switch
+
+        CBZ     R1,SVC_Next             ; Runtask deleted?
+        STMDB   R12!,{R4-R11}           ; Save Old context
+        STR     R12,[R1,#TCB_TSTACK]    ; Update os_tsk.run->tsk_stack
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            ; Check for Stack overflow
+        POP     {R2,R3}
+
+SVC_Next
+        STR     R2,[R3]                 ; os_tsk.run = os_tsk.new
+
+        LDR     R12,[R2,#TCB_TSTACK]    ; os_tsk.new->tsk_stack
+        LDMIA   R12!,{R4-R11}           ; Restore New Context
+        MSR     PSP,R12                 ; Write PSP
+
+SVC_Exit
+        MVN     LR,#:NOT:0xFFFFFFFD     ; set EXC_RETURN value
+        BX      LR
+
+        /*------------------- User SVC ------------------------------*/
+
+SVC_User
+        PUSH    {R4,LR}                 ; Save Registers
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                ; Overflow
+
+        LDR     R4,=SVC_Table-4
+        LDR     R4,[R4,R1,LSL #2]       ; Load SVC Function Address
+
+        LDM     R0,{R0-R3,R12}          ; Read R0-R3,R12 from stack
+        BLX     R4                      ; Call SVC Function
+
+        MRS     R12,PSP
+        STM     R12,{R0-R3}             ; Function return values
+SVC_Done
+        POP     {R4,PC}                 ; RETI
+
+        ALIGN
+}
+
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+__asm void PendSV_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(rt_pop_req)
+
+Sys_Switch
+        LDR     R3,=__cpp(&os_tsk)
+        LDM     R3,{R1,R2}              ; os_tsk.run, os_tsk.new
+        CMP     R1,R2
+        BEQ     Sys_Exit
+
+        MRS     R12,PSP                 ; Read PSP
+        STMDB   R12!,{R4-R11}           ; Save Old context
+        STR     R12,[R1,#TCB_TSTACK]    ; Update os_tsk.run->tsk_stack
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            ; Check for Stack overflow
+        POP     {R2,R3}
+
+        STR     R2,[R3]                 ; os_tsk.run = os_tsk.new
+
+        LDR     R12,[R2,#TCB_TSTACK]    ; os_tsk.new->tsk_stack
+        LDMIA   R12!,{R4-R11}           ; Restore New Context
+        MSR     PSP,R12                 ; Write PSP
+
+Sys_Exit
+        MVN     LR,#:NOT:0xFFFFFFFD     ; set EXC_RETURN value
+        BX      LR                      ; Return to Thread Mode
+
+        ALIGN
+}
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+__asm void SysTick_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(rt_systick)
+        B       Sys_Switch
+
+        ALIGN
+}
+
+
+/*-------------------------- OS_Tick_Handler --------------------------------*/
+
+__asm void OS_Tick_Handler (void) {
+        PRESERVE8
+
+        BL      __cpp(os_tick_irqack)
+        BL      __cpp(rt_systick)
+        B       Sys_Switch
+
+        ALIGN
+}
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_ARM/SVC_Table.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_ARM/SVC_Table.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,57 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.60
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+; * All rights reserved.
+; * Redistribution and use in source and binary forms, with or without
+; * modification, are permitted provided that the following conditions are met:
+; *  - Redistributions of source code must retain the above copyright
+; *    notice, this list of conditions and the following disclaimer.
+; *  - Redistributions in binary form must reproduce the above copyright
+; *    notice, this list of conditions and the following disclaimer in the
+; *    documentation and/or other materials provided with the distribution.
+; *  - Neither the name of ARM  nor the names of its contributors may be used 
+; *    to endorse or promote products derived from this software without 
+; *    specific prior written permission.
+; *
+; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+; * POSSIBILITY OF SUCH DAMAGE.
+; *---------------------------------------------------------------------------*/
+
+
+                AREA    SVC_TABLE, CODE, READONLY
+
+                EXPORT  SVC_Count
+
+SVC_Cnt         EQU    (SVC_End-SVC_Table)/4
+SVC_Count       DCD     SVC_Cnt
+
+; Import user SVC functions here.
+;               IMPORT  __SVC_1
+
+                EXPORT  SVC_Table
+SVC_Table
+; Insert user SVC functions here. SVC 0 used by RTL Kernel.
+;               DCD     __SVC_1                 ; user SVC function
+
+SVC_End
+
+                END
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_GCC/HAL_CM3.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_GCC/HAL_CM3.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,323 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM3.S
+ *      Purpose: Hardware Abstraction Layer for Cortex-M3
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+        .file   "HAL_CM3.S"
+        .syntax unified
+
+        .equ    TCB_TSTACK, 36
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+        .thumb
+
+        .section ".text"
+        .align  2
+
+
+/*--------------------------- rt_set_PSP ------------------------------------*/
+
+#       void rt_set_PSP (U32 stack);
+
+        .thumb_func
+        .type   rt_set_PSP, %function
+        .global rt_set_PSP
+rt_set_PSP:
+        .fnstart
+        .cantunwind
+
+        MSR     PSP,R0
+        BX      LR
+
+        .fnend
+        .size   rt_set_PSP, .-rt_set_PSP
+
+
+/*--------------------------- rt_get_PSP ------------------------------------*/
+
+#       U32 rt_get_PSP (void);
+
+        .thumb_func
+        .type   rt_get_PSP, %function
+        .global rt_get_PSP
+rt_get_PSP:
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP
+        BX      LR
+
+        .fnend
+        .size   rt_get_PSP, .-rt_get_PSP
+
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+#       void os_set_env (void);
+        /* Switch to Unprivileged/Privileged Thread mode, use PSP. */
+
+        .thumb_func
+        .type   os_set_env, %function
+        .global os_set_env
+os_set_env:
+        .fnstart
+        .cantunwind
+
+        MOV     R0,SP                   /* PSP = MSP */
+        MSR     PSP,R0
+        LDR     R0,=os_flags
+        LDRB    R0,[R0]
+        LSLS    R0,#31
+        ITE     NE
+        MOVNE   R0,#0x02                /* Privileged Thread mode, use PSP */
+        MOVEQ   R0,#0x03                /* Unprivileged Thread mode, use PSP */
+        MSR     CONTROL,R0
+        BX      LR
+
+        .fnend
+        .size   os_set_env, .-os_set_env
+
+
+/*--------------------------- _alloc_box ------------------------------------*/
+
+#      void *_alloc_box (void *box_mem);
+       /* Function wrapper for Unprivileged/Privileged mode. */
+
+        .thumb_func
+        .type   _alloc_box, %function
+        .global _alloc_box
+_alloc_box:
+        .fnstart
+        .cantunwind
+
+        LDR     R12,=rt_alloc_box
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        IT      NE
+        BXNE    R12
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        IT      EQ
+        BXEQ    R12
+        SVC     0
+        BX      LR
+
+        .fnend
+        .size   _alloc_box, .-_alloc_box
+
+
+/*--------------------------- _free_box -------------------------------------*/
+
+#       int _free_box (void *box_mem, void *box);
+        /* Function wrapper for Unprivileged/Privileged mode. */
+
+        .thumb_func
+        .type   _free_box, %function
+        .global _free_box
+_free_box:
+        .fnstart
+        .cantunwind
+
+        LDR     R12,=rt_free_box
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        IT      NE
+        BXNE    R12
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        IT      EQ
+        BXEQ    R12
+        SVC     0
+        BX      LR
+
+        .fnend
+        .size   _free_box, .-_free_box
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+#       void SVC_Handler (void);
+
+        .thumb_func
+        .type   SVC_Handler, %function
+        .global SVC_Handler
+SVC_Handler:
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP                  /* Read PSP */
+        LDR     R1,[R0,#24]             /* Read Saved PC from Stack */
+        LDRB    R1,[R1,#-2]             /* Load SVC Number */
+        CBNZ    R1,SVC_User
+
+        LDM     R0,{R0-R3,R12}          /* Read R0-R3,R12 from stack */
+        BLX     R12                     /* Call SVC Function */
+
+        MRS     R12,PSP                 /* Read PSP */
+        STM     R12,{R0-R2}             /* Store return values */
+
+        LDR     R3,=os_tsk
+        LDM     R3,{R1,R2}              /* os_tsk.run, os_tsk.new */
+        CMP     R1,R2
+        BEQ     SVC_Exit                /* no task switch */
+
+        CBZ     R1,SVC_Next             /* Runtask deleted? */
+        STMDB   R12!,{R4-R11}           /* Save Old context */
+        STR     R12,[R1,#TCB_TSTACK]    /* Update os_tsk.run->tsk_stack */
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            /* Check for Stack overflow */
+        POP     {R2,R3}
+
+SVC_Next:
+        STR     R2,[R3]                 /* os_tsk.run = os_tsk.new */
+
+        LDR     R12,[R2,#TCB_TSTACK]    /* os_tsk.new->tsk_stack */
+        LDMIA   R12!,{R4-R11}           /* Restore New Context */
+        MSR     PSP,R12                 /* Write PSP */
+
+SVC_Exit:
+        MVN     LR,#~0xFFFFFFFD         /* set EXC_RETURN value */
+        BX      LR
+
+        /*------------------- User SVC ------------------------------*/
+
+SVC_User:
+        PUSH    {R4,LR}                 /* Save Registers */
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                /* Overflow */
+
+        LDR     R4,=SVC_Table-4
+        LDR     R4,[R4,R1,LSL #2]       /* Load SVC Function Address */
+
+        LDM     R0,{R0-R3,R12}          /* Read R0-R3,R12 from stack */
+        BLX     R4                      /* Call SVC Function */
+
+        MRS     R12,PSP
+        STM     R12,{R0-R3}             /* Function return values */
+SVC_Done:
+        POP     {R4,PC}                 /* RETI */
+
+        .fnend
+        .size   SVC_Handler, .-SVC_Handler
+        
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+#       void PendSV_Handler (void);
+
+        .thumb_func
+        .type   PendSV_Handler, %function
+        .global PendSV_Handler
+        .global Sys_Switch
+PendSV_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      rt_pop_req
+
+Sys_Switch:
+        LDR     R3,=os_tsk
+        LDM     R3,{R1,R2}              /* os_tsk.run, os_tsk.new */
+        CMP     R1,R2
+        BEQ     Sys_Exit
+
+        MRS     R12,PSP                 /* Read PSP */
+        STMDB   R12!,{R4-R11}           /* Save Old context */
+        STR     R12,[R1,#TCB_TSTACK]    /* Update os_tsk.run->tsk_stack */
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            /* Check for Stack overflow */
+        POP     {R2,R3}
+
+        STR     R2,[R3]                 /* os_tsk.run = os_tsk.new */
+
+        LDR     R12,[R2,#TCB_TSTACK]    /* os_tsk.new->tsk_stack */
+        LDMIA   R12!,{R4-R11}           /* Restore New Context */
+        MSR     PSP,R12                 /* Write PSP */
+
+Sys_Exit:
+        MVN     LR,#~0xFFFFFFFD         /* set EXC_RETURN value */
+        BX      LR                      /* Return to Thread Mode */
+
+        .fnend
+        .size   PendSV_Handler, .-PendSV_Handler
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+#       void SysTick_Handler (void);
+
+        .thumb_func
+        .type   SysTick_Handler, %function
+        .global SysTick_Handler
+SysTick_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      rt_systick
+        B       Sys_Switch
+
+        .fnend
+        .size   SysTick_Handler, .-SysTick_Handler
+
+
+/*-------------------------- OS_Tick_Handler --------------------------------*/
+
+#       void OS_Tick_Handler (void);
+
+        .thumb_func
+        .type   OS_Tick_Handler, %function
+        .global OS_Tick_Handler
+OS_Tick_Handler:
+        .fnstart
+        .cantunwind
+
+        BL      os_tick_irqack
+        BL      rt_systick
+        B       Sys_Switch
+
+        .fnend
+        .size   OS_Tick_Handler, .-OS_Tick_Handler
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_GCC/SVC_Table.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M3/TOOLCHAIN_GCC/SVC_Table.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,56 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.60
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+; * All rights reserved.
+; * Redistribution and use in source and binary forms, with or without
+; * modification, are permitted provided that the following conditions are met:
+; *  - Redistributions of source code must retain the above copyright
+; *    notice, this list of conditions and the following disclaimer.
+; *  - Redistributions in binary form must reproduce the above copyright
+; *    notice, this list of conditions and the following disclaimer in the
+; *    documentation and/or other materials provided with the distribution.
+; *  - Neither the name of ARM  nor the names of its contributors may be used 
+; *    to endorse or promote products derived from this software without 
+; *    specific prior written permission.
+; *
+; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+; * POSSIBILITY OF SUCH DAMAGE.
+; *---------------------------------------------------------------------------*/
+
+
+        .file   "SVC_Table.S"
+
+
+        .section ".svc_table"
+
+        .global  SVC_Table
+SVC_Table:
+/* Insert user SVC functions here. SVC 0 used by RTL Kernel. */
+#       .long   __SVC_1                 /* user SVC function */
+SVC_End:
+
+        .global  SVC_Count
+SVC_Count:
+        .long   (SVC_End-SVC_Table)/4
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_ARM/HAL_CM4.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_ARM/HAL_CM4.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,309 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM4.C
+ *      Purpose: Hardware Abstraction Layer for Cortex-M4
+ *      Rev.:    V4.70
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_HAL_CM.h"
+#include "rt_Task.h"
+#include "rt_MemBox.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_set_PSP ------------------------------------*/
+
+__asm void rt_set_PSP (U32 stack) {
+        MSR     PSP,R0
+        BX      LR
+}
+
+
+/*--------------------------- rt_get_PSP ------------------------------------*/
+
+__asm U32 rt_get_PSP (void) {
+        MRS     R0,PSP
+        BX      LR
+}
+
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+__asm void os_set_env (void) {
+   /* Switch to Unprivileged/Privileged Thread mode, use PSP. */
+        MOV     R0,SP                   ; PSP = MSP
+        MSR     PSP,R0
+        LDR     R0,=__cpp(&os_flags)
+        LDRB    R0,[R0]
+        LSLS    R0,#31
+        MOVNE   R0,#0x02                ; Privileged Thread mode, use PSP
+        MOVEQ   R0,#0x03                ; Unprivileged Thread mode, use PSP
+        MSR     CONTROL,R0
+        BX      LR
+
+        ALIGN
+}
+
+
+/*--------------------------- _alloc_box ------------------------------------*/
+
+__asm void *_alloc_box (void *box_mem) {
+   /* Function wrapper for Unprivileged/Privileged mode. */
+        LDR     R12,=__cpp(rt_alloc_box)
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BXNE    R12
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BXEQ    R12
+        SVC     0
+        BX      LR
+
+        ALIGN
+}
+
+
+/*--------------------------- _free_box -------------------------------------*/
+
+__asm int _free_box (void *box_mem, void *box) {
+   /* Function wrapper for Unprivileged/Privileged mode. */
+        LDR     R12,=__cpp(rt_free_box)
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        BXNE    R12
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        BXEQ    R12
+        SVC     0
+        BX      LR
+
+        ALIGN
+}
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+__asm void SVC_Handler (void) {
+        PRESERVE8
+
+        IMPORT  SVC_Count
+        IMPORT  SVC_Table
+        IMPORT  rt_stk_check
+
+#ifdef  IFX_XMC4XXX
+        EXPORT  SVC_Handler_Veneer
+SVC_Handler_Veneer        
+#endif
+
+        MRS     R0,PSP                  ; Read PSP
+        LDR     R1,[R0,#24]             ; Read Saved PC from Stack
+        LDRB    R1,[R1,#-2]             ; Load SVC Number
+        CBNZ    R1,SVC_User
+
+        LDM     R0,{R0-R3,R12}          ; Read R0-R3,R12 from stack
+        PUSH    {R4,LR}                 ; Save EXC_RETURN
+        BLX     R12                     ; Call SVC Function 
+        POP     {R4,LR}                 ; Restore EXC_RETURN
+
+        MRS     R12,PSP                 ; Read PSP
+        STM     R12,{R0-R2}             ; Store return values
+
+        LDR     R3,=__cpp(&os_tsk)
+        LDM     R3,{R1,R2}              ; os_tsk.run, os_tsk.new
+        CMP     R1,R2
+#ifdef  IFX_XMC4XXX
+        PUSHEQ  {LR}
+        POPEQ   {PC}
+#else
+        BXEQ    LR                      ; RETI, no task switch
+#endif
+
+        CBZ     R1,SVC_Next             ; Runtask deleted?
+        TST     LR,#0x10                ; is it extended frame?
+        VSTMDBEQ R12!,{S16-S31}         ; yes, stack also VFP hi-regs
+        MOVEQ   R0,#0x01                ; os_tsk->stack_frame val
+        MOVNE   R0,#0x00
+        STRB    R0,[R1,#TCB_STACKF]     ; os_tsk.run->stack_frame = val
+        STMDB   R12!,{R4-R11}           ; Save Old context
+        STR     R12,[R1,#TCB_TSTACK]    ; Update os_tsk.run->tsk_stack
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            ; Check for Stack overflow
+        POP     {R2,R3}
+
+SVC_Next
+        STR     R2,[R3]                 ; os_tsk.run = os_tsk.new
+
+        LDR     R12,[R2,#TCB_TSTACK]    ; os_tsk.new->tsk_stack
+        LDMIA   R12!,{R4-R11}           ; Restore New Context
+        LDRB    R0,[R2,#TCB_STACKF]     ; Stack Frame
+        CMP     R0,#0                   ; Basic/Extended Stack Frame
+        VLDMIANE R12!,{S16-S31}         ; restore VFP hi-registers
+        MVNNE   LR,#:NOT:0xFFFFFFED     ; set EXC_RETURN value
+        MVNEQ   LR,#:NOT:0xFFFFFFFD
+        MSR     PSP,R12                 ; Write PSP
+
+SVC_Exit
+#ifdef  IFX_XMC4XXX
+        PUSH    {LR}
+        POP     {PC}
+#else
+        BX      LR
+#endif
+
+        /*------------------- User SVC ------------------------------*/
+
+SVC_User
+        PUSH    {R4,LR}                 ; Save Registers
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                ; Overflow
+
+        LDR     R4,=SVC_Table-4
+        LDR     R4,[R4,R1,LSL #2]       ; Load SVC Function Address
+
+        LDM     R0,{R0-R3,R12}          ; Read R0-R3,R12 from stack
+        BLX     R4                      ; Call SVC Function
+
+        MRS     R12,PSP
+        STM     R12,{R0-R3}             ; Function return values
+SVC_Done
+        POP     {R4,PC}                 ; RETI
+
+        ALIGN
+}
+
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+__asm void PendSV_Handler (void) {
+        PRESERVE8
+
+#ifdef  IFX_XMC4XXX
+        EXPORT  PendSV_Handler_Veneer
+PendSV_Handler_Veneer        
+#endif
+
+        PUSH    {R4,LR}                 ; Save EXC_RETURN
+        BL      __cpp(rt_pop_req)
+
+Sys_Switch
+        POP     {R4,LR}                 ; Restore EXC_RETURN
+
+        LDR     R3,=__cpp(&os_tsk)
+        LDM     R3,{R1,R2}              ; os_tsk.run, os_tsk.new
+        CMP     R1,R2
+#ifdef  IFX_XMC4XXX
+        PUSHEQ  {LR}
+        POPEQ   {PC}
+#else
+        BXEQ    LR                      ; RETI, no task switch
+#endif
+
+        MRS     R12,PSP                 ; Read PSP
+        TST     LR,#0x10                ; is it extended frame?
+        VSTMDBEQ R12!,{S16-S31}         ; yes, stack also VFP hi-regs
+        MOVEQ   R0,#0x01                ; os_tsk->stack_frame val
+        MOVNE   R0,#0x00
+        STRB    R0,[R1,#TCB_STACKF]     ; os_tsk.run->stack_frame = val
+        STMDB   R12!,{R4-R11}           ; Save Old context
+        STR     R12,[R1,#TCB_TSTACK]    ; Update os_tsk.run->tsk_stack
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            ; Check for Stack overflow
+        POP     {R2,R3}
+
+        STR     R2,[R3]                 ; os_tsk.run = os_tsk.new
+
+        LDR     R12,[R2,#TCB_TSTACK]    ; os_tsk.new->tsk_stack
+        LDMIA   R12!,{R4-R11}           ; Restore New Context
+        LDRB    R0,[R2,#TCB_STACKF]     ; Stack Frame
+        CMP     R0,#0                   ; Basic/Extended Stack Frame
+        VLDMIANE R12!,{S16-S31}         ; restore VFP hi-regs
+        MVNNE   LR,#:NOT:0xFFFFFFED     ; set EXC_RETURN value
+        MVNEQ   LR,#:NOT:0xFFFFFFFD
+        MSR     PSP,R12                 ; Write PSP
+
+Sys_Exit
+#ifdef  IFX_XMC4XXX
+        PUSH    {LR}
+        POP     {PC}
+#else
+        BX      LR                      ; Return to Thread Mode
+#endif
+
+        ALIGN
+}
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+__asm void SysTick_Handler (void) {
+        PRESERVE8
+
+#ifdef  IFX_XMC4XXX
+        EXPORT  SysTick_Handler_Veneer
+SysTick_Handler_Veneer        
+#endif
+
+        PUSH    {R4,LR}                 ; Save EXC_RETURN
+        BL      __cpp(rt_systick)
+        B       Sys_Switch
+
+        ALIGN
+}
+
+
+/*-------------------------- OS_Tick_Handler --------------------------------*/
+
+__asm void OS_Tick_Handler (void) {
+        PRESERVE8
+
+        PUSH    {R4,LR}                 ; Save EXC_RETURN
+        BL      __cpp(os_tick_irqack)
+        BL      __cpp(rt_systick)
+        B       Sys_Switch
+
+        ALIGN
+}
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_ARM/SVC_Table.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_ARM/SVC_Table.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,57 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.70
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH
+; * All rights reserved.
+; * Redistribution and use in source and binary forms, with or without
+; * modification, are permitted provided that the following conditions are met:
+; *  - Redistributions of source code must retain the above copyright
+; *    notice, this list of conditions and the following disclaimer.
+; *  - Redistributions in binary form must reproduce the above copyright
+; *    notice, this list of conditions and the following disclaimer in the
+; *    documentation and/or other materials provided with the distribution.
+; *  - Neither the name of ARM  nor the names of its contributors may be used 
+; *    to endorse or promote products derived from this software without 
+; *    specific prior written permission.
+; *
+; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+; * POSSIBILITY OF SUCH DAMAGE.
+; *---------------------------------------------------------------------------*/
+
+
+                AREA    SVC_TABLE, CODE, READONLY
+
+                EXPORT  SVC_Count
+
+SVC_Cnt         EQU    (SVC_End-SVC_Table)/4
+SVC_Count       DCD     SVC_Cnt
+
+; Import user SVC functions here.
+;               IMPORT  __SVC_1
+
+                EXPORT  SVC_Table
+SVC_Table
+; Insert user SVC functions here. SVC 0 used by RTL Kernel.
+;               DCD     __SVC_1                 ; user SVC function
+
+SVC_End
+
+                END
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_GCC/HAL_CM4.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_GCC/HAL_CM4.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,389 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    HAL_CM4.S
+ *      Purpose: Hardware Abstraction Layer for Cortex-M4
+ *      Rev.:    V4.70
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+        .file   "HAL_CM4.S"
+        .syntax unified
+
+        .equ    TCB_STACKF, 32
+        .equ    TCB_TSTACK, 36
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+        .thumb
+
+        .section ".text"
+        .align  2
+
+
+/*--------------------------- rt_set_PSP ------------------------------------*/
+
+#       void rt_set_PSP (U32 stack);
+
+        .thumb_func
+        .type   rt_set_PSP, %function
+        .global rt_set_PSP
+rt_set_PSP:
+        .fnstart
+        .cantunwind
+
+        MSR     PSP,R0
+        BX      LR
+
+        .fnend
+        .size   rt_set_PSP, .-rt_set_PSP
+
+
+/*--------------------------- rt_get_PSP ------------------------------------*/
+
+#       U32 rt_get_PSP (void);
+
+        .thumb_func
+        .type   rt_get_PSP, %function
+        .global rt_get_PSP
+rt_get_PSP:
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP
+        BX      LR
+
+        .fnend
+        .size   rt_get_PSP, .-rt_get_PSP
+
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+#       void os_set_env (void);
+        /* Switch to Unprivileged/Privileged Thread mode, use PSP. */
+
+        .thumb_func
+        .type   os_set_env, %function
+        .global os_set_env
+os_set_env:
+        .fnstart
+        .cantunwind
+
+        MOV     R0,SP                   /* PSP = MSP */
+        MSR     PSP,R0
+        LDR     R0,=os_flags
+        LDRB    R0,[R0]
+        LSLS    R0,#31
+        ITE     NE
+        MOVNE   R0,#0x02                /* Privileged Thread mode, use PSP */
+        MOVEQ   R0,#0x03                /* Unprivileged Thread mode, use PSP */
+        MSR     CONTROL,R0
+        BX      LR
+
+        .fnend
+        .size   os_set_env, .-os_set_env
+
+
+/*--------------------------- _alloc_box ------------------------------------*/
+
+#      void *_alloc_box (void *box_mem);
+       /* Function wrapper for Unprivileged/Privileged mode. */
+
+        .thumb_func
+        .type   _alloc_box, %function
+        .global _alloc_box
+_alloc_box:
+        .fnstart
+        .cantunwind
+
+        LDR     R12,=rt_alloc_box
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        IT      NE
+        BXNE    R12
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        IT      EQ
+        BXEQ    R12
+        SVC     0
+        BX      LR
+
+        .fnend
+        .size   _alloc_box, .-_alloc_box
+
+
+/*--------------------------- _free_box -------------------------------------*/
+
+#       int _free_box (void *box_mem, void *box);
+        /* Function wrapper for Unprivileged/Privileged mode. */
+
+        .thumb_func
+        .type   _free_box, %function
+        .global _free_box
+_free_box:
+        .fnstart
+        .cantunwind
+
+        LDR     R12,=rt_free_box
+        MRS     R3,IPSR
+        LSLS    R3,#24
+        IT      NE
+        BXNE    R12
+        MRS     R3,CONTROL
+        LSLS    R3,#31
+        IT      EQ
+        BXEQ    R12
+        SVC     0
+        BX      LR
+
+        .fnend
+        .size   _free_box, .-_free_box
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+#       void SVC_Handler (void);
+
+        .thumb_func
+        .type   SVC_Handler, %function
+        .global SVC_Handler
+SVC_Handler:
+        .ifdef  IFX_XMC4XXX
+        .global SVC_Handler_Veneer
+SVC_Handler_Veneer:
+        .endif
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP                  /* Read PSP */
+        LDR     R1,[R0,#24]             /* Read Saved PC from Stack */
+        LDRB    R1,[R1,#-2]             /* Load SVC Number */
+        CBNZ    R1,SVC_User
+
+        LDM     R0,{R0-R3,R12}          /* Read R0-R3,R12 from stack */
+        PUSH    {R4,LR}                 /* Save EXC_RETURN */
+        BLX     R12                     /* Call SVC Function */
+        POP     {R4,LR}                 /* Restore EXC_RETURN */
+
+        MRS     R12,PSP                 /* Read PSP */
+        STM     R12,{R0-R2}             /* Store return values */
+
+        LDR     R3,=os_tsk
+        LDM     R3,{R1,R2}              /* os_tsk.run, os_tsk.new */
+        CMP     R1,R2
+        .ifdef  IFX_XMC4XXX
+        ITT     EQ
+        PUSHEQ  {LR}
+        POPEQ   {PC}
+        .else
+        IT      EQ
+        BXEQ    LR                      /* RETI, no task switch */
+        .endif
+
+        CBZ     R1,SVC_Next             /* Runtask deleted? */
+        TST     LR,#0x10                /* is it extended frame? */
+        ITTE    EQ
+        VSTMDBEQ R12!,{S16-S31}         /* yes, stack also VFP hi-regs */
+        MOVEQ   R0,#0x01                /* os_tsk->stack_frame val */
+        MOVNE   R0,#0x00
+        STRB    R0,[R1,#TCB_STACKF]     /* os_tsk.run->stack_frame = val */
+        STMDB   R12!,{R4-R11}           /* Save Old context */
+        STR     R12,[R1,#TCB_TSTACK]    /* Update os_tsk.run->tsk_stack */
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            /* Check for Stack overflow */
+        POP     {R2,R3}
+
+SVC_Next:
+        STR     R2,[R3]                 /* os_tsk.run = os_tsk.new */
+
+        LDR     R12,[R2,#TCB_TSTACK]    /* os_tsk.new->tsk_stack */
+        LDMIA   R12!,{R4-R11}           /* Restore New Context */
+        LDRB    R0,[R2,#TCB_STACKF]     /* Stack Frame */
+        CMP     R0,#0                   /* Basic/Extended Stack Frame */
+        ITTE    NE
+        VLDMIANE R12!,{S16-S31}         /* restore VFP hi-registers */
+        MVNNE   LR,#~0xFFFFFFED         /* set EXC_RETURN value */
+        MVNEQ   LR,#~0xFFFFFFFD
+        MSR     PSP,R12                 /* Write PSP */
+
+SVC_Exit:
+        .ifdef  IFX_XMC4XXX
+        PUSH    {LR}
+        POP     {PC}
+        .else
+        BX      LR
+        .endif
+
+        /*------------------- User SVC ------------------------------*/
+
+SVC_User:
+        PUSH    {R4,LR}                 /* Save Registers */
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                /* Overflow */
+
+        LDR     R4,=SVC_Table-4
+        LDR     R4,[R4,R1,LSL #2]       /* Load SVC Function Address */
+
+        LDM     R0,{R0-R3,R12}          /* Read R0-R3,R12 from stack */
+        BLX     R4                      /* Call SVC Function */
+
+        MRS     R12,PSP
+        STM     R12,{R0-R3}             /* Function return values */
+SVC_Done:
+        POP     {R4,PC}                 /* RETI */
+
+        .fnend
+        .size   SVC_Handler, .-SVC_Handler
+        
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+#       void PendSV_Handler (void);
+
+        .thumb_func
+        .type   PendSV_Handler, %function
+        .global PendSV_Handler
+        .global Sys_Switch
+PendSV_Handler:
+        .ifdef  IFX_XMC4XXX
+        .global PendSV_Handler_Veneer
+PendSV_Handler_Veneer:
+        .endif
+        .fnstart
+        .cantunwind
+
+        PUSH    {R4,LR}                 /* Save EXC_RETURN */
+        BL      rt_pop_req
+
+Sys_Switch:
+        POP     {R4,LR}                 /* Restore EXC_RETURN */
+
+        LDR     R3,=os_tsk
+        LDM     R3,{R1,R2}              /* os_tsk.run, os_tsk.new */
+        CMP     R1,R2
+        .ifdef  IFX_XMC4XXX
+        ITT     EQ
+        PUSHEQ  {LR}
+        POPEQ   {PC}
+        .else
+        IT      EQ
+        BXEQ    LR                      /* RETI, no task switch */
+        .endif
+
+        MRS     R12,PSP                 /* Read PSP */
+        TST     LR,#0x10                /* is it extended frame? */
+        ITTE    EQ
+        VSTMDBEQ R12!,{S16-S31}         /* yes, stack also VFP hi-regs */
+        MOVEQ   R0,#0x01                /* os_tsk->stack_frame val */
+        MOVNE   R0,#0x00
+        STRB    R0,[R1,#TCB_STACKF]     /* os_tsk.run->stack_frame = val */
+        STMDB   R12!,{R4-R11}           /* Save Old context */
+        STR     R12,[R1,#TCB_TSTACK]    /* Update os_tsk.run->tsk_stack */
+
+        PUSH    {R2,R3}
+        BL      rt_stk_check            /* Check for Stack overflow */
+        POP     {R2,R3}
+
+        STR     R2,[R3]                 /* os_tsk.run = os_tsk.new */
+
+        LDR     R12,[R2,#TCB_TSTACK]    /* os_tsk.new->tsk_stack */
+        LDMIA   R12!,{R4-R11}           /* Restore New Context */
+        LDRB    R0,[R2,#TCB_STACKF]     /* Stack Frame */
+        CMP     R0,#0                   /* Basic/Extended Stack Frame */
+        ITTE    NE
+        VLDMIANE R12!,{S16-S31}         /* restore VFP hi-registers */
+        MVNNE   LR,#~0xFFFFFFED         /* set EXC_RETURN value */
+        MVNEQ   LR,#~0xFFFFFFFD
+        MSR     PSP,R12                 /* Write PSP */
+
+Sys_Exit:
+        .ifdef  IFX_XMC4XXX
+        PUSH    {LR}
+        POP     {PC}
+        .else
+        BX      LR                      /* Return to Thread Mode */
+        .endif
+
+        .fnend
+        .size   PendSV_Handler, .-PendSV_Handler
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+#       void SysTick_Handler (void);
+
+        .thumb_func
+        .type   SysTick_Handler, %function
+        .global SysTick_Handler
+SysTick_Handler:
+        .ifdef  IFX_XMC4XXX
+        .global SysTick_Handler_Veneer
+SysTick_Handler_Veneer:
+        .endif
+        .fnstart
+        .cantunwind
+
+        PUSH    {R4,LR}                 /* Save EXC_RETURN */
+        BL      rt_systick
+        B       Sys_Switch
+
+        .fnend
+        .size   SysTick_Handler, .-SysTick_Handler
+
+
+/*-------------------------- OS_Tick_Handler --------------------------------*/
+
+#       void OS_Tick_Handler (void);
+
+        .thumb_func
+        .type   OS_Tick_Handler, %function
+        .global OS_Tick_Handler
+OS_Tick_Handler:
+        .fnstart
+        .cantunwind
+
+        PUSH    {R4,LR}                 /* Save EXC_RETURN */
+        BL      os_tick_irqack
+        BL      rt_systick
+        B       Sys_Switch
+
+        .fnend
+        .size   OS_Tick_Handler, .-OS_Tick_Handler
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_GCC/SVC_Table.s
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/TARGET_M4/TOOLCHAIN_GCC/SVC_Table.s	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,56 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.70
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH
+; * All rights reserved.
+; * Redistribution and use in source and binary forms, with or without
+; * modification, are permitted provided that the following conditions are met:
+; *  - Redistributions of source code must retain the above copyright
+; *    notice, this list of conditions and the following disclaimer.
+; *  - Redistributions in binary form must reproduce the above copyright
+; *    notice, this list of conditions and the following disclaimer in the
+; *    documentation and/or other materials provided with the distribution.
+; *  - Neither the name of ARM  nor the names of its contributors may be used 
+; *    to endorse or promote products derived from this software without 
+; *    specific prior written permission.
+; *
+; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+; * POSSIBILITY OF SUCH DAMAGE.
+; *---------------------------------------------------------------------------*/
+
+
+        .file   "SVC_Table.S"
+
+
+        .section ".svc_table"
+
+        .global  SVC_Table
+SVC_Table:
+/* Insert user SVC functions here. SVC 0 used by RTL Kernel. */
+#       .long   __SVC_1                 /* user SVC function */
+SVC_End:
+
+        .global  SVC_Count
+SVC_Count:
+        .long   (SVC_End-SVC_Table)/4
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/cmsis_os.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/cmsis_os.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,772 @@
+/* ----------------------------------------------------------------------  
+ * Copyright (C) 2012 ARM Limited. All rights reserved.  
+ *  
+ * $Date:        5. June 2012
+ * $Revision:    V1.01
+ *  
+ * Project:      CMSIS-RTOS API
+ * Title:        cmsis_os.h RTX header file
+ *  
+ * Version 0.02
+ *    Initial Proposal Phase 
+ * Version 0.03
+ *    osKernelStart added, optional feature: main started as thread
+ *    osSemaphores have standard behavior
+ *    osTimerCreate does not start the timer, added osTimerStart
+ *    osThreadPass is renamed to osThreadYield
+ * Version 1.01
+ *    Support for C++ interface
+ *     - const attribute removed from the osXxxxDef_t typedef's 
+ *     - const attribute added to the osXxxxDef macros
+ *    Added: osTimerDelete, osMutexDelete, osSemaphoreDelete
+ *    Added: osKernelInitialize
+ * -------------------------------------------------------------------- */ 
+
+/**
+\page cmsis_os_h Header File Template: cmsis_os.h
+
+The file \b cmsis_os.h is a template header file for a CMSIS-RTOS compliant Real-Time Operating System (RTOS).
+Each RTOS that is compliant with CMSIS-RTOS shall provide a specific \b cmsis_os.h header file that represents
+its implementation.
+
+The file cmsis_os.h contains:
+ - CMSIS-RTOS API function definitions
+ - struct definitions for parameters and return types
+ - status and priority values used by CMSIS-RTOS API functions
+ - macros for defining threads and other kernel objects
+
+
+<b>Name conventions and header file modifications</b>
+
+All definitions are prefixed with \b os to give an unique name space for CMSIS-RTOS functions.
+Definitions that are prefixed \b os_ are not used in the application code but local to this header file.
+All definitions and functions that belong to a module are grouped and have a common prefix, i.e. \b osThread.
+ 
+Definitions that are marked with <b>CAN BE CHANGED</b> can be adapted towards the needs of the actual CMSIS-RTOS implementation. 
+These definitions can be specific to the underlying RTOS kernel.
+
+Definitions that are marked with <b>MUST REMAIN UNCHANGED</b> cannot be altered. Otherwise the CMSIS-RTOS implementation is no longer
+compliant to the standard. Note that some functions are optional and need not to be provided by every CMSIS-RTOS implementation.
+
+
+<b>Function calls from interrupt service routines</b>
+
+The following CMSIS-RTOS functions can be called from threads and interrupt service routines (ISR):
+  - \ref osSignalSet
+  - \ref osSemaphoreRelease
+  - \ref osPoolAlloc, \ref osPoolCAlloc, \ref osPoolFree
+  - \ref osMessagePut, \ref osMessageGet
+  - \ref osMailAlloc, \ref osMailCAlloc, \ref osMailGet, \ref osMailPut, \ref osMailFree
+
+Functions that cannot be called from an ISR are verifying the interrupt status and return in case that they are called 
+from an ISR context the status code \b osErrorISR. In some implementations this condition might be caught using the HARD FAULT vector.
+
+Some CMSIS-RTOS implementations support CMSIS-RTOS function calls from multiple ISR at the same time.
+If this is impossible, the CMSIS-RTOS rejects calls by nested ISR functions with the status code \b osErrorISRRecursive.
+
+
+<b>Define and reference object definitions</b>
+
+With <b>\#define osObjectsExternal</b> objects are defined as external symbols. This allows to create a consistent header file
+that is used throughout a project as shown below:
+
+<i>Header File</i>
+\code
+#include <cmsis_os.h>                                         // CMSIS RTOS header file
+
+// Thread definition
+extern void thread_sample (void const *argument);             // function prototype
+osThreadDef (thread_sample, osPriorityBelowNormal, 1, 100);
+
+// Pool definition
+osPoolDef(MyPool, 10, long);                      
+\endcode
+
+
+This header file defines all objects when included in a C/C++ source file. When <b>\#define osObjectsExternal</b> is 
+present before the header file, the objects are defined as external symbols. A single consistent header file can therefore be
+used throughout the whole project.
+
+<i>Example</i>
+\code
+#include "osObjects.h"     // Definition of the CMSIS-RTOS objects
+\endcode
+
+\code
+#define osObjectExternal   // Objects will be defined as external symbols
+#include "osObjects.h"     // Reference to the CMSIS-RTOS objects
+\endcode
+
+*/
+ 
+#ifndef _CMSIS_OS_H
+#define _CMSIS_OS_H
+
+/// \note MUST REMAIN UNCHANGED: \b osCMSIS identifies the CMSIS-RTOS API version.
+#define osCMSIS           0x10001      ///< API version (main [31:16] .sub [15:0])
+
+/// \note CAN BE CHANGED: \b osCMSIS_KERNEL identifies the underlying RTOS kernel and version number.
+#define osCMSIS_RTX     ((4<<16)|61)   ///< RTOS identification and version (main [31:16] .sub [15:0])
+
+/// \note MUST REMAIN UNCHANGED: \b osKernelSystemId shall be consistent in every CMSIS-RTOS.
+#define osKernelSystemId "RTX V4.61"   ///< RTOS identification string
+
+
+#define CMSIS_OS_RTX
+
+// The stack space occupied is mainly dependent on the underling C standard library
+#if defined(TOOLCHAIN_GCC) || defined(TOOLCHAIN_ARM_STD)
+#    define WORDS_STACK_SIZE   512
+#elif defined(TOOLCHAIN_ARM_MICRO)
+#    define WORDS_STACK_SIZE   128
+#endif
+
+#define DEFAULT_STACK_SIZE         (WORDS_STACK_SIZE*4)
+
+
+/// \note MUST REMAIN UNCHANGED: \b osFeature_xxx shall be consistent in every CMSIS-RTOS.
+#define osFeature_MainThread   1       ///< main thread      1=main can be thread, 0=not available
+#define osFeature_Pool         1       ///< Memory Pools:    1=available, 0=not available
+#define osFeature_MailQ        1       ///< Mail Queues:     1=available, 0=not available
+#define osFeature_MessageQ     1       ///< Message Queues:  1=available, 0=not available
+#define osFeature_Signals      16      ///< maximum number of Signal Flags available per thread
+#define osFeature_Semaphore    65535   ///< maximum count for \ref osSemaphoreCreate function
+#define osFeature_Wait         0       ///< osWait function: 1=available, 0=not available
+
+#if defined (__CC_ARM)
+#define os_InRegs __value_in_regs      // Compiler specific: force struct in registers
+#else
+#define os_InRegs
+#endif
+
+#include <stdint.h>
+#include <stddef.h>
+
+#ifdef  __cplusplus
+extern "C"
+{
+#endif
+
+#include "os_tcb.h"
+
+// ==== Enumeration, structures, defines ====
+
+/// Priority used for thread control.
+/// \note MUST REMAIN UNCHANGED: \b osPriority shall be consistent in every CMSIS-RTOS.
+typedef enum  {
+  osPriorityIdle          = -3,          ///< priority: idle (lowest)
+  osPriorityLow           = -2,          ///< priority: low
+  osPriorityBelowNormal   = -1,          ///< priority: below normal
+  osPriorityNormal        =  0,          ///< priority: normal (default)
+  osPriorityAboveNormal   = +1,          ///< priority: above normal
+  osPriorityHigh          = +2,          ///< priority: high 
+  osPriorityRealtime      = +3,          ///< priority: realtime (highest)
+  osPriorityError         =  0x84        ///< system cannot determine priority or thread has illegal priority
+} osPriority;
+
+/// Timeout value.
+/// \note MUST REMAIN UNCHANGED: \b osWaitForever shall be consistent in every CMSIS-RTOS.
+#define osWaitForever     0xFFFFFFFF     ///< wait forever timeout value
+
+/// Status code values returned by CMSIS-RTOS functions.
+/// \note MUST REMAIN UNCHANGED: \b osStatus shall be consistent in every CMSIS-RTOS.
+typedef enum  {
+  osOK                    =     0,       ///< function completed; no error or event occurred.
+  osEventSignal           =  0x08,       ///< function completed; signal event occurred.
+  osEventMessage          =  0x10,       ///< function completed; message event occurred.
+  osEventMail             =  0x20,       ///< function completed; mail event occurred.
+  osEventTimeout          =  0x40,       ///< function completed; timeout occurred.
+  osErrorParameter        =  0x80,       ///< parameter error: a mandatory parameter was missing or specified an incorrect object.
+  osErrorResource         =  0x81,       ///< resource not available: a specified resource was not available.
+  osErrorTimeoutResource  =  0xC1,       ///< resource not available within given time: a specified resource was not available within the timeout period.
+  osErrorISR              =  0x82,       ///< not allowed in ISR context: the function cannot be called from interrupt service routines.
+  osErrorISRRecursive     =  0x83,       ///< function called multiple times from ISR with same object.
+  osErrorPriority         =  0x84,       ///< system cannot determine priority or thread has illegal priority.
+  osErrorNoMemory         =  0x85,       ///< system is out of memory: it was impossible to allocate or reserve memory for the operation.
+  osErrorValue            =  0x86,       ///< value of a parameter is out of range.
+  osErrorOS               =  0xFF,       ///< unspecified RTOS error: run-time error but no other error message fits.
+  os_status_reserved      =  0x7FFFFFFF  ///< prevent from enum down-size compiler optimization.
+} osStatus; 
+
+
+/// Timer type value for the timer definition.
+/// \note MUST REMAIN UNCHANGED: \b os_timer_type shall be consistent in every CMSIS-RTOS.
+typedef enum  {
+  osTimerOnce             =     0,       ///< one-shot timer 
+  osTimerPeriodic         =     1        ///< repeating timer 
+} os_timer_type; 
+
+/// Entry point of a thread.
+/// \note MUST REMAIN UNCHANGED: \b os_pthread shall be consistent in every CMSIS-RTOS.
+typedef void (*os_pthread) (void const *argument); 
+
+/// Entry point of a timer call back function.
+/// \note MUST REMAIN UNCHANGED: \b os_ptimer shall be consistent in every CMSIS-RTOS.
+typedef void (*os_ptimer) (void const *argument); 
+
+// >>> the following data type definitions may shall adapted towards a specific RTOS
+
+/// Thread ID identifies the thread (pointer to a thread control block).
+/// \note CAN BE CHANGED: \b os_thread_cb is implementation specific in every CMSIS-RTOS.
+typedef struct os_thread_cb *osThreadId;
+
+/// Timer ID identifies the timer (pointer to a timer control block).
+/// \note CAN BE CHANGED: \b os_timer_cb is implementation specific in every CMSIS-RTOS.
+typedef struct os_timer_cb *osTimerId;
+
+/// Mutex ID identifies the mutex (pointer to a mutex control block).
+/// \note CAN BE CHANGED: \b os_mutex_cb is implementation specific in every CMSIS-RTOS.
+typedef struct os_mutex_cb *osMutexId;
+
+/// Semaphore ID identifies the semaphore (pointer to a semaphore control block).
+/// \note CAN BE CHANGED: \b os_semaphore_cb is implementation specific in every CMSIS-RTOS.
+typedef struct os_semaphore_cb *osSemaphoreId;
+
+/// Pool ID identifies the memory pool (pointer to a memory pool control block).
+/// \note CAN BE CHANGED: \b os_pool_cb is implementation specific in every CMSIS-RTOS.
+typedef struct os_pool_cb *osPoolId;
+
+/// Message ID identifies the message queue (pointer to a message queue control block).
+/// \note CAN BE CHANGED: \b os_messageQ_cb is implementation specific in every CMSIS-RTOS.
+typedef struct os_messageQ_cb *osMessageQId;
+
+/// Mail ID identifies the mail queue (pointer to a mail queue control block).
+/// \note CAN BE CHANGED: \b os_mailQ_cb is implementation specific in every CMSIS-RTOS.
+typedef struct os_mailQ_cb *osMailQId;
+
+
+/// Thread Definition structure contains startup information of a thread.
+/// \note CAN BE CHANGED: \b os_thread_def is implementation specific in every CMSIS-RTOS.
+typedef struct os_thread_def  {
+  os_pthread               pthread;      ///< start address of thread function
+  osPriority             tpriority;      ///< initial thread priority
+  uint32_t               stacksize;      ///< stack size requirements in bytes
+  unsigned char         *stack_pointer;  ///< pointer to the stack memory block
+  struct OS_TCB          tcb;
+} osThreadDef_t;
+
+/// Timer Definition structure contains timer parameters.
+/// \note CAN BE CHANGED: \b os_timer_def is implementation specific in every CMSIS-RTOS.
+typedef struct os_timer_def  {
+  os_ptimer                 ptimer;    ///< start address of a timer function
+  void                      *timer;    ///< pointer to internal data
+} osTimerDef_t;
+
+/// Mutex Definition structure contains setup information for a mutex.
+/// \note CAN BE CHANGED: \b os_mutex_def is implementation specific in every CMSIS-RTOS.
+typedef struct os_mutex_def  {
+  void                      *mutex;    ///< pointer to internal data
+} osMutexDef_t;
+
+/// Semaphore Definition structure contains setup information for a semaphore.
+/// \note CAN BE CHANGED: \b os_semaphore_def is implementation specific in every CMSIS-RTOS.
+typedef struct os_semaphore_def  {
+  void                  *semaphore;    ///< pointer to internal data
+} osSemaphoreDef_t;
+
+/// Definition structure for memory block allocation.
+/// \note CAN BE CHANGED: \b os_pool_def is implementation specific in every CMSIS-RTOS.
+typedef struct os_pool_def  {
+  uint32_t                 pool_sz;    ///< number of items (elements) in the pool
+  uint32_t                 item_sz;    ///< size of an item 
+  void                       *pool;    ///< pointer to memory for pool
+} osPoolDef_t;
+
+/// Definition structure for message queue.
+/// \note CAN BE CHANGED: \b os_messageQ_def is implementation specific in every CMSIS-RTOS.
+typedef struct os_messageQ_def  {
+  uint32_t                queue_sz;    ///< number of elements in the queue
+  void                       *pool;    ///< memory array for messages
+} osMessageQDef_t;
+
+/// Definition structure for mail queue.
+/// \note CAN BE CHANGED: \b os_mailQ_def is implementation specific in every CMSIS-RTOS.
+typedef struct os_mailQ_def  {
+  uint32_t                queue_sz;    ///< number of elements in the queue
+  uint32_t                 item_sz;    ///< size of an item 
+  void                       *pool;    ///< memory array for mail
+} osMailQDef_t;
+
+/// Event structure contains detailed information about an event. 
+/// \note MUST REMAIN UNCHANGED: \b os_event shall be consistent in every CMSIS-RTOS. 
+///       However the struct may be extended at the end.
+typedef struct  {
+  osStatus                 status;     ///< status code: event or error information
+  union  {
+    uint32_t                    v;     ///< message as 32-bit value 
+    void                       *p;     ///< message or mail as void pointer
+    int32_t               signals;     ///< signal flags 
+  } value;                             ///< event value
+  union  {
+    osMailQId             mail_id;     ///< mail id obtained by \ref osMailCreate 
+    osMessageQId       message_id;     ///< message id obtained by \ref osMessageCreate 
+  } def;                               ///< event definition
+} osEvent;
+
+
+//  ==== Kernel Control Functions ====
+
+/// Initialize the RTOS Kernel for creating objects.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osKernelInitialize shall be consistent in every CMSIS-RTOS. 
+osStatus osKernelInitialize (void);
+
+/// Start the RTOS Kernel.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osKernelStart shall be consistent in every CMSIS-RTOS. 
+osStatus osKernelStart (void);
+
+/// Check if the RTOS kernel is already started.
+/// \note MUST REMAIN UNCHANGED: \b osKernelRunning shall be consistent in every CMSIS-RTOS. 
+/// \return 0 RTOS is not started, 1 RTOS is started.
+int32_t osKernelRunning(void);
+
+
+//  ==== Thread Management ====
+
+/// Create a Thread Definition with function, priority, and stack requirements.
+/// \param         name         name of the thread function.
+/// \param         priority     initial priority of the thread function.
+/// \param         stacksz      stack size (in bytes) requirements for the thread function.
+/// \note CAN BE CHANGED: The parameters to \b osThreadDef shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#if defined (osObjectsExternal)  // object is external
+#define osThreadDef(name, priority, stacksz)  \
+extern osThreadDef_t os_thread_def_##name
+#else                            // define the object
+#define osThreadDef(name, priority, stacksz)  \
+unsigned char os_thread_def_stack_##name [stacksz]; \
+osThreadDef_t os_thread_def_##name = \
+{ (name), (priority), (stacksz), (os_thread_def_stack_##name)}
+#endif
+
+/// Access a Thread definition.
+/// \param         name          name of the thread definition object.
+/// \note CAN BE CHANGED: The parameter to \b osThread shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#define osThread(name)  \
+&os_thread_def_##name
+
+/// Create a thread and add it to Active Threads and set it to state READY.
+/// \param[in]     thread_def    thread definition referenced with \ref osThread.
+/// \param[in]     argument      pointer that is passed to the thread function as start argument.
+/// \return thread ID for reference by other functions or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osThreadCreate shall be consistent in every CMSIS-RTOS.
+osThreadId osThreadCreate (osThreadDef_t *thread_def, void *argument);
+
+/// Return the thread ID of the current running thread.
+/// \return thread ID for reference by other functions or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osThreadGetId shall be consistent in every CMSIS-RTOS.
+osThreadId osThreadGetId (void);
+
+/// Terminate execution of a thread and remove it from Active Threads.
+/// \param[in]     thread_id   thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osThreadTerminate shall be consistent in every CMSIS-RTOS.
+osStatus osThreadTerminate (osThreadId thread_id);
+
+/// Pass control to next thread that is in state \b READY.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osThreadYield shall be consistent in every CMSIS-RTOS.
+osStatus osThreadYield (void);
+
+/// Change priority of an active thread.  
+/// \param[in]     thread_id     thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
+/// \param[in]     priority      new priority value for the thread function.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osThreadSetPriority shall be consistent in every CMSIS-RTOS.
+osStatus osThreadSetPriority (osThreadId thread_id, osPriority priority);
+
+/// Get current priority of an active thread.
+/// \param[in]     thread_id     thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
+/// \return current priority value of the thread function.
+/// \note MUST REMAIN UNCHANGED: \b osThreadGetPriority shall be consistent in every CMSIS-RTOS.
+osPriority osThreadGetPriority (osThreadId thread_id);
+
+
+//  ==== Generic Wait Functions ====
+
+/// Wait for Timeout (Time Delay).
+/// \param[in]     millisec      time delay value 
+/// \return status code that indicates the execution status of the function.
+osStatus osDelay (uint32_t millisec);
+
+#if (defined (osFeature_Wait)  &&  (osFeature_Wait != 0))     // Generic Wait available
+
+/// Wait for Signal, Message, Mail, or Timeout.
+/// \param[in] millisec          timeout value or 0 in case of no time-out
+/// \return event that contains signal, message, or mail information or error code.
+/// \note MUST REMAIN UNCHANGED: \b osWait shall be consistent in every CMSIS-RTOS.
+os_InRegs osEvent osWait (uint32_t millisec);
+
+#endif  // Generic Wait available
+
+
+//  ==== Timer Management Functions ====
+/// Define a Timer object.
+/// \param         name          name of the timer object.
+/// \param         function      name of the timer call back function.
+/// \note CAN BE CHANGED: The parameter to \b osTimerDef shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#if defined (osObjectsExternal)  // object is external
+#define osTimerDef(name, function)  \
+extern osTimerDef_t os_timer_def_##name
+#else                            // define the object
+#define osTimerDef(name, function)  \
+uint32_t os_timer_cb_##name[5]; \
+osTimerDef_t os_timer_def_##name = \
+{ (function), (os_timer_cb_##name) }
+#endif
+
+/// Access a Timer definition.
+/// \param         name          name of the timer object.
+/// \note CAN BE CHANGED: The parameter to \b osTimer shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#define osTimer(name) \
+&os_timer_def_##name
+
+/// Create a timer.
+/// \param[in]     timer_def     timer object referenced with \ref osTimer.
+/// \param[in]     type          osTimerOnce for one-shot or osTimerPeriodic for periodic behavior.
+/// \param[in]     argument      argument to the timer call back function.
+/// \return timer ID for reference by other functions or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osTimerCreate shall be consistent in every CMSIS-RTOS.
+osTimerId osTimerCreate (osTimerDef_t *timer_def, os_timer_type type, void *argument);
+
+/// Start or restart a timer.
+/// \param[in]     timer_id      timer ID obtained by \ref osTimerCreate.
+/// \param[in]     millisec      time delay value of the timer.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osTimerStart shall be consistent in every CMSIS-RTOS.
+osStatus osTimerStart (osTimerId timer_id, uint32_t millisec);
+
+/// Stop the timer.
+/// \param[in]     timer_id      timer ID obtained by \ref osTimerCreate.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osTimerStop shall be consistent in every CMSIS-RTOS.
+osStatus osTimerStop (osTimerId timer_id);
+
+/// Delete a timer that was created by \ref osTimerCreate.
+/// \param[in]     timer_id      timer ID obtained by \ref osTimerCreate.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osTimerDelete shall be consistent in every CMSIS-RTOS.
+osStatus osTimerDelete (osTimerId timer_id);
+
+
+//  ==== Signal Management ====
+
+/// Set the specified Signal Flags of an active thread.
+/// \param[in]     thread_id     thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
+/// \param[in]     signals       specifies the signal flags of the thread that should be set.
+/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters.
+/// \note MUST REMAIN UNCHANGED: \b osSignalSet shall be consistent in every CMSIS-RTOS.
+int32_t osSignalSet (osThreadId thread_id, int32_t signals);
+
+/// Clear the specified Signal Flags of an active thread.
+/// \param[in]     thread_id     thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
+/// \param[in]     signals       specifies the signal flags of the thread that shall be cleared.
+/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters.
+/// \note MUST REMAIN UNCHANGED: \b osSignalClear shall be consistent in every CMSIS-RTOS.
+int32_t osSignalClear (osThreadId thread_id, int32_t signals);
+
+/// Get Signal Flags status of an active thread.
+/// \param[in]     thread_id     thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
+/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters.
+/// \note MUST REMAIN UNCHANGED: \b osSignalGet shall be consistent in every CMSIS-RTOS.
+int32_t osSignalGet (osThreadId thread_id);
+
+/// Wait for one or more Signal Flags to become signaled for the current \b RUNNING thread.
+/// \param[in]     signals       wait until all specified signal flags set or 0 for any single signal flag.
+/// \param[in]     millisec      timeout value or 0 in case of no time-out.
+/// \return event flag information or error code.
+/// \note MUST REMAIN UNCHANGED: \b osSignalWait shall be consistent in every CMSIS-RTOS.
+os_InRegs osEvent osSignalWait (int32_t signals, uint32_t millisec);
+
+
+//  ==== Mutex Management ====
+
+/// Define a Mutex.
+/// \param         name          name of the mutex object.
+/// \note CAN BE CHANGED: The parameter to \b osMutexDef shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#if defined (osObjectsExternal)  // object is external
+#define osMutexDef(name)  \
+extern osMutexDef_t os_mutex_def_##name
+#else                            // define the object
+#define osMutexDef(name)  \
+uint32_t os_mutex_cb_##name[3]; \
+osMutexDef_t os_mutex_def_##name = { (os_mutex_cb_##name) }
+#endif
+
+/// Access a Mutex definition.
+/// \param         name          name of the mutex object.
+/// \note CAN BE CHANGED: The parameter to \b osMutex shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#define osMutex(name)  \
+&os_mutex_def_##name
+
+/// Create and Initialize a Mutex object.
+/// \param[in]     mutex_def     mutex definition referenced with \ref osMutex.
+/// \return mutex ID for reference by other functions or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osMutexCreate shall be consistent in every CMSIS-RTOS.
+osMutexId osMutexCreate (osMutexDef_t *mutex_def);
+
+/// Wait until a Mutex becomes available.
+/// \param[in]     mutex_id      mutex ID obtained by \ref osMutexCreate.
+/// \param[in]     millisec      timeout value or 0 in case of no time-out.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osMutexWait shall be consistent in every CMSIS-RTOS.
+osStatus osMutexWait (osMutexId mutex_id, uint32_t millisec);
+
+/// Release a Mutex that was obtained by \ref osMutexWait.
+/// \param[in]     mutex_id      mutex ID obtained by \ref osMutexCreate.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osMutexRelease shall be consistent in every CMSIS-RTOS.
+osStatus osMutexRelease (osMutexId mutex_id);
+
+/// Delete a Mutex that was created by \ref osMutexCreate.
+/// \param[in]     mutex_id      mutex ID obtained by \ref osMutexCreate.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osMutexDelete shall be consistent in every CMSIS-RTOS.
+osStatus osMutexDelete (osMutexId mutex_id);
+
+
+//  ==== Semaphore Management Functions ====
+
+#if (defined (osFeature_Semaphore)  &&  (osFeature_Semaphore != 0))     // Semaphore available
+
+/// Define a Semaphore object.
+/// \param         name          name of the semaphore object.
+/// \note CAN BE CHANGED: The parameter to \b osSemaphoreDef shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#if defined (osObjectsExternal)  // object is external
+#define osSemaphoreDef(name)  \
+extern osSemaphoreDef_t os_semaphore_def_##name
+#else                            // define the object
+#define osSemaphoreDef(name)  \
+uint32_t os_semaphore_cb_##name[2]; \
+osSemaphoreDef_t os_semaphore_def_##name = { (os_semaphore_cb_##name) }
+#endif
+
+/// Access a Semaphore definition.
+/// \param         name          name of the semaphore object.
+/// \note CAN BE CHANGED: The parameter to \b osSemaphore shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#define osSemaphore(name)  \
+&os_semaphore_def_##name
+
+/// Create and Initialize a Semaphore object used for managing resources.
+/// \param[in]     semaphore_def semaphore definition referenced with \ref osSemaphore.
+/// \param[in]     count         number of available resources.
+/// \return semaphore ID for reference by other functions or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osSemaphoreCreate shall be consistent in every CMSIS-RTOS.
+osSemaphoreId osSemaphoreCreate (osSemaphoreDef_t *semaphore_def, int32_t count);
+
+/// Wait until a Semaphore token becomes available.
+/// \param[in]     semaphore_id  semaphore object referenced with \ref osSemaphoreCreate.
+/// \param[in]     millisec      timeout value or 0 in case of no time-out.
+/// \return number of available tokens, or -1 in case of incorrect parameters.
+/// \note MUST REMAIN UNCHANGED: \b osSemaphoreWait shall be consistent in every CMSIS-RTOS.
+int32_t osSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec);
+
+/// Release a Semaphore token.
+/// \param[in]     semaphore_id  semaphore object referenced with \ref osSemaphoreCreate.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osSemaphoreRelease shall be consistent in every CMSIS-RTOS.
+osStatus osSemaphoreRelease (osSemaphoreId semaphore_id);
+
+/// Delete a Semaphore that was created by \ref osSemaphoreCreate.
+/// \param[in]     semaphore_id  semaphore object referenced with \ref osSemaphoreCreate.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osSemaphoreDelete shall be consistent in every CMSIS-RTOS.
+osStatus osSemaphoreDelete (osSemaphoreId semaphore_id);
+
+#endif     // Semaphore available
+
+ 
+//  ==== Memory Pool Management Functions ====
+
+#if (defined (osFeature_Pool)  &&  (osFeature_Pool != 0))  // Memory Pool Management available
+
+/// \brief Define a Memory Pool.
+/// \param         name          name of the memory pool.
+/// \param         no            maximum number of blocks (objects) in the memory pool.
+/// \param         type          data type of a single block (object).
+/// \note CAN BE CHANGED: The parameter to \b osPoolDef shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#if defined (osObjectsExternal)  // object is external
+#define osPoolDef(name, no, type)   \
+extern osPoolDef_t os_pool_def_##name
+#else                            // define the object
+#define osPoolDef(name, no, type)   \
+uint32_t os_pool_m_##name[3+((sizeof(type)+3)/4)*(no)]; \
+osPoolDef_t os_pool_def_##name = \
+{ (no), sizeof(type), (os_pool_m_##name) }
+#endif
+
+/// \brief Access a Memory Pool definition.
+/// \param         name          name of the memory pool
+/// \note CAN BE CHANGED: The parameter to \b osPool shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#define osPool(name) \
+&os_pool_def_##name
+
+/// Create and Initialize a memory pool.
+/// \param[in]     pool_def      memory pool definition referenced with \ref osPool.
+/// \return memory pool ID for reference by other functions or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osPoolCreate shall be consistent in every CMSIS-RTOS.
+osPoolId osPoolCreate (osPoolDef_t *pool_def);
+
+/// Allocate a memory block from a memory pool.
+/// \param[in]     pool_id       memory pool ID obtain referenced with \ref osPoolCreate.
+/// \return address of the allocated memory block or NULL in case of no memory available.
+/// \note MUST REMAIN UNCHANGED: \b osPoolAlloc shall be consistent in every CMSIS-RTOS.
+void *osPoolAlloc (osPoolId pool_id);
+
+/// Allocate a memory block from a memory pool and set memory block to zero.
+/// \param[in]     pool_id       memory pool ID obtain referenced with \ref osPoolCreate.
+/// \return address of the allocated memory block or NULL in case of no memory available.
+/// \note MUST REMAIN UNCHANGED: \b osPoolCAlloc shall be consistent in every CMSIS-RTOS.
+void *osPoolCAlloc (osPoolId pool_id);
+
+/// Return an allocated memory block back to a specific memory pool.
+/// \param[in]     pool_id       memory pool ID obtain referenced with \ref osPoolCreate.
+/// \param[in]     block         address of the allocated memory block that is returned to the memory pool.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osPoolFree shall be consistent in every CMSIS-RTOS.
+osStatus osPoolFree (osPoolId pool_id, void *block);
+
+#endif   // Memory Pool Management available
+
+
+//  ==== Message Queue Management Functions ====
+
+#if (defined (osFeature_MessageQ)  &&  (osFeature_MessageQ != 0))     // Message Queues available
+
+/// \brief Create a Message Queue Definition.
+/// \param         name          name of the queue.
+/// \param         queue_sz      maximum number of messages in the queue.
+/// \param         type          data type of a single message element (for debugger).
+/// \note CAN BE CHANGED: The parameter to \b osMessageQDef shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#if defined (osObjectsExternal)  // object is external
+#define osMessageQDef(name, queue_sz, type)   \
+extern osMessageQDef_t os_messageQ_def_##name
+#else                            // define the object
+#define osMessageQDef(name, queue_sz, type)   \
+uint32_t os_messageQ_q_##name[4+(queue_sz)]; \
+osMessageQDef_t os_messageQ_def_##name = \
+{ (queue_sz), (os_messageQ_q_##name) }
+#endif
+
+/// \brief Access a Message Queue Definition.
+/// \param         name          name of the queue
+/// \note CAN BE CHANGED: The parameter to \b osMessageQ shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#define osMessageQ(name) \
+&os_messageQ_def_##name
+
+/// Create and Initialize a Message Queue.
+/// \param[in]     queue_def     queue definition referenced with \ref osMessageQ.
+/// \param[in]     thread_id     thread ID (obtained by \ref osThreadCreate or \ref osThreadGetId) or NULL.
+/// \return message queue ID for reference by other functions or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osMessageCreate shall be consistent in every CMSIS-RTOS.
+osMessageQId osMessageCreate (osMessageQDef_t *queue_def, osThreadId thread_id);
+
+/// Put a Message to a Queue.
+/// \param[in]     queue_id      message queue ID obtained with \ref osMessageCreate.
+/// \param[in]     info          message information.
+/// \param[in]     millisec      timeout value or 0 in case of no time-out.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osMessagePut shall be consistent in every CMSIS-RTOS.
+osStatus osMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec);
+
+/// Get a Message or Wait for a Message from a Queue.
+/// \param[in]     queue_id      message queue ID obtained with \ref osMessageCreate.
+/// \param[in]     millisec      timeout value or 0 in case of no time-out.
+/// \return event information that includes status code.
+/// \note MUST REMAIN UNCHANGED: \b osMessageGet shall be consistent in every CMSIS-RTOS.
+os_InRegs osEvent osMessageGet (osMessageQId queue_id, uint32_t millisec);
+
+#endif     // Message Queues available
+
+
+//  ==== Mail Queue Management Functions ====
+
+#if (defined (osFeature_MailQ)  &&  (osFeature_MailQ != 0))     // Mail Queues available
+
+/// \brief Create a Mail Queue Definition.
+/// \param         name          name of the queue
+/// \param         queue_sz      maximum number of messages in queue
+/// \param         type          data type of a single message element
+/// \note CAN BE CHANGED: The parameter to \b osMailQDef shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#if defined (osObjectsExternal)  // object is external
+#define osMailQDef(name, queue_sz, type) \
+extern osMailQDef_t os_mailQ_def_##name
+#else                            // define the object
+#define osMailQDef(name, queue_sz, type) \
+uint32_t os_mailQ_q_##name[4+(queue_sz)]; \
+uint32_t os_mailQ_m_##name[3+((sizeof(type)+3)/4)*(queue_sz)]; \
+void *   os_mailQ_p_##name[2] = { (os_mailQ_q_##name), os_mailQ_m_##name }; \
+osMailQDef_t os_mailQ_def_##name =  \
+{ (queue_sz), sizeof(type), (os_mailQ_p_##name) }
+#endif
+     
+/// \brief Access a Mail Queue Definition.
+/// \param         name          name of the queue
+/// \note CAN BE CHANGED: The parameter to \b osMailQ shall be consistent but the 
+///       macro body is implementation specific in every CMSIS-RTOS.
+#define osMailQ(name)  \
+&os_mailQ_def_##name
+
+/// Create and Initialize mail queue.
+/// \param[in]     queue_def     reference to the mail queue definition obtain with \ref osMailQ
+/// \param[in]     thread_id     thread ID (obtained by \ref osThreadCreate or \ref osThreadGetId) or NULL.
+/// \return mail queue ID for reference by other functions or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osMailCreate shall be consistent in every CMSIS-RTOS.
+osMailQId osMailCreate (osMailQDef_t *queue_def, osThreadId thread_id);
+
+/// Allocate a memory block from a mail.
+/// \param[in]     queue_id      mail queue ID obtained with \ref osMailCreate.
+/// \param[in]     millisec      timeout value or 0 in case of no time-out
+/// \return pointer to memory block that can be filled with mail or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osMailAlloc shall be consistent in every CMSIS-RTOS.
+void *osMailAlloc (osMailQId queue_id, uint32_t millisec);
+
+/// Allocate a memory block from a mail and set memory block to zero.
+/// \param[in]     queue_id      mail queue ID obtained with \ref osMailCreate.
+/// \param[in]     millisec      timeout value or 0 in case of no time-out
+/// \return pointer to memory block that can be filled with mail or NULL in case of error.
+/// \note MUST REMAIN UNCHANGED: \b osMailCAlloc shall be consistent in every CMSIS-RTOS.
+void *osMailCAlloc (osMailQId queue_id, uint32_t millisec);
+
+/// Put a mail to a queue.
+/// \param[in]     queue_id      mail queue ID obtained with \ref osMailCreate.
+/// \param[in]     mail          memory block previously allocated with \ref osMailAlloc or \ref osMailCAlloc.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osMailPut shall be consistent in every CMSIS-RTOS.
+osStatus osMailPut (osMailQId queue_id, void *mail);
+
+/// Get a mail from a queue.
+/// \param[in]     queue_id      mail queue ID obtained with \ref osMailCreate.
+/// \param[in]     millisec      timeout value or 0 in case of no time-out
+/// \return event that contains mail information or error code.
+/// \note MUST REMAIN UNCHANGED: \b osMailGet shall be consistent in every CMSIS-RTOS.
+os_InRegs osEvent osMailGet (osMailQId queue_id, uint32_t millisec);
+
+/// Free a memory block from a mail.
+/// \param[in]     queue_id      mail queue ID obtained with \ref osMailCreate.
+/// \param[in]     mail          pointer to the memory block that was obtained with \ref osMailGet.
+/// \return status code that indicates the execution status of the function.
+/// \note MUST REMAIN UNCHANGED: \b osMailFree shall be consistent in every CMSIS-RTOS.
+osStatus osMailFree (osMailQId queue_id, void *mail);
+                            
+#endif  // Mail Queues available
+
+
+#ifdef  __cplusplus
+}
+#endif
+
+#endif  // _CMSIS_OS_H
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/os_tcb.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/os_tcb.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,50 @@
+#ifndef OS_TCB_H
+#define OS_TCB_H
+
+/* Types */
+typedef char               S8;
+typedef unsigned char      U8;
+typedef short              S16;
+typedef unsigned short     U16;
+typedef int                S32;
+typedef unsigned int       U32;
+typedef long long          S64;
+typedef unsigned long long U64;
+typedef unsigned char      BIT;
+typedef unsigned int       BOOL;
+typedef void               (*FUNCP)(void);
+
+typedef struct OS_TCB {
+  /* General part: identical for all implementations.                        */
+  U8     cb_type;                 /* Control Block Type                      */
+  U8     state;                   /* Task state                              */
+  U8     prio;                    /* Execution priority                      */
+  U8     task_id;                 /* Task ID value for optimized TCB access  */
+  struct OS_TCB *p_lnk;           /* Link pointer for ready/sem. wait list   */
+  struct OS_TCB *p_rlnk;          /* Link pointer for sem./mbx lst backwards */
+  struct OS_TCB *p_dlnk;          /* Link pointer for delay list             */
+  struct OS_TCB *p_blnk;          /* Link pointer for delay list backwards   */
+  U16    delta_time;              /* Time until time out                     */
+  U16    interval_time;           /* Time interval for periodic waits        */
+  U16    events;                  /* Event flags                             */
+  U16    waits;                   /* Wait flags                              */
+  void   **msg;                   /* Direct message passing when task waits  */
+
+  /* Hardware dependant part: specific for CM processor                      */
+  U8     stack_frame;             /* Stack frame: 0=Basic, 1=Extended        */
+  U8     reserved;
+  U16    priv_stack;              /* Private stack size in bytes             */
+  U32    tsk_stack;               /* Current task Stack pointer (R13)        */
+  U32    *stack;                  /* Pointer to Task Stack memory block      */
+  
+  /* Library dependant part                                                   */
+#if defined (__CC_ARM) && !defined (__MICROLIB)
+ /* A memory space for arm standard library. */
+  U32 std_libspace[96/4];
+#endif
+  
+  /* Task entry point used for uVision debugger                              */
+  FUNCP  ptask;                   /* Task entry address                      */
+} *P_TCB;
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_CMSIS.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_CMSIS.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,1920 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    rt_CMSIS.c
+ *      Purpose: CMSIS RTOS API
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#define __CMSIS_GENERIC
+
+#if defined (__CORTEX_M4) || defined (__CORTEX_M4F)
+  #include "core_cm4.h"
+#elif defined (__CORTEX_M3)
+  #include "core_cm3.h"
+#elif defined (__CORTEX_M0)
+  #include "core_cm0.h"
+#elif defined (__CORTEX_M0PLUS)
+  #include "core_cm0plus.h"
+#else
+  #error "Missing __CORTEX_Mx definition"
+#endif
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_Task.h"
+#include "rt_Event.h"
+#include "rt_List.h"
+#include "rt_Time.h"
+#include "rt_Mutex.h"
+#include "rt_Semaphore.h"
+#include "rt_Mailbox.h"
+#include "rt_MemBox.h"
+#include "rt_HAL_CM.h"
+
+#define os_thread_cb OS_TCB
+
+#include "cmsis_os.h"
+
+#if (osFeature_Signals != 16)
+#error Invalid "osFeature_Signals" value!
+#endif
+#if (osFeature_Semaphore > 65535)
+#error Invalid "osFeature_Semaphore" value!
+#endif
+#if (osFeature_Wait != 0)
+#error osWait not supported!
+#endif
+
+
+// ==== Enumeration, structures, defines ====
+
+// Service Calls defines
+
+#if defined (__CC_ARM)          /* ARM Compiler */
+
+#define __NO_RETURN __declspec(noreturn)
+
+#define osEvent_type       osEvent
+#define osEvent_ret_status ret
+#define osEvent_ret_value  ret
+#define osEvent_ret_msg    ret
+#define osEvent_ret_mail   ret
+
+#define osCallback_type    osCallback
+#define osCallback_ret     ret
+
+#define SVC_0_1(f,t,...)                                                       \
+__svc_indirect(0) t  _##f (t(*)());                                            \
+                  t     f (void);                                              \
+__attribute__((always_inline))                                                 \
+static __inline   t __##f (void) {                                             \
+  return _##f(f);                                                              \
+}
+
+#define SVC_1_1(f,t,t1,...)                                                    \
+__svc_indirect(0) t  _##f (t(*)(t1),t1);                                       \
+                  t     f (t1 a1);                                             \
+__attribute__((always_inline))                                                 \
+static __inline   t __##f (t1 a1) {                                            \
+  return _##f(f,a1);                                                           \
+}
+
+#define SVC_2_1(f,t,t1,t2,...)                                                 \
+__svc_indirect(0) t  _##f (t(*)(t1,t2),t1,t2);                                 \
+                  t     f (t1 a1, t2 a2);                                      \
+__attribute__((always_inline))                                                 \
+static __inline   t __##f (t1 a1, t2 a2) {                                     \
+  return _##f(f,a1,a2);                                                        \
+}
+
+#define SVC_3_1(f,t,t1,t2,t3,...)                                              \
+__svc_indirect(0) t  _##f (t(*)(t1,t2,t3),t1,t2,t3);                           \
+                  t     f (t1 a1, t2 a2, t3 a3);                               \
+__attribute__((always_inline))                                                 \
+static __inline   t __##f (t1 a1, t2 a2, t3 a3) {                              \
+  return _##f(f,a1,a2,a3);                                                     \
+}
+
+#define SVC_4_1(f,t,t1,t2,t3,t4,...)                                           \
+__svc_indirect(0) t  _##f (t(*)(t1,t2,t3,t4),t1,t2,t3,t4);                     \
+                  t     f (t1 a1, t2 a2, t3 a3, t4 a4);                        \
+__attribute__((always_inline))                                                 \
+static __inline   t __##f (t1 a1, t2 a2, t3 a3, t4 a4) {                       \
+  return _##f(f,a1,a2,a3,a4);                                                  \
+}
+
+#define SVC_1_2 SVC_1_1 
+#define SVC_1_3 SVC_1_1 
+#define SVC_2_3 SVC_2_1 
+
+#elif defined (__GNUC__)        /* GNU Compiler */
+
+#define __NO_RETURN __attribute__((noreturn))
+
+typedef uint32_t __attribute__((vector_size(8)))  ret64;
+typedef uint32_t __attribute__((vector_size(16))) ret128;
+
+#define RET_pointer    __r0
+#define RET_int32_t    __r0
+#define RET_osStatus   __r0
+#define RET_osPriority __r0
+#define RET_osEvent    {(osStatus)__r0, {(uint32_t)__r1}, {(void *)__r2}}
+#define RET_osCallback {(void *)__r0, (void *)__r1}
+
+#define osEvent_type        ret128
+#define osEvent_ret_status (ret128){ret.status}
+#define osEvent_ret_value  (ret128){ret.status, ret.value.v}
+#define osEvent_ret_msg    (ret128){ret.status, ret.value.v, (uint32_t)ret.def.message_id}
+#define osEvent_ret_mail   (ret128){ret.status, ret.value.v, (uint32_t)ret.def.mail_id}
+
+#define osCallback_type     ret64
+#define osCallback_ret     (ret64) {(uint32_t)ret.fp, (uint32_t)ret.arg}
+
+#define SVC_ArgN(n) \
+  register int __r##n __asm("r"#n);
+
+#define SVC_ArgR(n,t,a) \
+  register t   __r##n __asm("r"#n) = a;
+
+#define SVC_Arg0()                                                             \
+  SVC_ArgN(0)                                                                  \
+  SVC_ArgN(1)                                                                  \
+  SVC_ArgN(2)                                                                  \
+  SVC_ArgN(3)
+
+#define SVC_Arg1(t1)                                                           \
+  SVC_ArgR(0,t1,a1)                                                            \
+  SVC_ArgN(1)                                                                  \
+  SVC_ArgN(2)                                                                  \
+  SVC_ArgN(3)
+
+#define SVC_Arg2(t1,t2)                                                        \
+  SVC_ArgR(0,t1,a1)                                                            \
+  SVC_ArgR(1,t2,a2)                                                            \
+  SVC_ArgN(2)                                                                  \
+  SVC_ArgN(3)
+
+#define SVC_Arg3(t1,t2,t3)                                                     \
+  SVC_ArgR(0,t1,a1)                                                            \
+  SVC_ArgR(1,t2,a2)                                                            \
+  SVC_ArgR(2,t3,a3)                                                            \
+  SVC_ArgN(3)
+
+#define SVC_Arg4(t1,t2,t3,t4)                                                  \
+  SVC_ArgR(0,t1,a1)                                                            \
+  SVC_ArgR(1,t2,a2)                                                            \
+  SVC_ArgR(2,t3,a3)                                                            \
+  SVC_ArgR(3,t4,a4)
+
+#if (defined (__CORTEX_M0)) || defined (__CORTEX_M0PLUS)
+#define SVC_Call(f)                                                            \
+  __asm volatile                                                                 \
+  (                                                                            \
+    "ldr r7,="#f"\n\t"                                                         \
+    "mov r12,r7\n\t"                                                           \
+    "svc 0"                                                                    \
+    :               "=r" (__r0), "=r" (__r1), "=r" (__r2), "=r" (__r3)         \
+    :                "r" (__r0),  "r" (__r1),  "r" (__r2),  "r" (__r3)         \
+    : "r7", "r12", "lr", "cc"                                                  \
+  );
+#else
+#define SVC_Call(f)                                                            \
+  __asm volatile                                                                 \
+  (                                                                            \
+    "ldr r12,="#f"\n\t"                                                        \
+    "svc 0"                                                                    \
+    :               "=r" (__r0), "=r" (__r1), "=r" (__r2), "=r" (__r3)         \
+    :                "r" (__r0),  "r" (__r1),  "r" (__r2),  "r" (__r3)         \
+    : "r12", "lr", "cc"                                                        \
+  );
+#endif
+
+#define SVC_0_1(f,t,rv)                                                        \
+__attribute__((always_inline))                                                 \
+static inline  t __##f (void) {                                                \
+  SVC_Arg0();                                                                  \
+  SVC_Call(f);                                                                 \
+  return (t) rv;                                                               \
+}
+
+#define SVC_1_1(f,t,t1,rv)                                                     \
+__attribute__((always_inline))                                                 \
+static inline  t __##f (t1 a1) {                                               \
+  SVC_Arg1(t1);                                                                \
+  SVC_Call(f);                                                                 \
+  return (t) rv;                                                               \
+}
+
+#define SVC_2_1(f,t,t1,t2,rv)                                                  \
+__attribute__((always_inline))                                                 \
+static inline  t __##f (t1 a1, t2 a2) {                                        \
+  SVC_Arg2(t1,t2);                                                             \
+  SVC_Call(f);                                                                 \
+  return (t) rv;                                                               \
+}
+
+#define SVC_3_1(f,t,t1,t2,t3,rv)                                               \
+__attribute__((always_inline))                                                 \
+static inline  t __##f (t1 a1, t2 a2, t3 a3) {                                 \
+  SVC_Arg3(t1,t2,t3);                                                          \
+  SVC_Call(f);                                                                 \
+  return (t) rv;                                                               \
+}
+
+#define SVC_4_1(f,t,t1,t2,t3,t4,rv)                                            \
+__attribute__((always_inline))                                                 \
+static inline  t __##f (t1 a1, t2 a2, t3 a3, t4 a4) {                          \
+  SVC_Arg4(t1,t2,t3,t4);                                                       \
+  SVC_Call(f);                                                                 \
+  return (t) rv;                                                               \
+}
+
+#define SVC_1_2 SVC_1_1 
+#define SVC_1_3 SVC_1_1 
+#define SVC_2_3 SVC_2_1 
+
+#elif defined (__ICCARM__)      /* IAR Compiler */
+
+#define __NO_RETURN __noreturn
+
+#define RET_osEvent        "=r"(ret.status), "=r"(ret.value), "=r"(ret.def)
+#define RET_osCallback     "=r"(ret.fp), "=r"(ret.arg)
+
+#define osEvent_type       osEvent
+#define osEvent_ret_status ret
+#define osEvent_ret_value  ret
+#define osEvent_ret_msg    ret
+#define osEvent_ret_mail   ret
+
+#define osCallback_type    uint64_t
+#define osCallback_ret     ((uint64_t)ret.fp | ((uint64_t)ret.arg)<<32)
+
+#define SVC_Setup(f)                                                           \
+  __asm(                                                                         \
+    "mov r12,%0\n"                                                             \
+    :: "r"(&f): "r12"                                                          \
+  );
+
+#define SVC_Ret3()                                                             \
+  __asm(                                                                         \
+    "ldr r0,[sp,#0]\n"                                                         \
+    "ldr r1,[sp,#4]\n"                                                         \
+    "ldr r2,[sp,#8]\n"                                                         \
+  );
+
+#define SVC_0_1(f,t,...)                                                       \
+t f (void);                                                                    \
+_Pragma("swi_number=0") __swi t _##f (void);                                   \
+static inline t __##f (void) {                                                 \
+  SVC_Setup(f);                                                                \
+  return _##f();                                                               \
+}
+
+#define SVC_1_1(f,t,t1,...)                                                    \
+t f (t1 a1);                                                                   \
+_Pragma("swi_number=0") __swi t _##f (t1 a1);                                  \
+static inline t __##f (t1 a1) {                                                \
+  SVC_Setup(f);                                                                \
+  return _##f(a1);                                                             \
+}
+
+#define SVC_2_1(f,t,t1,t2,...)                                                 \
+t f (t1 a1, t2 a2);                                                            \
+_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2);                           \
+static inline t __##f (t1 a1, t2 a2) {                                         \
+  SVC_Setup(f);                                                                \
+  return _##f(a1,a2);                                                          \
+}
+
+#define SVC_3_1(f,t,t1,t2,t3,...)                                              \
+t f (t1 a1, t2 a2, t3 a3);                                                     \
+_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2, t3 a3);                    \
+static inline t __##f (t1 a1, t2 a2, t3 a3) {                                  \
+  SVC_Setup(f);                                                                \
+  return _##f(a1,a2,a3);                                                       \
+}
+
+#define SVC_4_1(f,t,t1,t2,t3,t4,...)                                           \
+t f (t1 a1, t2 a2, t3 a3, t4 a4);                                              \
+_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2, t3 a3, t4 a4);             \
+static inline t __##f (t1 a1, t2 a2, t3 a3, t4 a4) {                           \
+  SVC_Setup(f);                                                                \
+  return _##f(a1,a2,a3,a4);                                                    \
+}
+
+#define SVC_1_2(f,t,t1,rr)                                                     \
+uint64_t f (t1 a1);                                                            \
+_Pragma("swi_number=0") __swi uint64_t _##f (t1 a1);                           \
+static inline t __##f (t1 a1) {                                                \
+  t ret;                                                                       \
+  SVC_Setup(f);                                                                \
+  _##f(a1);                                                                    \
+  __asm("" : rr : :);                                                            \
+  return ret;                                                                  \
+}
+
+#define SVC_1_3(f,t,t1,rr)                                                     \
+t f (t1 a1);                                                                   \
+void f##_ (t1 a1) {                                                            \
+  f(a1);                                                                       \
+  SVC_Ret3();                                                                  \
+}                                                                              \
+_Pragma("swi_number=0") __swi void _##f (t1 a1);                               \
+static inline t __##f (t1 a1) {                                                \
+  t ret;                                                                       \
+  SVC_Setup(f##_);                                                             \
+  _##f(a1);                                                                    \
+  __asm("" : rr : :);                                                            \
+  return ret;                                                                  \
+}
+
+#define SVC_2_3(f,t,t1,t2,rr)                                                  \
+t f (t1 a1, t2 a2);                                                            \
+void f##_ (t1 a1, t2 a2) {                                                     \
+  f(a1,a2);                                                                    \
+  SVC_Ret3();                                                                  \
+}                                                                              \
+_Pragma("swi_number=0") __swi void _##f (t1 a1, t2 a2);                        \
+static inline t __##f (t1 a1, t2 a2) {                                         \
+  t ret;                                                                       \
+  SVC_Setup(f##_);                                                             \
+  _##f(a1,a2);                                                                 \
+  __asm("" : rr : :);                                                            \
+  return ret;                                                                  \
+}
+
+#endif
+
+
+// Callback structure
+typedef struct {
+  void *fp;             // Function pointer
+  void *arg;            // Function argument
+} osCallback;
+
+
+// OS Section definitions
+#ifdef OS_SECTIONS_LINK_INFO
+extern const uint32_t  os_section_id$$Base;
+extern const uint32_t  os_section_id$$Limit;
+#endif
+
+// OS Timers external resources
+extern osThreadDef_t   os_thread_def_osTimerThread;
+extern osThreadId      osThreadId_osTimerThread;
+extern osMessageQDef_t os_messageQ_def_osTimerMessageQ;
+extern osMessageQId    osMessageQId_osTimerMessageQ;
+
+
+// ==== Helper Functions ====
+
+/// Convert timeout in millisec to system ticks
+static uint32_t rt_ms2tick (uint32_t millisec) {
+  uint32_t tick;
+
+  if (millisec == osWaitForever) return 0xFFFF; // Indefinite timeout
+  if (millisec > 4000000) return 0xFFFE;        // Max ticks supported
+
+  tick = ((1000 * millisec) + os_clockrate - 1)  / os_clockrate;
+  if (tick > 0xFFFE) return 0xFFFE;
+  
+  return tick;
+}
+
+/// Convert Thread ID to TCB pointer
+static P_TCB rt_tid2ptcb (osThreadId thread_id) {
+  P_TCB ptcb;
+
+  if (thread_id == NULL) return NULL;
+
+  if ((uint32_t)thread_id & 3) return NULL;
+
+#ifdef OS_SECTIONS_LINK_INFO
+  if ((os_section_id$$Base != 0) && (os_section_id$$Limit != 0)) {
+    if (thread_id  < (osThreadId)os_section_id$$Base)  return NULL;
+    if (thread_id >= (osThreadId)os_section_id$$Limit) return NULL;
+  }
+#endif
+
+  ptcb = thread_id;
+
+  if (ptcb->cb_type != TCB) return NULL;
+
+  return ptcb;
+}
+
+/// Convert ID pointer to Object pointer
+static void *rt_id2obj (void *id) {
+
+  if ((uint32_t)id & 3) return NULL;
+
+#ifdef OS_SECTIONS_LINK_INFO
+  if ((os_section_id$$Base != 0) && (os_section_id$$Limit != 0)) {
+    if (id  < (void *)os_section_id$$Base)  return NULL;
+    if (id >= (void *)os_section_id$$Limit) return NULL;
+  }
+#endif
+
+  return id;
+}
+
+
+// ==== Kernel Control ====
+
+uint8_t os_initialized;                         // Kernel Initialized flag
+uint8_t os_running;                             // Kernel Running flag
+
+// Kernel Control Service Calls declarations
+SVC_0_1(svcKernelInitialize, osStatus, RET_osStatus)
+SVC_0_1(svcKernelStart,      osStatus, RET_osStatus)
+SVC_0_1(svcKernelRunning,    int32_t,  RET_int32_t)
+
+extern void  sysThreadError   (osStatus status);
+osThreadId   svcThreadCreate  (osThreadDef_t *thread_def, void *argument);
+osMessageQId svcMessageCreate (osMessageQDef_t *queue_def, osThreadId thread_id);
+
+// Kernel Control Service Calls
+
+/// Initialize the RTOS Kernel for creating objects
+osStatus svcKernelInitialize (void) {
+  if (os_initialized) return osOK;
+
+  rt_sys_init();                                // RTX System Initialization
+  os_tsk.run->prio = 255;                       // Highest priority
+
+  sysThreadError(osOK);
+
+  os_initialized = 1;
+
+  return osOK;
+}
+
+/// Start the RTOS Kernel
+osStatus svcKernelStart (void) {
+
+  if (os_running) return osOK;
+
+  // Create OS Timers resources (Message Queue & Thread)
+  osMessageQId_osTimerMessageQ = svcMessageCreate (&os_messageQ_def_osTimerMessageQ, NULL);
+  osThreadId_osTimerThread = svcThreadCreate(&os_thread_def_osTimerThread, NULL);
+
+  rt_tsk_prio(0, 0);                            // Lowest priority
+  __set_PSP(os_tsk.run->tsk_stack + 8*4);       // New context
+  os_tsk.run = NULL;                            // Force context switch
+
+  rt_sys_start();
+
+  os_running = 1;
+
+  return osOK;
+}
+
+/// Check if the RTOS kernel is already started
+int32_t svcKernelRunning(void) {
+  return os_running;
+}
+
+// Kernel Control Public API
+
+/// Initialize the RTOS Kernel for creating objects
+osStatus osKernelInitialize (void) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  if ((__get_CONTROL() & 1) == 0) {             // Privileged mode
+    return   svcKernelInitialize();
+  } else {
+    return __svcKernelInitialize();
+  }
+}
+
+/// Start the RTOS Kernel
+osStatus osKernelStart (void) {
+  uint32_t stack[8];
+  
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  switch (__get_CONTROL() & 0x03) {
+    case 0x00:                                  // Privileged Thread mode & MSP
+      __set_PSP((uint32_t)(stack + 8));         // Initial PSP
+      if (os_flags & 1) {                       
+        __set_CONTROL(0x02);                    // Set Privileged Thread mode & PSP
+      } else {
+        __set_CONTROL(0x03);                    // Set Unprivileged Thread mode & PSP
+      }
+      __DSB();
+      __ISB();
+      break;
+    case 0x01:                                  // Unprivileged Thread mode & MSP
+      return osErrorOS;
+    case 0x02:                                  // Privileged Thread mode & PSP
+      if ((os_flags & 1) == 0) {                // Unprivileged Thread mode requested
+        __set_CONTROL(0x03);                    // Set Unprivileged Thread mode & PSP
+        __DSB();
+        __ISB();
+      }
+      break;
+    case 0x03:                                  // Unprivileged Thread mode & PSP
+      if  (os_flags & 1) return osErrorOS;      // Privileged Thread mode requested
+      break;
+  }
+  return __svcKernelStart();
+}
+
+/// Check if the RTOS kernel is already started
+int32_t osKernelRunning(void) {
+  if ((__get_IPSR() != 0) || ((__get_CONTROL() & 1) == 0)) {
+    // in ISR or Privileged
+    return os_running;
+  } else {
+    return __svcKernelRunning();
+  }
+}
+
+
+// ==== Thread Management ====
+
+__NO_RETURN void osThreadExit (void);
+
+// Thread Service Calls declarations
+SVC_2_1(svcThreadCreate,      osThreadId, osThreadDef_t *, void *,     RET_pointer)
+SVC_0_1(svcThreadGetId,       osThreadId,                              RET_pointer)
+SVC_1_1(svcThreadTerminate,   osStatus,   osThreadId,                  RET_osStatus)
+SVC_0_1(svcThreadYield,       osStatus,                                RET_osStatus)
+SVC_2_1(svcThreadSetPriority, osStatus,   osThreadId,      osPriority, RET_osStatus)
+SVC_1_1(svcThreadGetPriority, osPriority, osThreadId,                  RET_osPriority)
+
+// Thread Service Calls
+extern OS_TID rt_get_TID (void);
+extern void   rt_init_context (P_TCB p_TCB, U8 priority, FUNCP task_body);
+
+/// Create a thread and add it to Active Threads and set it to state READY
+osThreadId svcThreadCreate (osThreadDef_t *thread_def, void *argument) {
+  P_TCB  ptcb;
+  
+  if ((thread_def == NULL) ||
+      (thread_def->pthread == NULL) ||
+      (thread_def->tpriority < osPriorityIdle) ||
+      (thread_def->tpriority > osPriorityRealtime) ||
+      (thread_def->stacksize == 0) ||
+      (thread_def->stack_pointer == NULL) ) {
+    sysThreadError(osErrorParameter); 
+    return NULL; 
+  }
+  
+  U8 priority = thread_def->tpriority - osPriorityIdle + 1;
+  P_TCB task_context = &thread_def->tcb;
+  
+  /* If "size != 0" use a private user provided stack. */
+  task_context->stack      = (U32*)thread_def->stack_pointer;
+  task_context->priv_stack = thread_def->stacksize;
+  /* Pass parameter 'argv' to 'rt_init_context' */
+  task_context->msg = argument;
+  /* For 'size == 0' system allocates the user stack from the memory pool. */
+  rt_init_context (task_context, priority, (FUNCP)thread_def->pthread);
+
+  /* Find a free entry in 'os_active_TCB' table. */
+  OS_TID tsk = rt_get_TID ();
+  os_active_TCB[tsk-1] = task_context;
+  task_context->task_id = tsk;
+  DBG_TASK_NOTIFY(task_context, __TRUE);
+  rt_dispatch (task_context);
+  
+  ptcb = (P_TCB)os_active_TCB[tsk - 1];         // TCB pointer
+
+  *((uint32_t *)ptcb->tsk_stack + 13) = (uint32_t)osThreadExit;
+
+  return ptcb;
+}
+
+/// Return the thread ID of the current running thread
+osThreadId svcThreadGetId (void) {
+  OS_TID tsk;
+
+  tsk = rt_tsk_self();
+  if (tsk == 0) return NULL;
+  return (P_TCB)os_active_TCB[tsk - 1];
+}
+
+/// Terminate execution of a thread and remove it from ActiveThreads
+osStatus svcThreadTerminate (osThreadId thread_id) {
+  OS_RESULT res;
+  P_TCB     ptcb;
+  
+  ptcb = rt_tid2ptcb(thread_id);                // Get TCB pointer
+  if (ptcb == NULL) return osErrorParameter;
+  
+  res = rt_tsk_delete(ptcb->task_id);           // Delete task
+
+  if (res == OS_R_NOK) return osErrorResource;  // Delete task failed
+  
+  return osOK;
+}
+
+/// Pass control to next thread that is in state READY
+osStatus svcThreadYield (void) {
+  rt_tsk_pass();                                // Pass control to next task
+  return osOK;
+}
+
+/// Change priority of an active thread
+osStatus svcThreadSetPriority (osThreadId thread_id, osPriority priority) {
+  OS_RESULT res;
+  P_TCB     ptcb;
+
+  ptcb = rt_tid2ptcb(thread_id);                // Get TCB pointer
+  if (ptcb == NULL) return osErrorParameter;
+
+  if ((priority < osPriorityIdle) || (priority > osPriorityRealtime)) {
+    return osErrorValue;
+  }
+
+  res = rt_tsk_prio(                            // Change task priority
+    ptcb->task_id,                              // Task ID
+    priority - osPriorityIdle + 1               // New task priority
+  );
+
+  if (res == OS_R_NOK) return osErrorResource;  // Change task priority failed
+
+  return osOK;
+}
+
+/// Get current priority of an active thread
+osPriority svcThreadGetPriority (osThreadId thread_id) {
+  P_TCB ptcb;
+
+  ptcb = rt_tid2ptcb(thread_id);                // Get TCB pointer
+  if (ptcb == NULL) return osPriorityError;
+
+  return (osPriority)(ptcb->prio - 1 + osPriorityIdle); 
+}
+
+
+// Thread Public API
+
+/// Create a thread and add it to Active Threads and set it to state READY
+osThreadId osThreadCreate (osThreadDef_t *thread_def, void *argument) {
+  if (__get_IPSR() != 0) return NULL;           // Not allowed in ISR
+  if (((__get_CONTROL() & 1) == 0) && (os_running == 0)) {
+    // Privileged and not running
+    return   svcThreadCreate(thread_def, argument);
+  } else {
+    return __svcThreadCreate(thread_def, argument);
+  }
+}
+
+/// Return the thread ID of the current running thread
+osThreadId osThreadGetId (void) {
+  if (__get_IPSR() != 0) return NULL;           // Not allowed in ISR
+  return __svcThreadGetId();
+}
+
+/// Terminate execution of a thread and remove it from ActiveThreads
+osStatus osThreadTerminate (osThreadId thread_id) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcThreadTerminate(thread_id);
+}
+
+/// Pass control to next thread that is in state READY
+osStatus osThreadYield (void) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcThreadYield();
+}
+
+/// Change priority of an active thread
+osStatus osThreadSetPriority (osThreadId thread_id, osPriority priority) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcThreadSetPriority(thread_id, priority);
+}
+
+/// Get current priority of an active thread
+osPriority osThreadGetPriority (osThreadId thread_id) {
+  if (__get_IPSR() != 0) return osPriorityError;// Not allowed in ISR
+  return __svcThreadGetPriority(thread_id);
+}
+
+/// INTERNAL - Not Public
+/// Auto Terminate Thread on exit (used implicitly when thread exists)
+__NO_RETURN void osThreadExit (void) { 
+  __svcThreadTerminate(__svcThreadGetId()); 
+  for (;;);                                     // Should never come here
+}
+
+
+// ==== Generic Wait Functions ====
+
+// Generic Wait Service Calls declarations
+SVC_1_1(svcDelay,           osStatus, uint32_t, RET_osStatus)
+#if osFeature_Wait != 0
+SVC_1_3(svcWait,  os_InRegs osEvent,  uint32_t, RET_osEvent)
+#endif
+
+// Generic Wait Service Calls
+
+/// Wait for Timeout (Time Delay)
+osStatus svcDelay (uint32_t millisec) {
+  if (millisec == 0) return osOK;
+  rt_dly_wait(rt_ms2tick(millisec));
+  return osEventTimeout;
+}
+
+/// Wait for Signal, Message, Mail, or Timeout
+#if osFeature_Wait != 0
+os_InRegs osEvent_type svcWait (uint32_t millisec) {
+  osEvent ret;
+
+  if (millisec == 0) {
+    ret.status = osOK;
+    return osEvent_ret_status;
+  }
+
+  /* To Do: osEventSignal, osEventMessage, osEventMail */
+  rt_dly_wait(rt_ms2tick(millisec));
+  ret.status = osEventTimeout;
+
+  return osEvent_ret_status;
+}
+#endif
+
+
+// Generic Wait API
+
+/// Wait for Timeout (Time Delay)
+osStatus osDelay (uint32_t millisec) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcDelay(millisec);
+}
+
+/// Wait for Signal, Message, Mail, or Timeout
+os_InRegs osEvent osWait (uint32_t millisec) {
+  osEvent ret;
+
+#if osFeature_Wait == 0
+  ret.status = osErrorOS;
+  return ret;
+#else
+  if (__get_IPSR() != 0) {                      // Not allowed in ISR
+    ret.status = osErrorISR;
+    return ret;
+  }
+  return __svcWait(millisec);
+#endif
+}
+
+
+// ==== Timer Management ====
+
+// Timer definitions
+#define osTimerInvalid  0
+#define osTimerStopped  1
+#define osTimerRunning  2
+
+// Timer structures 
+
+typedef struct os_timer_cb_ {                   // Timer Control Block
+  struct os_timer_cb_ *next;                    // Pointer to next active Timer
+  uint8_t             state;                    // Timer State
+  uint8_t              type;                    // Timer Type (Periodic/One-shot)
+  uint16_t         reserved;                    // Reserved
+  uint16_t             tcnt;                    // Timer Delay Count
+  uint16_t             icnt;                    // Timer Initial Count 
+  void                 *arg;                    // Timer Function Argument
+  osTimerDef_t       *timer;                    // Pointer to Timer definition
+} os_timer_cb;
+
+// Timer variables
+os_timer_cb *os_timer_head;                     // Pointer to first active Timer
+
+
+// Timer Helper Functions
+
+// Insert Timer into the list sorted by time
+static void rt_timer_insert (os_timer_cb *pt, uint32_t tcnt) {
+  os_timer_cb *p, *prev;
+
+  prev = NULL;
+  p = os_timer_head;
+  while (p != NULL) {
+    if (tcnt < p->tcnt) break;
+    tcnt -= p->tcnt;
+    prev = p;
+    p = p->next;
+  }
+  pt->next = p;
+  pt->tcnt = (uint16_t)tcnt;
+  if (p != NULL) {
+    p->tcnt -= pt->tcnt;
+  }
+  if (prev != NULL) {
+    prev->next = pt;
+  } else {
+    os_timer_head = pt;
+  }
+}
+
+// Remove Timer from the list
+static int rt_timer_remove (os_timer_cb *pt) {
+  os_timer_cb *p, *prev;
+
+  prev = NULL;
+  p = os_timer_head;
+  while (p != NULL) {
+    if (p == pt) break;
+    prev = p;
+    p = p->next;
+  }
+  if (p == NULL) return -1;
+  if (prev != NULL) {
+    prev->next = pt->next;
+  } else {
+    os_timer_head = pt->next;
+  }
+  if (pt->next != NULL) {
+    pt->next->tcnt += pt->tcnt;
+  }
+
+  return 0;
+}
+
+
+// Timer Service Calls declarations
+SVC_3_1(svcTimerCreate,           osTimerId,  osTimerDef_t *, os_timer_type, void *, RET_pointer)
+SVC_2_1(svcTimerStart,            osStatus,   osTimerId,      uint32_t,              RET_osStatus)
+SVC_1_1(svcTimerStop,             osStatus,   osTimerId,                             RET_osStatus)
+SVC_1_1(svcTimerDelete,           osStatus,   osTimerId,                             RET_osStatus)
+SVC_1_2(svcTimerCall,   os_InRegs osCallback, osTimerId,                             RET_osCallback)
+
+// Timer Management Service Calls
+
+/// Create timer
+osTimerId svcTimerCreate (osTimerDef_t *timer_def, os_timer_type type, void *argument) {
+  os_timer_cb *pt;
+
+  if ((timer_def == NULL) || (timer_def->ptimer == NULL)) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  pt = timer_def->timer;
+  if (pt == NULL) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  if ((type != osTimerOnce) && (type != osTimerPeriodic)) {
+    sysThreadError(osErrorValue);
+    return NULL;
+  }
+
+  if (osThreadId_osTimerThread == NULL) {
+    sysThreadError(osErrorResource);
+    return NULL;
+  }
+
+  if (pt->state != osTimerInvalid){
+    sysThreadError(osErrorResource);
+    return NULL;
+  }
+
+  pt->state = osTimerStopped;
+  pt->type  =  (uint8_t)type;
+  pt->arg   = argument;
+  pt->timer = timer_def;
+
+  return (osTimerId)pt;
+}
+
+/// Start or restart timer
+osStatus svcTimerStart (osTimerId timer_id, uint32_t millisec) {
+  os_timer_cb *pt;
+  uint32_t     tcnt;
+
+  pt = rt_id2obj(timer_id);
+  if (pt == NULL) return osErrorParameter;
+
+  tcnt = rt_ms2tick(millisec);
+  if (tcnt == 0) return osErrorValue;
+
+  switch (pt->state) {
+    case osTimerRunning:
+      if (rt_timer_remove(pt) != 0) {
+        return osErrorResource;
+      }
+      break;
+    case osTimerStopped:
+      pt->state = osTimerRunning;
+      pt->icnt  = (uint16_t)tcnt;
+      break;
+    default:
+      return osErrorResource;
+  }
+  
+  rt_timer_insert(pt, tcnt);
+
+  return osOK;
+}
+
+/// Stop timer
+osStatus svcTimerStop (osTimerId timer_id) {
+  os_timer_cb *pt;
+
+  pt = rt_id2obj(timer_id);
+  if (pt == NULL) return osErrorParameter;
+
+  if (pt->state != osTimerRunning) return osErrorResource;
+
+  pt->state = osTimerStopped;
+
+  if (rt_timer_remove(pt) != 0) {
+    return osErrorResource;
+  }
+
+  return osOK;
+}
+
+/// Delete timer
+osStatus svcTimerDelete (osTimerId timer_id) {
+  os_timer_cb *pt;
+
+  pt = rt_id2obj(timer_id);
+  if (pt == NULL) return osErrorParameter;
+
+  switch (pt->state) {
+    case osTimerRunning:
+      rt_timer_remove(pt);
+      break;
+    case osTimerStopped:
+      break;
+    default:
+      return osErrorResource;
+  }
+
+  pt->state = osTimerInvalid;
+
+  return osOK;
+}
+
+/// Get timer callback parameters
+os_InRegs osCallback_type svcTimerCall (osTimerId timer_id) {
+  os_timer_cb *pt;
+  osCallback   ret;
+
+  pt = rt_id2obj(timer_id);
+  if (pt == NULL) {
+    ret.fp  = NULL;
+    ret.arg = NULL;
+    return osCallback_ret;
+  }
+
+  ret.fp  = (void *)pt->timer->ptimer;
+  ret.arg = pt->arg;
+
+  return osCallback_ret;
+}
+
+static __INLINE osStatus isrMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec);
+
+/// Timer Tick (called each SysTick)
+void sysTimerTick (void) {
+  os_timer_cb *pt, *p;
+
+  p = os_timer_head;
+  if (p == NULL) return;
+
+  p->tcnt--;
+  while ((p != NULL) && (p->tcnt == 0)) {
+    pt = p;
+    p = p->next;
+    os_timer_head = p;
+    isrMessagePut(osMessageQId_osTimerMessageQ, (uint32_t)pt, 0);
+    if (pt->type == osTimerPeriodic) {
+      rt_timer_insert(pt, pt->icnt);
+    } else {
+      pt->state = osTimerStopped;
+    }
+  }
+}
+
+
+// Timer Management Public API
+
+/// Create timer
+osTimerId osTimerCreate (osTimerDef_t *timer_def, os_timer_type type, void *argument) {
+  if (__get_IPSR() != 0) return NULL;           // Not allowed in ISR
+  if (((__get_CONTROL() & 1) == 0) && (os_running == 0)) {
+    // Privileged and not running
+    return   svcTimerCreate(timer_def, type, argument);
+  } else {
+    return __svcTimerCreate(timer_def, type, argument);
+  }
+}
+
+/// Start or restart timer
+osStatus osTimerStart (osTimerId timer_id, uint32_t millisec) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcTimerStart(timer_id, millisec);
+}
+
+/// Stop timer
+osStatus osTimerStop (osTimerId timer_id) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcTimerStop(timer_id);
+}
+
+/// Delete timer
+osStatus osTimerDelete (osTimerId timer_id) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcTimerDelete(timer_id);
+}
+
+/// INTERNAL - Not Public
+/// Get timer callback parameters (used by OS Timer Thread)
+os_InRegs osCallback osTimerCall (osTimerId timer_id) { 
+  return __svcTimerCall(timer_id); 
+}
+
+
+// Timer Thread
+__NO_RETURN void osTimerThread (void const *argument) {
+  osCallback cb;
+  osEvent    evt;
+
+  for (;;) {
+    evt = osMessageGet(osMessageQId_osTimerMessageQ, osWaitForever);
+    if (evt.status == osEventMessage) {
+      cb = osTimerCall(evt.value.p);
+      if (cb.fp != NULL) {
+        (*(os_ptimer)cb.fp)(cb.arg);
+      }
+    }
+  }
+}
+
+
+// ==== Signal Management ====
+
+// Signal Service Calls declarations
+SVC_2_1(svcSignalSet,             int32_t, osThreadId, int32_t,  RET_int32_t)
+SVC_2_1(svcSignalClear,           int32_t, osThreadId, int32_t,  RET_int32_t)
+SVC_1_1(svcSignalGet,             int32_t, osThreadId,           RET_int32_t)
+SVC_2_3(svcSignalWait,  os_InRegs osEvent, int32_t,    uint32_t, RET_osEvent)
+
+// Signal Service Calls
+
+/// Set the specified Signal Flags of an active thread
+int32_t svcSignalSet (osThreadId thread_id, int32_t signals) {
+  P_TCB   ptcb;
+  int32_t sig;
+
+  ptcb = rt_tid2ptcb(thread_id);                // Get TCB pointer
+  if (ptcb == NULL) return 0x80000000;
+
+  if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000;
+
+  sig = ptcb->events;                           // Previous signal flags
+
+  rt_evt_set(signals, ptcb->task_id);           // Set event flags
+
+  return sig;
+}
+
+/// Clear the specified Signal Flags of an active thread
+int32_t svcSignalClear (osThreadId thread_id, int32_t signals) {
+  P_TCB   ptcb;
+  int32_t sig;
+
+  ptcb = rt_tid2ptcb(thread_id);                // Get TCB pointer
+  if (ptcb == NULL) return 0x80000000;
+
+  if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000;
+
+  sig = ptcb->events;                           // Previous signal flags
+
+  rt_evt_clr(signals, ptcb->task_id);           // Clear event flags
+
+  return sig;
+}
+
+/// Get Signal Flags status of an active thread
+int32_t svcSignalGet (osThreadId thread_id) {
+  P_TCB ptcb;
+
+  ptcb = rt_tid2ptcb(thread_id);                // Get TCB pointer
+  if (ptcb == NULL) return 0x80000000;
+
+  return ptcb->events;                          // Return event flags
+}
+
+/// Wait for one or more Signal Flags to become signaled for the current RUNNING thread
+os_InRegs osEvent_type svcSignalWait (int32_t signals, uint32_t millisec) {
+  OS_RESULT res;
+  osEvent   ret;
+
+  if (signals & (0xFFFFFFFF << osFeature_Signals)) {
+    ret.status = osErrorValue;
+    return osEvent_ret_status;
+  }
+
+  if (signals != 0) {                           // Wait for all specified signals
+    res = rt_evt_wait(signals, rt_ms2tick(millisec), __TRUE);
+  } else {                                      // Wait for any signal
+    res = rt_evt_wait(0xFFFF,  rt_ms2tick(millisec), __FALSE);
+  }
+
+  if (res == OS_R_EVT) {
+    ret.status = osEventSignal;
+    ret.value.signals = signals ? signals : os_tsk.run->waits;
+  } else {
+    ret.status = millisec ? osEventTimeout : osOK;
+    ret.value.signals = 0;
+  }
+
+  return osEvent_ret_value;
+}
+
+
+// Signal ISR Calls
+
+/// Set the specified Signal Flags of an active thread
+static __INLINE int32_t isrSignalSet (osThreadId thread_id, int32_t signals) {
+  P_TCB   ptcb;
+  int32_t sig;
+
+  ptcb = rt_tid2ptcb(thread_id);                // Get TCB pointer
+  if (ptcb == NULL) return 0x80000000;
+
+  if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000;
+
+  sig = ptcb->events;                           // Previous signal flags
+
+  isr_evt_set(signals, ptcb->task_id);          // Set event flags
+
+  return sig;
+}
+
+
+// Signal Public API
+
+/// Set the specified Signal Flags of an active thread
+int32_t osSignalSet (osThreadId thread_id, int32_t signals) {
+  if (__get_IPSR() != 0) {                      // in ISR
+    return   isrSignalSet(thread_id, signals); 
+  } else {                                      // in Thread
+    return __svcSignalSet(thread_id, signals);
+  }
+}
+
+/// Clear the specified Signal Flags of an active thread
+int32_t osSignalClear (osThreadId thread_id, int32_t signals) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcSignalClear(thread_id, signals);
+}
+
+/// Get Signal Flags status of an active thread
+int32_t osSignalGet (osThreadId thread_id) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcSignalGet(thread_id);
+}
+
+/// Wait for one or more Signal Flags to become signaled for the current RUNNING thread
+os_InRegs osEvent osSignalWait (int32_t signals, uint32_t millisec) {
+  osEvent ret;
+
+  if (__get_IPSR() != 0) {                      // Not allowed in ISR
+    ret.status = osErrorISR;
+    return ret;
+  }
+  return __svcSignalWait(signals, millisec);
+}
+
+
+// ==== Mutex Management ====
+
+// Mutex Service Calls declarations
+SVC_1_1(svcMutexCreate,  osMutexId, osMutexDef_t *,           RET_pointer)
+SVC_2_1(svcMutexWait,    osStatus,  osMutexId,      uint32_t, RET_osStatus)
+SVC_1_1(svcMutexRelease, osStatus,  osMutexId,                RET_osStatus)
+SVC_1_1(svcMutexDelete,  osStatus,  osMutexId,                RET_osStatus)
+
+// Mutex Service Calls
+
+/// Create and Initialize a Mutex object
+osMutexId svcMutexCreate (osMutexDef_t *mutex_def) {
+  OS_ID mut;
+
+  if (mutex_def == NULL) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  mut = mutex_def->mutex;
+  if (mut == NULL) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  if (((P_MUCB)mut)->cb_type != 0) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  rt_mut_init(mut);                             // Initialize Mutex
+
+  return mut;
+}
+
+/// Wait until a Mutex becomes available
+osStatus svcMutexWait (osMutexId mutex_id, uint32_t millisec) {
+  OS_ID     mut;
+  OS_RESULT res;
+
+  mut = rt_id2obj(mutex_id);
+  if (mut == NULL) return osErrorParameter;
+
+  if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter;
+
+  res = rt_mut_wait(mut, rt_ms2tick(millisec)); // Wait for Mutex
+
+  if (res == OS_R_TMO) {
+    return (millisec ? osErrorTimeoutResource : osErrorResource);
+  }
+
+  return osOK;
+}
+
+/// Release a Mutex that was obtained with osMutexWait
+osStatus svcMutexRelease (osMutexId mutex_id) {
+  OS_ID     mut;
+  OS_RESULT res;
+
+  mut = rt_id2obj(mutex_id);
+  if (mut == NULL) return osErrorParameter;
+
+  if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter;
+
+  res = rt_mut_release(mut);                    // Release Mutex
+
+  if (res == OS_R_NOK) return osErrorResource;  // Thread not owner or Zero Counter
+
+  return osOK;
+}
+
+/// Delete a Mutex that was created by osMutexCreate
+osStatus svcMutexDelete (osMutexId mutex_id) {
+  OS_ID mut;
+
+  mut = rt_id2obj(mutex_id);
+  if (mut == NULL) return osErrorParameter;
+
+  if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter;
+
+  rt_mut_delete(mut);                           // Release Mutex
+
+  return osOK;
+}
+
+
+// Mutex Public API
+
+/// Create and Initialize a Mutex object
+osMutexId osMutexCreate (osMutexDef_t *mutex_def) {
+  if (__get_IPSR() != 0) return NULL;           // Not allowed in ISR
+  if (((__get_CONTROL() & 1) == 0) && (os_running == 0)) {
+    // Privileged and not running
+    return    svcMutexCreate(mutex_def);
+  } else {
+    return __svcMutexCreate(mutex_def);
+  }
+}
+
+/// Wait until a Mutex becomes available
+osStatus osMutexWait (osMutexId mutex_id, uint32_t millisec) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcMutexWait(mutex_id, millisec);
+}
+
+/// Release a Mutex that was obtained with osMutexWait
+osStatus osMutexRelease (osMutexId mutex_id) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcMutexRelease(mutex_id);
+}
+
+/// Delete a Mutex that was created by osMutexCreate
+osStatus osMutexDelete (osMutexId mutex_id) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcMutexDelete(mutex_id);
+}
+
+
+// ==== Semaphore Management ====
+
+// Semaphore Service Calls declarations
+SVC_2_1(svcSemaphoreCreate,  osSemaphoreId, const osSemaphoreDef_t *,  int32_t, RET_pointer)
+SVC_2_1(svcSemaphoreWait,    int32_t,       osSemaphoreId,      uint32_t, RET_int32_t)
+SVC_1_1(svcSemaphoreRelease, osStatus,      osSemaphoreId,                RET_osStatus)
+SVC_1_1(svcSemaphoreDelete,  osStatus,            osSemaphoreId,                RET_osStatus)
+
+// Semaphore Service Calls
+
+/// Create and Initialize a Semaphore object
+osSemaphoreId svcSemaphoreCreate (const osSemaphoreDef_t *semaphore_def, int32_t count) {
+  OS_ID sem;
+
+  if (semaphore_def == NULL) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  sem = semaphore_def->semaphore;
+  if (sem == NULL) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  if (((P_SCB)sem)->cb_type != 0) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  if (count > osFeature_Semaphore) {
+    sysThreadError(osErrorValue);
+    return NULL;
+  }
+
+  rt_sem_init(sem, count);                      // Initialize Semaphore
+  
+  return sem;
+}
+
+/// Wait until a Semaphore becomes available
+int32_t svcSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec) {
+  OS_ID     sem;
+  OS_RESULT res;
+
+  sem = rt_id2obj(semaphore_id);
+  if (sem == NULL) return -1;
+
+  if (((P_SCB)sem)->cb_type != SCB) return -1;
+
+  res = rt_sem_wait(sem, rt_ms2tick(millisec)); // Wait for Semaphore
+
+  if (res == OS_R_TMO) return 0;                // Timeout
+
+  return (((P_SCB)sem)->tokens + 1);
+}
+
+/// Release a Semaphore
+osStatus svcSemaphoreRelease (osSemaphoreId semaphore_id) {
+  OS_ID sem;
+
+  sem = rt_id2obj(semaphore_id);
+  if (sem == NULL) return osErrorParameter;
+
+  if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter;
+
+  if (((P_SCB)sem)->tokens == osFeature_Semaphore) return osErrorResource;
+  
+  rt_sem_send(sem);                             // Release Semaphore
+
+  return osOK;
+}
+
+/// Delete a Semaphore that was created by osSemaphoreCreate
+osStatus svcSemaphoreDelete (osSemaphoreId semaphore_id) {
+  OS_ID sem;
+
+  sem = rt_id2obj(semaphore_id);
+  if (sem == NULL) return osErrorParameter;
+
+  if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter;
+
+  rt_sem_delete(sem);                           // Delete Semaphore
+
+  return osOK;
+}
+
+
+// Semaphore ISR Calls
+
+/// Release a Semaphore
+static __INLINE osStatus isrSemaphoreRelease (osSemaphoreId semaphore_id) {
+  OS_ID sem;
+
+  sem = rt_id2obj(semaphore_id);
+  if (sem == NULL) return osErrorParameter;
+
+  if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter;
+
+  if (((P_SCB)sem)->tokens == osFeature_Semaphore) return osErrorResource;
+
+  isr_sem_send(sem);                            // Release Semaphore
+
+  return osOK;
+}
+
+
+// Semaphore Public API
+
+/// Create and Initialize a Semaphore object
+osSemaphoreId osSemaphoreCreate (osSemaphoreDef_t *semaphore_def, int32_t count) {
+  if (__get_IPSR() != 0) return NULL;           // Not allowed in ISR
+  if (((__get_CONTROL() & 1) == 0) && (os_running == 0)) {
+    // Privileged and not running
+    return   svcSemaphoreCreate(semaphore_def, count);
+  } else {
+    return __svcSemaphoreCreate(semaphore_def, count);
+  }
+}
+
+/// Wait until a Semaphore becomes available
+int32_t osSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec) {
+  if (__get_IPSR() != 0) return -1;             // Not allowed in ISR
+  return __svcSemaphoreWait(semaphore_id, millisec);
+}
+
+/// Release a Semaphore
+osStatus osSemaphoreRelease (osSemaphoreId semaphore_id) {
+  if (__get_IPSR() != 0) {                      // in ISR
+    return   isrSemaphoreRelease(semaphore_id);
+  } else {                                      // in Thread
+    return __svcSemaphoreRelease(semaphore_id);
+  }
+}
+
+/// Delete a Semaphore that was created by osSemaphoreCreate
+osStatus osSemaphoreDelete (osSemaphoreId semaphore_id) {
+  if (__get_IPSR() != 0) return osErrorISR;     // Not allowed in ISR
+  return __svcSemaphoreDelete(semaphore_id);
+}
+
+
+// ==== Memory Management Functions ====
+
+// Memory Management Helper Functions
+
+// Clear Memory Box (Zero init)
+static void rt_clr_box (void *box_mem, void *box) {
+  uint32_t *p, n;
+
+  if (box) {
+    p = box;
+    for (n = ((P_BM)box_mem)->blk_size; n; n -= 4) {
+      *p++ = 0;
+    }
+  }
+}
+
+// Memory Management Service Calls declarations
+SVC_1_1(svcPoolCreate, osPoolId, const osPoolDef_t *,           RET_pointer)
+SVC_2_1(sysPoolAlloc,  void *,   osPoolId,      uint32_t, RET_pointer)
+SVC_2_1(sysPoolFree,   osStatus, osPoolId,      void *,   RET_osStatus)
+
+// Memory Management Service & ISR Calls
+
+/// Create and Initialize memory pool
+osPoolId svcPoolCreate (const osPoolDef_t *pool_def) {
+  uint32_t blk_sz;
+
+  if ((pool_def == NULL) ||
+      (pool_def->pool_sz == 0) ||
+      (pool_def->item_sz == 0) ||
+      (pool_def->pool == NULL)) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  blk_sz = (pool_def->item_sz + 3) & ~3;
+
+  _init_box(pool_def->pool, sizeof(struct OS_BM) + pool_def->pool_sz * blk_sz, blk_sz);
+
+  return pool_def->pool;
+}
+
+/// Allocate a memory block from a memory pool
+void *sysPoolAlloc (osPoolId pool_id, uint32_t clr) {
+  void *ptr;
+
+  if (pool_id == NULL) return NULL;
+
+  ptr = rt_alloc_box(pool_id);
+  if (clr) {
+    rt_clr_box(pool_id, ptr);
+  }
+
+  return ptr;
+}
+
+/// Return an allocated memory block back to a specific memory pool
+osStatus sysPoolFree (osPoolId pool_id, void *block) {
+  int32_t res;
+    
+  if (pool_id == NULL) return osErrorParameter;
+
+  res = rt_free_box(pool_id, block);
+  if (res != 0) return osErrorValue;
+
+  return osOK;
+}
+
+
+// Memory Management Public API
+
+/// Create and Initialize memory pool
+osPoolId osPoolCreate (osPoolDef_t *pool_def) {
+  if (__get_IPSR() != 0) return NULL;           // Not allowed in ISR
+  if (((__get_CONTROL() & 1) == 0) && (os_running == 0)) {
+    // Privileged and not running
+    return   svcPoolCreate(pool_def);
+  } else {
+    return __svcPoolCreate(pool_def);
+  }
+}
+
+/// Allocate a memory block from a memory pool
+void *osPoolAlloc (osPoolId pool_id) {
+  if ((__get_IPSR() != 0) || ((__get_CONTROL() & 1) == 0)) {    // in ISR or Privileged
+    return   sysPoolAlloc(pool_id, 0);
+  } else {                                      // in Thread
+    return __sysPoolAlloc(pool_id, 0);
+  }
+}
+
+/// Allocate a memory block from a memory pool and set memory block to zero
+void *osPoolCAlloc (osPoolId pool_id) {
+  if ((__get_IPSR() != 0) || ((__get_CONTROL() & 1) == 0)) {    // in ISR or Privileged
+    return   sysPoolAlloc(pool_id, 1);
+  } else {                                      // in Thread
+    return __sysPoolAlloc(pool_id, 1);
+  }
+}
+
+/// Return an allocated memory block back to a specific memory pool
+osStatus osPoolFree (osPoolId pool_id, void *block) {
+  if ((__get_IPSR() != 0) || ((__get_CONTROL() & 1) == 0)) {    // in ISR or Privileged
+    return   sysPoolFree(pool_id, block);
+  } else {                                      // in Thread
+    return __sysPoolFree(pool_id, block);
+  }
+}
+
+
+// ==== Message Queue Management Functions ====
+
+// Message Queue Management Service Calls declarations
+SVC_2_1(svcMessageCreate,        osMessageQId,    osMessageQDef_t *, osThreadId,           RET_pointer)
+SVC_3_1(svcMessagePut,              osStatus,     osMessageQId,      uint32_t,   uint32_t, RET_osStatus)
+SVC_2_3(svcMessageGet,    os_InRegs osEvent,      osMessageQId,      uint32_t,             RET_osEvent)
+
+// Message Queue Service Calls
+
+/// Create and Initialize Message Queue
+osMessageQId svcMessageCreate (osMessageQDef_t *queue_def, osThreadId thread_id) {
+
+  if ((queue_def == NULL) ||
+      (queue_def->queue_sz == 0) ||
+      (queue_def->pool == NULL)) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+  
+  if (((P_MCB)queue_def->pool)->cb_type != 0) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  rt_mbx_init(queue_def->pool, 4*(queue_def->queue_sz + 4));
+
+  return queue_def->pool;
+}
+
+/// Put a Message to a Queue
+osStatus svcMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) {
+  OS_RESULT res;
+
+  if (queue_id == NULL) return osErrorParameter;
+
+  if (((P_MCB)queue_id)->cb_type != MCB) return osErrorParameter;
+
+  res = rt_mbx_send(queue_id, (void *)info, rt_ms2tick(millisec));
+
+  if (res == OS_R_TMO) {
+    return (millisec ? osErrorTimeoutResource : osErrorResource);
+  }
+
+  return osOK;
+}
+
+/// Get a Message or Wait for a Message from a Queue
+os_InRegs osEvent_type svcMessageGet (osMessageQId queue_id, uint32_t millisec) {
+  OS_RESULT res;
+  osEvent   ret;
+
+  if (queue_id == NULL) {
+    ret.status = osErrorParameter;
+    return osEvent_ret_status;
+  }
+
+  if (((P_MCB)queue_id)->cb_type != MCB) {
+    ret.status = osErrorParameter;
+    return osEvent_ret_status;
+  }
+
+  res = rt_mbx_wait(queue_id, &ret.value.p, rt_ms2tick(millisec));
+  
+  if (res == OS_R_TMO) {
+    ret.status = millisec ? osEventTimeout : osOK;
+    return osEvent_ret_value;
+  }
+
+  ret.status = osEventMessage;
+
+  return osEvent_ret_value;
+}
+
+
+// Message Queue ISR Calls
+
+/// Put a Message to a Queue
+static __INLINE osStatus isrMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) {
+
+  if ((queue_id == NULL) || (millisec != 0)) {
+    return osErrorParameter;
+  }
+
+  if (((P_MCB)queue_id)->cb_type != MCB) return osErrorParameter;
+
+  if (rt_mbx_check(queue_id) == 0) {            // Check if Queue is full
+    return osErrorResource;
+  }
+
+  isr_mbx_send(queue_id, (void *)info);
+
+  return osOK;
+}
+
+/// Get a Message or Wait for a Message from a Queue
+static __INLINE os_InRegs osEvent isrMessageGet (osMessageQId queue_id, uint32_t millisec) {
+  OS_RESULT res;
+  osEvent   ret;
+
+  if ((queue_id == NULL) || (millisec != 0)) {
+    ret.status = osErrorParameter;
+    return ret;
+  }
+
+  if (((P_MCB)queue_id)->cb_type != MCB) {
+    ret.status = osErrorParameter;
+    return ret;
+  }
+
+  res = isr_mbx_receive(queue_id, &ret.value.p);
+  
+  if (res != OS_R_MBX) {
+    ret.status = osOK;
+    return ret;
+  }
+
+  ret.status = osEventMessage; 
+
+  return ret;
+}
+
+
+// Message Queue Management Public API
+
+/// Create and Initialize Message Queue
+osMessageQId osMessageCreate (osMessageQDef_t *queue_def, osThreadId thread_id) {
+  if (__get_IPSR() != 0) return NULL;           // Not allowed in ISR
+  if (((__get_CONTROL() & 1) == 0) && (os_running == 0)) {
+    // Privileged and not running
+    return   svcMessageCreate(queue_def, thread_id);
+  } else {
+    return __svcMessageCreate(queue_def, thread_id);
+  }
+}
+
+/// Put a Message to a Queue
+osStatus osMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) {
+  if (__get_IPSR() != 0) {                      // in ISR
+    return   isrMessagePut(queue_id, info, millisec);
+  } else {                                      // in Thread
+    return __svcMessagePut(queue_id, info, millisec);
+  }
+}
+
+/// Get a Message or Wait for a Message from a Queue
+os_InRegs osEvent osMessageGet (osMessageQId queue_id, uint32_t millisec) {
+  if (__get_IPSR() != 0) {                      // in ISR
+    return   isrMessageGet(queue_id, millisec);
+  } else {                                      // in Thread
+    return __svcMessageGet(queue_id, millisec);
+  }
+}
+
+
+// ==== Mail Queue Management Functions ====
+
+// Mail Queue Management Service Calls declarations
+SVC_2_1(svcMailCreate, osMailQId, osMailQDef_t *, osThreadId,                   RET_pointer)
+SVC_4_1(sysMailAlloc,  void *,    osMailQId,      uint32_t, uint32_t, uint32_t, RET_pointer)
+SVC_3_1(sysMailFree,   osStatus,  osMailQId,      void *,   uint32_t,           RET_osStatus)
+
+// Mail Queue Management Service & ISR Calls
+
+/// Create and Initialize mail queue
+osMailQId svcMailCreate (osMailQDef_t *queue_def, osThreadId thread_id) {
+  uint32_t blk_sz;
+  P_MCB    pmcb;
+  void    *pool;
+
+  if ((queue_def == NULL) ||
+      (queue_def->queue_sz == 0) ||
+      (queue_def->item_sz  == 0) ||
+      (queue_def->pool == NULL)) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  pmcb = *(((void **)queue_def->pool) + 0);
+  pool = *(((void **)queue_def->pool) + 1);
+
+  if ((pool == NULL) || (pmcb == NULL) || (pmcb->cb_type != 0)) {
+    sysThreadError(osErrorParameter);
+    return NULL;
+  }
+
+  blk_sz = (queue_def->item_sz + 3) & ~3;
+
+  _init_box(pool, sizeof(struct OS_BM) + queue_def->queue_sz * blk_sz, blk_sz);
+
+  rt_mbx_init(pmcb, 4*(queue_def->queue_sz + 4));
+
+
+  return queue_def->pool;
+}
+
+/// Allocate a memory block from a mail
+void *sysMailAlloc (osMailQId queue_id, uint32_t millisec, uint32_t isr, uint32_t clr) {
+  P_MCB pmcb;
+  void *pool;
+  void *mem;
+
+  if (queue_id == NULL) return NULL;
+
+  pmcb = *(((void **)queue_id) + 0);
+  pool = *(((void **)queue_id) + 1);
+
+  if ((pool == NULL) || (pmcb == NULL)) return NULL;
+
+  if (isr && (millisec != 0)) return NULL;
+
+  mem = rt_alloc_box(pool);
+  if (clr) {
+    rt_clr_box(pool, mem);
+  }
+
+  if ((mem == NULL) && (millisec != 0)) {
+    // Put Task to sleep when Memory not available
+    if (pmcb->p_lnk != NULL) {
+      rt_put_prio((P_XCB)pmcb, os_tsk.run);
+    } else {
+      pmcb->p_lnk = os_tsk.run;
+      os_tsk.run->p_lnk = NULL;
+      os_tsk.run->p_rlnk = (P_TCB)pmcb;
+      // Task is waiting to allocate a message
+      pmcb->state = 3;
+    }
+    rt_block(rt_ms2tick(millisec), WAIT_MBX);
+  }
+
+  return mem;  
+}
+
+/// Free a memory block from a mail
+osStatus sysMailFree (osMailQId queue_id, void *mail, uint32_t isr) {
+  P_MCB   pmcb;
+  P_TCB   ptcb;
+  void   *pool;
+  void   *mem;
+  int32_t res;
+
+  if (queue_id == NULL) return osErrorParameter;
+
+  pmcb = *(((void **)queue_id) + 0);
+  pool = *(((void **)queue_id) + 1);
+
+  if ((pmcb == NULL) || (pool == NULL)) return osErrorParameter;
+
+  res = rt_free_box(pool, mail);
+
+  if (res != 0) return osErrorValue;
+
+  if (pmcb->state == 3) {
+    // Task is waiting to allocate a message
+    if (isr) {
+      rt_psq_enq (pmcb, (U32)pool);
+      rt_psh_req ();
+    } else {
+      mem = rt_alloc_box(pool);
+      if (mem != NULL) {
+        ptcb = rt_get_first((P_XCB)pmcb);
+        if (pmcb->p_lnk == NULL) {
+          pmcb->state = 0;
+        }
+        rt_ret_val(ptcb, (U32)mem);
+        rt_rmv_dly(ptcb);
+        rt_dispatch(ptcb);
+      }
+    }
+  }
+
+  return osOK;
+}
+
+
+// Mail Queue Management Public API
+
+/// Create and Initialize mail queue
+osMailQId osMailCreate (osMailQDef_t *queue_def, osThreadId thread_id) {
+  if (__get_IPSR() != 0) return NULL;           // Not allowed in ISR
+  if (((__get_CONTROL() & 1) == 0) && (os_running == 0)) {
+    // Privileged and not running
+    return   svcMailCreate(queue_def, thread_id);
+  } else {
+    return __svcMailCreate(queue_def, thread_id);
+  }
+}
+
+/// Allocate a memory block from a mail
+void *osMailAlloc (osMailQId queue_id, uint32_t millisec) {
+  if (__get_IPSR() != 0) {                      // in ISR
+    return   sysMailAlloc(queue_id, millisec, 1, 0);
+  } else {                                      // in Thread
+    return __sysMailAlloc(queue_id, millisec, 0, 0);
+  }
+}
+
+/// Allocate a memory block from a mail and set memory block to zero
+void *osMailCAlloc (osMailQId queue_id, uint32_t millisec) {
+  if (__get_IPSR() != 0) {                      // in ISR
+    return   sysMailAlloc(queue_id, millisec, 1, 1);
+  } else {                                      // in Thread
+    return __sysMailAlloc(queue_id, millisec, 0, 1);
+  }
+}
+
+/// Free a memory block from a mail
+osStatus osMailFree (osMailQId queue_id, void *mail) {
+  if (__get_IPSR() != 0) {                      // in ISR
+    return   sysMailFree(queue_id, mail, 1);
+  } else {                                      // in Thread
+    return __sysMailFree(queue_id, mail, 0);
+  }
+}
+
+/// Put a mail to a queue
+osStatus osMailPut (osMailQId queue_id, void *mail) {
+  if (queue_id == NULL) return osErrorParameter;
+  if (mail == NULL)     return osErrorValue;
+  return osMessagePut(*((void **)queue_id), (uint32_t)mail, 0);
+}
+
+/// Get a mail from a queue
+os_InRegs osEvent osMailGet (osMailQId queue_id, uint32_t millisec) {
+  osEvent ret;
+
+  if (queue_id == NULL) {
+    ret.status = osErrorParameter;
+    return ret;
+  }
+
+  ret = osMessageGet(*((void **)queue_id), millisec);
+  if (ret.status == osEventMessage) ret.status = osEventMail;
+
+  return ret;
+}
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Event.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Event.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,190 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_EVENT.C
+ *      Purpose: Implements waits and wake-ups for event flags
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_Event.h"
+#include "rt_List.h"
+#include "rt_Task.h"
+#include "rt_HAL_CM.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_evt_wait -----------------------------------*/
+
+OS_RESULT rt_evt_wait (U16 wait_flags, U16 timeout, BOOL and_wait) {
+  /* Wait for one or more event flags with optional time-out.                */
+  /* "wait_flags" identifies the flags to wait for.                          */
+  /* "timeout" is the time-out limit in system ticks (0xffff if no time-out) */
+  /* "and_wait" specifies the AND-ing of "wait_flags" as condition to be met */
+  /* to complete the wait. (OR-ing if set to 0).                             */
+  U32 block_state;
+
+  if (and_wait) {
+    /* Check for AND-connected events */
+    if ((os_tsk.run->events & wait_flags) == wait_flags) {
+      os_tsk.run->events &= ~wait_flags;
+      return (OS_R_EVT);
+    }
+    block_state = WAIT_AND;
+  }
+  else {
+    /* Check for OR-connected events */
+    if (os_tsk.run->events & wait_flags) {
+      os_tsk.run->waits = os_tsk.run->events & wait_flags;
+      os_tsk.run->events &= ~wait_flags;
+      return (OS_R_EVT);
+    }
+    block_state = WAIT_OR;
+  }
+  /* Task has to wait */
+  os_tsk.run->waits = wait_flags;
+  rt_block (timeout, (U8)block_state);
+  return (OS_R_TMO);
+}
+
+
+/*--------------------------- rt_evt_set ------------------------------------*/
+
+void rt_evt_set (U16 event_flags, OS_TID task_id) {
+  /* Set one or more event flags of a selectable task. */
+  P_TCB p_tcb;
+
+  p_tcb = os_active_TCB[task_id-1];
+  if (p_tcb == NULL) {
+    return;
+  }
+  p_tcb->events |= event_flags;
+  event_flags    = p_tcb->waits;
+  /* If the task is not waiting for an event, it should not be put */
+  /* to ready state. */
+  if (p_tcb->state == WAIT_AND) {
+    /* Check for AND-connected events */
+    if ((p_tcb->events & event_flags) == event_flags) {
+      goto wkup;
+    }
+  }
+  if (p_tcb->state == WAIT_OR) {
+    /* Check for OR-connected events */
+    if (p_tcb->events & event_flags) {
+      p_tcb->waits  &= p_tcb->events;
+wkup: p_tcb->events &= ~event_flags;
+      rt_rmv_dly (p_tcb);
+      p_tcb->state   = READY;
+#ifdef __CMSIS_RTOS
+      rt_ret_val2(p_tcb, 0x08/*osEventSignal*/, p_tcb->waits); 
+#else
+      rt_ret_val (p_tcb, OS_R_EVT);
+#endif
+      rt_dispatch (p_tcb);
+    }
+  }
+}
+
+
+/*--------------------------- rt_evt_clr ------------------------------------*/
+
+void rt_evt_clr (U16 clear_flags, OS_TID task_id) {
+  /* Clear one or more event flags (identified by "clear_flags") of a */
+  /* selectable task (identified by "task"). */
+  P_TCB task = os_active_TCB[task_id-1];
+
+  if (task == NULL) {
+    return;
+  }
+  task->events &= ~clear_flags;
+}
+
+
+/*--------------------------- isr_evt_set -----------------------------------*/
+
+void isr_evt_set (U16 event_flags, OS_TID task_id) {
+  /* Same function as "os_evt_set", but to be called by ISRs. */
+  P_TCB p_tcb = os_active_TCB[task_id-1];
+
+  if (p_tcb == NULL) {
+    return;
+  }
+  rt_psq_enq (p_tcb, event_flags);
+  rt_psh_req ();
+}
+
+
+/*--------------------------- rt_evt_get ------------------------------------*/
+
+U16 rt_evt_get (void) {
+  /* Get events of a running task after waiting for OR connected events. */
+  return (os_tsk.run->waits);
+}
+
+
+/*--------------------------- rt_evt_psh ------------------------------------*/
+
+void rt_evt_psh (P_TCB p_CB, U16 set_flags) {
+  /* Check if task has to be waken up */
+  U16 event_flags;
+
+  p_CB->events |= set_flags;
+  event_flags = p_CB->waits;
+  if (p_CB->state == WAIT_AND) {
+    /* Check for AND-connected events */
+    if ((p_CB->events & event_flags) == event_flags) {
+      goto rdy;
+    }
+  }
+  if (p_CB->state == WAIT_OR) {
+    /* Check for OR-connected events */
+    if (p_CB->events & event_flags) {
+      p_CB->waits  &= p_CB->events;
+rdy:  p_CB->events &= ~event_flags;
+      rt_rmv_dly (p_CB);
+      p_CB->state   = READY;
+#ifdef __CMSIS_RTOS
+      rt_ret_val2(p_CB, 0x08/*osEventSignal*/, p_CB->waits); 
+#else
+      rt_ret_val (p_CB, OS_R_EVT);
+#endif
+      rt_put_prio (&os_rdy, p_CB);
+    }
+  }
+}
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Event.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Event.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_EVENT.H
+ *      Purpose: Implements waits and wake-ups for event flags
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Functions */
+extern OS_RESULT rt_evt_wait (U16 wait_flags,  U16 timeout, BOOL and_wait);
+extern void      rt_evt_set  (U16 event_flags, OS_TID task_id);
+extern void      rt_evt_clr  (U16 clear_flags, OS_TID task_id);
+extern void      isr_evt_set (U16 event_flags, OS_TID task_id);
+extern U16       rt_evt_get  (void);
+extern void      rt_evt_psh  (P_TCB p_CB, U16 set_flags);
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_HAL_CM.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_HAL_CM.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,276 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_HAL_CM.H
+ *      Purpose: Hardware Abstraction Layer for Cortex-M definitions
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Definitions */
+#define INITIAL_xPSR    0x01000000
+#define DEMCR_TRCENA    0x01000000
+#define ITM_ITMENA      0x00000001
+#define MAGIC_WORD      0xE25A2EA5
+
+#if defined (__CC_ARM)          /* ARM Compiler */
+
+#if ((__TARGET_ARCH_7_M || __TARGET_ARCH_7E_M) && !NO_EXCLUSIVE_ACCESS)
+ #define __USE_EXCLUSIVE_ACCESS
+#else
+ #undef  __USE_EXCLUSIVE_ACCESS
+#endif
+
+#elif defined (__GNUC__)        /* GNU Compiler */
+
+#undef  __USE_EXCLUSIVE_ACCESS
+
+#if defined (__CORTEX_M0) || defined (__CORTEX_M0PLUS)
+#define __TARGET_ARCH_6S_M 1
+#else
+#define __TARGET_ARCH_6S_M 0
+#endif
+
+#if defined (__VFP_FP__) && !defined(__SOFTFP__)
+#define __TARGET_FPU_VFP 1
+#else
+#define __TARGET_FPU_VFP 0
+#endif
+
+#define __inline inline
+#define __weak   __attribute__((weak))
+
+#ifndef __CMSIS_GENERIC
+
+__attribute__((always_inline)) static inline void __enable_irq(void)
+{
+  __asm volatile ("cpsie i");
+}
+
+__attribute__((always_inline)) static inline U32 __disable_irq(void)
+{
+  U32 result;
+
+  __asm volatile ("mrs %0, primask" : "=r" (result));
+  __asm volatile ("cpsid i");
+  return(result & 1);
+}
+
+#endif
+
+__attribute__(( always_inline)) static inline U8 __clz(U32 value)
+{
+  U8 result;
+  
+  __asm volatile ("clz %0, %1" : "=r" (result) : "r" (value));
+  return(result);
+}
+
+#elif defined (__ICCARM__)      /* IAR Compiler */
+
+#undef  __USE_EXCLUSIVE_ACCESS
+
+#if (__CORE__ == __ARM6M__)
+#define __TARGET_ARCH_6S_M 1
+#else
+#define __TARGET_ARCH_6S_M 0
+#endif
+
+#if defined __ARMVFP__
+#define __TARGET_FPU_VFP 1
+#else
+#define __TARGET_FPU_VFP 0
+#endif
+
+#define __inline inline
+
+#ifndef __CMSIS_GENERIC
+
+static inline void __enable_irq(void)
+{
+  __asm volatile ("cpsie i");
+}
+
+static inline U32 __disable_irq(void)
+{
+  U32 result;
+  
+  __asm volatile ("mrs %0, primask" : "=r" (result));
+  __asm volatile ("cpsid i");
+  return(result & 1);
+}
+
+#endif
+
+static inline U8 __clz(U32 value)
+{
+  U8 result;
+  
+  __asm volatile ("clz %0, %1" : "=r" (result) : "r" (value));
+  return(result);
+}
+
+#endif
+
+/* NVIC registers */
+#define NVIC_ST_CTRL    (*((volatile U32 *)0xE000E010))
+#define NVIC_ST_RELOAD  (*((volatile U32 *)0xE000E014))
+#define NVIC_ST_CURRENT (*((volatile U32 *)0xE000E018))
+#define NVIC_ISER         ((volatile U32 *)0xE000E100)
+#define NVIC_ICER         ((volatile U32 *)0xE000E180)
+#if (__TARGET_ARCH_6S_M)
+#define NVIC_IP           ((volatile U32 *)0xE000E400)
+#else
+#define NVIC_IP           ((volatile U8  *)0xE000E400)
+#endif
+#define NVIC_INT_CTRL   (*((volatile U32 *)0xE000ED04))
+#define NVIC_AIR_CTRL   (*((volatile U32 *)0xE000ED0C))
+#define NVIC_SYS_PRI2   (*((volatile U32 *)0xE000ED1C))
+#define NVIC_SYS_PRI3   (*((volatile U32 *)0xE000ED20))
+
+#define OS_PEND_IRQ()   NVIC_INT_CTRL  = (1<<28)
+#define OS_PENDING      ((NVIC_INT_CTRL >> 26) & (1<<2 | 1))
+#define OS_UNPEND(fl)   NVIC_INT_CTRL  = (*fl = OS_PENDING) << 25
+#define OS_PEND(fl,p)   NVIC_INT_CTRL  = (fl | p<<2) << 26
+#define OS_LOCK()       NVIC_ST_CTRL   =  0x0005
+#define OS_UNLOCK()     NVIC_ST_CTRL   =  0x0007
+
+#define OS_X_PENDING    ((NVIC_INT_CTRL >> 28) & 1)
+#define OS_X_UNPEND(fl) NVIC_INT_CTRL  = (*fl = OS_X_PENDING) << 27
+#define OS_X_PEND(fl,p) NVIC_INT_CTRL  = (fl | p) << 28
+#if (__TARGET_ARCH_6S_M)
+#define OS_X_INIT(n)    NVIC_IP[n>>2] |= 0xFF << (8*(n & 0x03)); \
+                        NVIC_ISER[n>>5] = 1 << (n & 0x1F)
+#else
+#define OS_X_INIT(n)    NVIC_IP[n] = 0xFF; \
+                        NVIC_ISER[n>>5] = 1 << (n & 0x1F)
+#endif
+#define OS_X_LOCK(n)    NVIC_ICER[n>>5] = 1 << (n & 0x1F)
+#define OS_X_UNLOCK(n)  NVIC_ISER[n>>5] = 1 << (n & 0x1F)
+
+/* Core Debug registers */
+#define DEMCR           (*((volatile U32 *)0xE000EDFC))
+
+/* ITM registers */
+#define ITM_CONTROL     (*((volatile U32 *)0xE0000E80))
+#define ITM_ENABLE      (*((volatile U32 *)0xE0000E00))
+#define ITM_PORT30_U32  (*((volatile U32 *)0xE0000078))
+#define ITM_PORT31_U32  (*((volatile U32 *)0xE000007C))
+#define ITM_PORT31_U16  (*((volatile U16 *)0xE000007C))
+#define ITM_PORT31_U8   (*((volatile U8  *)0xE000007C))
+
+/* Variables */
+extern BIT dbg_msg;
+
+/* Functions */
+#ifdef __USE_EXCLUSIVE_ACCESS
+ #define rt_inc(p)     while(__strex((__ldrex(p)+1),p))
+ #define rt_dec(p)     while(__strex((__ldrex(p)-1),p))
+#else
+ #define rt_inc(p)     __disable_irq();(*p)++;__enable_irq();
+ #define rt_dec(p)     __disable_irq();(*p)--;__enable_irq();
+#endif
+
+__inline static U32 rt_inc_qi (U32 size, U8 *count, U8 *first) {
+  U32 cnt,c2;
+#ifdef __USE_EXCLUSIVE_ACCESS
+  do {
+    if ((cnt = __ldrex(count)) == size) {
+      __clrex();
+      return (cnt); }
+  } while (__strex(cnt+1, count));
+  do {
+    c2 = (cnt = __ldrex(first)) + 1;
+    if (c2 == size) c2 = 0;
+  } while (__strex(c2, first));
+#else
+  __disable_irq();
+  if ((cnt = *count) < size) {
+    *count = cnt+1;
+    c2 = (cnt = *first) + 1;
+    if (c2 == size) c2 = 0;
+    *first = c2; 
+  }
+  __enable_irq ();
+#endif
+  return (cnt);
+}
+
+__inline static void rt_systick_init (void) {
+  NVIC_ST_RELOAD  = os_trv;
+  NVIC_ST_CURRENT = 0;
+  NVIC_ST_CTRL    = 0x0007;
+  NVIC_SYS_PRI3  |= 0xFF000000;
+}
+
+__inline static void rt_svc_init (void) {
+#if !(__TARGET_ARCH_6S_M)
+  int sh,prigroup;
+#endif
+  NVIC_SYS_PRI3 |= 0x00FF0000;
+#if (__TARGET_ARCH_6S_M)
+  NVIC_SYS_PRI2 |= (NVIC_SYS_PRI3<<(8+1)) & 0xFC000000;
+#else
+  sh       = 8 - __clz (~((NVIC_SYS_PRI3 << 8) & 0xFF000000));
+  prigroup = ((NVIC_AIR_CTRL >> 8) & 0x07);
+  if (prigroup >= sh) {
+    sh = prigroup + 1;
+  }
+  NVIC_SYS_PRI2 = ((0xFEFFFFFF << sh) & 0xFF000000) | (NVIC_SYS_PRI2 & 0x00FFFFFF);
+#endif
+}
+
+extern void rt_set_PSP (U32 stack);
+extern U32  rt_get_PSP (void);
+extern void os_set_env (void);
+extern void *_alloc_box (void *box_mem);
+extern int  _free_box (void *box_mem, void *box);
+
+extern void rt_init_stack (P_TCB p_TCB, FUNCP task_body);
+extern void rt_ret_val  (P_TCB p_TCB, U32 v0);
+extern void rt_ret_val2 (P_TCB p_TCB, U32 v0, U32 v1);
+
+extern void dbg_init (void);
+extern void dbg_task_notify (P_TCB p_tcb, BOOL create);
+extern void dbg_task_switch (U32 task_id);
+
+#ifdef DBG_MSG
+#define DBG_INIT() dbg_init()
+#define DBG_TASK_NOTIFY(p_tcb,create) if (dbg_msg) dbg_task_notify(p_tcb,create)
+#define DBG_TASK_SWITCH(task_id)      if (dbg_msg && (os_tsk.new_tsk != os_tsk.run)) \
+                                                   dbg_task_switch(task_id)
+#else
+#define DBG_INIT()
+#define DBG_TASK_NOTIFY(p_tcb,create)
+#define DBG_TASK_SWITCH(task_id)
+#endif
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_List.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_List.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,320 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_LIST.C
+ *      Purpose: Functions for the management of different lists
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_List.h"
+#include "rt_Task.h"
+#include "rt_Time.h"
+#include "rt_HAL_CM.h"
+
+/*----------------------------------------------------------------------------
+ *      Global Variables
+ *---------------------------------------------------------------------------*/
+
+/* List head of chained ready tasks */
+struct OS_XCB  os_rdy;
+/* List head of chained delay tasks */
+struct OS_XCB  os_dly;
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_put_prio -----------------------------------*/
+
+void rt_put_prio (P_XCB p_CB, P_TCB p_task) {
+  /* Put task identified with "p_task" into list ordered by priority.       */
+  /* "p_CB" points to head of list; list has always an element at end with  */
+  /* a priority less than "p_task->prio".                                   */
+  P_TCB p_CB2;
+  U32 prio;
+  BOOL sem_mbx = __FALSE;
+
+  if (p_CB->cb_type == SCB || p_CB->cb_type == MCB || p_CB->cb_type == MUCB) {
+    sem_mbx = __TRUE;
+  }
+  prio = p_task->prio;
+  p_CB2 = p_CB->p_lnk;
+  /* Search for an entry in the list */
+  while (p_CB2 != NULL && prio <= p_CB2->prio) {
+    p_CB = (P_XCB)p_CB2;
+    p_CB2 = p_CB2->p_lnk;
+  }
+  /* Entry found, insert the task into the list */
+  p_task->p_lnk = p_CB2;
+  p_CB->p_lnk = p_task;
+  if (sem_mbx) {
+    if (p_CB2 != NULL) {
+      p_CB2->p_rlnk = p_task;
+    }
+    p_task->p_rlnk = (P_TCB)p_CB;
+  }
+  else {
+    p_task->p_rlnk = NULL;
+  }
+}
+
+
+/*--------------------------- rt_get_first ----------------------------------*/
+
+P_TCB rt_get_first (P_XCB p_CB) {
+  /* Get task at head of list: it is the task with highest priority. */
+  /* "p_CB" points to head of list. */
+  P_TCB p_first;
+
+  p_first = p_CB->p_lnk;
+  p_CB->p_lnk = p_first->p_lnk;
+  if (p_CB->cb_type == SCB || p_CB->cb_type == MCB || p_CB->cb_type == MUCB) {
+    if (p_first->p_lnk != NULL) {
+      p_first->p_lnk->p_rlnk = (P_TCB)p_CB;
+      p_first->p_lnk = NULL;
+    }
+    p_first->p_rlnk = NULL;
+  }
+  else {
+    p_first->p_lnk = NULL;
+  }
+  return (p_first);
+}
+
+
+/*--------------------------- rt_put_rdy_first ------------------------------*/
+
+void rt_put_rdy_first (P_TCB p_task) {
+  /* Put task identified with "p_task" at the head of the ready list. The   */
+  /* task must have at least a priority equal to highest priority in list.  */
+  p_task->p_lnk = os_rdy.p_lnk;
+  p_task->p_rlnk = NULL;
+  os_rdy.p_lnk = p_task;
+}
+
+
+/*--------------------------- rt_get_same_rdy_prio --------------------------*/
+
+P_TCB rt_get_same_rdy_prio (void) {
+  /* Remove a task of same priority from ready list if any exists. Other-   */
+  /* wise return NULL.                                                      */
+  P_TCB p_first;
+
+  p_first = os_rdy.p_lnk;
+  if (p_first->prio == os_tsk.run->prio) {
+    os_rdy.p_lnk = os_rdy.p_lnk->p_lnk;
+    return (p_first);
+  }
+  return (NULL);
+}
+
+
+/*--------------------------- rt_resort_prio --------------------------------*/
+
+void rt_resort_prio (P_TCB p_task) {
+  /* Re-sort ordered lists after the priority of 'p_task' has changed.      */
+  P_TCB p_CB;
+
+  if (p_task->p_rlnk == NULL) {
+    if (p_task->state == READY) {
+      /* Task is chained into READY list. */
+      p_CB = (P_TCB)&os_rdy;
+      goto res;
+    }
+  }
+  else {
+    p_CB = p_task->p_rlnk;
+    while (p_CB->cb_type == TCB) {
+      /* Find a header of this task chain list. */
+      p_CB = p_CB->p_rlnk;
+    }
+res:rt_rmv_list (p_task);
+    rt_put_prio ((P_XCB)p_CB, p_task);
+  }
+}
+
+
+/*--------------------------- rt_put_dly ------------------------------------*/
+
+void rt_put_dly (P_TCB p_task, U16 delay) {
+  /* Put a task identified with "p_task" into chained delay wait list using */
+  /* a delay value of "delay".                                              */
+  P_TCB p;
+  U32 delta,idelay = delay;
+
+  p = (P_TCB)&os_dly;
+  if (p->p_dlnk == NULL) {
+    /* Delay list empty */
+    delta = 0;
+    goto last;
+  }
+  delta = os_dly.delta_time;
+  while (delta < idelay) {
+    if (p->p_dlnk == NULL) {
+      /* End of list found */
+last: p_task->p_dlnk = NULL;
+      p->p_dlnk = p_task;
+      p_task->p_blnk = p;
+      p->delta_time = (U16)(idelay - delta);
+      p_task->delta_time = 0;
+      return;
+    }
+    p = p->p_dlnk;
+    delta += p->delta_time;
+  }
+  /* Right place found */
+  p_task->p_dlnk = p->p_dlnk;
+  p->p_dlnk = p_task;
+  p_task->p_blnk = p;
+  if (p_task->p_dlnk != NULL) {
+    p_task->p_dlnk->p_blnk = p_task;
+  }
+  p_task->delta_time = (U16)(delta - idelay);
+  p->delta_time -= p_task->delta_time;
+}
+
+
+/*--------------------------- rt_dec_dly ------------------------------------*/
+
+void rt_dec_dly (void) {
+  /* Decrement delta time of list head: remove tasks having a value of zero.*/
+  P_TCB p_rdy;
+
+  if (os_dly.p_dlnk == NULL) {
+    return;
+  }
+  os_dly.delta_time--;
+  while ((os_dly.delta_time == 0) && (os_dly.p_dlnk != NULL)) {
+    p_rdy = os_dly.p_dlnk;
+    if (p_rdy->p_rlnk != NULL) {
+      /* Task is really enqueued, remove task from semaphore/mailbox */
+      /* timeout waiting list. */
+      p_rdy->p_rlnk->p_lnk = p_rdy->p_lnk;
+      if (p_rdy->p_lnk != NULL) {
+        p_rdy->p_lnk->p_rlnk = p_rdy->p_rlnk;
+        p_rdy->p_lnk = NULL;
+      }
+      p_rdy->p_rlnk = NULL;
+    }
+    rt_put_prio (&os_rdy, p_rdy);
+    os_dly.delta_time = p_rdy->delta_time;
+    if (p_rdy->state == WAIT_ITV) {
+      /* Calculate the next time for interval wait. */
+      p_rdy->delta_time = p_rdy->interval_time + (U16)os_time;
+    }
+    p_rdy->state   = READY;
+    os_dly.p_dlnk = p_rdy->p_dlnk;
+    if (p_rdy->p_dlnk != NULL) {
+      p_rdy->p_dlnk->p_blnk =  (P_TCB)&os_dly;
+      p_rdy->p_dlnk = NULL;
+    }
+    p_rdy->p_blnk = NULL;
+  }
+}
+
+
+/*--------------------------- rt_rmv_list -----------------------------------*/
+
+void rt_rmv_list (P_TCB p_task) {
+  /* Remove task identified with "p_task" from ready, semaphore or mailbox  */
+  /* waiting list if enqueued.                                              */
+  P_TCB p_b;
+
+  if (p_task->p_rlnk != NULL) {
+    /* A task is enqueued in semaphore / mailbox waiting list. */
+    p_task->p_rlnk->p_lnk = p_task->p_lnk;
+    if (p_task->p_lnk != NULL) {
+      p_task->p_lnk->p_rlnk = p_task->p_rlnk;
+    }
+    return;
+  }
+
+  p_b = (P_TCB)&os_rdy;
+  while (p_b != NULL) {
+    /* Search the ready list for task "p_task" */
+    if (p_b->p_lnk == p_task) {
+      p_b->p_lnk = p_task->p_lnk;
+      return;
+    }
+    p_b = p_b->p_lnk;
+  }
+}
+
+
+/*--------------------------- rt_rmv_dly ------------------------------------*/
+
+void rt_rmv_dly (P_TCB p_task) {
+  /* Remove task identified with "p_task" from delay list if enqueued.      */
+  P_TCB p_b;
+
+  p_b = p_task->p_blnk;
+  if (p_b != NULL) {
+    /* Task is really enqueued */
+    p_b->p_dlnk = p_task->p_dlnk;
+    if (p_task->p_dlnk != NULL) {
+      /* 'p_task' is in the middle of list */
+      p_b->delta_time += p_task->delta_time;
+      p_task->p_dlnk->p_blnk = p_b;
+      p_task->p_dlnk = NULL;
+    }
+    else {
+      /* 'p_task' is at the end of list */
+      p_b->delta_time = 0;
+    }
+    p_task->p_blnk = NULL;
+  }
+}
+
+
+/*--------------------------- rt_psq_enq ------------------------------------*/
+
+void rt_psq_enq (OS_ID entry, U32 arg) {
+  /* Insert post service request "entry" into ps-queue. */
+  U32 idx;
+
+  idx = rt_inc_qi (os_psq->size, &os_psq->count, &os_psq->first);
+  if (idx < os_psq->size) {
+    os_psq->q[idx].id  = entry;
+    os_psq->q[idx].arg = arg;
+  }
+  else {
+    os_error (OS_ERR_FIFO_OVF);
+  }
+}
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_List.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_List.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_LIST.H
+ *      Purpose: Functions for the management of different lists
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Definitions */
+
+/* Values for 'cb_type' */
+#define TCB             0
+#define MCB             1
+#define SCB             2
+#define MUCB            3
+#define HCB             4
+
+/* Variables */
+extern struct OS_XCB os_rdy;
+extern struct OS_XCB os_dly;
+
+/* Functions */
+extern void  rt_put_prio      (P_XCB p_CB, P_TCB p_task);
+extern P_TCB rt_get_first     (P_XCB p_CB);
+extern void  rt_put_rdy_first (P_TCB p_task);
+extern P_TCB rt_get_same_rdy_prio (void);
+extern void  rt_resort_prio   (P_TCB p_task);
+extern void  rt_put_dly       (P_TCB p_task, U16 delay);
+extern void  rt_dec_dly       (void);
+extern void  rt_rmv_list      (P_TCB p_task);
+extern void  rt_rmv_dly       (P_TCB p_task);
+extern void  rt_psq_enq       (OS_ID entry, U32 arg);
+
+/* This is a fast macro generating in-line code */
+#define rt_rdy_prio(void) (os_rdy.p_lnk->prio)
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Mailbox.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Mailbox.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,292 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_MAILBOX.C
+ *      Purpose: Implements waits and wake-ups for mailbox messages
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_List.h"
+#include "rt_Mailbox.h"
+#include "rt_MemBox.h"
+#include "rt_Task.h"
+#include "rt_HAL_CM.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_mbx_init -----------------------------------*/
+
+void rt_mbx_init (OS_ID mailbox, U16 mbx_size) {
+  /* Initialize a mailbox */
+  P_MCB p_MCB = mailbox;
+
+  p_MCB->cb_type = MCB;
+  p_MCB->state   = 0;
+  p_MCB->isr_st  = 0;
+  p_MCB->p_lnk   = NULL;
+  p_MCB->first   = 0;
+  p_MCB->last    = 0;
+  p_MCB->count   = 0;
+  p_MCB->size    = (mbx_size + sizeof(void *) - sizeof(struct OS_MCB)) /
+                                                     (U32)sizeof (void *);
+}
+
+
+/*--------------------------- rt_mbx_send -----------------------------------*/
+
+OS_RESULT rt_mbx_send (OS_ID mailbox, void *p_msg, U16 timeout) {
+  /* Send message to a mailbox */
+  P_MCB p_MCB = mailbox;
+  P_TCB p_TCB;
+
+  if ((p_MCB->p_lnk != NULL) && (p_MCB->state == 1)) {
+    /* A task is waiting for message */
+    p_TCB = rt_get_first ((P_XCB)p_MCB);
+#ifdef __CMSIS_RTOS
+    rt_ret_val2(p_TCB, 0x10/*osEventMessage*/, (U32)p_msg);
+#else
+    *p_TCB->msg = p_msg;
+    rt_ret_val (p_TCB, OS_R_MBX);
+#endif
+    rt_rmv_dly (p_TCB);
+    rt_dispatch (p_TCB);
+  }
+  else {
+    /* Store message in mailbox queue */
+    if (p_MCB->count == p_MCB->size) {
+      /* No free message entry, wait for one. If message queue is full, */
+      /* then no task is waiting for message. The 'p_MCB->p_lnk' list   */
+      /* pointer can now be reused for send message waits task list.    */
+      if (timeout == 0) {
+        return (OS_R_TMO);
+      }
+      if (p_MCB->p_lnk != NULL) {
+        rt_put_prio ((P_XCB)p_MCB, os_tsk.run);
+      }
+      else {
+        p_MCB->p_lnk = os_tsk.run;
+        os_tsk.run->p_lnk  = NULL;
+        os_tsk.run->p_rlnk = (P_TCB)p_MCB;
+        /* Task is waiting to send a message */      
+        p_MCB->state = 2;
+      }
+      os_tsk.run->msg = p_msg;
+      rt_block (timeout, WAIT_MBX);
+      return (OS_R_TMO);
+    }
+    /* Yes, there is a free entry in a mailbox. */
+    p_MCB->msg[p_MCB->first] = p_msg;
+    rt_inc (&p_MCB->count);
+    if (++p_MCB->first == p_MCB->size) {
+      p_MCB->first = 0;
+    }
+  }
+  return (OS_R_OK);
+}
+
+
+/*--------------------------- rt_mbx_wait -----------------------------------*/
+
+OS_RESULT rt_mbx_wait (OS_ID mailbox, void **message, U16 timeout) {
+  /* Receive a message; possibly wait for it */
+  P_MCB p_MCB = mailbox;
+  P_TCB p_TCB;
+
+  /* If a message is available in the fifo buffer */
+  /* remove it from the fifo buffer and return. */
+  if (p_MCB->count) {
+    *message = p_MCB->msg[p_MCB->last];
+    if (++p_MCB->last == p_MCB->size) {
+      p_MCB->last = 0;
+    }
+    if ((p_MCB->p_lnk != NULL) && (p_MCB->state == 2)) {
+      /* A task is waiting to send message */
+      p_TCB = rt_get_first ((P_XCB)p_MCB);
+#ifdef __CMSIS_RTOS
+      rt_ret_val(p_TCB, 0/*osOK*/);
+#else
+      rt_ret_val(p_TCB, OS_R_OK);
+#endif
+      p_MCB->msg[p_MCB->first] = p_TCB->msg;
+      if (++p_MCB->first == p_MCB->size) {
+        p_MCB->first = 0;
+      }
+      rt_rmv_dly (p_TCB);
+      rt_dispatch (p_TCB);
+    }
+    else {
+      rt_dec (&p_MCB->count);
+    }
+    return (OS_R_OK);
+  }
+  /* No message available: wait for one */
+  if (timeout == 0) {
+    return (OS_R_TMO);
+  }
+  if (p_MCB->p_lnk != NULL) {
+    rt_put_prio ((P_XCB)p_MCB, os_tsk.run);
+  }
+  else {
+    p_MCB->p_lnk = os_tsk.run;
+    os_tsk.run->p_lnk = NULL;
+    os_tsk.run->p_rlnk = (P_TCB)p_MCB;
+    /* Task is waiting to receive a message */      
+    p_MCB->state = 1;
+  }
+  rt_block(timeout, WAIT_MBX);
+#ifndef __CMSIS_RTOS
+  os_tsk.run->msg = message;
+#endif
+  return (OS_R_TMO);
+}
+
+
+/*--------------------------- rt_mbx_check ----------------------------------*/
+
+OS_RESULT rt_mbx_check (OS_ID mailbox) {
+  /* Check for free space in a mailbox. Returns the number of messages     */
+  /* that can be stored to a mailbox. It returns 0 when mailbox is full.   */
+  P_MCB p_MCB = mailbox;
+
+  return (p_MCB->size - p_MCB->count);
+}
+
+
+/*--------------------------- isr_mbx_send ----------------------------------*/
+
+void isr_mbx_send (OS_ID mailbox, void *p_msg) {
+  /* Same function as "os_mbx_send", but to be called by ISRs. */
+  P_MCB p_MCB = mailbox;
+
+  rt_psq_enq (p_MCB, (U32)p_msg);
+  rt_psh_req ();
+}
+
+
+/*--------------------------- isr_mbx_receive -------------------------------*/
+
+OS_RESULT isr_mbx_receive (OS_ID mailbox, void **message) {
+  /* Receive a message in the interrupt function. The interrupt function   */
+  /* should not wait for a message since this would block the rtx os.      */
+  P_MCB p_MCB = mailbox;
+
+  if (p_MCB->count) {
+    /* A message is available in the fifo buffer. */
+    *message = p_MCB->msg[p_MCB->last];
+    if (p_MCB->state == 2) {
+      /* A task is locked waiting to send message */
+      rt_psq_enq (p_MCB, 0);
+      rt_psh_req ();
+    }
+    rt_dec (&p_MCB->count);
+    if (++p_MCB->last == p_MCB->size) {
+      p_MCB->last = 0;
+    }
+    return (OS_R_MBX);
+  }
+  return (OS_R_OK);
+}
+
+
+/*--------------------------- rt_mbx_psh ------------------------------------*/
+
+void rt_mbx_psh (P_MCB p_CB, void *p_msg) {
+  /* Store the message to the mailbox queue or pass it to task directly. */
+  P_TCB p_TCB;
+  void *mem;
+
+  if (p_CB->p_lnk != NULL) switch (p_CB->state) {
+#ifdef __CMSIS_RTOS
+    case 3:
+      /* Task is waiting to allocate memory, remove it from the waiting list */
+      mem = rt_alloc_box(p_msg);
+      if (mem == NULL) break;
+      p_TCB = rt_get_first ((P_XCB)p_CB);
+      rt_ret_val(p_TCB, (U32)mem);
+      p_TCB->state = READY;
+      rt_rmv_dly (p_TCB);
+      rt_put_prio (&os_rdy, p_TCB);
+      break;
+#endif
+    case 2:
+      /* Task is waiting to send a message, remove it from the waiting list */
+      p_TCB = rt_get_first ((P_XCB)p_CB);
+#ifdef __CMSIS_RTOS
+      rt_ret_val(p_TCB, 0/*osOK*/);
+#else
+      rt_ret_val(p_TCB, OS_R_OK);
+#endif
+      p_CB->msg[p_CB->first] = p_TCB->msg;
+      rt_inc (&p_CB->count);
+      if (++p_CB->first == p_CB->size) {
+        p_CB->first = 0;
+      }
+      p_TCB->state = READY;
+      rt_rmv_dly (p_TCB);
+      rt_put_prio (&os_rdy, p_TCB);
+      break;
+    case 1:
+      /* Task is waiting for a message, pass the message to the task directly */
+      p_TCB = rt_get_first ((P_XCB)p_CB);
+#ifdef __CMSIS_RTOS
+      rt_ret_val2(p_TCB, 0x10/*osEventMessage*/, (U32)p_msg);
+#else
+      *p_TCB->msg = p_msg;
+      rt_ret_val (p_TCB, OS_R_MBX);
+#endif
+      p_TCB->state = READY;
+      rt_rmv_dly (p_TCB);
+      rt_put_prio (&os_rdy, p_TCB);
+      break;
+  } else {
+      /* No task is waiting for a message, store it to the mailbox queue */
+      if (p_CB->count < p_CB->size) {
+        p_CB->msg[p_CB->first] = p_msg;
+        rt_inc (&p_CB->count);
+        if (++p_CB->first == p_CB->size) {
+          p_CB->first = 0;
+        }
+      }
+      else {
+        os_error (OS_ERR_MBX_OVF);
+      }
+  }
+}
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Mailbox.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Mailbox.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_MAILBOX.H
+ *      Purpose: Implements waits and wake-ups for mailbox messages
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Functions */
+extern void      rt_mbx_init  (OS_ID mailbox, U16 mbx_size);
+extern OS_RESULT rt_mbx_send  (OS_ID mailbox, void *p_msg,    U16 timeout);
+extern OS_RESULT rt_mbx_wait  (OS_ID mailbox, void **message, U16 timeout);
+extern OS_RESULT rt_mbx_check (OS_ID mailbox);
+extern void      isr_mbx_send (OS_ID mailbox, void *p_msg);
+extern OS_RESULT isr_mbx_receive (OS_ID mailbox, void **message);
+extern void      rt_mbx_psh   (P_MCB p_CB,    void *p_msg);
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_MemBox.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_MemBox.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_MEMBOX.C
+ *      Purpose: Interface functions for fixed memory block management system
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_MemBox.h"
+#include "rt_HAL_CM.h"
+
+/*----------------------------------------------------------------------------
+ *      Global Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- _init_box -------------------------------------*/
+
+int _init_box  (void *box_mem, U32 box_size, U32 blk_size) {
+  /* Initialize memory block system, returns 0 if OK, 1 if fails. */
+  void *end;
+  void *blk;
+  void *next;
+  U32  sizeof_bm;
+
+  /* Create memory structure. */
+  if (blk_size & BOX_ALIGN_8) {
+    /* Memory blocks 8-byte aligned. */ 
+    blk_size = ((blk_size & ~BOX_ALIGN_8) + 7) & ~7;
+    sizeof_bm = (sizeof (struct OS_BM) + 7) & ~7;
+  }
+  else {
+    /* Memory blocks 4-byte aligned. */
+    blk_size = (blk_size + 3) & ~3;
+    sizeof_bm = sizeof (struct OS_BM);
+  }
+  if (blk_size == 0) {
+    return (1);
+  }
+  if ((blk_size + sizeof_bm) > box_size) {
+    return (1);
+  }
+  /* Create a Memory structure. */
+  blk = ((U8 *) box_mem) + sizeof_bm;
+  ((P_BM) box_mem)->free = blk;
+  end = ((U8 *) box_mem) + box_size;
+  ((P_BM) box_mem)->end      = end;
+  ((P_BM) box_mem)->blk_size = blk_size;
+
+  /* Link all free blocks using offsets. */
+  end = ((U8 *) end) - blk_size;
+  while (1)  {
+    next = ((U8 *) blk) + blk_size;
+    if (next > end)  break;
+    *((void **)blk) = next;
+    blk = next;
+  }
+  /* end marker */
+  *((void **)blk) = 0;
+  return (0);
+}
+
+/*--------------------------- rt_alloc_box ----------------------------------*/
+
+void *rt_alloc_box (void *box_mem) {
+  /* Allocate a memory block and return start address. */
+  void **free;
+#ifndef __USE_EXCLUSIVE_ACCESS
+  int  irq_dis;
+
+  irq_dis = __disable_irq ();
+  free = ((P_BM) box_mem)->free;
+  if (free) {
+    ((P_BM) box_mem)->free = *free;
+  }
+  if (!irq_dis) __enable_irq ();
+#else
+  do {
+    if ((free = (void **)__ldrex(&((P_BM) box_mem)->free)) == 0) {
+      __clrex();
+      break;
+    }
+  } while (__strex((U32)*free, &((P_BM) box_mem)->free));
+#endif
+  return (free);
+}
+
+
+/*--------------------------- _calloc_box -----------------------------------*/
+
+void *_calloc_box (void *box_mem)  {
+  /* Allocate a 0-initialized memory block and return start address. */
+  void *free;
+  U32 *p;
+  U32 i;
+
+  free = _alloc_box (box_mem);
+  if (free)  {
+    p = free;
+    for (i = ((P_BM) box_mem)->blk_size; i; i -= 4)  {
+      *p = 0;
+      p++;
+    }
+  }
+  return (free);
+}
+
+
+/*--------------------------- rt_free_box -----------------------------------*/
+
+int rt_free_box (void *box_mem, void *box) {
+  /* Free a memory block, returns 0 if OK, 1 if box does not belong to box_mem */
+#ifndef __USE_EXCLUSIVE_ACCESS
+  int irq_dis;
+#endif
+
+  if (box < box_mem || box >= ((P_BM) box_mem)->end) {
+    return (1);
+  }
+
+#ifndef __USE_EXCLUSIVE_ACCESS
+  irq_dis = __disable_irq ();
+  *((void **)box) = ((P_BM) box_mem)->free;
+  ((P_BM) box_mem)->free = box;
+  if (!irq_dis) __enable_irq ();
+#else
+  do {
+    *((void **)box) = (void *)__ldrex(&((P_BM) box_mem)->free);
+  } while (__strex ((U32)box, &((P_BM) box_mem)->free));
+#endif
+  return (0);
+}
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_MemBox.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_MemBox.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_MEMBOX.H
+ *      Purpose: Interface functions for fixed memory block management system
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Functions */
+#define rt_init_box     _init_box
+#define rt_calloc_box   _calloc_box
+extern int     _init_box   (void *box_mem, U32 box_size, U32 blk_size);
+extern void *rt_alloc_box  (void *box_mem);
+extern void *  _calloc_box (void *box_mem);
+extern int   rt_free_box   (void *box_mem, void *box);
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Mutex.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Mutex.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,197 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_MUTEX.C
+ *      Purpose: Implements mutex synchronization objects
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_List.h"
+#include "rt_Task.h"
+#include "rt_Mutex.h"
+#include "rt_HAL_CM.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_mut_init -----------------------------------*/
+
+void rt_mut_init (OS_ID mutex) {
+  /* Initialize a mutex object */
+  P_MUCB p_MCB = mutex;
+
+  p_MCB->cb_type = MUCB;
+  p_MCB->prio    = 0;
+  p_MCB->level   = 0;
+  p_MCB->p_lnk   = NULL;
+  p_MCB->owner   = NULL;
+}
+
+
+/*--------------------------- rt_mut_delete ---------------------------------*/
+
+#ifdef __CMSIS_RTOS
+OS_RESULT rt_mut_delete (OS_ID mutex) {
+  /* Delete a mutex object */
+  P_MUCB p_MCB = mutex;
+  P_TCB  p_TCB;
+
+  /* Restore owner task's priority. */
+  if (p_MCB->level != 0) {
+    p_MCB->owner->prio = p_MCB->prio;
+    if (p_MCB->owner != os_tsk.run) {
+      rt_resort_prio (p_MCB->owner);
+    }
+  }
+
+  while (p_MCB->p_lnk != NULL) {
+    /* A task is waiting for mutex. */
+    p_TCB = rt_get_first ((P_XCB)p_MCB);
+    rt_ret_val(p_TCB, 0/*osOK*/);
+    rt_rmv_dly(p_TCB);
+    p_TCB->state = READY;
+    rt_put_prio (&os_rdy, p_TCB);
+  }
+
+  if (os_rdy.p_lnk && (os_rdy.p_lnk->prio > os_tsk.run->prio)) {
+    /* preempt running task */
+    rt_put_prio (&os_rdy, os_tsk.run);
+    os_tsk.run->state = READY;
+    rt_dispatch (NULL);
+  }
+
+  p_MCB->cb_type = 0;
+
+  return (OS_R_OK);
+}
+#endif
+
+
+/*--------------------------- rt_mut_release --------------------------------*/
+
+OS_RESULT rt_mut_release (OS_ID mutex) {
+  /* Release a mutex object */
+  P_MUCB p_MCB = mutex;
+  P_TCB  p_TCB;
+
+  if (p_MCB->level == 0 || p_MCB->owner != os_tsk.run) {
+    /* Unbalanced mutex release or task is not the owner */
+    return (OS_R_NOK);
+  }
+  if (--p_MCB->level != 0) {
+    return (OS_R_OK);
+  }
+  /* Restore owner task's priority. */
+  os_tsk.run->prio = p_MCB->prio;
+  if (p_MCB->p_lnk != NULL) {
+    /* A task is waiting for mutex. */
+    p_TCB = rt_get_first ((P_XCB)p_MCB);
+#ifdef __CMSIS_RTOS
+    rt_ret_val(p_TCB, 0/*osOK*/);
+#else
+    rt_ret_val(p_TCB, OS_R_MUT); 
+#endif
+    rt_rmv_dly (p_TCB);
+    /* A waiting task becomes the owner of this mutex. */
+    p_MCB->level     = 1;
+    p_MCB->owner     = p_TCB;
+    p_MCB->prio      = p_TCB->prio;
+    /* Priority inversion, check which task continues. */
+    if (os_tsk.run->prio >= rt_rdy_prio()) {
+      rt_dispatch (p_TCB);
+    }
+    else {
+      /* Ready task has higher priority than running task. */
+      rt_put_prio (&os_rdy, os_tsk.run);
+      rt_put_prio (&os_rdy, p_TCB);
+      os_tsk.run->state = READY;
+      p_TCB->state      = READY;
+      rt_dispatch (NULL);
+    }
+  }
+  else {
+    /* Check if own priority raised by priority inversion. */
+    if (rt_rdy_prio() > os_tsk.run->prio) {
+      rt_put_prio (&os_rdy, os_tsk.run);
+      os_tsk.run->state = READY;
+      rt_dispatch (NULL);
+    }
+  }
+  return (OS_R_OK);
+}
+
+
+/*--------------------------- rt_mut_wait -----------------------------------*/
+
+OS_RESULT rt_mut_wait (OS_ID mutex, U16 timeout) {
+  /* Wait for a mutex, continue when mutex is free. */
+  P_MUCB p_MCB = mutex;
+
+  if (p_MCB->level == 0) {
+    p_MCB->owner = os_tsk.run;
+    p_MCB->prio  = os_tsk.run->prio;
+    goto inc;
+  }
+  if (p_MCB->owner == os_tsk.run) {
+    /* OK, running task is the owner of this mutex. */
+inc:p_MCB->level++;
+    return (OS_R_OK);
+  }
+  /* Mutex owned by another task, wait until released. */
+  if (timeout == 0) {
+    return (OS_R_TMO);
+  }
+  /* Raise the owner task priority if lower than current priority. */
+  /* This priority inversion is called priority inheritance.       */
+  if (p_MCB->prio < os_tsk.run->prio) {
+    p_MCB->owner->prio = os_tsk.run->prio;
+    rt_resort_prio (p_MCB->owner);
+  }
+  if (p_MCB->p_lnk != NULL) {
+    rt_put_prio ((P_XCB)p_MCB, os_tsk.run);
+  }
+  else {
+    p_MCB->p_lnk = os_tsk.run;
+    os_tsk.run->p_lnk  = NULL;
+    os_tsk.run->p_rlnk = (P_TCB)p_MCB;
+  }
+  rt_block(timeout, WAIT_MUT);
+  return (OS_R_TMO);
+}
+
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Mutex.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Mutex.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_MUTEX.H
+ *      Purpose: Implements mutex synchronization objects
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Functions */
+extern void      rt_mut_init    (OS_ID mutex);
+extern OS_RESULT rt_mut_delete  (OS_ID mutex);
+extern OS_RESULT rt_mut_release (OS_ID mutex);
+extern OS_RESULT rt_mut_wait    (OS_ID mutex, U16 timeout);
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Robin.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Robin.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_ROBIN.C
+ *      Purpose: Round Robin Task switching
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_List.h"
+#include "rt_Task.h"
+#include "rt_Time.h"
+#include "rt_Robin.h"
+#include "rt_HAL_CM.h"
+
+/*----------------------------------------------------------------------------
+ *      Global Variables
+ *---------------------------------------------------------------------------*/
+
+struct OS_ROBIN os_robin;
+
+
+/*----------------------------------------------------------------------------
+ *      Global Functions
+ *---------------------------------------------------------------------------*/
+
+/*--------------------------- rt_init_robin ---------------------------------*/
+
+__weak void rt_init_robin (void) {
+  /* Initialize Round Robin variables. */
+  os_robin.task = NULL;
+  os_robin.tout = (U16)os_rrobin;
+}
+
+/*--------------------------- rt_chk_robin ----------------------------------*/
+
+__weak void rt_chk_robin (void) {
+  /* Check if Round Robin timeout expired and switch to the next ready task.*/
+  P_TCB p_new;
+
+  if (os_robin.task != os_rdy.p_lnk) {
+    /* New task was suspended, reset Round Robin timeout. */
+    os_robin.task = os_rdy.p_lnk;
+    os_robin.time = (U16)os_time + os_robin.tout - 1;
+  }
+  if (os_robin.time == (U16)os_time) {
+    /* Round Robin timeout has expired, swap Robin tasks. */
+    os_robin.task = NULL;
+    p_new = rt_get_first (&os_rdy);
+    rt_put_prio ((P_XCB)&os_rdy, p_new);
+  }
+}
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Robin.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Robin.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_ROBIN.H
+ *      Purpose: Round Robin Task switching definitions
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Variables */
+extern struct OS_ROBIN os_robin;
+
+/* Functions */
+extern void rt_init_robin (void);
+extern void rt_chk_robin  (void);
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Semaphore.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Semaphore.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,183 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_SEMAPHORE.C
+ *      Purpose: Implements binary and counting semaphores
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_List.h"
+#include "rt_Task.h"
+#include "rt_Semaphore.h"
+#include "rt_HAL_CM.h"
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_sem_init -----------------------------------*/
+
+void rt_sem_init (OS_ID semaphore, U16 token_count) {
+  /* Initialize a semaphore */
+  P_SCB p_SCB = semaphore;
+
+  p_SCB->cb_type = SCB;
+  p_SCB->p_lnk  = NULL;
+  p_SCB->tokens = token_count;
+}
+
+
+/*--------------------------- rt_sem_delete ---------------------------------*/
+
+#ifdef __CMSIS_RTOS
+OS_RESULT rt_sem_delete (OS_ID semaphore) {
+  /* Delete semaphore */
+  P_SCB p_SCB = semaphore;
+  P_TCB p_TCB;
+
+  while (p_SCB->p_lnk != NULL) {
+    /* A task is waiting for token */
+    p_TCB = rt_get_first ((P_XCB)p_SCB);
+    rt_ret_val(p_TCB, 0);
+    rt_rmv_dly(p_TCB);
+    p_TCB->state = READY;
+    rt_put_prio (&os_rdy, p_TCB);
+  }
+
+  if (os_rdy.p_lnk && (os_rdy.p_lnk->prio > os_tsk.run->prio)) {
+    /* preempt running task */
+    rt_put_prio (&os_rdy, os_tsk.run);
+    os_tsk.run->state = READY;
+    rt_dispatch (NULL);
+  }
+
+  p_SCB->cb_type = 0;
+
+  return (OS_R_OK);
+}
+#endif
+
+
+/*--------------------------- rt_sem_send -----------------------------------*/
+
+OS_RESULT rt_sem_send (OS_ID semaphore) {
+  /* Return a token to semaphore */
+  P_SCB p_SCB = semaphore;
+  P_TCB p_TCB;
+
+  if (p_SCB->p_lnk != NULL) {
+    /* A task is waiting for token */
+    p_TCB = rt_get_first ((P_XCB)p_SCB);
+#ifdef __CMSIS_RTOS
+    rt_ret_val(p_TCB, 1);
+#else
+    rt_ret_val(p_TCB, OS_R_SEM);
+#endif
+    rt_rmv_dly (p_TCB);
+    rt_dispatch (p_TCB);
+  }
+  else {
+    /* Store token. */
+    p_SCB->tokens++;
+  }
+  return (OS_R_OK);
+}
+
+
+/*--------------------------- rt_sem_wait -----------------------------------*/
+
+OS_RESULT rt_sem_wait (OS_ID semaphore, U16 timeout) {
+  /* Obtain a token; possibly wait for it */
+  P_SCB p_SCB = semaphore;
+
+  if (p_SCB->tokens) {
+    p_SCB->tokens--;
+    return (OS_R_OK);
+  }
+  /* No token available: wait for one */
+  if (timeout == 0) {
+    return (OS_R_TMO);
+  }
+  if (p_SCB->p_lnk != NULL) {
+    rt_put_prio ((P_XCB)p_SCB, os_tsk.run);
+  }
+  else {
+    p_SCB->p_lnk = os_tsk.run;
+    os_tsk.run->p_lnk = NULL;
+    os_tsk.run->p_rlnk = (P_TCB)p_SCB;
+  }
+  rt_block(timeout, WAIT_SEM);
+  return (OS_R_TMO);
+}
+
+
+/*--------------------------- isr_sem_send ----------------------------------*/
+
+void isr_sem_send (OS_ID semaphore) {
+  /* Same function as "os_sem"send", but to be called by ISRs */
+  P_SCB p_SCB = semaphore;
+
+  rt_psq_enq (p_SCB, 0);
+  rt_psh_req ();
+}
+
+
+/*--------------------------- rt_sem_psh ------------------------------------*/
+
+void rt_sem_psh (P_SCB p_CB) {
+  /* Check if task has to be waken up */
+  P_TCB p_TCB;
+
+  if (p_CB->p_lnk != NULL) {
+    /* A task is waiting for token */
+    p_TCB = rt_get_first ((P_XCB)p_CB);
+    rt_rmv_dly (p_TCB);
+    p_TCB->state   = READY;
+#ifdef __CMSIS_RTOS
+    rt_ret_val(p_TCB, 1);
+#else
+    rt_ret_val(p_TCB, OS_R_SEM);
+#endif
+    rt_put_prio (&os_rdy, p_TCB);
+  }
+  else {
+    /* Store token */
+    p_CB->tokens++;
+  }
+}
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Semaphore.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Semaphore.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_SEMAPHORE.H
+ *      Purpose: Implements binary and counting semaphores
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Functions */
+extern void      rt_sem_init  (OS_ID semaphore, U16 token_count);
+extern OS_RESULT rt_sem_delete(OS_ID semaphore);
+extern OS_RESULT rt_sem_send  (OS_ID semaphore);
+extern OS_RESULT rt_sem_wait  (OS_ID semaphore, U16 timeout);
+extern void      isr_sem_send (OS_ID semaphore);
+extern void      rt_sem_psh (P_SCB p_CB);
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_System.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_System.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,299 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_SYSTEM.C
+ *      Purpose: System Task Manager
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_Task.h"
+#include "rt_System.h"
+#include "rt_Event.h"
+#include "rt_List.h"
+#include "rt_Mailbox.h"
+#include "rt_Semaphore.h"
+#include "rt_Time.h"
+#include "rt_Robin.h"
+#include "rt_HAL_CM.h"
+
+/*----------------------------------------------------------------------------
+ *      Global Variables
+ *---------------------------------------------------------------------------*/
+
+int os_tick_irqn;
+
+/*----------------------------------------------------------------------------
+ *      Local Variables
+ *---------------------------------------------------------------------------*/
+
+static volatile BIT os_lock;
+static volatile BIT os_psh_flag;
+static          U8  pend_flags;
+
+/*----------------------------------------------------------------------------
+ *      Global Functions
+ *---------------------------------------------------------------------------*/
+
+#if defined (__CC_ARM)
+__asm void $$RTX$$version (void) {
+   /* Export a version number symbol for a version control. */
+
+                EXPORT  __RL_RTX_VER
+
+__RL_RTX_VER    EQU     0x450
+}
+#endif
+
+
+/*--------------------------- rt_suspend ------------------------------------*/
+U32 rt_suspend (void) {
+  /* Suspend OS scheduler */
+  U32 delta = 0xFFFF;
+  
+  rt_tsk_lock();
+  
+  if (os_dly.p_dlnk) {
+    delta = os_dly.delta_time;
+  }
+#ifndef __CMSIS_RTOS
+  if (os_tmr.next) {
+    if (os_tmr.tcnt < delta) delta = os_tmr.tcnt;
+  }
+#endif
+  
+  return (delta);
+}
+
+
+/*--------------------------- rt_resume -------------------------------------*/
+void rt_resume (U32 sleep_time) {
+  /* Resume OS scheduler after suspend */
+  P_TCB next;
+  U32   delta;
+
+  os_tsk.run->state = READY;
+  rt_put_rdy_first (os_tsk.run);
+
+  os_robin.task = NULL;
+
+  /* Update delays. */
+  if (os_dly.p_dlnk) {
+    delta = sleep_time;
+    if (delta >= os_dly.delta_time) {
+      delta   -= os_dly.delta_time;
+      os_time += os_dly.delta_time;
+      os_dly.delta_time = 1;
+      while (os_dly.p_dlnk) {
+        rt_dec_dly();
+        if (delta == 0) break;
+        delta--;
+        os_time++;
+      }
+    } else {
+      os_time           += delta;
+      os_dly.delta_time -= delta;
+    }
+  } else {
+    os_time += sleep_time;
+  }
+  
+#ifndef __CMSIS_RTOS
+  /* Check the user timers. */
+  if (os_tmr.next) {
+    delta = sleep_time;
+    if (delta >= os_tmr.tcnt) {
+      delta   -= os_tmr.tcnt;
+      os_tmr.tcnt = 1;
+      while (os_tmr.next) {
+        rt_tmr_tick();
+        if (delta == 0) break;
+        delta--;
+      }
+    } else {
+      os_tmr.tcnt -= delta;
+    }
+  }
+#endif
+
+  /* Switch back to highest ready task */
+  next = rt_get_first (&os_rdy);
+  rt_switch_req (next);
+
+  rt_tsk_unlock();
+}
+
+
+/*--------------------------- rt_tsk_lock -----------------------------------*/
+
+void rt_tsk_lock (void) {
+  /* Prevent task switching by locking out scheduler */
+  if (os_tick_irqn < 0) {
+    OS_LOCK();
+    os_lock = __TRUE;
+    OS_UNPEND (&pend_flags);
+  } else {
+    OS_X_LOCK(os_tick_irqn);
+    os_lock = __TRUE;
+    OS_X_UNPEND (&pend_flags);
+  }
+}
+
+
+/*--------------------------- rt_tsk_unlock ---------------------------------*/
+
+void rt_tsk_unlock (void) {
+  /* Unlock scheduler and re-enable task switching */
+  if (os_tick_irqn < 0) {
+    OS_UNLOCK();
+    os_lock = __FALSE;
+    OS_PEND (pend_flags, os_psh_flag);
+    os_psh_flag = __FALSE;
+  } else {
+    OS_X_UNLOCK(os_tick_irqn);
+    os_lock = __FALSE;
+    OS_X_PEND (pend_flags, os_psh_flag);
+    os_psh_flag = __FALSE;
+  }
+}
+
+
+/*--------------------------- rt_psh_req ------------------------------------*/
+
+void rt_psh_req (void) {
+  /* Initiate a post service handling request if required. */
+  if (os_lock == __FALSE) {
+    OS_PEND_IRQ ();
+  }
+  else {
+    os_psh_flag = __TRUE;
+  }
+}
+
+
+/*--------------------------- rt_pop_req ------------------------------------*/
+
+void rt_pop_req (void) {
+  /* Process an ISR post service requests. */
+  struct OS_XCB *p_CB;
+  P_TCB next;
+  U32  idx;
+
+  os_tsk.run->state = READY;
+  rt_put_rdy_first (os_tsk.run);
+
+  idx = os_psq->last;
+  while (os_psq->count) {
+    p_CB = os_psq->q[idx].id;
+    if (p_CB->cb_type == TCB) {
+      /* Is of TCB type */
+      rt_evt_psh ((P_TCB)p_CB, (U16)os_psq->q[idx].arg);
+    }
+    else if (p_CB->cb_type == MCB) {
+      /* Is of MCB type */
+      rt_mbx_psh ((P_MCB)p_CB, (void *)os_psq->q[idx].arg);
+    }
+    else {
+      /* Must be of SCB type */
+      rt_sem_psh ((P_SCB)p_CB);
+    }
+    if (++idx == os_psq->size) idx = 0;
+    rt_dec (&os_psq->count);
+  }
+  os_psq->last = idx;
+
+  next = rt_get_first (&os_rdy);
+  rt_switch_req (next);
+}
+
+
+/*--------------------------- os_tick_init ----------------------------------*/
+
+__weak int os_tick_init (void) {
+  /* Initialize SysTick timer as system tick timer. */
+  rt_systick_init ();
+  return (-1);  /* Return IRQ number of SysTick timer */
+}
+
+
+/*--------------------------- os_tick_irqack --------------------------------*/
+
+__weak void os_tick_irqack (void) {
+  /* Acknowledge timer interrupt. */
+}
+
+
+/*--------------------------- rt_systick ------------------------------------*/
+
+extern void sysTimerTick(void);
+
+void rt_systick (void) {
+  /* Check for system clock update, suspend running task. */
+  P_TCB next;
+
+  os_tsk.run->state = READY;
+  rt_put_rdy_first (os_tsk.run);
+
+  /* Check Round Robin timeout. */
+  rt_chk_robin ();
+
+  /* Update delays. */
+  os_time++;
+  rt_dec_dly ();
+
+  /* Check the user timers. */
+#ifdef __CMSIS_RTOS
+  sysTimerTick();
+#else
+  rt_tmr_tick ();
+#endif
+  
+  /* Switch back to highest ready task */
+  next = rt_get_first (&os_rdy);
+  rt_switch_req (next);
+}
+
+/*--------------------------- rt_stk_check ----------------------------------*/
+__weak void rt_stk_check (void) {
+    /* Check for stack overflow. */
+    if (os_tsk.run->task_id == 0x01) {
+        // TODO: For the main thread the check should be done against the main heap pointer
+    } else {
+        if ((os_tsk.run->tsk_stack < (U32)os_tsk.run->stack) ||
+            (os_tsk.run->stack[0] != MAGIC_WORD)) {
+            os_error (OS_ERR_STK_OVF);
+        }
+    }
+}
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_System.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_System.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_SYSTEM.H
+ *      Purpose: System Task Manager definitions
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Variables */
+#define os_psq  ((P_PSQ)&os_fifo)
+extern int os_tick_irqn;
+
+/* Functions */
+extern U32  rt_suspend    (void);
+extern void rt_resume     (U32 sleep_time);
+extern void rt_tsk_lock   (void);
+extern void rt_tsk_unlock (void);
+extern void rt_psh_req    (void);
+extern void rt_pop_req    (void);
+extern void rt_systick    (void);
+extern void rt_stk_check  (void);
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Task.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Task.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,339 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_TASK.C
+ *      Purpose: Task functions and system start up.
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_System.h"
+#include "rt_Task.h"
+#include "rt_List.h"
+#include "rt_MemBox.h"
+#include "rt_Robin.h"
+#include "rt_HAL_CM.h"
+
+/*----------------------------------------------------------------------------
+ *      Global Variables
+ *---------------------------------------------------------------------------*/
+
+/* Running and next task info. */
+struct OS_TSK os_tsk;
+
+/* Task Control Blocks of idle demon */
+struct OS_TCB os_idle_TCB;
+
+
+/*----------------------------------------------------------------------------
+ *      Local Functions
+ *---------------------------------------------------------------------------*/
+
+OS_TID rt_get_TID (void) {
+  U32 tid;
+
+  for (tid = 1; tid <= os_maxtaskrun; tid++) {
+    if (os_active_TCB[tid-1] == NULL) {
+      return ((OS_TID)tid);
+    }
+  }
+  return (0);
+}
+
+#if defined (__CC_ARM) && !defined (__MICROLIB)
+/*--------------------------- __user_perthread_libspace ---------------------*/
+extern void  *__libspace_start;
+
+void *__user_perthread_libspace (void) {
+  /* Provide a separate libspace for each task. */
+  if (os_tsk.run == NULL) {
+    /* RTX not running yet. */
+    return (&__libspace_start);
+  }
+  return (void *)(os_tsk.run->std_libspace);
+}
+#endif
+
+/*--------------------------- rt_init_context -------------------------------*/
+
+void rt_init_context (P_TCB p_TCB, U8 priority, FUNCP task_body) {
+  /* Initialize general part of the Task Control Block. */
+  p_TCB->cb_type = TCB;
+  p_TCB->state   = READY;
+  p_TCB->prio    = priority;
+  p_TCB->p_lnk   = NULL;
+  p_TCB->p_rlnk  = NULL;
+  p_TCB->p_dlnk  = NULL;
+  p_TCB->p_blnk  = NULL;
+  p_TCB->delta_time    = 0;
+  p_TCB->interval_time = 0;
+  p_TCB->events  = 0;
+  p_TCB->waits   = 0;
+  p_TCB->stack_frame = 0;
+
+  rt_init_stack (p_TCB, task_body);
+}
+
+
+/*--------------------------- rt_switch_req ---------------------------------*/
+
+void rt_switch_req (P_TCB p_new) {
+  /* Switch to next task (identified by "p_new"). */
+  os_tsk.new_tsk   = p_new;
+  p_new->state = RUNNING;
+  DBG_TASK_SWITCH(p_new->task_id);
+}
+
+
+/*--------------------------- rt_dispatch -----------------------------------*/
+
+void rt_dispatch (P_TCB next_TCB) {
+  /* Dispatch next task if any identified or dispatch highest ready task    */
+  /* "next_TCB" identifies a task to run or has value NULL (=no next task)  */
+  if (next_TCB == NULL) {
+    /* Running task was blocked: continue with highest ready task */
+    next_TCB = rt_get_first (&os_rdy);
+    rt_switch_req (next_TCB);
+  }
+  else {
+    /* Check which task continues */
+    if (next_TCB->prio > os_tsk.run->prio) {
+      /* preempt running task */
+      rt_put_rdy_first (os_tsk.run);
+      os_tsk.run->state = READY;
+      rt_switch_req (next_TCB);
+    }
+    else {
+      /* put next task into ready list, no task switch takes place */
+      next_TCB->state = READY;
+      rt_put_prio (&os_rdy, next_TCB);
+    }
+  }
+}
+
+
+/*--------------------------- rt_block --------------------------------------*/
+
+void rt_block (U16 timeout, U8 block_state) {
+  /* Block running task and choose next ready task.                         */
+  /* "timeout" sets a time-out value or is 0xffff (=no time-out).           */
+  /* "block_state" defines the appropriate task state */
+  P_TCB next_TCB;
+
+  if (timeout) {
+    if (timeout < 0xffff) {
+      rt_put_dly (os_tsk.run, timeout);
+    }
+    os_tsk.run->state = block_state;
+    next_TCB = rt_get_first (&os_rdy);
+    rt_switch_req (next_TCB);
+  }
+}
+
+
+/*--------------------------- rt_tsk_pass -----------------------------------*/
+
+void rt_tsk_pass (void) {
+  /* Allow tasks of same priority level to run cooperatively.*/
+  P_TCB p_new;
+
+  p_new = rt_get_same_rdy_prio();
+  if (p_new != NULL) {
+    rt_put_prio ((P_XCB)&os_rdy, os_tsk.run);
+    os_tsk.run->state = READY;
+    rt_switch_req (p_new);
+  }
+}
+
+
+/*--------------------------- rt_tsk_self -----------------------------------*/
+
+OS_TID rt_tsk_self (void) {
+  /* Return own task identifier value. */
+  if (os_tsk.run == NULL) {
+    return (0);
+  }
+  return (os_tsk.run->task_id);
+}
+
+
+/*--------------------------- rt_tsk_prio -----------------------------------*/
+
+OS_RESULT rt_tsk_prio (OS_TID task_id, U8 new_prio) {
+  /* Change execution priority of a task to "new_prio". */
+  P_TCB p_task;
+
+  if (task_id == 0) {
+    /* Change execution priority of calling task. */
+    os_tsk.run->prio = new_prio;
+run:if (rt_rdy_prio() > new_prio) {
+      rt_put_prio (&os_rdy, os_tsk.run);
+      os_tsk.run->state   = READY;
+      rt_dispatch (NULL);
+    }
+    return (OS_R_OK);
+  }
+
+  /* Find the task in the "os_active_TCB" array. */
+  if (task_id > os_maxtaskrun || os_active_TCB[task_id-1] == NULL) {
+    /* Task with "task_id" not found or not started. */
+    return (OS_R_NOK);
+  }
+  p_task = os_active_TCB[task_id-1];
+  p_task->prio = new_prio;
+  if (p_task == os_tsk.run) {
+    goto run;
+  }
+  rt_resort_prio (p_task);
+  if (p_task->state == READY) {
+    /* Task enqueued in a ready list. */
+    p_task = rt_get_first (&os_rdy);
+    rt_dispatch (p_task);
+  }
+  return (OS_R_OK);
+}
+
+/*--------------------------- rt_tsk_delete ---------------------------------*/
+
+OS_RESULT rt_tsk_delete (OS_TID task_id) {
+  /* Terminate the task identified with "task_id". */
+  P_TCB task_context;
+
+  if (task_id == 0 || task_id == os_tsk.run->task_id) {
+    /* Terminate itself. */
+    os_tsk.run->state     = INACTIVE;
+    os_tsk.run->tsk_stack = rt_get_PSP ();
+    rt_stk_check ();
+    os_active_TCB[os_tsk.run->task_id-1] = NULL;
+    
+    os_tsk.run->stack = NULL;
+    DBG_TASK_NOTIFY(os_tsk.run, __FALSE);
+    os_tsk.run = NULL;
+    rt_dispatch (NULL);
+    /* The program should never come to this point. */
+  }
+  else {
+    /* Find the task in the "os_active_TCB" array. */
+    if (task_id > os_maxtaskrun || os_active_TCB[task_id-1] == NULL) {
+      /* Task with "task_id" not found or not started. */
+      return (OS_R_NOK);
+    }
+    task_context = os_active_TCB[task_id-1];
+    rt_rmv_list (task_context);
+    rt_rmv_dly (task_context);
+    os_active_TCB[task_id-1] = NULL;
+    
+    task_context->stack = NULL;
+    DBG_TASK_NOTIFY(task_context, __FALSE);
+  }
+  return (OS_R_OK);
+}
+
+
+/*--------------------------- rt_sys_init -----------------------------------*/
+
+#ifdef __CMSIS_RTOS
+void rt_sys_init (void) {
+#else
+void rt_sys_init (FUNCP first_task, U32 prio_stksz, void *stk) {
+#endif
+  /* Initialize system and start up task declared with "first_task". */
+  U32 i;
+
+  DBG_INIT();
+
+  /* Initialize dynamic memory and task TCB pointers to NULL. */
+  for (i = 0; i < os_maxtaskrun; i++) {
+    os_active_TCB[i] = NULL;
+  }
+  
+  /* Set up TCB of idle demon */
+  os_idle_TCB.task_id = 255;
+  os_idle_TCB.priv_stack = idle_task_stack_size;
+  os_idle_TCB.stack = idle_task_stack;
+  rt_init_context (&os_idle_TCB, 0, os_idle_demon);
+
+  /* Set up ready list: initially empty */
+  os_rdy.cb_type = HCB;
+  os_rdy.p_lnk   = NULL;
+  /* Set up delay list: initially empty */
+  os_dly.cb_type = HCB;
+  os_dly.p_dlnk  = NULL;
+  os_dly.p_blnk  = NULL;
+  os_dly.delta_time = 0;
+
+  /* Fix SP and systemvariables to assume idle task is running  */
+  /* Transform main program into idle task by assuming idle TCB */
+#ifndef __CMSIS_RTOS
+  rt_set_PSP (os_idle_TCB.tsk_stack+32);
+#endif
+  os_tsk.run = &os_idle_TCB;
+  os_tsk.run->state = RUNNING;
+
+  /* Initialize ps queue */
+  os_psq->first = 0;
+  os_psq->last  = 0;
+  os_psq->size  = os_fifo_size;
+
+  rt_init_robin ();
+
+  /* Intitialize SVC and PendSV */
+  rt_svc_init ();
+
+#ifndef __CMSIS_RTOS
+  /* Intitialize and start system clock timer */
+  os_tick_irqn = os_tick_init ();
+  if (os_tick_irqn >= 0) {
+    OS_X_INIT(os_tick_irqn);
+  }
+
+  /* Start up first user task before entering the endless loop */
+  rt_tsk_create (first_task, prio_stksz, stk, NULL);
+#endif
+}
+
+
+/*--------------------------- rt_sys_start ----------------------------------*/
+
+#ifdef __CMSIS_RTOS
+void rt_sys_start (void) {
+  /* Start system */
+
+  /* Intitialize and start system clock timer */
+  os_tick_irqn = os_tick_init ();
+  if (os_tick_irqn >= 0) {
+    OS_X_INIT(os_tick_irqn);
+  }
+}
+#endif
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Task.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Task.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_TASK.H
+ *      Purpose: Task functions and system start up.
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Definitions */
+#define __CMSIS_RTOS    1
+
+/* Values for 'state'   */
+#define INACTIVE        0
+#define READY           1
+#define RUNNING         2
+#define WAIT_DLY        3
+#define WAIT_ITV        4
+#define WAIT_OR         5
+#define WAIT_AND        6
+#define WAIT_SEM        7
+#define WAIT_MBX        8
+#define WAIT_MUT        9
+
+/* Return codes */
+#define OS_R_TMO        0x01
+#define OS_R_EVT        0x02
+#define OS_R_SEM        0x03
+#define OS_R_MBX        0x04
+#define OS_R_MUT        0x05
+
+#define OS_R_OK         0x00
+#define OS_R_NOK        0xff
+
+/* Variables */
+extern struct OS_TSK os_tsk;
+extern struct OS_TCB os_idle_TCB;
+
+/* Functions */
+extern void      rt_switch_req (P_TCB p_new);
+extern void      rt_dispatch   (P_TCB next_TCB);
+extern void      rt_block      (U16 timeout, U8 block_state);
+extern void      rt_tsk_pass   (void);
+extern OS_TID    rt_tsk_self   (void);
+extern OS_RESULT rt_tsk_prio   (OS_TID task_id, U8 new_prio);
+extern OS_RESULT rt_tsk_delete (OS_TID task_id);
+extern void      rt_sys_init   (void);
+extern void      rt_sys_start  (void);
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Time.c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Time.c	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_TIME.C
+ *      Purpose: Delay and interval wait functions
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+#include "rt_TypeDef.h"
+#include "RTX_Conf.h"
+#include "rt_Task.h"
+#include "rt_Time.h"
+
+/*----------------------------------------------------------------------------
+ *      Global Variables
+ *---------------------------------------------------------------------------*/
+
+/* Free running system tick counter */
+U32 os_time;
+
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+
+/*--------------------------- rt_time_get -----------------------------------*/
+
+U32 rt_time_get (void) {
+  /* Get system time tick */
+  return (os_time);
+}
+
+
+/*--------------------------- rt_dly_wait -----------------------------------*/
+
+void rt_dly_wait (U16 delay_time) {
+  /* Delay task by "delay_time" */
+  rt_block (delay_time, WAIT_DLY);
+}
+
+
+/*--------------------------- rt_itv_set ------------------------------------*/
+
+void rt_itv_set (U16 interval_time) {
+  /* Set interval length and define start of first interval */
+  os_tsk.run->interval_time = interval_time;
+  os_tsk.run->delta_time = interval_time + (U16)os_time;
+}
+
+
+/*--------------------------- rt_itv_wait -----------------------------------*/
+
+void rt_itv_wait (void) {
+  /* Wait for interval end and define start of next one */
+  U16 delta;
+
+  delta = os_tsk.run->delta_time - (U16)os_time;
+  os_tsk.run->delta_time += os_tsk.run->interval_time;
+  if ((delta & 0x8000) == 0) {
+    rt_block (delta, WAIT_ITV);
+  }
+}
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_Time.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_Time.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_TIME.H
+ *      Purpose: Delay and interval wait functions definitions
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+
+/* Variables */
+extern U32 os_time;
+
+/* Functions */
+extern U32  rt_time_get (void);
+extern void rt_dly_wait (U16 delay_time);
+extern void rt_itv_set  (U16 interval_time);
+extern void rt_itv_wait (void);
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
+
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed-rtos/rtx/rt_TypeDef.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed-rtos/rtx/rt_TypeDef.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------
+ *      RL-ARM - RTX
+ *----------------------------------------------------------------------------
+ *      Name:    RT_TYPEDEF.H
+ *      Purpose: Type Definitions
+ *      Rev.:    V4.60
+ *----------------------------------------------------------------------------
+ *
+ * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH
+ * All rights reserved.
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *  - Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  - Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *  - Neither the name of ARM  nor the names of its contributors may be used 
+ *    to endorse or promote products derived from this software without 
+ *    specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *---------------------------------------------------------------------------*/
+#ifndef RT_TYPE_DEF_H
+#define RT_TYPE_DEF_H
+
+#include "os_tcb.h"
+
+typedef U32     OS_TID;
+typedef void    *OS_ID;
+typedef U32     OS_RESULT;
+
+#define TCB_STACKF      32        /* 'stack_frame' offset                    */
+#define TCB_TSTACK      36        /* 'tsk_stack' offset                      */
+
+typedef struct OS_PSFE {          /* Post Service Fifo Entry                 */
+  void  *id;                      /* Object Identification                   */
+  U32    arg;                     /* Object Argument                         */
+} *P_PSFE;
+
+typedef struct OS_PSQ {           /* Post Service Queue                      */
+  U8     first;                   /* FIFO Head Index                         */
+  U8     last;                    /* FIFO Tail Index                         */
+  U8     count;                   /* Number of stored items in FIFO          */
+  U8     size;                    /* FIFO Size                               */
+  struct OS_PSFE q[1];            /* FIFO Content                            */
+} *P_PSQ;
+
+typedef struct OS_TSK {
+  P_TCB  run;                     /* Current running task                    */
+  P_TCB  new_tsk;                 /* Scheduled task to run                   */
+} *P_TSK;
+
+typedef struct OS_ROBIN {         /* Round Robin Control                     */
+  P_TCB  task;                    /* Round Robin task                        */
+  U16    time;                    /* Round Robin switch time                 */
+  U16    tout;                    /* Round Robin timeout                     */
+} *P_ROBIN;
+
+typedef struct OS_XCB {
+  U8     cb_type;                 /* Control Block Type                      */
+  struct OS_TCB *p_lnk;           /* Link pointer for ready/sem. wait list   */
+  struct OS_TCB *p_rlnk;          /* Link pointer for sem./mbx lst backwards */
+  struct OS_TCB *p_dlnk;          /* Link pointer for delay list             */
+  struct OS_TCB *p_blnk;          /* Link pointer for delay list backwards   */
+  U16    delta_time;              /* Time until time out                     */
+} *P_XCB;
+
+typedef struct OS_MCB {
+  U8     cb_type;                 /* Control Block Type                      */
+  U8     state;                   /* State flag variable                     */
+  U8     isr_st;                  /* State flag variable for isr functions   */
+  struct OS_TCB *p_lnk;           /* Chain of tasks waiting for message      */
+  U16    first;                   /* Index of the message list begin         */
+  U16    last;                    /* Index of the message list end           */
+  U16    count;                   /* Actual number of stored messages        */
+  U16    size;                    /* Maximum number of stored messages       */
+  void   *msg[1];                 /* FIFO for Message pointers 1st element   */
+} *P_MCB;
+
+typedef struct OS_SCB {
+  U8     cb_type;                 /* Control Block Type                      */
+  U8     mask;                    /* Semaphore token mask                    */
+  U16    tokens;                  /* Semaphore tokens                        */
+  struct OS_TCB *p_lnk;           /* Chain of tasks waiting for tokens       */
+} *P_SCB;
+
+typedef struct OS_MUCB {
+  U8     cb_type;                 /* Control Block Type                      */
+  U8     prio;                    /* Owner task default priority             */
+  U16    level;                   /* Call nesting level                      */
+  struct OS_TCB *p_lnk;           /* Chain of tasks waiting for mutex        */
+  struct OS_TCB *owner;           /* Mutex owner task                        */
+} *P_MUCB;
+
+typedef struct OS_XTMR {
+  struct OS_TMR  *next;
+  U16    tcnt;
+} *P_XTMR;
+
+typedef struct OS_TMR {
+  struct OS_TMR  *next;           /* Link pointer to Next timer              */
+  U16    tcnt;                    /* Timer delay count                       */
+  U16    info;                    /* User defined call info                  */
+} *P_TMR;
+
+typedef struct OS_BM {
+  void *free;                     /* Pointer to first free memory block      */
+  void *end;                      /* Pointer to memory block end             */
+  U32  blk_size;                  /* Memory block size                       */
+} *P_BM;
+
+/* Definitions */
+#define __TRUE          1
+#define __FALSE         0
+#define NULL            ((void *) 0)
+
+#endif
diff -r 000000000000 -r 964eb6a2ef00 mbed/mbed.bld
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed/mbed.bld	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/mbed_official/code/mbed/builds/5e5da4a5990b
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 motors/motors.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/motors/motors.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,27 @@
+#include "motors.h"
+
+Motors::Motors(TB6612 * L, TB6612 * R, PinName STBY):
+    Left(L), Right(R), enable(STBY)
+{
+    enable = 1;
+}
+
+void Motors::flip()
+{
+    TB6612 * temp = Left;
+    Left = Right;
+    Right = temp;
+
+    Left->scale *= -1;
+    Right->scale *= -1;              
+}    
+void Motors::reverse(bool m)
+{
+    if(m)
+        Right->scale *= -1; //reverse right motor
+    else
+        Left->scale *= -1;  //reverse left motor
+}
+
+//TODO: write in a function that automatically sets the motors to be oriented properly. Use the
+//gyroscopes and accelerometer to do this.
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 motors/motors.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/motors/motors.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,24 @@
+#ifndef MOTORS_H
+#define MOTORS_H
+
+#include "mbed.h"
+#include "TB6612.h"
+
+class Motors
+{
+    private:
+        
+    void stop(void const *args);
+    
+    public:    
+    
+    TB6612 * Left;
+    TB6612 * Right;        
+    DigitalOut enable;
+    
+    Motors(TB6612 * L, TB6612 * R, PinName STBY);
+    
+    void flip();                
+    void reverse(bool m);   //reverse one of the motors (0=right, 1=left) 
+};
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 reckon/reckon.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/reckon/reckon.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,66 @@
+#include "reckon.h"
+#include "math.h"
+
+#define M_PI 3.14159265359
+
+Reckon::Reckon(ADNS5090& sensorL, ADNS5090& sensorR, float radius) : optical_flow_L(sensorL), optical_flow_R(sensorR), r(radius)
+{
+    reset();
+}
+
+void Reckon::reset(){
+    flowX=0;
+    flowY=0;
+    flowYaw = 0;
+    flow_dx_L = 0;
+    flow_dx_R = 0;
+    flow_dy_L = 0;
+    flow_dy_R = 0;
+}
+
+float Reckon::reduce_angle(float &ang){
+    
+            if(ang > M_PI)        
+                ang -= 2*M_PI;
+            else if(ang < -M_PI)
+                ang += 2*M_PI;
+            return ang;   
+    }
+
+float Reckon::dest_angle(float x_dest, float y_dest){    
+    float dest_angle = atan2(y_dest - y,x_dest - x);   
+    return reduce_angle(dest_angle);
+}
+
+float Reckon::dest_distance(float x_dest, float y_dest){    
+    return sqrt(pow(x_dest-x,2)+pow(y_dest-y,2));
+}
+
+
+bool Reckon::updateOpticalFlow(){
+    
+    bool motionL = optical_flow_L.updateMotion();
+    bool motionR = optical_flow_R.updateMotion();
+    
+    if(motionL || motionR){
+        float dx = (optical_flow_L.dx() + optical_flow_R.dx())/2;
+        float dy = (optical_flow_L.dy() + optical_flow_R.dy())/2;
+        float dAngle = (optical_flow_R.dy() - optical_flow_L.dy())/r;
+        
+        flowYaw += dAngle/2;        
+        float cos_ = cos(flowYaw);
+        float sin_ = sin(flowYaw);                
+        flowX += dx*cos_ - dy*sin_;
+        flowY += dx*sin_ + dy*cos_;        
+        flowYaw += dAngle/2;
+        
+        reduce_angle(flowYaw);
+        flow_dx_L += optical_flow_L.dx();
+        flow_dy_L += optical_flow_L.dy();
+        flow_dx_R += optical_flow_R.dx();
+        flow_dy_R += optical_flow_R.dy();
+        
+        return true;
+    }else
+        return false;
+}
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 reckon/reckon.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/reckon/reckon.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,48 @@
+#ifndef RECKON_H
+#define RECKON_H
+
+#include "mbed.h"
+#include "ADNS5090.h"
+
+//TODO: include a function to swap motors if they are connected wrong.
+
+#define DEGREES(radians)((radians)*180/M_PI)
+
+class Reckon
+{
+    public:
+    
+    ADNS5090&   optical_flow_L;
+    ADNS5090&   optical_flow_R;    
+    float r;
+    
+    float x;
+    float y;
+    float accX;
+    float accY;
+    float accZ;
+    
+    float flowX;
+    float flowY;
+    float flowYaw;
+    float flow_dx_L;
+    float flow_dx_R;
+    float flow_dy_L;
+    float flow_dy_R;
+    float gyroYaw;
+    
+    Reckon(ADNS5090& L,ADNS5090& R, float radius);    
+    
+    static float reduce_angle( float &);
+    
+    float dest_angle(float x_dest, float y_dest);
+    float dest_distance(float x_dest, float y_dest);
+    
+    bool updateOpticalFlow();               //new
+    void reset();     
+    
+    private:    
+    Timer frametime;
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 robot/calibration/bot08_cal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/robot/calibration/bot08_cal.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,12 @@
+#ifndef CAL_H
+#define CAL_H
+
+#define L_MOTOR_SCALE               0.85
+#define R_MOTOR_SCALE               1
+
+#define L_MOUSE_PX_PER_MM           14.474   //pixels per mm
+#define R_MOUSE_PX_PER_MM           12.406  //pixels per mm
+
+#define MOUSE_DISTANCE              30     //mm
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 robot/calibration/bot32_cal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/robot/calibration/bot32_cal.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,12 @@
+#ifndef CAL_H
+#define CAL_H
+
+#define L_MOTOR_SCALE               1
+#define R_MOTOR_SCALE               0.94
+
+#define L_MOUSE_PX_PER_MM           9.593   //pixels per mm
+#define R_MOUSE_PX_PER_MM           10.51  //pixels per mm
+
+#define MOUSE_DISTANCE              30     //mm
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 robot/calibration/bot36_cal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/robot/calibration/bot36_cal.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,12 @@
+#ifndef CAL_H
+#define CAL_H
+
+#define L_MOTOR_SCALE               1
+#define R_MOTOR_SCALE               1
+
+#define L_MOUSE_PX_PER_MM           13.87   //pixels per mm
+#define R_MOUSE_PX_PER_MM           11  //pixels per mm
+
+#define MOUSE_DISTANCE              30     //mm
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 964eb6a2ef00 robot/robot.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/robot/robot.cpp	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,73 @@
+#include "robot.h"
+#include "bot08_cal.h"
+
+/**Note: Initialize ALL UNUSED ANALOG IN pins as digital out to reduce noise on analog reads*//////
+
+DigitalOut      led(LED_PIN);
+
+HC05            bt(TX_BT,RX_BT,EN_BT);
+
+AnalogIn irL(IR_L);
+AnalogIn irC(IR_C);
+AnalogIn irR(IR_R);
+DigitalOut irBack(IR_B);
+AnalogIn voltage_sensor(VOLTAGESENSOR_PIN);
+
+ACS712          current_sensor;
+ADNS5090        opt_flow_L(MOSI_MOUSE,MISO_MOUSE,SCLK_MOUSE,NCS_MOUSE_L,L_MOUSE_PX_PER_MM);
+ADNS5090        opt_flow_R(MOSI_MOUSE,MISO_MOUSE,SCLK_MOUSE,NCS_MOUSE_R,R_MOUSE_PX_PER_MM);
+Reckon          reckon(opt_flow_L, opt_flow_R, MOUSE_DISTANCE);
+
+MPU6050 mpu;
+MPU6051 mpu2;
+DigitalOut imuSwitch(IMU_POWER_PIN);
+DigitalOut imu2Switch(IMU2_POWER_PIN);
+IMU_DATA imu_data;
+IMU_DATA imu2_data;
+
+TB6612 MotorA(MOT_PWMA_PIN, MOT_AIN1_PIN, MOT_AIN2_PIN);
+TB6612 MotorB(MOT_PWMB_PIN, MOT_BIN1_PIN, MOT_BIN2_PIN);
+Motors motors( &MotorA, &MotorB, MOT_STBY_PIN);
+
+nRF24L01P rf(PTD2, PTD3, PTD1, PTD0, PTC17, PTD4);    // mosi, miso, sck, csn, ce, irq //CSN has been changed from PTD5 to PTC17
+
+
+bool send_flag; //indicates when robot should send all data
+bool obstacle_flag; //indicates an obstacle - robot should stop
+bool fwd_flag;
+bool calibrate_flag;
+bool calibrate_optFlow_flag;
+
+unsigned long long long_time = 0;
+Timer t;
+
+float getTime()
+{   return (float)(long_time + t.read_us())/1000000 ;   }
+
+void initRobot()
+{   
+    LED_OFF
+    
+    MotorA.scale = R_MOTOR_SCALE;
+    MotorB.scale = L_MOTOR_SCALE;    
+    
+    current_sensor.calibrate();
+    
+    LED_ON
+    
+    bt.start(); //this turns on the bluetooth switch
+    rf.powerUp();   //turn on RF comm
+    send_flag = 0;
+    obstacle_flag = 0;
+    
+    wait_ms(60);
+    opt_flow_L.setDPI();
+    opt_flow_R.setDPI();
+    bt.baud(BT_BAUD_RATE);
+    motors.flip();
+    
+    
+    LED_OFF //good to go
+    t.start();      //start timer
+}
+
diff -r 000000000000 -r 964eb6a2ef00 robot/robot.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/robot/robot.h	Wed Mar 18 22:23:48 2015 +0000
@@ -0,0 +1,121 @@
+#ifndef ROBOT_H
+#define ROBOT_H
+
+#include "mbed.h"
+#include "rtos.h"
+#include "stdint.h"
+
+#include "HC05.h"
+#include "nRF24L01P.h"
+
+#include "MPU6050_6Axis_MotionApps20.h"
+#include "MPU6051_6Axis_MotionApps20.h"
+#include "DMP.h"
+#include "IMUDATA.h"
+#include "ADNS5090.h"
+#include "ACS712.h"
+
+#include "reckon.h"
+#include "motors.h"
+
+#define BT_BAUD_RATE        115200        //Baud rate of 9600
+#define TX_BT               PTA2        //Bluetooth connection pins
+#define RX_BT               PTA1        //Bluetooth connection pins
+#define EN_BT               PTE30        //Bluetooth connection pins
+
+#define MOSI_MOUSE          PTB16        //Bluetooth connection pins
+#define MISO_MOUSE          PTB17        //Bluetooth connection pins
+#define SCLK_MOUSE          PTB11        //Bluetooth connection pins
+#define NCS_MOUSE_L         PTB9        //Bluetooth connection pins
+#define NCS_MOUSE_R         PTB8        //Bluetooth connection pins
+
+//#define IMU_SDA_PIN         PTE0
+//#define IMU_SCL_PIN         PTE1
+#define IMU_POWER_PIN       PTD6
+#define IMU2_POWER_PIN      PTD4 //PTD4
+//#define IMU_NOTUSED_PIN     PTE23
+
+#define LED_PIN     PTE3        //status LED pin
+#define LED_OFF  led = 1;        //status LED pin
+#define LED_ON   led = 0;        //status LED pin
+
+//#define CURRENTSENSOR_PIN PTC2
+#define VOLTAGESENSOR_PIN PTB0
+//#define HIGH_CURRENT_SWITCH PTB18   //turn this to high to get high current flow
+
+
+//#define CURRENT_R1 180 //160.0     //values of the current sensor opamp resistors
+//#define CURRENT_R2 10
+//#define CURRENT_R3 80
+//#define CURRENT_R4 84.7
+//#define VREF3_3 3.3        //digital logic voltage
+//#define VREF5 5.0       //5v voltage        //NOTE: 5v voltage is consistent when using new batts, but not using old blue batts
+
+#define IR_L PTB1
+#define IR_C PTB2
+#define IR_R PTB3
+#define IR_B PTC6     //turn GPIO to high to multiplex L,C,R ADC to rear sensors
+
+
+#define MOT_AIN1_PIN   PTA14
+#define MOT_AIN2_PIN   PTA13
+#define MOT_PWMA_PIN   PTA4    //Motor control pins  
+
+#define MOT_BIN1_PIN   PTA16
+#define MOT_BIN2_PIN   PTA17
+#define MOT_PWMB_PIN   PTA5
+
+#define MOT_STBY_PIN   PTA15
+
+//used for RF device
+#define TRANSFER_SIZE   4
+#define ROBOT1_ADDRESS      ((unsigned long long) 0x17E7E7E7E7 )
+#define ROBOT2_ADDRESS      ((unsigned long long) 0xC2C2C2C2C2 )
+#define ROBOT3_ADDRESS      ((unsigned long long) 0x37E7E7E7E7 )
+#define ALLROBOT_ADDRESS    ((unsigned long long) 0xE7E7E7E7E7 )
+#define ADDRESS_WIDTH       5
+const float M_PI = 3.14159265;
+
+extern DigitalOut led;
+
+extern HC05 bt;
+
+extern bool send_flag;
+extern bool obstacle_flag;   //this alerts the robot if there is an obstacle somewhere. 
+extern bool fwd_flag;   //indicates that the robot is trying to move forward
+extern bool calibrate_flag;
+extern bool calibrate_optFlow_flag;
+
+extern AnalogIn irL;
+extern AnalogIn irC;
+extern AnalogIn irR;
+extern DigitalOut irBack;
+extern AnalogIn voltage_sensor;
+
+extern ACS712 current_sensor;
+extern ADNS5090 opt_flow_L;
+extern ADNS5090 opt_flow_R;
+
+extern MPU6050 mpu;
+extern MPU6051 mpu2;
+
+extern DigitalOut imuSwitch;
+extern DigitalOut imu2Switch;
+extern IMU_DATA imu_data;
+extern IMU_DATA imu2_data;
+
+extern Reckon  reckon;
+
+extern Motors motors;
+extern RtosTimer *MotorStopTimer;
+
+extern nRF24L01P rf;    // RF communication device
+
+extern unsigned long long long_time;
+extern Timer t;
+float getTime();
+
+void initRobot();
+void moveMotors(int Lspeed, int Rspeed, int ms);
+
+#endif
\ No newline at end of file