System Management code

Dependencies:   mbed CANBuffer Watchdog MODSERIAL mbed-rtos xbeeRelay IAP

Fork of SystemManagement by Martin Deng

Files at this revision

API Documentation at this revision

Comitter:
pspatel321
Date:
Fri Oct 24 22:09:04 2014 +0000
Parent:
12:e0adb697fcdb
Child:
14:8d4959210d4b
Child:
25:900579201439
Commit message:
Fork showing Parth's changes to current monitor, IMD, and fanpump.

Changed in this revision

CoulombCounter/CoulombCounter.cpp Show annotated file Show diff for this revision Revisions of this file
CoulombCounter/CoulombCounter.h Show annotated file Show diff for this revision Revisions of this file
CoulombCounter/RTCStore.h Show annotated file Show diff for this revision Revisions of this file
CurrentMonitor/CurrentMonitor.cpp Show diff for this revision Revisions of this file
CurrentMonitor/CurrentMonitor.h Show diff for this revision Revisions of this file
FanPump/FanPump.cpp Show annotated file Show diff for this revision Revisions of this file
FanPump/FanPump.h Show annotated file Show diff for this revision Revisions of this file
Get_IMD/Get_IMD.h Show diff for this revision Revisions of this file
Get_IMD/IMD.cpp Show diff for this revision Revisions of this file
Get_IMD/IMD.h Show diff for this revision Revisions of this file
IMD/IMD.cpp Show annotated file Show diff for this revision Revisions of this file
IMD/IMD.h Show annotated file Show diff for this revision Revisions of this file
LPCDigitalIn.lib Show annotated file Show diff for this revision Revisions of this file
RTCStore/Store_RTC.h Show diff for this revision Revisions of this file
SysManagement_kiran_full.lib Show diff for this revision Revisions of this file
SysMngmt.cpp Show annotated file Show diff for this revision Revisions of this file
Watchdog.lib Show annotated file Show diff for this revision Revisions of this file
mbed-rtos.lib Show annotated file Show diff for this revision Revisions of this file
mbed.bld Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/CoulombCounter/CoulombCounter.cpp	Fri Oct 24 22:09:04 2014 +0000
@@ -0,0 +1,33 @@
+#include "CoulombCounter.h"
+
+const float MSEC_HRS = 2.77778e-7;                          // Multiplier to convert milliseconds to hours
+const float BAT_ISENSE_MULTIPLIER = 6.2299;                 // Multiplier to convert float to amps
+const float BAT_ISENSE_OFFSET = 0.5*BAT_ISENSE_MULTIPLIER;  // Offset to convert float to amps
+const float BAT_ISENSE_LIMS = 3.0;                          // Over-current limit = +/- 3A
+
+CoulombCounter::CoulombCounter(PinName _IsensePin, int mSec, int _rtcGPREG_counter, int _rtcGPREG_capacity) : BatISense(p19) {
+    mSec = _mSec;
+    rtcGPREG_counter = _rtcGPREG_counter;
+    rtcGPREG_capacity = _rtcGPREG_capacity;
+    
+    // Take the initial reading
+    currentSample = BatISense*BAT_ISENSE_MULTIPLIER+BAT_ISENSE_OFFSET;
+    if (currentSample < -BAT_ISENSE_LIMS || currentSample > BAT_ISENSE_LIMS) overCurrent = true;
+    else overCurrent = false;
+    
+    // Start counting
+    sampler.attach_us(this, &CoulombCounter::sample, mSec*1000);
+}
+
+void CouloumbCounter::sample() {
+    // Take the reading
+    currentSample = BatISense.read()*BAT_ISENSE_MULTIPLIER+BAT_ISENSE_OFFSET;
+    
+    // Signal error on over current
+    if (currentSample < -BAT_ISENSE_LIMS || currentSample > BAT_ISENSE_LIMS) {
+        overCurrent = true;
+    } else overCurrent = false;
+    
+    // Integrate
+    store.write(ampHours()+currentSample*mSec*MSEC_HRS, rtcGPREG_counter);
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/CoulombCounter/CoulombCounter.h	Fri Oct 24 22:09:04 2014 +0000
@@ -0,0 +1,41 @@
+#ifndef _FILE_CURRENTMONITOR_H
+#define _FILE_CURRENTMONITOR_H
+
+#include "mbed.h"
+#include "CANBuffer.h"
+#include "Store_RTC.h"
+
+RTCStore store;
+
+class CoulombCounter {
+public:
+
+    // Configures for a certain pin, millisecond sample period, and which GPREG in RTC to use to store the ampHours
+    CoulombCounter(int _mSec, int _rtcGPREG_counter, int _rtcGPREG_capacity);
+    
+    // Allow zeroing the SOC when the battery is fully charged/dead, SOC in % from 0 to 1
+    void resetToSOC(float SOC) { store.write(SOC*capacity(), rtcGPREG_counter); }  
+   
+   // Allow zeroing the SOC (via zeroing the Ah) when the battery is fully charged/dead           
+    void resetToAh(float Ah) { store.write(Ah, rtcGPREG_counter); }
+    
+    // Allow change of capacity spec (changes SOC)
+    void changeCapacity(float capAh) {store.write(capAh, rtcGPREG_capacity); }
+        
+    bool overCurrent;                                           // Sensor above range
+    float current() { return currentSample; }                   // Last current reading in Amps
+    float ampHours() { return store.read(rtcGPREG_counter);  }
+    float capacity() { return store.read(rtcGPREG_capacity); }
+    float SOC() { return ampHours()/capacity(); }
+    
+private:
+    Ticker sampler;         // Used to capture next sample and coulomb count
+    void sample();
+    int mSec;
+    float currentSample;
+    
+    int rtcGPREG_counter;
+    int rtcGPREG_capacity;
+    AnalogIn BatISense;     // Analog input pin
+};
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/CoulombCounter/RTCStore.h	Fri Oct 24 22:09:04 2014 +0000
@@ -0,0 +1,38 @@
+/*  Test Code
+    #include "Battery_Status.h"
+    #include"mbed.h"   
+    BatteryStatus battery;
+    
+    int main()
+    {
+        //battery.write(6.92,0);
+        printf("LPC_RTC->GPREG0:%f\n\r",battery.read(0));
+        //battery.write(7.92,1);
+        printf("LPC_RTC->GPREG1:%f\n\r",battery.read(1));
+        //battery.write(8.92,2);
+        printf("LPC_RTC->GPREG2:%f\n\r",battery.read(2));
+        //battery.write(9.92,3);
+        printf("LPC_RTC->GPREG3:%f\n\r",battery.read(3));
+        //battery.write(10.92,4);
+        printf("LPC_RTC->GPREG4:%f\n\r",battery.read(4));
+    }
+*/        
+
+#ifndef _RTC_STORE_H
+#define _RTC_STORE_H
+#include "mbed.h"
+
+class RTCStore {
+public:
+    RTCStore() {
+        LPC_SC->PCONP |= (1<<9);        // Enable RTC Peripheral
+    }
+    void write(float data, int block) {
+        *((float*)(&LPC_RTC->GPREG0)+sizeof(float)*block) = data;
+    }
+    float read(int block) {
+        return *((float*)((&LPC_RTC->GPREG0)+sizeof(float)*block));
+    }              
+};
+#endif
+    
\ No newline at end of file
--- a/CurrentMonitor/CurrentMonitor.cpp	Tue Oct 21 23:44:15 2014 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,68 +0,0 @@
-#include "mbed.h"
-#include "CurrentMonitor.h"
-#include "Store_RTC.h"
-
-#define MSEC_HRS 2.77778e-7
-#define DC_DC_ISENSE_OFFSET_V 0.5
-#define DC_DC_ISENSE_INCREMENT 0.133
-
-#define BAT_ISENSE_OFFSET_V 1.65
-#define BAT_ISENSE_INCREMENT 0.5297
-
-CANBuffer *tx_Current_Buffer;
-
-double BATmA_Hr;
-float DCA_msec,BATA_msec;
-float Bat_I_Ratio,DC_I_Ratio;
-
-AnalogIn BatISense(p19);
-AnalogIn DCSense(p20);
-
-RTCStore store;
-
-union converter{
-    float data;
-    char ch[4];    
-} convert;
-
-CurrentMonitor::CurrentMonitor(CANBuffer *can){
-    tx_Current_Buffer = can;
-}
-
-void update_current(const void *arg){
-    char data[4] = {0};
-    while(1){
-        float bat_reading = store.read(1);
-        convert.data = bat_reading;
-        
-        data[0] = convert.ch[0];
-        data[1] = convert.ch[1];
-        data[2] = convert.ch[2];
-        data[3] = convert.ch[3];
-        
-        CANMessage txMessage(TX_CURRENT_ID, data, 4);
-        tx_Current_Buffer->txWrite(txMessage);
-        
-        Thread::wait(100);          //10 Hz update
-    }
-}
-
-void monitor_current(const void *arg){
-    while(1){
-        Bat_I_Ratio=BatISense.read();
-        BATA_msec=(((Bat_I_Ratio*3.3) - BAT_ISENSE_OFFSET_V)/BAT_ISENSE_INCREMENT);
-        BATmA_Hr+=(BATA_msec*MSEC_HRS);
-        store.write(BATmA_Hr,0);
-                
-        DC_I_Ratio=DCSense.read(); 
-        DCA_msec=(((DC_I_Ratio*3.3) - DC_DC_ISENSE_OFFSET_V)/DC_DC_ISENSE_INCREMENT);
-        store.write(DCA_msec,1);
-        
-        Thread::wait(1);            //1 Khz coulomb counter   
-    }   
-}
-
-void CurrentMonitor::start_update(){
-    Thread monitor_thread(monitor_current);
-    Thread update_thread(update_current);
-}
\ No newline at end of file
--- a/CurrentMonitor/CurrentMonitor.h	Tue Oct 21 23:44:15 2014 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,18 +0,0 @@
-#ifndef _FILE_CURRENTMONITOR_H
-#define _FILE_CURRENTMONITOR_H
-
-#include "mbed.h"
-#include "rtos.h"
-#include "CANBuffer.h"
-
-const int TX_CURRENT_ID = ((4 << 8) | 3);
-
-class CurrentMonitor{
-public:
-    CurrentMonitor(CANBuffer *can);
-    void start_update(); 
-
-private:
-
-};
-#endif
\ No newline at end of file
--- a/FanPump/FanPump.cpp	Tue Oct 21 23:44:15 2014 +0000
+++ b/FanPump/FanPump.cpp	Fri Oct 24 22:09:04 2014 +0000
@@ -1,110 +1,56 @@
-#include "mbed.h"
 #include "FanPump.h"
 
-PwmOut pwmPins[PIN_NUM] = { 
-    PwmOut(P2_0),         // pump 1
-    PwmOut(P2_1),         // pump 2
-    PwmOut(P2_2),         // fan 1
-    PwmOut(P2_3),         // fan 2
-};
-
-PinStatus pin_status[PIN_NUM];
-CANBuffer *tx_Fan_Buffer;
+static FanPump* instance[6] = { NULL };
 
-FanPump::FanPump(CANBuffer *can){
-    for(int i = 0; i < PIN_NUM; i++){
-        pin_status[i].cur_duty = 0.0;
-        pin_status[i].new_duty = 0.0;
-        
-        pin_status[i].pin = &pwmPins[i];
-        pin_status[i].pin->period_ms(10);
-        pin_status[i].pin->write(0.0);
-        
-        pin_threads[i] = NULL;
-    }  
-
-    tx_Fan_Buffer = can;
+// Interrupt handler, must be called from static context, calls all the slew functions
+void pwmIRQ() {
+    if (LPC_PWM1->IR & 1) {
+        for (int i = 0; i < 6; i++) {
+            if (instance[i] != NULL) instance[i]->slew();   
+        }
+    }
+    LPC_PWM1->IR = 0x73F;   // Clear interrupts
 }
 
-// this is not a member function. For some reason, thread does weird things
-// with functions in classes. Apparently pointers get messed up when pointing to
-// a function in a class
-void ramp_pin(void const *arg)
-{
-    PinStatus *pin_stat = (PinStatus *)arg;
-    float *cur_duty = &(pin_stat->cur_duty);
-    float *new_duty = &(pin_stat->new_duty);
-    
-    while(*cur_duty != *new_duty)
-    {
-        if(*new_duty > *cur_duty){
-            *cur_duty += 1.0;
-            
-            if(*cur_duty > *new_duty)
-                *cur_duty = *new_duty;   
-        } else if(*new_duty < *cur_duty){
-            *cur_duty -= 1.0;
-            
-            if(*cur_duty < *new_duty)
-                *cur_duty = *new_duty;   
-        }
-        
-        pin_stat->pin->write((*cur_duty));
-        
-        Thread::wait(5);    //1% duty cycle per 0.005 s
+// Called on each timer expire for each pwm object
+void FanPump::slew() {
+    uint32_t currPulseT = *(&LPC_PWM1->MR0+pin);
+    uint32_t currPulse_us = currPulseT / 24;
+    uint32_t setPointT = setPoint_us * 24;      // Convert us into ticks
+    if (currPulseT == setPointT) return;        // Nothing to slew here, already at its setpoint
+
+    if (currPulseT < setPointT) {
+        if (setPoint_us - currPulse_us < maxChange_us) pwm.pulsewidth_us(setPoint_us); // Close to the setpoint, write it directly
+        else pwm.pulsewidth_us(currPulse_us + maxChange_us);       
+    } else {
+        if (currPulse_us - setPoint_us < maxChange_us) pwm.pulsewidth_us(setPoint_us);
+        else pwm.pulsewidth_us(currPulse_us - maxChange_us);
     }
 }
 
-void FanPump::set_fan_pump(FanPumpSelect fan_pump, float duty){
-    if((int)fan_pump >= PIN_NUM || duty > 100.0)
-        return;
+FanPump::FanPump(PinName pin, float period, float slew) : pwm(pin) {
+    setPoint_us = 0;
+    period_us = period / 1.0e6;
+    pwm.period_us(period_us);
+    maxChange_us = (period / slew) * period_us;
     
-    free_pin(fan_pump);
-
-    pin_status[fan_pump].new_duty = duty;
-    pin_threads[fan_pump] = new Thread(ramp_pin, &pin_status[fan_pump]);
-}
-
-void FanPump::shutdown(FanPumpSelect fan_pump){
-    free_pin(fan_pump);
+    // Match the pin# to the PWM object for the interrupt
+    if (pin == p26 || pin == LED1) pin = 1;
+    if (pin == p25 || pin == LED2) pin = 2;
+    if (pin == p24 || pin == LED3) pin = 3;
+    if (pin == p23 || pin == LED4) pin = 4;
+    if (pin == p22)                pin = 5;
+    if (pin == p21)                pin = 6;
+    instance[pin-1] = this;
     
-    pin_status[fan_pump].cur_duty = 0;
-    pin_status[fan_pump].new_duty = 0;
-    pin_status[fan_pump].pin->write(0);
-}
-
-void FanPump::shutdown_all(){
-    for(int i = 0; i < PIN_NUM; i++)
-        FanPump::shutdown((FanPumpSelect)i);    
+    LPC_PWM1->IR = 0x73F;   // Clear interrupts
+    NVIC_SetVector(PWM1_IRQn, (uint32_t)&pwmIRQ);
+    NVIC_SetPriority(PWM1_IRQn, 0);
+    NVIC_EnableIRQ(PWM1_IRQn);
+    LPC_PWM1->MR |= 1;  // Enable interrupt on MR0 (when the pwm period expires)
 }
-
-void FanPump::free_pin(FanPumpSelect fan_pump){
-    if(pin_threads[fan_pump] != NULL){
-        pin_threads[fan_pump]->terminate();
-        free(pin_threads[fan_pump]);    
-    }    
-}
-
-void update_fans_pumps(void const *arg){
-    char data[8] = {0};
-    while(1){
-        memcpy(&pin_status[0].cur_duty, data, sizeof(float));
-        memcpy(&pin_status[1].cur_duty, data+4, sizeof(float));
-        
-        CANMessage txPumpMessage(TX_PUMP_ID, data, 8);
-        tx_Fan_Buffer->txWrite(txPumpMessage);
-        
-        memcpy(&pin_status[2].cur_duty, data, sizeof(float));
-        memcpy(&pin_status[3].cur_duty, data+4, sizeof(float));
-        
-        CANMessage txFanMessage(TX_FAN_ID, data, 8);
-        tx_Fan_Buffer->txWrite(txFanMessage);
-        
-        Thread::wait(100);  // 10 Hz update    
-    }    
-}
-
-void FanPump::start_update()
-{
-    Thread update_thread(update_fans_pumps);
+void FanPump::write(float duty) {
+    if (duty < 0) duty = 0;
+    if (duty > 1) duty = 1;
+    setPoint_us = duty * period_us;
 }
\ No newline at end of file
--- a/FanPump/FanPump.h	Tue Oct 21 23:44:15 2014 +0000
+++ b/FanPump/FanPump.h	Fri Oct 24 22:09:04 2014 +0000
@@ -2,38 +2,22 @@
 #define _FILE_FANPUMP_H
 
 #include "mbed.h"
-#include "rtos.h"
-#include "CANBuffer.h"
-
-typedef enum {
-    Pump1 = 0,
-    Pump2 = 1,
-    Fan1 = 2,
-    Fan2 = 3,
-} FanPumpSelect;
-
-typedef struct{
-    float cur_duty;
-    float new_duty;
-    PwmOut *pin;    
-} PinStatus;
-
-const int PIN_NUM = 4;
-const int TX_FAN_ID = ((0x4 << 8) | 0x11);
-const int RX_FAN_ID = ((0x4 << 8) | 0x81);
-const int TX_PUMP_ID = ((0x4 << 8) | 0x10);
-const int RX_PUMP_ID = ((0x4 << 8) | 0x80);
 
 class FanPump{
 public:
-    FanPump(CANBuffer *can);
-    void set_fan_pump(FanPumpSelect fan, float duty);
-    void shutdown(FanPumpSelect fan);
-    void shutdown_all();
-    void start_update();
+    // Takes Pwmout pin, period (seconds), duty cycle slew rate in second^-1 (1 means duty 0 to 1 occurs over 1 second, 0 means no slew)
+    // Use slew rate to implement soft start
+    FanPump(PinName pin, float period, float slew);
+    void write(float duty);
+    float read();       // Read the last setpoint
+    float readRaw();    // Read the raw current duty (may be mid-transition)
     
+    void slew();        // Slew rate callback function
 private:
-    Thread *pin_threads[PIN_NUM];
-    void free_pin(FanPumpSelect fan);
+    PwmOut pwm;         // mbed PWM out
+    int pin;            // pwm channel#
+    static uint32_t period_us; // Period in microseconds (shared by all channels)
+    uint32_t setPoint_us;
+    uint32_t maxChange_us;     // Max pulsewidth change allowed to achieve the slew rate
 };
 #endif
\ No newline at end of file
--- a/Get_IMD/Get_IMD.h	Tue Oct 21 23:44:15 2014 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,133 +0,0 @@
-#include "mbed.h"
-#include "string.h"
-
-DigitalOut myled(LED1);
-
-//Serial pc(USBTX,USBRX);
-
-#ifndef GET_IMD_H
-#define GET_IMD_H  
-
-    typedef struct
-    {
-        float Frequency;
-        float Duty_Cycle;
-        char State[50];
-        char Encoded_Status;
-    }IMD_Measurement_Output;
-    
-    bool FirstFE=true;
-    bool FirstRE=true;
-    uint32_t ON_Period =0;
-    uint32_t INT0_RE,INT0_FE;
-    uint32_t CAP0RE=0, CAP0FE=1, CRO_I=4;
-    IMD_Measurement_Output Result;
-    
-    extern "C" void TIMER0_IRQHandler(void)
-    {
-        INT0_RE=LPC_TIM0->CCR;
-        INT0_FE=LPC_TIM0->CCR;
-        
-        
-        if(((INT0_FE & (1 << CAP0FE)) >> CAP0FE))
-        {
-            if(!FirstFE)
-            {
-                //pc.printf("LPC_TIM1->TC in FE:%d\n\r",LPC_TIM1->TC);                
-                ON_Period = LPC_TIM1->TC;
-                //pc.printf("On Period:%d\n\r",ON_Period);
-                LPC_TIM0->CCR   |=  ((1<<0) | (1<<2));      //Copy TC to CRO on Rising Edge AND Generate Interrupt                
-                LPC_TIM0->CCR   &=  ~(1<<1);     //Disable Falling Edge
-            }
-            else
-                FirstFE=false;                            
-        }
-        else if((INT0_RE & (1 << CAP0RE))>> CAP0RE)
-        {
-            //pc.printf("On Period In RE:%d\n\r",ON_Period);
-            if(!FirstRE)
-            {
-                //pc.printf("LPC_TIM1->TC in RE:%d\n\r",LPC_TIM1->TC);
-                //pc.printf("On Period In RE:%d\n\r",ON_Period);
-                Result.Frequency=((1/(float)LPC_TIM1->TC)*1000);
-                Result.Duty_Cycle=((ON_Period/(float)LPC_TIM1->TC)*100);
-                LPC_TIM0->CCR   |=  ((1<<1) | (1<<2));      //Copy TC to CRO on Falling Edge AND Generate Interrupt                             
-                LPC_TIM0->CCR   &=  ~(1<<0);                //Disable Rising Edge
-                LPC_TIM1->TCR   |=  (1<<1);                 //Reset Timer1
-                LPC_TIM1->TCR   &=  ~(1<<1);                 //Restart Timer1
-            }
-            else
-                FirstRE=false;    
-        }
-        LPC_TIM0->IR |= (1<<CRO_I);                         //Reset Counter0 Interrupt
-        return;  
-    }
-    
-    void init()
-    {
-        Result.Frequency=0;
-        Result.Duty_Cycle=0;
-        strcpy(Result.State,"");
-        //Set pin as capture mode
-        //Initialize Counter2
-        LPC_PINCON->PINSEL3 |=  ((1<<21) | (1<<20));          //Set Pin1.26 as CAP0.0 
-        LPC_SC->PCONP       |=  (1<<1);                    //PowerOn Timer/Counter0.
-        LPC_TIM0->CCR       |=  ((1<<1) | (1<<2));          //Copy TC to CRO on Falling Edge AND Generate Interrupt
-        NVIC_SetPriority(TIMER0_IRQn,255);
-        NVIC_EnableIRQ(TIMER0_IRQn);                        //Enable TIMER0 IRQ      
-        
-        //Initiallize Timer1
-        LPC_SC->PCONP       |=  (1<<2);                     //PoewerOn Timer/Counter1
-        LPC_SC->PCLKSEL0    |=  ((1<<4) | (1<<5));          //Prescale Timer1 CCLK/8  
-        LPC_TIM1->CTCR      &=  ~((1<<1) | (1<<0));         //Set Timer/Counter1 as as Timer mode
-        LPC_TIM1->PR        =   11985;                      //Timeout every 1msec(Timer Resolution)
-        LPC_TIM1->TCR       |=  (1<<1);                     //Reset Timer1
-        LPC_TIM1->TCR       |=  (1<<0);                     //Enable Timer1
-        //LPC_TIM1->TCR       &=  ~(1<<1);                 //Restart Timer1              
-        FirstRE=false;
-        FirstFE=false;
-    }    
-    
-    void Disable()
-    {
-        LPC_TIM1->TCR   |=  (1<<1);                     //Reset Timer1
-        LPC_TIM0->IR    |=  (1<<4);                     //Reset Counter0 Interrupt
-        NVIC_DisableIRQ(TIMER0_IRQn);
-    }
-    
-    IMD_Measurement_Output Get_Measurement()
-    {
-        init();
-        wait_ms(300);
-        Disable();
-        if(Result.Frequency >=5 && Result.Frequency <15){
-                strcpy(Result.State, "Normal condition");
-                Result.Encoded_Status='1';
-            }
-        else if(Result.Frequency >=15 && Result.Frequency <25){
-                strcpy(Result.State, "underVoltage condition");
-                Result.Encoded_Status='2';
-            }
-        else if(Result.Frequency >=25 && Result.Frequency <35)
-                {
-                    if(Result.Duty_Cycle <=15){
-                        strcpy(Result.State, "Insulation measurement:good");
-                        Result.Encoded_Status='3';
-                    }
-                    else if(Result.Duty_Cycle > 85 && Result.Duty_Cycle < 100){
-                        strcpy(Result.State, "Insulation measurement:bad");
-                        Result.Encoded_Status='4';
-                    }    
-                }
-        else if(Result.Frequency >=35 && Result.Frequency <45){
-                strcpy(Result.State, "Device error");
-                Result.Encoded_Status='5';
-            }
-        else if(Result.Frequency >=45 && Result.Frequency <55){
-                strcpy(Result.State, "Connection fault earth");    
-                Result.Encoded_Status='6';
-            }                                            
-        return Result; 
-    }
-    
-    #endif/* GET_IMD_H */
\ No newline at end of file
--- a/Get_IMD/IMD.cpp	Tue Oct 21 23:44:15 2014 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,68 +0,0 @@
-#include "IMD.h"
-
-CANBuffer *tx_IMD_Buffer;
-
-IMD::IMD(CANBuffer *can): _p(P1_26) {
-    _p.rise(this, &IMD::rise);
-    _p.fall(this, &IMD::fall);
-    _period = 0.0;
-    _pulsewidth = 0.0;
-    
-    tx_IMD_Buffer = can;
-}
-
-void IMD::rise() {
-    _period = _t.read();
-    _t.reset();
-}
-    
-void IMD::fall() {
-    _pulsewidth = _t.read();
-}
-
-float IMD::frequency() { return 1/_period; }
-float IMD::pulse_width() { return _pulsewidth; }
-float IMD::duty() { return _pulsewidth / _period; }
-
-/*
-    Status      State
-    1           Normal
-    2           under voltage
-    3           Insulation measurement: good
-    4           Insulation measurement: bad
-    5           Device error
-    6           Connection fault earth
-*/
-void update_IMD(void const *arg){
-    IMD *instance = (IMD *)arg;
-    char data[1] = {0};
-    while(1){
-        float freq = instance->frequency();
-        float duty = instance->duty();
-        
-        if(freq >= 5 && freq <15){
-            data[0] = 1;   
-        }else if(freq >= 15 && freq < 25){
-            data[0] = 2;   
-        }else if(freq >= 25 && freq < 35){
-            if(duty <= 15){
-                data[0] = 3;
-            } else if(duty > 85 && duty < 100){
-                data[0] = 4;   
-            }   
-        }else if(freq >= 35 && freq < 45){
-            data[0] = 5;   
-        }else if(freq >= 45 && freq < 55){
-            data[0] = 6;
-        }
-        
-        CANMessage txMessage(TX_IMD_ID, data, 1);
-        tx_IMD_Buffer->txWrite(txMessage);
-        
-        Thread::wait(100);  //10 Hz update    
-    }
-}
-
-void IMD::start_update(){
-    Thread update_thread(update_IMD, this);
-}
--- a/Get_IMD/IMD.h	Tue Oct 21 23:44:15 2014 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,28 +0,0 @@
-// copied idea from http://developer.mbed.org/forum/mbed/topic/466/?page=1#comment-2457
-
-#ifndef _FILE_IMD_H
-#define _FILE_IMD_H  
-
-#include "mbed.h"
-#include "CANBuffer.h"
-#include "rtos.h"
-
-const int TX_IMD_ID = ((0x4 << 8) | 0x20);
-
-class IMD{
-    public:
-        IMD(CANBuffer *can);
-        void start_update();
-        float frequency();
-        float pulse_width();
-        float duty();
-        
-    private:
-        InterruptIn _p;
-        Timer _t;
-        float _pulsewidth, _period;
-        void rise();
-        void fall();      
-};
-
-#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/IMD/IMD.cpp	Fri Oct 24 22:09:04 2014 +0000
@@ -0,0 +1,127 @@
+#include "IMD.h"
+#include <math.h>
+
+static IMD* instance;
+
+const uint32_t PCLK = 24000000;     // Timer counting clock = 24Mhz
+const uint32_t TIMEOUT_TICKS = PCLK*ZERO_HZ_TIMEOUT;    // Zeroing timeout in clock ticks = seconds * PCLK
+const float EXTRA = 0.01;           // Margin on the IMD PWM limits
+const float ULIM = 50000000;        // Max value produced by IMD
+
+// Interrupt function, must be static context
+void TIM0_IRQ() {
+    // Capture event was found
+    if (LPC_TIM0->IR & 1<<4) instance->edgeIRQ();
+    
+    // MR0 (zero Hz timeout) event was found
+    if (LPC_TIM0->IR & 1) instance->zeroIRQ();
+    LPC_TIM0->IR=0x3F;        // Clear interrupt flags
+}
+
+IMD::IMD() {
+    instance = this;
+    first = true;
+    startTime = 0;
+    widthTicks = 0;                 // Zero low, so that duty = 0/1 = 0%
+    periodTicks = 1;
+    
+    LPC_SC->PCONP |= (1<<2);        // Power on timer1
+    LPC_SC->PCLKSEL0 &= ~(3<<4);    // Clock at 24MHz
+    
+    *(p1_26.pinsel_addr) |= 3 << p1_26.selmode_num;     // Set pin as capture pin
+    *(p1_26.pinmode_addr) |= (3 << p1_26.selmode_num);  // Pull down
+    
+    LPC_TIM0->TCR=2;       // Stop counter and hold at 0, for configuration, set to 1 to start operation
+    LPC_TIM0->IR=0x3F;     // Clear any interrupt flags
+    LPC_TIM0->CTCR=0;      // Use pclk, not external pin
+    LPC_TIM0->PR=0;        // No prescale value, clock at full pclk=24Mhz
+    LPC_TIM0->EMR=0;       // Do not use external match pins
+    
+    NVIC_SetVector(TIMER1_IRQn, (uint32_t)&TIM0_IRQ);   // Point to the edge interrupt handler
+    NVIC_SetPrioriry(TIMER1_IRQn, 0);                   // Highest Priority
+    NVIC_EnableIRQ(TIMER1_IRQn);                        // Enable IRQ
+    LPC_TIM0->CCR = RISING;          // Generate interrupt on capture, capture on rising edge to start
+    LPC_TIM0->MCR = 1;               // Interrupt on Match0 to establish the zero speed timeout
+    LPC_TIM0->MR0 = LPC_TIM0->TC+TIMEOUT_TICKS;
+    LPC_TIM0->TCR = 1;               // Start counting, GO!
+}
+
+void IMD::edgeIRQ() {
+    enum EdgeT type = LPC_TIM0->CCR;
+    uint32_t capTime = LPC_TIM0->CR0;
+    LPC_TIM0->MR0 = capTime+TIMEOUT_TICKS;        // Set the next zeroing timeout
+    
+    // Special case - on first pulse after a timeout or on startup, period cannot be calculated
+    //    so set startTime such that periodTicks remains unchanged from its zero state (periodTicks=1)
+    if (first) {
+        first = false;
+        startTime = capTime - 1;   
+    }
+        if (type == RISING) {
+        periodTicks = capTime - startTime;  // Get the period on Rising edge
+        startTime = capTime;                // Set the start of the next pulse
+    }
+    if (type == FALLING) {
+        widthTicks = capTime - startTime;   // Get the pulse width on Falling edge   
+    }
+    
+    // Switch interrupt types to capture the next edge
+    if (type == RISING)  LPC_TIM0->CCR = FALIING;
+    if (type == FALLING) LPC_TIM0->CCR = RISING;
+}
+
+void IMD::zeroIRQ() {
+    enum EdgeT type = LPC_TIM0->CCR;
+    periodTicks = 1;
+    first = true;
+    
+    // Timeout occurred after FALLING edge, now looking for RISING edge
+    if (type == RISING) {
+        widthTicks = 0;     // Signal is low = 0/1 = 0% duty
+    }
+    if (type == FALLING) {
+        widthTicks = 1;     // Signal is high = 1/1 = 100% duty   
+    }
+}
+float IMD::frequency() {
+    // Handle the case where we want to say 0Hz not infinity Hz
+    if (periodTicks == 1 || periodTicks == 0) return 0;
+    else return (float)(PCLK)/(float)(periodTicks);
+}
+float IMD::duty() {
+    return (float)(widthTicks)/(float)(periodTicks);
+}
+
+char IMD::status() {
+    float freq = frequency();
+    if (freq == 0)                      return 0;   // IMD off
+    else if (05 < freq && freq <= 15)   return 1;   // 10Hz normal mode
+    else if (15 < freq && freq <= 25)   return 2;   // 20Hz undervoltage mode
+    else if (25 < freq && freq <= 35)   return 3;   // 30Hz speed start mode
+    else if (45 < freq && freq <= 55)   return 4;   // 40Hz IMD error
+    else if (55 < freq && freq <= 65)   return 5;   // 50Hz Ground error
+    else return -1;                                 // Invalid
+}
+
+float IMD::resistance() {
+    char status = status();
+    float duty = duty();
+    
+    // In normal or undervoltage mode, where Rf is available
+    if (status == 1 || status == 2) {
+        if (0.05-EXTRA <= duty && duty >= 0.95+EXTRA) {
+            float rf = (0.9*1200e3/(duty-0.05)) - 1200e3;
+            if (rf < 0) rf = 0;
+            if (rf > 50e6) rf = 50e6;
+            return rf;
+        }
+        else return -1;
+    }
+    // In speed start, where only good/bad estimate is available
+    if (status == 3) {
+        if (0.05-EXTRA <= duty && duty >= 0.10+EXTRA)       return 50e6;        // Good
+        else if (0.90-EXTRA <= duty && duty >= 0.95+EXTRA)  return 0;           // Bad
+        else return -1;
+    }
+    return NaN;
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/IMD/IMD.h	Fri Oct 24 22:09:04 2014 +0000
@@ -0,0 +1,53 @@
+// copied idea from http://developer.mbed.org/forum/mbed/topic/466/?page=1#comment-2457
+
+#ifndef _FILE_IMD_H
+#define _FILE_IMD_H  
+
+#include "mbed.h"
+#include "LPCDigitalIn.h"
+
+const float ZERO_HZ_TIMEOUT = 0.1;     // Time (sec) that must pass without an edge to call it 0 Hz, set to greater than the longest expected pulse width
+
+enum EdgeT {
+    RISING=5,
+    FALLING=6,
+    BOTH=7,  
+};
+class IMD{
+public:
+    IMD();
+    
+    // Get the IMD status
+    /*
+    Status      State
+    0           IMD off
+    1           Normal
+    2           under voltage
+    3           Speed Start
+    4           IMD error
+    5           Ground error
+    */
+    char status();
+    
+    // Gets the insulation resistance reading
+    // Returns 0 to 50,000,000 in normal/UV modes
+    // Returns 0 or 50,000,000 in speed start (good/bad only)
+    // -1 for invalid measurement (out of permissible range)
+    // and NaN for not applicable mode
+    float resistance();
+    
+    // Interrupt function for the edge type detected
+    void edgeIRQ();
+    // Used to zero (reset) the data on timeout
+    void zeroIRQ();
+    
+private:
+    float frequency();
+    float duty();
+    uint32_t startTime;
+    uint32_t widthTicks;
+    uint32_t periodTicks;
+    bool first;
+};
+
+#endif
\ No newline at end of file
--- a/LPCDigitalIn.lib	Tue Oct 21 23:44:15 2014 +0000
+++ b/LPCDigitalIn.lib	Fri Oct 24 22:09:04 2014 +0000
@@ -1,1 +1,1 @@
-https://mbed.org/teams/Penn-Electric-Racing/code/LPCDigitalIn/#fbd18a1431cf
+https://mbed.org/teams/Penn-Electric-Racing/code/LPCDigitalIn/#963ce3b85931
--- a/RTCStore/Store_RTC.h	Tue Oct 21 23:44:15 2014 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,51 +0,0 @@
-/*  Test Code
-    #include "Battery_Status.h"
-    #include"mbed.h"   
-    BatteryStatus battery;
-    
-    int main()
-    {
-        //battery.write(6.92,0);
-        printf("LPC_RTC->GPREG0:%f\n\r",battery.read(0));
-        //battery.write(7.92,1);
-        printf("LPC_RTC->GPREG1:%f\n\r",battery.read(1));
-        //battery.write(8.92,2);
-        printf("LPC_RTC->GPREG2:%f\n\r",battery.read(2));
-        //battery.write(9.92,3);
-        printf("LPC_RTC->GPREG3:%f\n\r",battery.read(3));
-        //battery.write(10.92,4);
-        printf("LPC_RTC->GPREG4:%f\n\r",battery.read(4));
-    }
-*/        
-
-#ifndef _BATTERY_STATUS_
-#define _BATTERY_STATUS_
-#include"mbed.h"
-
-// General purpose register 0
-#define _GPREG_BASE 0x40024044
-
-// RTC = Real-Time Clock
-
-class RTCStore
-{
-    public:
-      RTCStore()
-      {
-          LPC_SC->PCONP |= (1<<9);        //Enable RTC Peripheral
-      }
-      
-      void write(float data, int block)
-      {
-         *(uint32_t*)(_GPREG_BASE + (0x04*block)) = *((uint32_t*)&data);
-         //LPC_RTC->GPREG0 = *((uint32_t*)&data);
-      }
-      
-      float read(int block)
-      {
-          return *((float*)(uint32_t*)(_GPREG_BASE + (0x04*block)));
-          //return *((float*)&(LPC_RTC->GPREG0));
-      }              
-};
-#endif /* _BATTERY_STATUS_ */
-    
\ No newline at end of file
--- a/SysManagement_kiran_full.lib	Tue Oct 21 23:44:15 2014 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,1 +0,0 @@
-http://developer.mbed.org/users/martydd3/code/SystemManagement/#e02eb179aed3
--- a/SysMngmt.cpp	Tue Oct 21 23:44:15 2014 +0000
+++ b/SysMngmt.cpp	Fri Oct 24 22:09:04 2014 +0000
@@ -4,7 +4,6 @@
     Revised Oct 19, 2014: First team repository version
 */
 
-#include "Store_RTC.h"
 #include "XBee_Lib.h"
 #include "CANBuffer.h"
 
--- a/Watchdog.lib	Tue Oct 21 23:44:15 2014 +0000
+++ b/Watchdog.lib	Fri Oct 24 22:09:04 2014 +0000
@@ -1,1 +1,1 @@
-http://developer.mbed.org/teams/Penn-Electric-Racing/code/Watchdog/#390a291e8c4b
+http://developer.mbed.org/teams/Penn-Electric-Racing/code/Watchdog/#cb296650f43e
--- a/mbed-rtos.lib	Tue Oct 21 23:44:15 2014 +0000
+++ b/mbed-rtos.lib	Fri Oct 24 22:09:04 2014 +0000
@@ -1,1 +1,1 @@
-http://developer.mbed.org/users/mbed_official/code/mbed-rtos/#631c0f1008c3
+http://developer.mbed.org/users/mbed_official/code/mbed-rtos/#aaa1b2c7c64c
--- a/mbed.bld	Tue Oct 21 23:44:15 2014 +0000
+++ b/mbed.bld	Fri Oct 24 22:09:04 2014 +0000
@@ -1,1 +1,1 @@
-http://mbed.org/users/mbed_official/code/mbed/builds/0b3ab51c8877
\ No newline at end of file
+http://mbed.org/users/mbed_official/code/mbed/builds/552587b429a1
\ No newline at end of file