WANG YUCHAO / Mbed 2 deprecated Motor_DRV8323RH_for_20190

Dependencies:   mbed FastPWM3

Files at this revision

API Documentation at this revision

Comitter:
benkatz
Date:
Sun Jun 04 19:00:22 2017 +0000
Parent:
27:501fee691e0e
Child:
29:0dbc822dd29a
Commit message:
Use external oscillator

Changed in this revision

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/user_config.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
hw_setup.cpp 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-dev.lib Show annotated file Show diff for this revision Revisions of this file
mbed.bld Show diff for this revision Revisions of this file
structs.h Show annotated file Show diff for this revision Revisions of this file
--- a/Calibration/calibration.cpp	Wed May 17 14:53:22 2017 +0000
+++ b/Calibration/calibration.cpp	Sun Jun 04 19:00:22 2017 +0000
@@ -8,12 +8,13 @@
 #include "user_config.h"
 
 void order_phases(PositionSensor *ps, GPIOStruct *gpio, ControllerStruct *controller, PreferenceWriter *prefs){   
+    
     ///Checks phase order, to ensure that positive Q current produces
     ///torque in the positive direction wrt the position sensor.
     printf("\n\r Checking phase ordering\n\r");
     float theta_ref = 0;
     float theta_actual = 0;
-    float v_d = .2;                                                             //Put all volts on the D-Axis
+    float v_d = .25;                                                             //Put all volts on the D-Axis
     float v_q = 0.0;
     float v_u, v_v, v_w = 0;
     float dtc_u, dtc_v, dtc_w = .5;
@@ -78,11 +79,14 @@
     float delta = 2*PI*NPP/(n*n2);                                              // change in angle between samples
     float error_f[n] = {0};                                                     // error vector rotating forwards
     float error_b[n] = {0};                                                     // error vector rotating backwards
+    const int  n_lut = 128;
+    int lut[n_lut]= {0};                                                        // clear any old lookup table before starting.
+    ps->WriteLUT(lut); 
     int raw_f[n] = {0};
     int raw_b[n] = {0};
     float theta_ref = 0;
     float theta_actual = 0;
-    float v_d = .2;                                                             // Put volts on the D-Axis
+    float v_d = .25;                                                             // Put volts on the D-Axis
     float v_q = 0.0;
     float v_u, v_v, v_w = 0;
     float dtc_u, dtc_v, dtc_w = .5;
@@ -200,8 +204,8 @@
             mean += error_filt[i]/n;
             }
         int raw_offset = (raw_f[0] + raw_b[n-1])/2;                             //Insensitive to errors in this direction, so 2 points is plenty
-        const int  n_lut = 128;
-        int lut[n_lut];
+        
+        
         printf("\n\r Encoder non-linearity compensation table\n\r");
         printf(" Sample Number : Lookup Index : Lookup Value : Cogging Current Lookup\n\r\n\r");
         for (int i = 0; i<n_lut; i++){                                          // build lookup table
--- a/Config/current_controller_config.h	Wed May 17 14:53:22 2017 +0000
+++ b/Config/current_controller_config.h	Sun Jun 04 19:00:22 2017 +0000
@@ -6,7 +6,7 @@
 #define K_SCALE 0.0001f            // K_loop/Loop BW (Hz)
 #define KI_D 0.06f                  // 1/samples
 #define KI_Q 0.06f                  // 1/samples
-#define V_BUS 17.0f                 // Volts
+#define V_BUS 22.0f                 // Volts
 
 #define D_INT_LIM V_BUS/(K_D*KI_D)  // Amps*samples
 #define Q_INT_LIM V_BUS/(K_Q*KI_Q)  // Amps*samples
--- a/Config/user_config.h	Wed May 17 14:53:22 2017 +0000
+++ b/Config/user_config.h	Sun Jun 04 19:00:22 2017 +0000
@@ -11,11 +11,14 @@
 #define THETA_MIN               __float_reg[4]                                  // Minimum position setpoint
 #define THETA_MAX               __float_reg[5]                                  // Maximum position setpoint
 
+
 #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 ENCODER_LUT             __int_reg[4]                                    // Encoder offset LUT - 128 elements long
 
+
 extern float __float_reg[];
 extern int __int_reg[];
 
--- a/FOC/foc.cpp	Wed May 17 14:53:22 2017 +0000
+++ b/FOC/foc.cpp	Sun Jun 04 19:00:22 2017 +0000
@@ -58,8 +58,17 @@
     }
 
 void reset_foc(ControllerStruct *controller){
+    TIM1->CCR3 = (PWM_ARR>>1)*(0.5f);
+    TIM1->CCR1 = (PWM_ARR>>1)*(0.5f);
+    TIM1->CCR2 = (PWM_ARR>>1)*(0.5f);
+    controller->i_d_ref = 0;
+    controller->i_q_ref = 0;
+    controller->i_d = 0;
+    controller->i_q = 0;
     controller->q_int = 0;
     controller->d_int = 0;
+    controller->v_q = 0;
+    controller->v_d = 0;
     }
 
 
@@ -82,16 +91,14 @@
        //dq0(controller->theta_elec, controller->i_a, controller->i_b, controller->i_c, &controller->i_d, &controller->i_q);    //dq0 transform on currents
        controller->i_d = 0.6666667f*(c*controller->i_a + (0.86602540378f*s-.5f*c)*controller->i_b + (-0.86602540378f*s-.5f*c)*controller->i_c);   ///Faster DQ0 Transform
        controller->i_q = 0.6666667f*(-s*controller->i_a - (-0.86602540378f*c-.5f*s)*controller->i_b - (0.86602540378f*c-.5f*s)*controller->i_c);
-       ///Cogging compensation lookup, doesn't actually work yet///
-       //int ind = theta * (128.0f/(2.0f*PI));
-       //float cogging_current = controller->cogging[ind];
+
        float cogging_current = 0.05f*s*controller->i_q_ref;
        
        /// PI Controller ///
        float i_d_error = controller->i_d_ref - controller->i_d;
-       float i_q_error = controller->i_q_ref - controller->i_q;// + cogging_current;
+       float i_q_error = controller->i_q_ref - controller->i_q + cogging_current;
        float v_d_ff = 2.0f*(2*controller->i_d_ref*R_PHASE);   //feed-forward voltage
-       float v_q_ff =  controller->dtheta_elec*WB*1.73205081;
+       float v_q_ff =  controller->dtheta_elec*WB*1.73205081f;
        controller->d_int += i_d_error;   
        controller->q_int += i_q_error;
        
@@ -102,6 +109,9 @@
        controller->v_d = K_SCALE*I_BW*i_d_error + K_SCALE*I_BW*controller->d_int;// + v_d_ff;  
        controller->v_q = K_SCALE*I_BW*i_q_error + K_SCALE*I_BW*controller->q_int;// + v_q_ff; 
        
+       //controller->v_q = 4.0f;;
+       //controller->v_d = 0.0f;
+       
        //controller->v_d = v_d_ff;
        //controller->v_q = v_q_ff; 
        
@@ -128,11 +138,11 @@
        controller->theta_elec = theta;                                          //For some reason putting this at the front breaks thins
        
 
-       if(controller->loop_count >400){
+       if(controller->loop_count >40){
            //controller->i_q_ref = -controller->i_q_ref;
           controller->loop_count  = 0;
            
-           //printf("%.1f  %.1f  %.1f  %.1f  %.1f\n\r", controller->i_d, controller->i_q, controller->v_d, controller->v_q, controller->dtheta_mech);
+           //printf("%.2f  %.2f  %.2f\n\r", controller->i_a, controller->i_b, controller->i_c);
            //printf("%f\n\r", controller->theta_elec);
            //pc.printf("%f    %f    %f\n\r", controller->i_a, controller->i_b, controller->i_c);
            //pc.printf("%f    %f\n\r", controller->i_d, controller->i_q);
@@ -142,7 +152,7 @@
     
     
 void torque_control(ControllerStruct *controller){
-    float torque_ref = -controller->kp*(controller->p_des - controller->theta_mech) + controller->t_ff;// + controller->kd*(controller->v_des - GR*controller->dtheta_mech);
+    float torque_ref = controller->kp*(controller->p_des - controller->theta_mech) + controller->t_ff + controller->kd*(controller->v_des - controller->dtheta_mech);
     //float torque_ref = -.1*(controller->p_des - controller->theta_mech);
     controller->i_q_ref = torque_ref/KT_OUT;    
     controller->i_d_ref = 0;
--- a/PositionSensor/PositionSensor.cpp	Wed May 17 14:53:22 2017 +0000
+++ b/PositionSensor/PositionSensor.cpp	Sun Jun 04 19:00:22 2017 +0000
@@ -92,6 +92,8 @@
 
 void PositionSensorAM5147::ZeroPosition(){
     rotations = 0;
+    MechOffset = 0;
+    Sample();
     MechOffset = GetMechPosition();
     }
     
--- a/hw_setup.cpp	Wed May 17 14:53:22 2017 +0000
+++ b/hw_setup.cpp	Sun Jun 04 19:00:22 2017 +0000
@@ -6,7 +6,7 @@
 #include "FastPWM.h"
 
 void Init_PWM(GPIOStruct *gpio){
-    
+
     RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;                        // enable the clock to GPIOC
     RCC->APB1ENR |= 0x00000001;                                 // enable TIM2 clock
     RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;                         // enable TIM1 clock
--- a/main.cpp	Wed May 17 14:53:22 2017 +0000
+++ b/main.cpp	Sun Jun 04 19:00:22 2017 +0000
@@ -10,18 +10,6 @@
 #define SETUP_MODE 4
 #define ENCODER_MODE 5
 
-#define P_MASK
-#define D_MASK
-#define KP_MASK
-#define KD_MASK
-#define TFF_MASK
-
-/*
-const unsigned int BOARDNUM = 0x2;
-//const unsigned int a_id =                            
-const unsigned int cmd_ID = (BOARDNUM<<8) + 0x7;
-*/
-const unsigned int TX_ID = 0x01;
 
 
 float __float_reg[64];                                                          // Floats stored in flash
@@ -78,7 +66,7 @@
  #define KP_MIN 0.0f
  #define KP_MAX 500.0f
  #define KD_MIN 0.0f
- #define KD_MAX 100.0f
+ #define KD_MAX 5.0f
  #define T_MIN -18.0f
  #define T_MAX 18.0f
  
@@ -98,11 +86,12 @@
     int p_int = float_to_uint(p, P_MIN, P_MAX, 16);
     int v_int = float_to_uint(v, V_MIN, V_MAX, 12);
     int i_int = float_to_uint(i, -I_MAX, I_MAX, 12);
-    msg->data[0] = p_int>>8;
-    msg->data[1] = p_int&0xFF;
-    msg->data[2] = v_int>>4;
-    msg->data[3] = ((v_int&0xF)<<4) + (i_int>>8);
-    msg->data[4] = i_int&0xFF;
+    msg->data[0] = CAN_ID;
+    msg->data[1] = p_int>>8;
+    msg->data[2] = p_int&0xFF;
+    msg->data[3] = v_int>>4;
+    msg->data[4] = ((v_int&0xF)<<4) + (i_int>>8);
+    msg->data[5] = i_int&0xFF;
     }
     
 /// CAN Command Packet Structure ///
@@ -122,23 +111,23 @@
 /// 6: [kd[3-0], torque[11-8]]
 /// 7: [torque[7-0]]
 void unpack_cmd(CANMessage msg, ControllerStruct * controller){
-    int p_int = (msg.data[0]<<8)|msg.data[1];
-    int v_int = (msg.data[2]<<4)|(msg.data[3]>>4);
-    int kp_int = ((msg.data[3]&0xF)<<8)|msg.data[4];
-    int kd_int = (msg.data[5]<<4)|(msg.data[6]>>4);
-    int t_int = ((msg.data[6]&0xF)<<8)|msg.data[7];
+        int p_int = (msg.data[0]<<8)|msg.data[1];
+        int v_int = (msg.data[2]<<4)|(msg.data[3]>>4);
+        int kp_int = ((msg.data[3]&0xF)<<8)|msg.data[4];
+        int kd_int = (msg.data[5]<<4)|(msg.data[6]>>4);
+        int t_int = ((msg.data[6]&0xF)<<8)|msg.data[7];
+        
+        controller->p_des = uint_to_float(p_int, P_MIN, P_MAX, 16);
+        controller->v_des = uint_to_float(v_int, V_MIN, V_MAX, 12);
+        controller->kp = uint_to_float(kp_int, KP_MIN, KP_MAX, 12);
+        controller->kd = uint_to_float(kd_int, KD_MIN, KD_MAX, 12);
+        controller->t_ff = uint_to_float(t_int, T_MIN, T_MAX, 12);
     
-    controller->p_des = uint_to_float(p_int, P_MIN, P_MAX, 16);
-    controller->v_des = uint_to_float(v_int, V_MIN, V_MAX, 12);
-    controller->kp = uint_to_float(kp_int, KP_MIN, KP_MAX, 12);
-    controller->kd = uint_to_float(kd_int, KD_MIN, KD_MAX, 12);
-    controller->t_ff = uint_to_float(t_int, T_MIN, T_MAX, 12);
     
-    /*
-    printf("Received   ");
-    printf("%.3f  %.3f  %.3f  %.3f  %.3f   %.3f", controller->p_des, controller->v_des, controller->kp, controller->kd, controller->t_ff, controller->i_q_ref);
-    printf("\n\r");
-    */
+    //printf("Received   ");
+    //printf("%.3f  %.3f  %.3f  %.3f  %.3f   %.3f", controller->p_des, controller->v_des, controller->kp, controller->kd, controller->t_ff, controller->i_q_ref);
+    //printf("\n\r");
+    
     
     }
 
@@ -146,11 +135,27 @@
     //msgAvailable = true;
     //printf("%.3f   %.3f   %.3f\n\r", controller.theta_mech, controller.dtheta_mech, controller.i_q);
     can.read(rxMsg);  
-    if((rxMsg.id == CAN_ID) && (state == MOTOR_MODE)){
-        unpack_cmd(rxMsg, &controller);
-        pack_reply(&txMsg, controller.theta_mech, controller.dtheta_mech, controller.i_q);
-        can.write(txMsg);
-    }
+    
+    if((rxMsg.id == CAN_ID)){
+        controller.timeout = 0;
+        if(((rxMsg.data[0]==0xFF) & (rxMsg.data[1]==0xFF) & (rxMsg.data[2]==0xFF) & (rxMsg.data[3]==0xFF) & (rxMsg.data[4]==0xFF) & (rxMsg.data[5]==0xFF) & (rxMsg.data[6]==0xFF) & (rxMsg.data[7]==0xFC))){
+            state = MOTOR_MODE;
+            state_change = 1;
+            }
+        else if(((rxMsg.data[0]==0xFF) & (rxMsg.data[1]==0xFF) & (rxMsg.data[2]==0xFF) & (rxMsg.data[3]==0xFF) * (rxMsg.data[4]==0xFF) & (rxMsg.data[5]==0xFF) & (rxMsg.data[6]==0xFF) & (rxMsg.data[7]==0xFD))){
+            state = REST_MODE;
+            state_change = 1;
+            GPIOC->ODR &= !(1 << 5); 
+            }
+        else if(((rxMsg.data[0]==0xFF) & (rxMsg.data[1]==0xFF) & (rxMsg.data[2]==0xFF) & (rxMsg.data[3]==0xFF) * (rxMsg.data[4]==0xFF) & (rxMsg.data[5]==0xFF) & (rxMsg.data[6]==0xFF) & (rxMsg.data[7]==0xFE))){
+            spi.ZeroPosition();
+            }
+        else if(state == MOTOR_MODE){
+            unpack_cmd(rxMsg, &controller);
+            pack_reply(&txMsg, controller.theta_mech, controller.dtheta_mech, controller.i_q);
+            can.write(txMsg);
+            }
+        }
     
 }
 
@@ -168,22 +173,25 @@
 
 void enter_setup_state(void){
     printf("\n\r\n\r Configuration Options \n\r\n\n");
-    printf(" %-7s %-25s %-5s %-5s %-5s\n\r\n\r", "prefix", "parameter", "min", "max", "current value");
-    printf(" %-7s %-25s %-5s %-5s %.1f\n\r", "b", "Current Bandwidth (Hz)", "100", "2000", I_BW);
-    printf(" %-7s %-25s %-5s %-5s %-5i\n\r", "i", "CAN ID", "0", "127", CAN_ID);
-    printf(" %-7s %-25s %-5s %-5s %-5i\n\r", "m", "CAN Master ID", "0", "127", CAN_MASTER);
-    printf(" %-7s %-25s %-5s %-5s %.1f\n\r", "l", "Torque Limit (N-m)", "0.0", "18.0", TORQUE_LIMIT);
+    printf(" %-4s %-31s %-5s %-6s %-5s\n\r\n\r", "prefix", "parameter", "min", "max", "current value");
+    printf(" %-4s %-31s %-5s %-6s %.1f\n\r", "b", "Current Bandwidth (Hz)", "100", "2000", I_BW);
+    printf(" %-4s %-31s %-5s %-6s %-5i\n\r", "i", "CAN ID", "0", "127", CAN_ID);
+    printf(" %-4s %-31s %-5s %-6s %-5i\n\r", "m", "CAN Master ID", "0", "127", CAN_MASTER);
+    printf(" %-4s %-31s %-5s %-6s %.1f\n\r", "l", "Torque Limit (N-m)", "0.0", "18.0", TORQUE_LIMIT);
+    printf(" %-4s %-31s %-5s %-6s %d\n\r", "t", "CAN Timeout (cycles)(0 = none)", "0", "100000", CAN_TIMEOUT);
     printf("\n\r To change a value, type 'prefix''value''ENTER'\n\r i.e. 'b1000''ENTER'\n\r\n\r");
     state_change = 0;
     }
     
 void enter_torque_mode(void){
+    gpio.enable->write(1);                                                      // Enable gate drive
+    reset_foc(&controller);                                                     // Tesets integrators, and other control loop parameters
+    wait(.001);
     controller.i_d_ref = 0;
-    controller.i_q_ref = 6;                                                     // Current Setpoints
-    reset_foc(&controller);                                                     // Tesets integrators, and other control loop parameters
-    gpio.enable->write(1);                                                      // Enable gate drive
+    controller.i_q_ref = 0;                                                     // Current Setpoints
     GPIOC->ODR |= (1 << 5);                                                     // Turn on status LED
     state_change = 0;
+    printf("\n\r Entering Motor Mode \n\r");
     }
     
 void calibrate(void){
@@ -238,27 +246,38 @@
             case MOTOR_MODE:                                                   // Run torque control
                 if(state_change){
                     enter_torque_mode();
+                    count = 0;
                     }
+                else{
                 count++;
-                toggle.write(1);
+                //toggle.write(1);
                 controller.theta_elec = spi.GetElecPosition();
-                controller.theta_mech = spi.GetMechPosition();
-                controller.dtheta_mech = spi.GetMechVelocity();  
+                controller.theta_mech = (1.0f/GR)*spi.GetMechPosition();
+                controller.dtheta_mech = (1.0f/GR)*spi.GetMechVelocity();  
                 //TIM1->CCR3 = 0x708*(1.0f);
                 //TIM1->CCR1 = 0x708*(1.0f);
                 //TIM1->CCR2 = 0x708*(1.0f);     
                 
                 //controller.i_q_ref = controller.t_ff/KT_OUT;   
-                torque_control(&controller);      
-                //controller.i_q_ref = 1; 
+                
+                torque_control(&controller);     
+                if((controller.timeout > CAN_TIMEOUT) && (CAN_TIMEOUT > 0)){
+                    controller.i_d_ref = 0;
+                    controller.i_q_ref = 0;
+                    } 
+                //controller.i_q_ref = .5; 
                 commutate(&controller, &gpio, controller.theta_elec);           // Run current loop
                 spi.Sample();                                                   // Sample position sensor
-                toggle.write(0);
+                //toggle.write(0);
+                controller.timeout += 1;
                 
-                if(count > 100){
-                     count = 0;
-                     //printf("%d  %d\n\r", controller.adc1_raw, controller.adc2_raw);
+                if(count == 1){
+                     //count = 0;
+                     wait(.001);
+                    //printf(" Started commutating\n\r");
                      }
+                     }
+                     
                 break;
             case SETUP_MODE:
                 if(state_change){
@@ -327,6 +346,9 @@
                     case 'l':
                         TORQUE_LIMIT = fmaxf(fminf(atof(cmd_val), 18.0f), 0.0f);
                         break;
+                    case 't':
+                        CAN_TIMEOUT = atoi(cmd_val);
+                        break;
                     default:
                         printf("\n\r '%c' Not a valid command prefix\n\r\n\r", cmd_id);
                         break;
@@ -388,8 +410,8 @@
     can.filter(CAN_ID<<21, 0xFFE00004, CANStandard, 0);
     //can.filter(CAN_ID, 0xF, CANStandard, 0);
     can.attach(&onMsgReceived);                                     // attach 'CAN receive-complete' interrupt handler                                                                    
-    txMsg.id = TX_ID;
-    txMsg.len = 5;
+    txMsg.id = CAN_MASTER;
+    txMsg.len = 6;
     rxMsg.len = 8;
     
     prefs.load();                                                               // Read flash
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed-dev.lib	Sun Jun 04 19:00:22 2017 +0000
@@ -0,0 +1,1 @@
+https://mbed.org/users/mbed_official/code/mbed-dev/#986ec039fa06
--- a/mbed.bld	Wed May 17 14:53:22 2017 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,1 +0,0 @@
-https://mbed.org/users/mbed_official/code/mbed/builds/97feb9bacc10
\ No newline at end of file
--- a/structs.h	Wed May 17 14:53:22 2017 +0000
+++ b/structs.h	Sun Jun 04 19:00:22 2017 +0000
@@ -29,6 +29,7 @@
     int adc1_offset, adc2_offset;
     float i_d_ref, i_q_ref;
     int loop_count;
+    int timeout;
     int mode;
     float p_des, v_des, kp, kd, t_ff;
     float cogging[128];