Modified Motor Driver Firmware to include Flash + Thermal

Dependencies:   FastPWM3 mbed-dev-STM-lean

Files at this revision

API Documentation at this revision

Comitter:
benkatz
Date:
Sun Jul 21 21:42:49 2019 +0000
Parent:
51:6cd89bd6fcaa
Commit message:
testing gb-54;

Changed in this revision

CAN/CAN_com.cpp Show annotated file Show diff for this revision Revisions of this file
Calibration/calibration.cpp Show annotated file Show diff for this revision Revisions of this file
Config/current_controller_config.h Show annotated file Show diff for this revision Revisions of this file
Config/motor_config.h Show annotated file Show diff for this revision Revisions of this file
Config/user_config.h Show annotated file Show diff for this revision Revisions of this file
DRV8323/DRV.cpp Show annotated file Show diff for this revision Revisions of this file
DRV8323/DRV.h Show annotated file Show diff for this revision Revisions of this file
FOC/foc.cpp Show annotated file Show diff for this revision Revisions of this file
PositionSensor/PositionSensor.cpp Show annotated file Show diff for this revision Revisions of this file
PositionSensor/PositionSensor.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
--- a/CAN/CAN_com.cpp	Wed Jul 17 03:40:12 2019 +0000
+++ b/CAN/CAN_com.cpp	Sun Jul 21 21:42:49 2019 +0000
@@ -6,9 +6,9 @@
  #define V_MIN -45.0f
  #define V_MAX 45.0f
  #define KP_MIN 0.0f
- #define KP_MAX 500.0f
+ #define KP_MAX 50.0f
  #define KD_MIN 0.0f
- #define KD_MAX 5.0f
+ #define KD_MAX 0.5f
  #define T_MIN -18.0f
  #define T_MAX 18.0f
  
--- a/Calibration/calibration.cpp	Wed Jul 17 03:40:12 2019 +0000
+++ b/Calibration/calibration.cpp	Sun Jul 21 21:42:49 2019 +0000
@@ -59,14 +59,18 @@
         printf("%.4f   %.4f\n\r", theta_ref/(NPP), theta_actual);
         }
         sample_counter++;
-       theta_ref += 0.001f;
+       theta_ref += 0.0005f;
         }
     float theta_end = ps->GetMechPositionFixed();
     int direction = (theta_end - theta_start)>0;
+    float ratio = abs(4.0f*PI/(theta_end-theta_start));
+    int pole_pairs = (int) roundf(ratio);
     printf("Theta Start:   %f    Theta End:  %f\n\r", theta_start, theta_end);
     printf("Direction:  %d\n\r", direction);
     if(direction){printf("Phasing correct\n\r");}
     else if(!direction){printf("Phasing incorrect.  Swapping phases V and W\n\r");}
+    printf("Pole Pairs:  %d\n\r", pole_pairs);
+    NPP = pole_pairs;
     PHASE_ORDER = direction;
     }
     
@@ -143,7 +147,7 @@
             TIM1->CCR1 = (PWM_ARR>>1)*(1.0f-dtc_v);
             TIM1->CCR2 = (PWM_ARR>>1)*(1.0f-dtc_w);
             }
-            wait_us(100);
+            wait_us(200);
             ps->Sample(DT);
         }
        ps->Sample(DT);
@@ -168,7 +172,7 @@
             TIM1->CCR1 = (PWM_ARR>>1)*(1.0f-dtc_v);
             TIM1->CCR2 = (PWM_ARR>>1)*(1.0f-dtc_w);
             }
-            wait_us(100);
+            wait_us(200);
             ps->Sample(DT);
         }
        ps->Sample(DT);                                                            // sample position sensor
--- a/Config/current_controller_config.h	Wed Jul 17 03:40:12 2019 +0000
+++ b/Config/current_controller_config.h	Sun Jul 21 21:42:49 2019 +0000
@@ -4,9 +4,9 @@
 // Current controller///
 #define K_D .05f                    // Loop gain,  Volts/Amp
 #define K_Q .05f                    // Loop gain,  Volts/Amp
-#define K_SCALE 0.0001f             // K_loop/Loop BW (Hz) 0.0042
-#define KI_D 0.0255f                // PI zero, in radians per sample
-#define KI_Q 0.0255f                // PI zero, in radians per sample
+#define K_SCALE 0.0004f             // K_loop/Loop BW (Hz) 0.0042
+#define KI_D 0.031f                // PI zero, in radians per sample
+#define KI_Q 0.031f                // PI zero, in radians per sample
 #define V_BUS 24.0f                 // Volts
 #define OVERMODULATION 1.15f        // 1.0 = no overmodulation
 
--- a/Config/motor_config.h	Wed Jul 17 03:40:12 2019 +0000
+++ b/Config/motor_config.h	Sun Jul 21 21:42:49 2019 +0000
@@ -1,14 +1,13 @@
 #ifndef MOTOR_CONFIG_H
 #define MOTOR_CONFIG_H
 
-#define R_PHASE 0.13f           //Ohms
-#define L_D 0.00002f            //Henries
-#define L_Q 0.00002f            //Henries
-#define KT .08f                 //N-m per peak phase amp, = WB*NPP*3/2
-#define NPP 21                  //Number of pole pairs
+#define R_PHASE 7.5f           //Ohms
+#define L_D 0.006f            //Henries
+#define L_Q 0.006f            //Henries
+#define KT 0.268f                 //N-m per peak phase amp, = WB*NPP*3/2
 #define GR 1.0f                 //Gear ratio
-#define KT_OUT 0.45f            //KT*GR
-#define WB 0.0025f              //Flux linkage, Webers.  
+#define KT_OUT 0.268f            //KT*GR
+#define WB 0.025f              //Flux linkage, Webers.  
 #define R_TH 1.25f              //Kelvin per watt
 #define INV_M_TH 0.03125f       //Kelvin per joule
 
--- a/Config/user_config.h	Wed Jul 17 03:40:12 2019 +0000
+++ b/Config/user_config.h	Sun Jul 21 21:42:49 2019 +0000
@@ -1,4 +1,4 @@
-/// Values stored in flash, which are modifieable by user actions ///
+/// Values stored in flash ///
 
 #ifndef USER_CONFIG_H
 #define USER_CONFIG_H
@@ -13,10 +13,12 @@
 #define I_FW_MAX                __float_reg[6]                                  // Maximum field weakening current
 
 
+
 #define PHASE_ORDER             __int_reg[0]                                    // Phase swapping during calibration
 #define CAN_ID                  __int_reg[1]                                    // CAN bus ID
 #define CAN_MASTER              __int_reg[2]                                    // CAN bus "master" ID
 #define CAN_TIMEOUT             __int_reg[3]                                    // CAN bus timeout period
+#define NPP                     __int_reg[4]                                    // Number of Pole-Pairs
 #define ENCODER_LUT             __int_reg[5]                                    // Encoder offset LUT - 128 elements long
 
 
--- a/DRV8323/DRV.cpp	Wed Jul 17 03:40:12 2019 +0000
+++ b/DRV8323/DRV.cpp	Sun Jul 21 21:42:49 2019 +0000
@@ -73,7 +73,11 @@
     uint16_t val2 = read_FSR2();
     wait_us(10);
     
-    if(val1 & (1<<10)){printf("\n\rFAULT\n\r");}
+    if(val1 & (1<<10))
+        {
+            printf("\n\rFAULT\n\r");
+            fault = 1;
+        }
 
     if(val1 & (1<<9)){printf("VDS_OCP\n\r");}
     if(val1 & (1<<8)){printf("GDF\n\r");}
@@ -104,6 +108,7 @@
     uint16_t val = (read_register(DCR)) & (~(0x1<<2));
     write_register(DCR, val);
     }
+
     
 void DRV832x::disable_gd(void)
 {
@@ -115,4 +120,9 @@
 {
     uint16_t val = 0x1<<4 + 0x1<<3 + 0x1<<2;
     write_register(CSACR, val);
-    }
\ No newline at end of file
+    }
+    
+int DRV832x::get_fault(void)
+{
+    return fault;
+}
--- a/DRV8323/DRV.h	Wed Jul 17 03:40:12 2019 +0000
+++ b/DRV8323/DRV.h	Sun Jul 21 21:42:49 2019 +0000
@@ -164,10 +164,12 @@
         void disable_gd(void);
         void calibrate(void);
         void print_faults();
+        int get_fault();
         
     private:
         SPI *_spi;
         DigitalOut *_cs;
+        int fault;
         uint16_t spi_write(uint16_t val);
 };
 
--- a/FOC/foc.cpp	Wed Jul 17 03:40:12 2019 +0000
+++ b/FOC/foc.cpp	Sun Jul 21 21:42:49 2019 +0000
@@ -65,18 +65,18 @@
 void zero_current(int *offset_1, int *offset_2){                                // Measure zero-offset of the current sensors
     int adc1_offset = 0;
     int adc2_offset = 0;
-    int n = 1024;
+    int n = 2048;
     for (int i = 0; i<n; i++){                                                  // Average n samples of the ADC
         TIM1->CCR3 = (PWM_ARR>>1)*(1.0f);                                               // Write duty cycles
         TIM1->CCR2 = (PWM_ARR>>1)*(1.0f);
         TIM1->CCR1 = (PWM_ARR>>1)*(1.0f);
         ADC1->CR2  |= 0x40000000;                                               // Begin sample and conversion
-        wait(.001);
+        wait(.0001);
         adc2_offset += ADC2->DR;
         adc1_offset += ADC1->DR;
         }
-    *offset_1 = adc1_offset/n;
-    *offset_2 = adc2_offset/n;
+    *offset_1 = (int)((float)adc1_offset/(float)n);
+    *offset_2 = (int)((float)adc2_offset/(float)n);
     }
     
 void init_controller_params(ControllerStruct *controller){
@@ -196,8 +196,8 @@
        limit_norm(&controller->v_d, &controller->v_q, OVERMODULATION*controller->v_bus);       // Normalize voltage vector to lie within curcle of radius v_bus
        float dtc_d = controller->v_d/controller->v_bus;
        float dtc_q = controller->v_q/controller->v_bus;
-       linearize_dtc(&dtc_d);
-       linearize_dtc(&dtc_q);
+       //linearize_dtc(&dtc_d);
+       //linearize_dtc(&dtc_q);
        controller->v_d = dtc_d*controller->v_bus;
        controller->v_q = dtc_q*controller->v_bus;
        abc(controller->theta_elec + 0.0f*DT*controller->dtheta_elec, controller->v_d, controller->v_q, &controller->v_u, &controller->v_v, &controller->v_w); //inverse dq0 transform on voltages
--- a/PositionSensor/PositionSensor.cpp	Wed Jul 17 03:40:12 2019 +0000
+++ b/PositionSensor/PositionSensor.cpp	Sun Jul 21 21:42:49 2019 +0000
@@ -8,7 +8,7 @@
 PositionSensorAM5147::PositionSensorAM5147(int CPR, float offset, int ppairs){
     //_CPR = CPR;
     _CPR = CPR;
-    _ppairs = ppairs;
+    //_ppairs = ppairs;
     ElecOffset = offset;
     rotations = 0;
     spi = new SPI(PC_12, PC_11, PC_10);
@@ -125,7 +125,11 @@
 void PositionSensorAM5147::WriteLUT(int new_lut[128]){
     memcpy(offset_lut, new_lut, sizeof(offset_lut));
     }
-    
+
+void PositionSensorAM5147::SetNPP(int npp)
+{
+    _ppairs = npp;
+} 
 
 
 PositionSensorEncoder::PositionSensorEncoder(int CPR, float offset, int ppairs) {
--- a/PositionSensor/PositionSensor.h	Wed Jul 17 03:40:12 2019 +0000
+++ b/PositionSensor/PositionSensor.h	Sun Jul 21 21:42:49 2019 +0000
@@ -12,7 +12,8 @@
     virtual int GetRawPosition(void) = 0;
     virtual void SetElecOffset(float offset) = 0;
     virtual int GetCPR(void) = 0;
-    virtual  void WriteLUT(int new_lut[128]) = 0;
+    virtual void WriteLUT(int new_lut[128]) = 0;
+    virtual void SetNPP(int npp) = 0;
 };
   
   
@@ -56,6 +57,7 @@
     virtual void SetMechOffset(float offset);
     virtual int GetCPR(void);
     virtual void WriteLUT(int new_lut[128]);
+    virtual void SetNPP(int npp);
 private:
     float position, ElecPosition, ElecOffset, MechPosition, MechOffset, modPosition, oldModPosition, oldVel, velVec[40], MechVelocity, ElecVelocity, ElecVelocityFilt;
     int raw, _CPR, rotations, old_counts, _ppairs;
--- a/main.cpp	Wed Jul 17 03:40:12 2019 +0000
+++ b/main.cpp	Sun Jul 21 21:42:49 2019 +0000
@@ -52,7 +52,7 @@
 //DigitalOut drv_en_gate(PA_11);
 DRV832x drv(&drv_spi, &drv_cs);
 
-PositionSensorAM5147 spi(16384, 0.0, NPP);  
+PositionSensorAM5147 spi(16384, 0.0, 0.0);  
 
 volatile int count = 0;
 volatile int state = REST_MODE;
@@ -221,6 +221,7 @@
                     controller.kd = 0;
                     controller.t_ff = 0;
                     } 
+                
 
                 torque_control(&controller);
                 commutate(&controller, &observer, &gpio, controller.theta_elec);           // Run current loop
@@ -413,8 +414,10 @@
     if(isnan(CAN_ID) || CAN_ID==-1){CAN_ID = 1;}
     if(isnan(CAN_MASTER) || CAN_MASTER==-1){CAN_MASTER = 0;}
     if(isnan(CAN_TIMEOUT) || CAN_TIMEOUT==-1){CAN_TIMEOUT = 0;}
+    if(isnan(NPP) || NPP==-1){NPP = 1;}
     spi.SetElecOffset(E_OFFSET);                                                // Set position sensor offset
     spi.SetMechOffset(M_OFFSET);
+    spi.SetNPP(NPP);
     int lut[128] = {0};
     memcpy(&lut, &ENCODER_LUT, sizeof(lut));
     spi.WriteLUT(lut);                                                          // Set potision sensor nonlinearity lookup table
@@ -430,6 +433,7 @@
     printf(" Position Sensor Electrical Offset:   %.4f\n\r", E_OFFSET);
     printf(" Output Zero Position:  %.4f\n\r", M_OFFSET);
     printf(" CAN ID:  %d\n\r", CAN_ID);
+    printf(" Pole-Pairs:  %d\n\r", NPP);
     
 
 
@@ -448,8 +452,10 @@
 
     int counter = 0;
     while(1) {
+        
         drv.print_faults();
-       wait(.1);
+        //if(drv.get_fault()>0){drv.write_DCR(0x0, 0x0, 0x0, PWM_MODE_3X, 0x0, 0x0, 0x0, 0x0, 0x1);}
+        wait(.1);
        //printf("%.4f\n\r", controller.v_bus);
        /*
         if(state == MOTOR_MODE)