This thread has been locked.
If you have a related question, please click the "Ask a related question" button in the top right corner. The newly created question will be automatically linked to this question.
/* ============================================================================== System Name: HVPM_Sensored File Name: HVPM_Sensored.C Description: Primary system file for the Real Implementation of Sensored Field Orientation Control for Three Phase Permanent-Magnet Synchronous Motor (PMSM) ================================================================================= */ // Include header files used in the main function #include "PeripheralHeaderIncludes.h" #define MATH_TYPE IQ_MATH #include "IQmathLib.h" #include "HVPM_Sensored.h" #include "HVPM_Sensored-Settings.h" #include "SCI_Settings.h" // SCI initial settings file #include <math.h> //#include "angle_math.h" // include header for angle math group of objects // Sonradan ekleme #include "esmopos.h" // include header for esmo and related objects #include "smopos.h" // Include header for the SMOPOS object #include "smopos_const.h" // Include header for the SMOPOS object #include "volt_calc.h" /// #ifdef FLASH #pragma CODE_SECTION(MainISR,"ramfuncs"); #pragma CODE_SECTION(OffsetISR,"ramfuncs"); #pragma CODE_SECTION(QepIEL,"ramfuncs"); // interrupt for Ivent latch on rising edge mode #pragma CODE_SECTION(sciaRxFifoIs,"ramfuncs"); #endif // Prototype statements for functions found within this file. interrupt void MainISR(void); interrupt void OffsetISR(void); interrupt void sciaRxFifoIs(void); interrupt void QepIEL(void); // interrupt for Ivent latch on rising edge mode void DeviceInit(); void MemCopy(); void InitFlash(); void HVDMC_Protection(void); Uint16 CRC16Hesapla(int *p_mes, Uint32 len); #define RS422_PROTOCOL 2 //2.PROTOCOL #define PROTOCOL RS422_PROTOCOL//I2C_PROTOCOL // //PROTOCOL_SECIMI #define CPU_FREQ 60E6 //CPU_CLOCK_FREQUENCY #define LSPCLK_FREQ CPU_FREQ/4 // #define BAUDRATE 115200 #define SCI_PRD (LSPCLK_FREQ/(BAUDRATE*8))-1 //SCI_MODUL_BAUD_RATE_VALUE // State Machine function prototypes //------------------------------------ // Alpha states void A0(void); //state A0 void B0(void); //state B0 void C0(void); //state C0 // A branch states void A1(void); //state A1 void A2(void); //state A2 void A3(void); //state A3 // B branch states void B1(void); //state B1 void B2(void); //state B2 void B3(void); //state B3 // C branch states void C1(void); //state C1 void C2(void); //state C2 void C3(void); //state C3 // Variable declarations void (*Alpha_State_Ptr)(void); // Base States pointer void (*A_Task_Ptr)(void); // State pointer A branch void (*B_Task_Ptr)(void); // State pointer B branch void (*C_Task_Ptr)(void); // State pointer C branch // Used for running BackGround in flash, and ISR in RAM extern Uint16 *RamfuncsLoadStart, *RamfuncsLoadEnd, *RamfuncsRunStart; int16 VTimer0[4]; // Virtual Timers slaved off CPU Timer 0 (A events) int16 VTimer1[4]; // Virtual Timers slaved off CPU Timer 1 (B events) int16 VTimer2[4]; // Virtual Timers slaved off CPU Timer 2 (C events) int16 SerialCommsTimer; // Global variables used in this system Uint16 OffsetFlag = 0; _iq offsetA = 0; _iq offsetB = 0; _iq offsetC = 0; _iq offsetDC_bara = 0; // Sonradan girilen deger int16 calibrated_value = 200; float DC_bara_current = 0; // 8 bitlik akým deðeri karþýlýð to EKU float initialCurrentLimit = 0.60; float DC_bara_current_real = 0; // DC bara gerçek deðer (miliamper) float Vts_temp = 0; // Vts temperature int16 Vts_temp_16 = 0; _iq K1 = _IQ(0.998); //Offset filter coefficient K1: 0.05/(T+0.05); _iq K2 = _IQ(0.001999); //Offset filter coefficient K2: T/(T+0.05); extern _iq IQsinTable[]; extern _iq IQcosTable[]; _iq VdTesting = _IQ(0.0); // Vd reference (pu) _iq VqTesting = _IQ(0.153604); //0.3824580 // Vq reference (pu) _iq IdRef = _IQ(0.0); // Id reference (pu) _iq IqRef = _IQ(0.1509);//_IQ(0.1807); _iq thetaAngle = 0; #if (BUILDLEVEL<LEVEL3) // Speed reference (pu) _iq SpeedRef = _IQ(0.060593); // For Open Loop tests #else _iq SpeedRef = _IQ(0.04); // For Closed Loop tests 670RPM #endif float32 T = 0.001 / ISR_FREQUENCY; // Samping period (sec), see parameter.h Uint32 IsrTicker = 0; Uint16 BackTicker = 0; Uint16 lsw = 0; Uint16 TripFlagDMC = 0; //Trip status Uint16 Init_IFlag = 0; Uint16 sayac_cal_flag = 0; // Default ADC initialization int ChSel[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; int TrigSel[16] = { 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5 }; int ACQPS[16] = { 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8 }; int16 DlogCh1 = 0; int16 DlogCh2 = 0; int16 DlogCh3 = 0; int16 DlogCh4 = 0; int16 SpeedRefRPM = 0; int16 Speed_Fark = 0; int16 Max_fark = 10; _iq pi_spd_Umin_alt_limit = _IQ(-0.3); _iq pi_spd_Umin_ust_limit = _IQ(0.008); _iq pi_spd_degisim = _IQ(0.002);//_IQ(0.001); _iq pi_spd_Umin_ilk_deger = _IQ(0.005); //--------------Sonradan girilen degerler---------------- int vektor_sayac=0; int RS422_int_flag = 0; //YKS'nin_RS422_kesmesine_gittiðini_ifade_eder int High_voltaj = 0; //YKSnin_High_Voltajini_ifade_eder int Pompa_calisiyor = 16; //YKS_motor_ve_pompa_calisiyor int Pompa_duruyor = 8; //YKS_motor_ve_pompa_duruyor int Pompa_geriye_donuyor = 4; //YKS_motor_ve_pompa_geriye_donuyor int Pompa_sikismis = 2; //YKS_motor_ve_pompa_sikismis int Baglanti_yok = 32; //YKS_RS_422_uzerinden_hic_data_alamýyor int Baglanti_yok_sayac = 0; int Baglanti_yok_flag = 0; int Baglanti_hatasi = 64; //YKS_RS_422_uzerinden_dogru_data_alamýyor int Baglanti_hata_sayaci = 0; //YKS_RS_422_Baglanti_hata_sayaci //kac_defa_yanlis_data_geldiginiþ_sayar int Baglanti_hata_flag = 0; //YKS_RS_422_hattinda_baglantinin_yanlis_oldugunu_gosterir int YKS_hiz_emrini_uygula = 1; //YKS_motor_ve_pompa_donsun int YKS_dur_emrini_uygula = 2; //YKS_motor_ve_pompa_dursun int YKS_geri_donerek_dur_emrini_uygula = 4; //YKS_motor_ve_pompa_geri_donsun_ve_dursun int Ref_Speed_RPM_higByte = 0; //YKS_MOTORU_REFERENS_RPM_HIGH_BYTE int Ref_Speed_RPM_lowByte = 0; //YKS_MOTORU_REFERENS_RPM_LOW_BYTE int Commen_type = 0; //EKU_TO_YKS_EMIR_TURLERI int Commen_type_ilk = 0; //EKU_TO_YKS_EMIR_TURLERI_DUMMY int CRC16_HIGH_RX = 0; //CRC16_HIGH_RX_BIT int CRC16_LOW_RX = 0; //CRC16_LOW_RX_BIT int CRC16_HIGH_RX_HESAP = 0; //CRC16_HIGH_RX_HESAP_BIT int CRC16_LOW_RX_HESAP = 0; //CRC16_LOW_RX_HESAP_BIT Uint16 CRC16_HESAP_RX = 0; //RX_CRC_16_HESAP int YKS_RXCHECKSUM = 0; //YKS_MOTORU_RECIVER_CHECKSUM int YKS_HIZ_CHECKSUM = 0; //YKS_MOTORU_ALINAN_DATA_CHECKSUM int RS_422_ADRESS_RX = 0; //RS_422_RECIVER_ADERSS int Speed_RPM_higByte = 5; //YKS_MOTORU_ESTIMATED_RPM_HIGH_BYTE int Speed_RPM_lowByte = 10; //YKS_MOTORU_ESTIMATED_RPM_LOW_BYTE int YKS_VOLTAGE = 15; //YKS_MOTORU_HAT_VOLTAGE int YKS_CURRENT = 20; //YKS_MOTORU_HAT_CURRENT int YKS_STATE = 0; //YKS_STATE_BITI int CRC16_HIGH_TX = 0; //CRC16_HIGH_TX_BIT int CRC16_LOW_TX = 0; //CRC16_HIGH_TX_BIT int CRC16_HIGH_TX_HESAP = 0; //CRC16_HIGH_TX_HESAP_BIT int CRC16_LOW_TX_HESAP = 0; //CRC16_LOW_TX_HESAP_BIT Uint16 CRC16_HESAP_TX = 0; //TX_CRC_16_HESAP Uint32 YKS_CURRENT_TOPLAM = 0; //YKS_20_CYCLE_TOPLAM_DC_BARA_AKIMI int ORTALAMA_AKIM_SAYAC = 0; //YKS_MOTORU_DC_AKIM_SAYACI int YKS_TXCHECKSUM = 50; //YKS_MOTORU_TRANSMITER_CHECKSUM int YKS_Start = 0; //YKS_MOTORU_STARTER int GERI_DONUSLU_SAYAC = 0; //YKS_MOTORU_GERI_DONUSLU_DUR_ZAMAN_SAYACI int SAYAC_BALANGIC = 0; //MOTOR HAREKET SAYKIL SAYACI float YENI_REF_HIZ_FROM_RS422 = 0; //YKS_MOTORU_YENI_REFERANS_HIZ_FROM_RS422 float IDCIDC = 0; float IDC_TOPLAM = 0; float IDC_TOPLAM_ORTALAMA = 0; int N_IDC_TOPLAM = 0; float IDC_KARE_TOPLAM = 0; int N_IDC_KARE_TOPLAM = 0; float IDC_RMS = 0; float VOLTAJ_CARPAN = ( ( BARA_VOLTAGE_RS1 + BARA_VOLTAGE_RS2 ) / BARA_VOLTAGE_RS1 ) * ADC_1Bit_VOLTAGE; //[(340/256) / (330/4096)] = 16.485 12 BITLIK ADC'nin 8 BITLIK //ADC'YE DONUSUMU 8 BITLIK ADC'DE 255=340V 12 BITLIK ADC'DE 4095=330V //VOLTAJ_BOLEN OPTIMIZASYON SONRASI 16.65 OLARAK BELIRLENDI float AKIM_CARPAN = 85.33; //0.02594628 ; //0.25925; //3.69; //[(3000/256) / (13000/4096)] = 3.69 12 BITLIK ADC'nin 8 BITLIK //ADC'YE DONUSUMU 8 BITLIK ADC'DE 256=3000mA 12 BITLIK ADC'DE 4096=13000mA //AKIM_BOLEN OPTIMIZASYON SONRASI ??? OLARAK BELIRLENDI int ilk_start = 1; Uint32 I_DC_SENSOR_TOPLAM = 0; int I_DC_SENSOR_SAYAC = 0; Uint32 I_DC_SENSOR_HESAP = 0; float I_DC_SENSOR = 0; float I_DC_SENSOR_ORT_TOPLAM = 0; int I_DC_SENSOR_ORT_TOPLAM_SAYAC = 0; float I_DC_SENSOR_ORT = 0; float I_DC_SENSOR_ORT_DUZELTME = 0; float Akim = 0; Uint16 Sensor_voltaj = 0; Uint16 deneme = 0; Uint16 deneme2 = 0; Uint16 rotor_lock = 0; int rotor_lock_sayac = 0; /*--------- Current Sensing variables ---------------------------*/ Uint16 sayac_sqr = 0; float DC_Current_Sqr = 0.0; float DC_Current_Sqr_Ort = 0.0; float DC_bara_current_temp = 0.0; float verilenRPM_x0 = 0.0; int olculen = 0.0; float FARK_HIZ = 0; float phase_WU = 0.0; int a = 0; Uint16 motor_ready_flg = 0; Uint16 index_deger = 0; Uint16 index_say = 1; float dc_akim = 0.0; int16 check_qep = 0; int16 check_qep_1 = 0; _iq fark = 0; float fark_1 = 0; int sayac = 0; int sayac_son = 7 * SAYAC_SON; int sayac_c = 0; int sayac_cal_son = 7 * SAYAC_CAL; //------------------------------------------------------- /* CRC calculation macros */ #define CRC_16_INIT_VAL 0xFFFF #define CRC_16(crcval,newchar) crcval = (crcval>> 8) ^ crc_16_table[(crcval ^ newchar) & 0x00ff] static const Uint16 crc_16_table[256] = { 0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf, 0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7, 0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e, 0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876, 0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd, 0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5, 0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c, 0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974, 0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb, 0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3, 0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a, 0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72, 0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9, 0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1, 0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738, 0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70, 0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7, 0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff, 0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036, 0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e, 0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5, 0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd, 0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134, 0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c, 0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3, 0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb, 0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232, 0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a, 0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1, 0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9, 0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330, 0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78 }; volatile Uint16 EnableFlag = TRUE; Uint16 LockRotorFlag = FALSE; Uint16 SpeedLoopPrescaler = 10; // Speed loop prescaler Uint16 SpeedLoopCount = 1; // Speed loop counter // Instance an eSMO position estimator ESMOPOS esmo1 = ESMOPOS_DEFAULTS; // Instance a PI controller for eSMO angle tuning PI_CONTROLLER pi_smo = PI_CONTROLLER_DEFAULTS; // Instance a sliding-mode position observer constant Module SMOPOS_CONST smo1_const = SMOPOS_CONST_DEFAULTS; _iq smoK_set = _IQ(0.35); // sliding mode gain - final value _IQ(0.35); // Instance a phase voltage calculation PHASEVOLTAGE volt1 = PHASEVOLTAGE_DEFAULTS; // Instance a few transform objects CLARKE clarke1 = CLARKE_DEFAULTS; PARK park1 = PARK_DEFAULTS; IPARK ipark1 = IPARK_DEFAULTS; // Instance PI regulators to regulate the d and q axis currents, and speed PI_CONTROLLER pi_spd = PI_CONTROLLER_DEFAULTS; PI_CONTROLLER pi_id = PI_CONTROLLER_DEFAULTS; PI_CONTROLLER pi_iq = PI_CONTROLLER_DEFAULTS; // Instance a PWM driver instance PWMGEN pwm1 = PWMGEN_DEFAULTS; // Instance a PWM DAC driver instance PWMDAC pwmdac1 = PWMDAC_DEFAULTS; // Instance a Space Vector PWM modulator. This modulator generates a, b and c // phases based on the d and q stationery reference frame inputs SVGEN svgen1 = SVGEN_DEFAULTS; // Instance a ramp controller to smoothly ramp the frequency RMPCNTL rc1 = RMPCNTL_DEFAULTS; // Instance a ramp generator to simulate an Anglele RAMPGEN rg1 = RAMPGEN_DEFAULTS; // Instance a speed calculator based on QEP SPEED_MEAS_QEP speed1 = SPEED_MEAS_QEP_DEFAULTS; // Instance a QEP interface driver QEP qep1 = QEP_DEFAULTS; // Instance a SCI receive SCI_COMM sci_rec1 = SCI_DEFAULTS; // Create an instance of DATALOG Module DLOG_4CH dlog = DLOG_4CH_DEFAULTS; void main(void) { DeviceInit(); // Device Life support & GPIO SCI_INIT_MACRO(1, BAUDRATE) //start preferences of the sci module //Only used if running from FLASH //Note that the variable FLASH is defined by the compiler #ifdef FLASH // Copy time critical code and Flash setup code to RAM // The RamfuncsLoadStart, RamfuncsLoadEnd, anfd RamfuncsRunStart // symbols are created by the linker. Refer to the linker files. MemCopy(&RamfuncsLoadStart, &RamfuncsLoadEnd, &RamfuncsRunStart); // Call Flash Initialization to setup flash waitstates // This function must reside in RAM InitFlash(); // Call the flash wrapper init function #endif //(FLASH) // Waiting for enable flag set while( EnableFlag == FALSE ) { BackTicker++; } // Timing sync for background loops // Timer period definitions found in device specific PeripheralHeaderIncludes.h CpuTimer0Regs.PRD.all = mSec0_0666; // A tasks CpuTimer1Regs.PRD.all = mSec6_66; // B tasks CpuTimer2Regs.PRD.all = mSec50; // C tasks // Tasks State-machine init Alpha_State_Ptr = &A0; A_Task_Ptr = &A1; B_Task_Ptr = &B1; C_Task_Ptr = &C1; // Initialize PWM module pwm1.PeriodMax = SYSTEM_FREQUENCY * 1000000 * T / 2; // Prescaler X1 (T1), ISR period = T x 1 pwm1.HalfPerMax = pwm1.PeriodMax / 2; pwm1.Deadband = 2.0 * SYSTEM_FREQUENCY; // 120 counts -> 2.0 usec for TBCLK = SYSCLK/1 PWM_INIT_MACRO(1, 2, 3, pwm1) // Initialize PWMDAC module pwmdac1.PeriodMax = 500; // @60Mhz, 1500->20kHz, 1000-> 30kHz, 500->60kHz pwmdac1.HalfPerMax = pwmdac1.PeriodMax / 2; PWMDAC_INIT_MACRO(6, pwmdac1) // PWM 6A,6B PWMDAC_INIT_MACRO(7, pwmdac1) // PWM 7A,7B // Initialize DATALOG module dlog.iptr1 = &DlogCh1; dlog.iptr2 = &DlogCh2; dlog.iptr3 = &DlogCh3; dlog.iptr4 = &DlogCh4; dlog.trig_value = 0x1; dlog.size = 0x0c8; dlog.prescalar = 5; dlog.init(&dlog); // Initialize ADC for DMC Kit Rev 1.1 ChSel[0] = 0; // Dummy meas. avoid 1st sample issue Rev0 Picollo*/ ChSel[1] = 11; // ChSelect: ADC A1-> Phase A Current ADC_A2 2 ChSel[2] = 10; // ChSelect: ADC B1-> Phase B Current // ADC_A1 1 ChSel[3] = 9; // ChSelect: ADC A3-> Phase C Current ADC_A0 ChSel[4] = 12; // ChSelect: ADC B7-> Phase A Voltage ADC_B5 ChSel[5] = 14; // ChSelect: ADC B6-> Phase B Voltage ADC_B6 ChSel[6] = 15; // ChSelect: ADC B6-> Phase C Voltage ADC_B6 ChSel[7] = 2; // ChSelect: ADC A7-> DC Bus Voltage ADC_A4 4 ChSel[8] = 8; // ChSelect: ADC A7-> DC Bus Current ADC_A3 ChSel[9] = 1; // ChSelect: ADC B0-> Vts SPM temperature ADC_MACRO_INIT(ChSel, TrigSel, ACQPS) // Initialize QEP module qep1.LineEncoder = 1024; //2500; qep1.MechScaler = _IQ30(0.25 / qep1.LineEncoder); qep1.PolePairs = POLES / 2; qep1.CalibratedAngle = 0; //200 // 700//750; // 16785 680 QEP_INIT_MACRO(1, qep1) // Initialize the Speed module for QEP based speed calculation speed1.K1 = _IQ21(1/(BASE_FREQ*T)); speed1.K2 = _IQ(1/(1+T*2*PI*5)); // Low-pass cut-off frequency speed1.K3 = _IQ(1) - speed1.K2; speed1.BaseRpm = 120 * ( BASE_FREQ / POLES ); // Initialize the RAMPGEN module rg1.StepAngleMax = _IQ(BASE_FREQ*T); pi_spd.Kp = _IQ(10.0);//_IQ(1); pi_spd.Ki = _IQ(0.01);//_IQ(0.001218);//_IQ(0.000062286); pi_spd.Umax = _IQ(0.95); pi_spd.Umin = _IQ(-0.95);// Pompaya göre optimize edilmesi gerekebilir. // Initialize the PI module for Id pi_id.Kp = _IQ(1);//_IQ(1.0);//_IQ(0.5);//_IQ(1.05);//_IQ(1.05); //_IQ(1.0);//_IQ(4.0);//_IQ(0.5); pi_id.Ki = _IQ(0.00082);//_IQ(T/0.04);// _IQ(T/0.01);//_IQ(T/0.04); //*RS/LS); ///0.04); pi_id.Umax = _IQ(0.86); //_IQ(0.45); pi_id.Umin = _IQ(-0.86); // _IQ(-0.45); // Initialize the PI module for Iq pi_iq.Kp = _IQ(0.202);//_IQ(0.5);//_IQ(1.1);//_IQ(1.1); //_IQ(1.0); pi_iq.Ki = _IQ(0.0001);//_IQ(T/0.04); //*RS/LS); ///0.04); pi_iq.Umax = _IQ(0.502); //_IQ(0.85); //_IQ(-0.88); pi_iq.Umin = _IQ(-0.502); //_IQ(-0.85); //_IQ(-0.88); // Initialize eSMO parameters esmo1.Fsmopos = _IQ(smo1_const.Fsmopos); esmo1.Gsmopos = _IQ(smo1_const.Gsmopos); esmo1.Kslide = _IQ(0.05308703613); esmo1.base_wTs = _IQ(BASE_FREQ*T); // Initialize the PI module for smo angle filter pi_smo.Kp = _IQ(5.0); pi_smo.Ki = _IQdiv(_IQ(100*0.001/ISR_FREQUENCY), pi_smo.Kp); pi_smo.Umax = _IQ(1.0); pi_smo.Umin = _IQ(-1.0); // Initialize the SMOPOS constant module smo1_const.Rs = RS; smo1_const.Ls = LS; smo1_const.Ib = BASE_CURRENT; smo1_const.Vb = BASE_VOLTAGE; smo1_const.Ts = T; SMO_CONST_MACRO(smo1_const) // Note that the vectorial sum of d-q PI outputs should be less than 1.0 which refers to maximum duty cycle for SVGEN. // Another duty cycle limiting factor is current sense through shunt resistors which depends on hardware/software implementation. // Depending on the application requirements 3,2 or a single shunt resistor can be used for current waveform reconstruction. // The higher number of shunt resistors allow the higher duty cycle operation and better dc bus utilization. // The users should adjust the PI saturation levels carefully during open loop tests (i.e pi_id.Umax, pi_iq.Umax and Umins) as in project manuals. // Violation of this procedure yields distorted current waveforms and unstable closed loop operations which may damage the inverter. //Call HVDMC Protection function HVDMC_Protection(); // RS422_Init(); // Reassign ISRs. EALLOW; // This is needed to write to EALLOW protected registers PieVectTable.SCIRXINTA = &sciaRxFifoIs; PieVectTable.ADCINT1 = &OffsetISR; PieVectTable.EQEP1_INT = &QepIEL; // Enable PIE group 1 interrupt 1 for ADC1_INT PieCtrlRegs.PIEIER1.bit.INTx1 = 1; PieCtrlRegs.PIEIER9.bit.INTx1 = 1; // PIE Group 9, INT1 PieCtrlRegs.PIEIER5.bit.INTx1 = 1; // PIE Group 5, INT1 QEP IEL kesmesi için // Enable EOC interrupt(after the 4th conversion) AdcRegs.ADCINTOVFCLR.bit.ADCINT1 = 1; AdcRegs.ADCINTFLGCLR.bit.ADCINT1 = 1; AdcRegs.INTSEL1N2.bit.INT1CONT = 1; // AdcRegs.INTSEL1N2.bit.INT1SEL = 4; AdcRegs.INTSEL1N2.bit.INT1E = 1; // Enable CPU INT1 for ADC1_INT: IER |= M_INT1; IER |= M_INT9; //SONRADAN // SCI kesmesi için IER |= M_INT5; //SONRADAN // QEP IEL kesmesi için // Enable global Interrupts and higher priority real-time debug events: EINT; // Enable Global interrupt INTM ERTM; // Enable Global realtime interrupt DBGM EDIS; /* setting for Qep with IEL */ EQep1Regs.QCLR.all = 0x0FFF; EQep1Regs.QFRC.all = 0x0000; EQep1Regs.QEINT.all = 0; EQep1Regs.QEINT.bit.IEL = 1; EQep1Regs.QCLR.bit.INT = 0; // adc_offset = AdcResult.ADCRESULT8; // IDLE loop. Just sit and loop forever: for ( ;; ) //infinite loop { // State machine entry & exit point //=========================================================== ( *Alpha_State_Ptr )(); // jump to an Alpha state (A0,B0,...) //=========================================================== } } //END MAIN CODE //================================================================================= // STATE-MACHINE SEQUENCING AND SYNCRONIZATION FOR SLOW BACKGROUND TASKS //================================================================================= //--------------------------------- FRAMEWORK ------------------------------------- void A0(void) { // loop rate synchronizer for A-tasks if ( CpuTimer0Regs.TCR.bit.TIF == 1 ) { CpuTimer0Regs.TCR.bit.TIF = 1; // clear flag //----------------------------------------------------------- ( *A_Task_Ptr )(); // jump to an A Task (A1,A2,A3,...) //----------------------------------------------------------- VTimer0[0]++; // virtual timer 0, instance 0 (spare) SerialCommsTimer++; } Alpha_State_Ptr = &B0; // Comment out to allow only A tasks } void B0(void) { // loop rate synchronizer for B-tasks if ( CpuTimer1Regs.TCR.bit.TIF == 1 ) { CpuTimer1Regs.TCR.bit.TIF = 1; // clear flag //----------------------------------------------------------- ( *B_Task_Ptr )(); // jump to a B Task (B1,B2,B3,...) //----------------------------------------------------------- VTimer1[0]++; // virtual timer 1, instance 0 (spare) } Alpha_State_Ptr = &C0; // Allow C state tasks } void C0(void) { // loop rate synchronizer for C-tasks if ( CpuTimer2Regs.TCR.bit.TIF == 1 ) { CpuTimer2Regs.TCR.bit.TIF = 1; // clear flag //----------------------------------------------------------- ( *C_Task_Ptr )(); // jump to a C Task (C1,C2,C3,...) //----------------------------------------------------------- VTimer2[0]++; //virtual timer 2, instance 0 (spare) } Alpha_State_Ptr = &A0; // Back to State A0 } //================================================================================= // A - TASKS (executed in every 1 msec) //================================================================================= //-------------------------------------------------------- void A1(void) // SPARE (not used) //-------------------------------------------------------- { if ( EPwm1Regs.TZFLG.bit.OST == 0x1 ) TripFlagDMC = 1; // Trip on DMC (halt and IPM fault trip ) //-------------------------------------------------- //------------------- //the next time CpuTimer0 'counter' reaches Period value go to A2 A_Task_Ptr = &A2; //------------------- } //----------------------------------------------------------------- void A2(void) // SPARE (not used) //----------------------------------------------------------------- { //------------------- //the next time CpuTimer0 'counter' reaches Period value go to A3 A_Task_Ptr = &A3; //------------------- } //----------------------------------------- void A3(void) // SPARE (not used) //----------------------------------------- { //----------------- //the next time CpuTimer0 'counter' reaches Period value go to A1 A_Task_Ptr = &A1; //----------------- } //================================================================================= // B - TASKS (executed in every 5 msec) //================================================================================= //----------------------------------- USER ---------------------------------------- //---------------------------------------- void B1(void) // Toggle GPIO-00 //---------------------------------------- { //----------------- SCI_TRANSMIT_MACRO(1, sci_rec1) Vts_temp = 0.04027 * ( AdcResult.ADCRESULT9 ) - 4.9697; // Vts_temp_16 = (int16)Vts_temp; //the next time CpuTimer1 'counter' reaches Period value go to B2 B_Task_Ptr = &B2; //----------------- } //---------------------------------------- void B2(void) // SPARE //---------------------------------------- { /*-----------------------Current Sensing Calculation-----------------------*/ static float A_de = 1; //5.065;//2.01; DC_bara_current_real = ( abs(_IQtoIQ12(offsetDC_bara) - AdcResult.ADCRESULT8) ) * A_de; // Phase DC bara 40.2 DC_Current_Sqr += powf(DC_bara_current_real, 2); sayac_sqr++; if ( sayac_sqr == 100 ) { DC_Current_Sqr_Ort = DC_Current_Sqr / sayac_sqr; DC_bara_current_temp = sqrtf(DC_Current_Sqr_Ort); DC_bara_current = DC_bara_current_temp * 0.001671; // (3.3V/4096)/(opamp kazanc*akim bara direnc) sayac_sqr = 1; DC_Current_Sqr = DC_bara_current_temp; } /*---------------------------------------------------------*/ //----------------- //the next time CpuTimer1 'counter' reaches Period value go to B3 B_Task_Ptr = &B3; //----------------- } //---------------------------------------- void B3(void) // SPARE //---------------------------------------- { //----------------- //the next time CpuTimer1 'counter' reaches Period value go to B1 B_Task_Ptr = &B1; //----------------- } //================================================================================= // C - TASKS (executed in every 50 msec) //================================================================================= //--------------------------------- USER ------------------------------------------ //---------------------------------------- void C1(void) // Toggle GPIO-34 //---------------------------------------- { GpioDataRegs.GPACLEAR.bit.GPIO6 = 1; if ( EPwm1Regs.TZFLG.bit.OST == 0x1 ) // TripZ for PWMs is low (fault trip) { TripFlagDMC = 1; // GpioDataRegs.GPBTOGGLE.bit.GPIO42 = 1; } if ( GpioDataRegs.GPADAT.bit.GPIO9 == 0 ) // Over Current Prot. for Integrated Power Module is high (fault trip) { TripFlagDMC = 1; GpioDataRegs.GPASET.bit.GPIO8 = 1; GpioDataRegs.GPASET.bit.GPIO6 = 1; } GpioDataRegs.GPATOGGLE.bit.GPIO7 = 1; // Turn on/off LD3 on the controlCARD (KDYS Run Led) //----------------- //the next time CpuTimer2 'counter' reaches Period value go to C2 //--------------EKLEME---------------------------------------------// olculen = speed1.SpeedRpm; // ölçülen hýz bilgisi aliniyor Motorun saat yönünde dönmesi istendiði için ifadenin baþýna - koyuldu #if ( PROG_START_COND == PROG_START_COND3 || PROG_START_COND == PROG_START_COND4) verilenRPM_x0 = YENI_REF_HIZ_FROM_RS422; // Eküden gelen hýz bilgisi Ref olarak alýnýyor #endif C_Task_Ptr = &C2; //----------------- } //---------------------------------------- void C2(void) // SPARE //---------------------------------------- { ////////////////////////////////////////////////////////////////////////////////////////////////// // EKU'DEN GELEN REFERANS(HIGH,LOW) HIZ BILGISININ GERCEK HIZA DONUSUMU // YENI_REF_HIZ_FROM_RS422 = ( Ref_Speed_RPM_higByte * 256 ) + Ref_Speed_RPM_lowByte; //YENI_REFERANS_HIZ = RS422_RPM_HIGH * 256 + RS422_RPM_LOW ////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////// // EKU'DEN GELEN DATA CRC16 HESAPLANMASI // CRC16_HESAP_RX = CRC16Hesapla(sci_rec1.sci_receive_data, 4); //YKS_CRC16_HESAP_FONKSIYON_CAGIRMASI CRC16_HIGH_RX_HESAP = ( CRC16_HESAP_RX >> 8 ) & 0x00FF; //YKS_CRC16_HESAPLANAN_HIGH_BYTE CRC16_LOW_RX_HESAP = CRC16_HESAP_RX & 0x00FF; //YKS_CRC16_HESAPLANAN_LOW_BYTE ////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////// // YKS DC BARA AKIMININ HESAPLANMASI // ////////////////////////////// 10.02.2016 YKS DC BARA AKIMI ALGILAMA //////////////////////////// if ( lsw == 0 ) // { // YKS_CURRENT = 0; // } // else // { // // YKS_CURRENT = I_DC_SENSOR_ORT_DUZELTME * AKIM_CARPAN; // (I_DC_SENSOR_ORT - 0.03) * AKIM_CARPAN = (ölçülen deðer - ölçüm hatasý) * GERÇEK AKIMI 8 BÝTE ÇEVÝRME (255/3 = 85)) //08.12.2016 YKS_CURRENT = DC_bara_current * AKIM_CARPAN; //I_DC_SENSOR_ORT * AKIM_CARPAN; // (I_DC_SENSOR_ORT - 0.03) * AKIM_CARPAN = (ölçülen deðer - ölçüm hatasý) * GERÇEK AKIMI 8 BÝTE ÇEVÝRME (255/3 = 85)) //08.12.2016 } // ////////////////////////////// 10.02.2016 YKS DC BARA AKIMI ALGILAMA //////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////// //YKS HIGH VOLTAJ BESLEMESI KONTROLU HIGH VOLTAJ 110DAN KUCUKSE HIGH VOLTAJ YOK.// if ( YKS_VOLTAGE < 80 ) //YKS DC BARA VOLTAJI 110V'DAN KUCUK MU? { // High_voltaj = 0; // } // else if ( YKS_VOLTAGE > 80 ) //YKS DC BARA VOLTAJI 110V'DAN BUYUK MU? { // High_voltaj = 1; // } // ////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////// // YKS MOTORU CALISMAZKEN SISTEMIN O ANKI DURUMUNU GOSTERIYOR // if ( lsw == 0 ) // { // YKS_STATE = Pompa_duruyor + High_voltaj; // } // ////////////////////////////////////////////////////////////////////////////////// if ( rotor_lock == 0 ) { ////////////////////////////////////////////////////////////////////////////////////////////////////////// // ADERS KARSILASTIRMASI YAPILIR, ARESLER DOGRU ISE CRC16 ALGORITMASI ILE GELEN DATALARDA BOZULMA OLUP // // OLMADIGI KONNTROL EDILIYOR. BOZULMA YOK ISE COMMEN_TYPE GORE KONUTLAR ICA EDILIYOR // if ( RS_422_ADRESS_RX == received_address ) // ADRES KARSILASTIRMASI YAPILIOYOR { // if ( ( CRC16_HIGH_RX_HESAP == CRC16_HIGH_RX ) && ( CRC16_LOW_RX_HESAP == CRC16_LOW_RX ) ) // CRC16 ILE DATADA BOZULMA OLUP OLMADIGI KONTROL EDILIYOR { // Baglanti_hata_sayaci = 0; // Baglanti_hata_flag = 0; // if ( Commen_type == YKS_dur_emrini_uygula ) // EKUDEN DUR EMRI GELIRSE UYGULANACAK KOMUT { // lsw = 0; // YKS_Start = 0; // SpeedRef = 0; // YKS_STATE = Pompa_duruyor + High_voltaj; // } // else if ( ( Commen_type == YKS_geri_donerek_dur_emrini_uygula ) && ( GERI_DONUSLU_SAYAC <= 3 ) ) // EKUDEN GERI DONUSLU DUR EMRI GELDIGINDE UYGULANACAK KOMUT { // lsw = 0; // YKS_Start = 0; // SpeedRef = 0; // YKS_STATE = Pompa_duruyor + High_voltaj; // } // else if ( Commen_type == YKS_hiz_emrini_uygula ) // EKUDEN CALIS EMRI GELDIGINDE UYGULANACAK KOMUT { // SpeedRef = _IQ(YENI_REF_HIZ_FROM_RS422 / speed1.BaseRpm); // YKS_STATE = Pompa_calisiyor + High_voltaj; // GERI_DONUSLU_SAYAC = 0; // if ( lsw == 0 ) // { // YKS_Start = 1; // ilk_start = 1; } // if ( YKS_Start == 1 ) // { // lsw = 1; // YKS_Start = 2; // } // } // } // else if ( ( CRC16_HIGH_RX_HESAP != CRC16_HIGH_RX ) || ( CRC16_LOW_RX_HESAP != CRC16_LOW_RX ) ) // EKUDEN KOMUT GELEN KOMUTUN CRC16'SI ILE HESAPLANAN CRC16 ESLESMEDIGI ZAMAN UYGULANACAK KOMUT { // if ( Baglanti_hata_sayaci < 20 ) // { // Baglanti_hata_sayaci = Baglanti_hata_sayaci + 1; // } // // else if ( Baglanti_hata_sayaci == 20 ) // { // Baglanti_hata_flag = 1; // } // } // } // else // EKUDEN GELEN KOMUTUN ADRESI ISTENEN ADRES ILE ESLESMEDIGI ZAMAN UYGULANANCAK KOMUT { // if ( Baglanti_hata_sayaci < 20 ) // { // Baglanti_hata_sayaci = Baglanti_hata_sayaci + 1; // } // else if ( Baglanti_hata_sayaci == 20 ) // { // Baglanti_hata_flag = 1; // } // } // ////////////////////////////////////////////////////////////////////////////////////////////////////////// } else if ( rotor_lock == 1 ) { lsw = 1; // YKS_Start = 0; // SpeedRef = _IQ(YENI_REF_HIZ_FROM_RS422 / speed1.BaseRpm) + _IQ(0.003); // IqRef = _IQ(0.2); //_IQ(0.3); rotor_lock = 0; } else if ( rotor_lock == 2 ) { if ( rotor_lock_sayac <= 15 ) { lsw = 1; // YKS_Start = 0; // SpeedRef = _IQ(-0.3); // IqRef = _IQ(0.2); //_IQ(0.3); rotor_lock = 0; rotor_lock_sayac = rotor_lock_sayac + 1; } else if ( rotor_lock_sayac > 15 ) { lsw = 0; SpeedRef = _IQ(0); IqRef = _IQ(0.2); //_IQ(0.3); rotor_lock = 0; rotor_lock_sayac = 0; } } ////////////////////////////////////////////////////////////////////////////////// // BAGLANTI HATASI VAR ISE YKS_STATE'TI EKUYE GONDERILECEK DURUMLAR // if ( Baglanti_hata_flag == 1 ) // { // if ( olculen > 0 ) // { // YKS_STATE = Baglanti_hatasi + High_voltaj + Pompa_calisiyor; // } // else if ( olculen < 0 ) // { // YKS_STATE = Baglanti_hatasi + High_voltaj + Pompa_geriye_donuyor; // } // else if ( olculen == 0 ) // { // YKS_STATE = Baglanti_hatasi + High_voltaj + Pompa_duruyor; // } // } // ////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////// // RS422'DEN DATA GELMIYOR ISE YKS_STATE'TI EKUYE GONDERILECEK DURUMLAR // if ( RS422_int_flag == 0 ) // { // Baglanti_yok_sayac = Baglanti_yok_sayac + 1; // if ( Baglanti_yok_sayac == 20 ) // { // Baglanti_yok_flag = 1; // Baglanti_yok_sayac = 19; // } // } // else // { // Baglanti_yok_sayac = 0; // RS422_int_flag = 0; // Baglanti_yok_flag = 0; // } // //////////////////////////////////////////////////////////////////////////// if ( Baglanti_yok_flag == 1 ) // { // if ( olculen > 0 ) // { // YKS_STATE = Baglanti_yok + High_voltaj + Pompa_calisiyor; // } // else if ( olculen < 0 ) // { // YKS_STATE = Baglanti_yok + High_voltaj + Pompa_geriye_donuyor; // } // else if ( olculen == 0 ) // { // YKS_STATE = Baglanti_yok + High_voltaj + Pompa_duruyor; // } // } // ////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////// // GERI DONUSLU DUR EMRI GELDIGINDE YKS'NIN GERI DONMEYE BASLAMASI // if ( ( Commen_type == YKS_geri_donerek_dur_emrini_uygula ) && ( GERI_DONUSLU_SAYAC < 5 ) ) // { // GERI_DONUSLU_SAYAC = GERI_DONUSLU_SAYAC + 1; // } // else if ( ( GERI_DONUSLU_SAYAC >= 5 ) && ( GERI_DONUSLU_SAYAC < 20 ) ) //GERI DONME EYLEMININ YAPILDIGI YER { // SpeedRef = _IQ(-0.3); // lsw = 1; // IqRef = _IQ(0.2); //_IQ(0.4); // YKS_STATE = Pompa_geriye_donuyor + High_voltaj; // GERI_DONUSLU_SAYAC = GERI_DONUSLU_SAYAC + 1; // } // else if ( GERI_DONUSLU_SAYAC == 20 ) //GERI DONME EYLEMININ BITTIGI YER { // GERI_DONUSLU_SAYAC = 0; // Commen_type = YKS_dur_emrini_uygula; // lsw = 0; // YKS_Start = 0; // SpeedRef = 0; // IqRef = _IQ(0.2); //_IQ(0.3); // } // ////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////// if ( ( rotor_lock == 1 ) && ( rotor_lock == 2 ) ) // { // olculen = 0; // YKS_STATE = Pompa_sikismis + High_voltaj; // } // ////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////// // YKS'DEN GIDECEK OLAN HIZ VE VOLTAJ FEEDBACKLERININ HESAPLANMASI // Speed_RPM_higByte = ( olculen >> 8 ) & 0xFF; //ESTIMATED EDILEN RPM HIGH BYTE Speed_RPM_lowByte = olculen & 0xFF; //ESTIMATED EDILEN RPM LOW BYTE YKS_VOLTAGE = ( AdcResult.ADCRESULT7 * VOLTAJ_CARPAN ) / ADC_8Bit_CONV; //YKS_SURUCUSU_BESLEME_VOLTAJI ///////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////// // YKS'DEN EKUYE GIDEN YKS BILGILERI // sci_rec1.sci_trans_data[0] = trasmited_address; //RDS_422_TRANSIVER_ADRES sci_rec1.sci_trans_data[1] = YKS_STATE; //YKS STATE BILGISI sci_rec1.sci_trans_data[2] = Speed_RPM_higByte; //ESTIMATED_SPEED_HIGH_BYTE sci_rec1.sci_trans_data[3] = Speed_RPM_lowByte; //ESTIMATED_SPEED_LOW_BYTE sci_rec1.sci_trans_data[4] = YKS_VOLTAGE; //YKS_MOTOR_VOLTAGE sci_rec1.sci_trans_data[5] = YKS_CURRENT; //YKS_MOTOR_CURRENT ////////////////////////////////////////////////////////// // YKS'DEN GIDEN DATA CRC16 HESAPLANMASI // CRC16_HESAP_TX = CRC16Hesapla(sci_rec1.sci_trans_data, 6); //CRC16 HESAPLAMA FONKSIYONUN CAGRILMASI CRC16_HIGH_TX = ( CRC16_HESAP_TX >> 8 ) & 0x00FF; //HESAPLANAN CRC16 HIGH BYTE CRC16_LOW_TX = CRC16_HESAP_TX & 0x00FF; //HESAPLANAN CRC16 LOW BYTE ////////////////////////////////////////////////////////// sci_rec1.sci_trans_data[6] = CRC16_HIGH_TX; //YKS'DEN EKU'YE GIDEN HESAPLANMIS CRC16 HIGH BYTE sci_rec1.sci_trans_data[7] = CRC16_LOW_TX; //YKS'DEN EKU'YE GIDEN HESAPLANMIS CRC16 LOW BYTE ////////////////////////////////////////////////////////// //RS422_TRANSMIT #if ((PROG_START_COND == PROG_START_COND2) || (PROG_START_COND == PROG_START_COND3)) if ( ( index_deger < index_say ) && ( motor_ready_flg != 0 ) && ( verilenRPM_x0 != 0 ) ) { lsw = 1; } else if ( ( index_deger >= index_say ) && ( motor_ready_flg != 0 ) && ( verilenRPM_x0 != 0 ) ) { lsw = 2; } else if ( verilenRPM_x0 == 0 ) { lsw = 0; index_deger = 0; } #endif #if (PROG_START_COND == PROG_START_COND4) if ( motor_ready_flg != 0 ) { SpeedRef = _IQ(verilenRPM_x0 / speed1.BaseRpm); } if ( motor_ready_flg == 0 ) { SpeedRef = _IQ(verilenRPM_x0 / speed1.BaseRpm); lsw = 1; } #endif SpeedRef = _IQ(verilenRPM_x0 / speed1.BaseRpm); //----------------- //the next time CpuTimer2 'counter' reaches Period value go to C3 C_Task_Ptr = &C3; //----------------- } //----------------------------------------- void C3(void) // SPARE //----------------------------------------- { //----------------- if ( sayac < sayac_son && lsw==2) { sayac++; } // sayac_son süresi hesaplanýyor. //the next time CpuTimer2 'counter' reaches Period value go to C1 /* Speed_Fark = abs(SpeedRefRPM - speed1.SpeedRpm); if ((SpeedRefRPM > speed1.SpeedRpm) && (Speed_Fark > Max_fark)) { pi_spd.Umin = pi_spd.Umin + pi_spd_degisim; } else if ((SpeedRefRPM > speed1.SpeedRpm) && (Speed_Fark < Max_fark)) { pi_spd.Umin = pi_spd.Umin; } else if ((SpeedRefRPM < speed1.SpeedRpm) && (Speed_Fark > Max_fark)) { pi_spd.Umin = pi_spd.Umin - pi_spd_degisim; } else if ((SpeedRefRPM < speed1.SpeedRpm) && (Speed_Fark < Max_fark)) { pi_spd.Umin = pi_spd.Umin; } if (pi_spd.Umin < pi_spd_Umin_alt_limit) { pi_spd.Umin = pi_spd_Umin_alt_limit; } else if (pi_spd.Umin > pi_spd_Umin_ust_limit) { pi_spd.Umin = pi_spd_Umin_ust_limit; } if ((lsw == 0) || ((lsw == 1) && (SpeedRefRPM > 0))) { pi_spd.Umin = pi_spd_Umin_ilk_deger; } */ C_Task_Ptr = &C1; //----------------- } // MainISR interrupt void MainISR(void) { // Verifying the ISR IsrTicker++; // =============================== LEVEL 1 ====================================== // Checks target independent modules, duty cycle waveforms and PWM update // Keep the motors disconnected at this level // ============================================================================== #if (BUILDLEVEL==LEVEL1) // ------------------------------------------------------------------------------ // Connect inputs of the RMP module and call the ramp control macro // ------------------------------------------------------------------------------ rc1.TargetValue = SpeedRef; RC_MACRO(rc1) // ------------------------------------------------------------------------------ // Connect inputs of the RAMP GEN module and call the ramp generator macro // ------------------------------------------------------------------------------ rg1.Freq = rc1.SetpointValue; RG_MACRO(rg1) // ------------------------------------------------------------------------------ // Connect inputs of the INV_PARK module and call the inverse park trans. macro // There are two option for trigonometric functions: // IQ sin/cos look-up table provides 512 discrete sin and cos points in Q30 format // IQsin/cos PU functions interpolate the data in the lookup table yielding higher resolution. // ------------------------------------------------------------------------------ ipark1.Ds = VdTesting; ipark1.Qs = VqTesting; //ipark1.Sine =_IQ30toIQ(IQsinTable[_IQtoIQ9(rg1.Out)]); //ipark1.Cosine=_IQ30toIQ(IQcosTable[_IQtoIQ9(rg1.Out)]); ipark1.Sine=_IQsinPU(rg1.Out); ipark1.Cosine=_IQcosPU(rg1.Out); IPARK_MACRO(ipark1) // ------------------------------------------------------------------------------ // Connect inputs of the SVGEN_DQ module and call the space-vector gen. macro // ------------------------------------------------------------------------------ svgen1.Ualpha = ipark1.Alpha; svgen1.Ubeta = ipark1.Beta; SVGENDQ_MACRO(svgen1) // ------------------------------------------------------------------------------ // Connect inputs of the PWM_DRV module and call the PWM signal generation macro // ------------------------------------------------------------------------------ pwm1.MfuncC1 = svgen1.Ta; pwm1.MfuncC2 = svgen1.Tb; pwm1.MfuncC3 = svgen1.Tc; PWM_MACRO(1,2,3,pwm1)// Calculate the new PWM compare values // ------------------------------------------------------------------------------ // Connect inputs of the PWMDAC module // ------------------------------------------------------------------------------ /* pwmdac1.MfuncC1 = svgen1.Ta; pwmdac1.MfuncC2 = svgen1.Tb; PWMDAC_MACRO(6,pwmdac1) // PWMDAC 6A, 6B pwmdac1.MfuncC1 = svgen1.Tc; pwmdac1.MfuncC2 = svgen1.Tb-svgen1.Tc; PWMDAC_MACRO(7,pwmdac1) */ // ------------------------------------------------------------------------------ // Connect inputs of the DATALOG module // ------------------------------------------------------------------------------ DlogCh1 = (int16)_IQtoIQ15(svgen1.Ta); DlogCh2 = (int16)_IQtoIQ15(svgen1.Tb); DlogCh3 = (int16)_IQtoIQ15(svgen1.Tc); DlogCh4 = (int16)_IQtoIQ15(svgen1.Tb-svgen1.Tc); #endif // (BUILDLEVEL==LEVEL1) // =============================== LEVEL 2 ====================================== // Level 2 verifies the analog-to-digital conversion, offset compensation, // clarke/park transformations (CLARKE/PARK), phase voltage calculations // ============================================================================== #if (BUILDLEVEL==LEVEL2) // ------------------------------------------------------------------------------ // Connect inputs of the RMP module and call the ramp control macro // ------------------------------------------------------------------------------ rc1.TargetValue = SpeedRef; RC_MACRO(rc1) // ------------------------------------------------------------------------------ // Connect inputs of the RAMP GEN module and call the ramp generator macro // ------------------------------------------------------------------------------ rg1.Freq = rc1.SetpointValue; RG_MACRO(rg1) // ------------------------------------------------------------------------------ // Measure phase currents, subtract the offset and normalize from (-0.5,+0.5) to (-1,+1). // Connect inputs of the CLARKE module and call the clarke transformation macro // ------------------------------------------------------------------------------ clarke1.As = _IQmpy2(offsetA - _IQ12toIQ(AdcResult.ADCRESULT1));// Phase A curr. clarke1.Bs = _IQmpy2(offsetB - _IQ12toIQ(AdcResult.ADCRESULT2));// Phase B curr. CLARKE_MACRO(clarke1) // ------------------------------------------------------------------------------ // Connect inputs of the PARK module and call the park trans. macro // ------------------------------------------------------------------------------ park1.Alpha = clarke1.Alpha; park1.Beta = clarke1.Beta; park1.Angle = rg1.Out; park1.Sine = _IQsinPU(park1.Angle); park1.Cosine = _IQcosPU(park1.Angle); PARK_MACRO(park1) // ------------------------------------------------------------------------------ // Connect inputs of the INV_PARK module and call the inverse park trans. macro // ------------------------------------------------------------------------------ ipark1.Ds = VdTesting; ipark1.Qs = VqTesting; ipark1.Sine=park1.Sine; ipark1.Cosine=park1.Cosine; IPARK_MACRO(ipark1) // ------------------------------------------------------------------------------ // Connect inputs of the SVGEN_DQ module and call the space-vector gen. macro // ------------------------------------------------------------------------------ svgen1.Ualpha = ipark1.Alpha; svgen1.Ubeta = ipark1.Beta; SVGENDQ_MACRO(svgen1) // ------------------------------------------------------------------------------ // Connect inputs of the PWM_DRV module and call the PWM signal generation macro // ------------------------------------------------------------------------------ pwm1.MfuncC1 = svgen1.Ta; pwm1.MfuncC2 = svgen1.Tb; pwm1.MfuncC3 = svgen1.Tc; PWM_MACRO(1,2,3,pwm1)// Calculate the new PWM compare values // ------------------------------------------------------------------------------ // Connect inputs of the DATALOG module // ------------------------------------------------------------------------------ DlogCh1 = (int16)_IQtoIQ15(svgen1.Ta); DlogCh2 = (int16)_IQtoIQ15(rg1.Out); DlogCh3 = (int16)_IQtoIQ15(clarke1.Bs); DlogCh4 = (int16)_IQtoIQ15(clarke1.As); #endif // (BUILDLEVEL==LEVEL2) // =============================== LEVEL 3 ====================================== // Level 3 verifies the dq-axis current regulation performed by PID and speed // measurement modules. // ============================================================================== // lsw=0: lock the rotor of the motor, // lsw=1: close the current loop, #if (BUILDLEVEL==LEVEL3) // ------------------------------------------------------------------------------ // Connect inputs of the RMP module and call the ramp control macro // ------------------------------------------------------------------------------ if ( lsw == 0 ) rc1.TargetValue = 0; else rc1.TargetValue = _IQ(verilenRPM_x0 / speed1.BaseRpm); //SpeedRef; RC_MACRO(rc1) // ------------------------------------------------------------------------------ // Connect inputs of the RAMP GEN module and call the ramp generator macro // ------------------------------------------------------------------------------ rg1.Freq = rc1.SetpointValue; RG_MACRO(rg1) // ------------------------------------------------------------------------------ // Measure phase currents, subtract the offset and normalize from (-0.5,+0.5) to (-1,+1). // Connect inputs of the CLARKE module and call the clarke transformation macro // ------------------------------------------------------------------------------ clarke1.As = _IQmpy2(offsetA - _IQ12toIQ(AdcResult.ADCRESULT1)); // Phase A curr. clarke1.Bs = _IQmpy2(offsetB - _IQ12toIQ(AdcResult.ADCRESULT2)); // Phase B curr. CLARKE_MACRO(clarke1) // ------------------------------------------------------------------------------ // Connect inputs of the PARK module and call the park trans. macro // ------------------------------------------------------------------------------ park1.Alpha = clarke1.Alpha; park1.Beta = clarke1.Beta; if ( lsw == 0 ) park1.Angle = 0; else if ( lsw == 1 ) park1.Angle = rg1.Out; park1.Sine = _IQsinPU(park1.Angle); park1.Cosine = _IQcosPU(park1.Angle); PARK_MACRO(park1) // ------------------------------------------------------------------------------ // Connect inputs of the PI module and call the PID IQ controller macro // ------------------------------------------------------------------------------ if ( lsw == 0 ) pi_iq.Ref = 0; else pi_iq.Ref = IqRef; pi_iq.Fbk = park1.Qs; PI_MACRO(pi_iq) // ------------------------------------------------------------------------------ // Connect inputs of the PI module and call the PID ID controller macro // ------------------------------------------------------------------------------ if ( lsw == 0 ) pi_id.Ref = _IQ(0.05); // Lock the rotor else pi_id.Ref = IdRef; pi_id.Fbk = park1.Ds; PI_MACRO(pi_id) // ------------------------------------------------------------------------------ // Connect inputs of the INV_PARK module and call the inverse park trans. macro // ------------------------------------------------------------------------------ ipark1.Ds = pi_id.Out; ipark1.Qs = pi_iq.Out; ipark1.Sine = park1.Sine; ipark1.Cosine = park1.Cosine; IPARK_MACRO(ipark1) // ------------------------------------------------------------------------------ // Detect calibration angle and call the QEP module // ------------------------------------------------------------------------------ if (lsw==0) {EQep1Regs.QCLR.bit.IEL = 1;} // Reset position cnt.EQep1Regs.QPOSCNT=0; if ((EQep1Regs.QFLG.bit.IEL==1) && Init_IFlag==0) // Check the index occurrence {qep1.CalibratedAngle= EQep1Regs.QPOSILAT; Init_IFlag++;} // Keep the latched pos. at the first index*/ if (lsw!=0) QEP_MACRO(1,qep1); fark =_IQabs( (qep1.ElecTheta) - (rg1.Out)); fark_1 = _IQtoF(fark); // ------------------------------------------------------------------------------ // Connect inputs of the SPEED_FR module and call the speed calculation macro // ------------------------------------------------------------------------------ speed1.ElecTheta = _IQ24toIQ((int32 )qep1.ElecTheta); speed1.DirectionQep = (int32) ( qep1.DirectionQep ); SPEED_FR_MACRO(speed1) // ------------------------------------------------------------------------------ // Connect inputs of the SVGEN_DQ module and call the space-vector gen. macro // ------------------------------------------------------------------------------ if ( lsw == 0 ) { svgen1.Ualpha = 0; svgen1.Ubeta = 0; } else { svgen1.Ualpha = ipark1.Alpha; svgen1.Ubeta = ipark1.Beta; } SVGENDQ_MACRO(svgen1) // ------------------------------------------------------------------------------ // Connect inputs of the PWM_DRV module and call the PWM signal generation macro // ------------------------------------------------------------------------------ pwm1.MfuncC1 = svgen1.Ta; pwm1.MfuncC2 = svgen1.Tb; pwm1.MfuncC3 = svgen1.Tc; PWM_MACRO(1, 2, 3, pwm1) // Calculate the new PWM compare values // ------------------------------------------------------------------------------ // Connect inputs of the PWMDAC module // ------------------------------------------------------------------------------ pwmdac1.MfuncC1 = clarke1.As; pwmdac1.MfuncC2 = clarke1.Bs; PWMDAC_MACRO(6, pwmdac1) // PWMDAC 6A, 6B pwmdac1.MfuncC1 = rg1.Out; pwmdac1.MfuncC2 = speed1.ElecTheta; PWMDAC_MACRO(7, pwmdac1) // PWMDAC 7A, 7B // ------------------------------------------------------------------------------ // Connect inputs of the DATALOG module // ------------------------------------------------------------------------------ DlogCh1 = (int16) _IQtoIQ15(qep1.ElecTheta); DlogCh2 = (int16) _IQtoIQ15(rg1.Out); DlogCh3 = (int16) _IQtoIQ15(clarke1.As); DlogCh4 = (int16) _IQtoIQ15(clarke1.Bs); #endif // (BUILDLEVEL==LEVEL3) // =============================== LEVEL 4 ====================================== // Level 4 verifies the speed regulator performed by PI module. // The system speed loop is closed by using the measured speed as a feedback. // ============================================================================== // lsw=0: lock the rotor of the motor, // lsw=1: close the current loop, // lsw=2: close the speed loop (sensored FOC). #if (BUILDLEVEL==LEVEL4_CAL) //---------------------------------------------------------// // ------------------------------------------------------------------------------ // Connect inputs of the RMP module and call the ramp control macro // ------------------------------------------------------------------------------ if ( lsw == 0 ) rc1.TargetValue = 0; else rc1.TargetValue = SpeedRef; RC_MACRO(rc1) SpeedRefRPM = _IQmpy(speed1.BaseRpm, SpeedRef); /*Initial rotor alginment edition*/ /* if ( DC_bara_current > initialCurrentLimit ) { vektor_sayac=1; }*/ /* Motor fazi hizalamasi icin lsw=2 ve vektor sayac=0 durumunda hizalama algoritmasinin * calismasi icin baslangic hizi verilip FOC algoritmasi Id=pi.spd.Out ve Iq=0 durumu * algoritmada donduruluyor. * */ if ( vektor_sayac == 0 ) { verilenRPM_x0 = 500; lsw=2; } /* Motor fazi hizalamasi tamamlamasi icin 2sn süre bekleniyor. Sonra enceoder position counter * degeri 0 a cekilip encoder resetleniyor * */ if ( sayac >= sayac_son && vektor_sayac == 0 ) // ilk elektrik verilmesinden 2sn gectikten sonra { lsw = 0; verilenRPM_x0 = 0; EQep1Regs.QPOSCNT = 0; EQep1Regs.QCLR.bit.IEL = 1; speed1.ElecTheta = 0; qep1.ElecTheta = 0; vektor_sayac = 1; } /* Encoder calibrasyon islemi tamamlandiktan ve motor lsw=0 konumuna getirilip durdurulduktan sonra * motoru once lsw=1 konumundan baslatip encoder index degerinden gectikten sonra * lsw=2 konumunda motorun calistirilmasina devam etmek icin * */ if ( vektor_sayac == 1 && verilenRPM_x0 != 0 ) { lsw = 1; vektor_sayac = 2; Init_IFlag = 1; // Diger durumlar; calibration degerinin posilattan encoder angle degerine atanmasi ve lsw=2 durumuna // gecilmesi gibi, onlar qep index alt kesme fonksiyonunda yapilmistir. } // ------------------------------------------------------------------------------ // Connect inputs of the RAMP GEN module and call the ramp generator macro // ------------------------------------------------------------------------------ rg1.Freq = rc1.SetpointValue; RG_MACRO(rg1) // ------------------------------------------------------------------------------ // Measure phase currents, subtract the offset and normalize from (-0.5,+0.5) to (-1,+1). // Connect inputs of the CLARKE module and call the clarke transformation macro // ------------------------------------------------------------------------------ clarke1.As = _IQmpy2(offsetA -_IQ12toIQ(AdcResult.ADCRESULT1));// Phase A curr. SPM U Phase clarke1.Bs = _IQmpy2(offsetB - _IQ12toIQ(AdcResult.ADCRESULT2 ));// Phase B curr. SPM V Phase CLARKE_MACRO(clarke1) // clarke1.Cs = -clarke1.As - clarke1.Bs; // ------------------------------------------------------------------------------ // Connect inputs of the PARK module and call the park trans. macro // ------------------------------------------------------------------------------ park1.Alpha = clarke1.Alpha; park1.Beta = clarke1.Beta; if ( lsw == 0 ) park1.Angle = 0; else if ( lsw == 1 ) park1.Angle = rg1.Out; else if ( lsw == 2 && vektor_sayac == 0 ) { park1.Angle = 0; } else park1.Angle = _IQ24toIQ((int32)qep1.ElecTheta);//esmo1.Theta - thetaAngle; //qep1.ElecTheta; park1.Sine = _IQsinPU(park1.Angle); park1.Cosine = _IQcosPU(park1.Angle); PARK_MACRO(park1) // ------------------------------------------------------------------------------ // Connect inputs of the PI module and call the PID speed controller macro // ------------------------------------------------------------------------------ if ( SpeedLoopCount == SpeedLoopPrescaler ) { pi_spd.Ref = rc1.SetpointValue; pi_spd.Fbk = speed1.Speed; PI_MACRO(pi_spd); SpeedLoopCount = 1; } else SpeedLoopCount++; if ( lsw != 2 ) { pi_spd.ui = 0; pi_spd.i1 = 0; } // ------------------------------------------------------------------------------ // Connect inputs of the PI module and call the PID IQ controller macro // ------------------------------------------------------------------------------ if ( lsw == 0 ) pi_iq.Ref = 0; else if ( lsw == 1 ) pi_iq.Ref = IqRef; else if ( lsw == 2 && vektor_sayac == 0 ) { pi_iq.Ref = 0; } else pi_iq.Ref = pi_spd.Out; pi_iq.Fbk = park1.Qs; PI_MACRO(pi_iq) // ------------------------------------------------------------------------------ // Connect inputs of the PI module and call the PID ID controller macro // ------------------------------------------------------------------------------ if ( lsw == 0 ) pi_id.Ref = _IQ(0.05); else if ( lsw == 1 ) pi_id.Ref = IdRef; else if ( lsw == 2 && vektor_sayac == 0 ) { pi_id.Ref = pi_spd.Out;//IqRef;//pi_spd.Out; } else pi_id.Ref = IdRef; pi_id.Fbk = park1.Ds; PI_MACRO(pi_id) // ------------------------------------------------------------------------------ // Connect inputs of the INV_PARK module and call the inverse park trans. macro // ------------------------------------------------------------------------------ if ( lsw == 2 && vektor_sayac == 0 ) { ipark1.Ds = pi_id.Out; ipark1.Qs = pi_iq.Out; /*--Initial rotor angle allignment--*/ ipark1.Angle = 0; ipark1.Sine = _IQsinPU(ipark1.Angle); ipark1.Cosine = _IQcosPU(ipark1.Angle); } else { ipark1.Ds = pi_id.Out; ipark1.Qs = pi_iq.Out; ipark1.Sine = park1.Sine; ipark1.Cosine = park1.Cosine; } IPARK_MACRO(ipark1) // ------------------------------------------------------------------------------ // Detect calibration angle (optional) and call the QEP module // ------------------------------------------------------------------------------ if ( lsw != 0 ) QEP_MACRO(1, qep1) fark = _IQabs((_IQ24toIQ((int32)qep1.ElecTheta)) - ( rg1.Out )); fark_1 = _IQtoF(fark); // ------------------------------------------------------------------------------ // Connect inputs of the SPEED_FR module and call the speed calculation macro // ------------------------------------------------------------------------------ // // Connect inputs of the VOLT_CALC module and call the phase voltage macro // // ------------------------------------------------------------------------------ // volt1.DcBusVolt = _IQ12toIQ(AdcResult.ADCRESULT7); // volt1.MfuncV1 = svgen1.Ta; // volt1.MfuncV2 = svgen1.Tb; // volt1.MfuncV3 = svgen1.Tc; // PHASEVOLT_MACRO(volt1) // // // ------------------------------------------------------------------------------ // // Connect inputs of the eSMO_POS module and call the eSMO module // // ------------------------------------------------------------------------------ // // // Low Kslide responds better to loop transients // // Increase Kslide for better torque response after closing the speed loop // if ((lsw == 2) && (esmo1.Kslide < smoK_set)) // esmo1.Kslide += _IQ(0.00001); // else if (lsw < 2) //////// // esmo1.Kslide = _IQ(0.05308703613); /////// // // esmo1.Ialpha = clarke1.Alpha; // esmo1.Ibeta = clarke1.Beta; // esmo1.Valpha = volt1.Valpha; // esmo1.Vbeta = volt1.Vbeta; // esmo1.runSpeed = speed1.Speed; // esmo1.cmdSpeed = rc1.SetpointValue; // eSMO_MODULE(&esmo1); // // /******************************************************************** // * Supplemental filter to remove jitters from esmo estimated angle // * ******************************************************************/ // esmo1.Theta = angleFilter(&pi_smo, &esmo1); // optional - uncomment to include // ------------------------------------------------------------------------------ // Connect inputs of the SPEED_EST module and call the estimated speed macro // ------------------------------------------------------------------------------ // speed3.EstimatedTheta = esmo1.Theta; speed1.ElecTheta = _IQ24toIQ((int32)qep1.ElecTheta);//esmo1.Theta;//_IQ24toIQ((int32)qep1.ElecTheta); speed1.DirectionQep = (int32)( qep1.DirectionQep ); SPEED_FR_MACRO(speed1) // ------------------------------------------------------------------------------ // Connect inputs of the SVGEN_DQ module and call the space-vector gen. macro // ------------------------------------------------------------------------------ // if ( lsw == 0 ) // { // svgen1.Ualpha = 0; // svgen1.Ubeta = 0; // } // else // { svgen1.Ualpha = ipark1.Alpha; svgen1.Ubeta = ipark1.Beta; // } SVGENDQ_MACRO(svgen1) // ------------------------------------------------------------------------------ // Connect inputs of the PWM_DRV module and call the PWM signal generation macro // ------------------------------------------------------------------------------ pwm1.MfuncC1 = svgen1.Ta; pwm1.MfuncC2 = svgen1.Tb; pwm1.MfuncC3 = svgen1.Tc; PWM_MACRO(1, 2, 3, pwm1) // Calculate the new PWM compare values // ------------------------------------------------------------------------------ // Connect inputs of the PWMDAC module // ------------------------------------------------------------------------------ pwmdac1.MfuncC1 = clarke1.As; pwmdac1.MfuncC2 = clarke1.Bs; PWMDAC_MACRO(6,pwmdac1) // PWMDAC 6A, 6B pwmdac1.MfuncC1 = rg1.Out; pwmdac1.MfuncC2 = speed1.ElecTheta ; PWMDAC_MACRO(7,pwmdac1) // ------------------------------------------------------------------------------ // Connect inputs of the DATALOG module // ------------------------------------------------------------------------------ DlogCh1 = (int16) _IQtoIQ15(fark); //rg1.Out DlogCh2 = (int16) _IQtoIQ15(pi_iq.Fbk); //qep1.ElecTheta DlogCh3 = (int16) _IQtoIQ15(clarke1.As); DlogCh4 = (int16) _IQtoIQ15(clarke1.Bs); #endif #if (BUILDLEVEL==LEVEL4) // ------------------------------------------------------------------------------ // Connect inputs of the RMP module and call the ramp control macro // ------------------------------------------------------------------------------ if(lsw==0)rc1.TargetValue = 0; else rc1.TargetValue = SpeedRef; RC_MACRO(rc1) // ------------------------------------------------------------------------------ // Connect inputs of the RAMP GEN module and call the ramp generator macro // ------------------------------------------------------------------------------ rg1.Freq = rc1.SetpointValue; RG_MACRO(rg1) // ------------------------------------------------------------------------------ // Measure phase currents, subtract the offset and normalize from (-0.5,+0.5) to (-1,+1). // Connect inputs of the CLARKE module and call the clarke transformation macro // ------------------------------------------------------------------------------ clarke1.As = _IQmpy2(offsetA -_IQ12toIQ(AdcResult.ADCRESULT1));// Phase A curr. SPM U Phase clarke1.Bs = _IQmpy2(offsetB - _IQ12toIQ(AdcResult.ADCRESULT2 ));// Phase B curr. SPM V Phase CLARKE_MACRO(clarke1) // ------------------------------------------------------------------------------ // Connect inputs of the PARK module and call the park trans. macro // ------------------------------------------------------------------------------ park1.Alpha = clarke1.Alpha; park1.Beta = clarke1.Beta; if(lsw==0) park1.Angle = 0; else if(lsw==1) park1.Angle = rg1.Out; else park1.Angle = qep1.ElecTheta; park1.Sine = _IQsinPU(park1.Angle); park1.Cosine = _IQcosPU(park1.Angle); PARK_MACRO(park1) // ------------------------------------------------------------------------------ // Connect inputs of the PI module and call the PID speed controller macro // ------------------------------------------------------------------------------ if (SpeedLoopCount==SpeedLoopPrescaler) { pi_spd.Ref = rc1.SetpointValue; pi_spd.Fbk = speed1.Speed; PI_MACRO(pi_spd); SpeedLoopCount=1; } else SpeedLoopCount++; if(lsw!=2) {pi_spd.ui=0; pi_spd.i1=0;} // ------------------------------------------------------------------------------ // Connect inputs of the PI module and call the PID IQ controller macro // ------------------------------------------------------------------------------ if(lsw==0) pi_iq.Ref = 0; else if(lsw==1) pi_iq.Ref = IqRef; else pi_iq.Ref = pi_spd.Out; pi_iq.Fbk = park1.Qs; PI_MACRO(pi_iq) // ------------------------------------------------------------------------------ // Connect inputs of the PI module and call the PID ID controller macro // ------------------------------------------------------------------------------ if(lsw==0) pi_id.Ref = _IQ(0.1); else pi_id.Ref = IdRef; pi_id.Fbk = park1.Ds; PI_MACRO(pi_id) // ------------------------------------------------------------------------------ // Connect inputs of the INV_PARK module and call the inverse park trans. macro // ------------------------------------------------------------------------------ ipark1.Ds = pi_id.Out; ipark1.Qs = pi_iq.Out; ipark1.Sine=park1.Sine; ipark1.Cosine=park1.Cosine; IPARK_MACRO(ipark1) // ------------------------------------------------------------------------------ // Detect calibration angle (optional) and call the QEP module // ------------------------------------------------------------------------------ if (lsw==0) {EQep1Regs.QPOSCNT=0; EQep1Regs.QCLR.bit.IEL = 1;} // Reset position cnt. // if ((EQep1Regs.QFLG.bit.IEL==1) && Init_IFlag==0) // Check the first index occurrence // {qep1.CalibratedAngle= EQep1Regs.QPOSILAT; Init_IFlag++;} // Keep the latched position if (lsw!=0) QEP_MACRO(1,qep1); // ------------------------------------------------------------------------------ // Connect inputs of the SPEED_FR module and call the speed calculation macro // ------------------------------------------------------------------------------ speed1.ElecTheta = _IQ24toIQ((int32)qep1.ElecTheta); speed1.DirectionQep = (int32)(qep1.DirectionQep); SPEED_FR_MACRO(speed1) // ------------------------------------------------------------------------------ // Connect inputs of the SVGEN_DQ module and call the space-vector gen. macro // ------------------------------------------------------------------------------ svgen1.Ualpha = ipark1.Alpha; svgen1.Ubeta = ipark1.Beta; SVGENDQ_MACRO(svgen1) // ------------------------------------------------------------------------------ // Connect inputs of the PWM_DRV module and call the PWM signal generation macro // ------------------------------------------------------------------------------ pwm1.MfuncC1 = svgen1.Ta; pwm1.MfuncC2 = svgen1.Tb; pwm1.MfuncC3 = svgen1.Tc; PWM_MACRO(1,2,3,pwm1) // Calculate the new PWM compare values // ------------------------------------------------------------------------------ // Connect inputs of the PWMDAC module // ------------------------------------------------------------------------------ pwmdac1.MfuncC1 = clarke1.As; pwmdac1.MfuncC2 = clarke1.Bs; PWMDAC_MACRO(6,pwmdac1) // PWMDAC 6A, 6B pwmdac1.MfuncC1 = rg1.Out; pwmdac1.MfuncC2 = speed1.ElecTheta ; PWMDAC_MACRO(7,pwmdac1) // ------------------------------------------------------------------------------ // Connect inputs of the DATALOG module // ------------------------------------------------------------------------------ DlogCh1 = (int16)_IQtoIQ15(qep1.ElecTheta); DlogCh2 = (int16)_IQtoIQ15(rg1.Out); DlogCh3 = (int16)_IQtoIQ15(clarke1.As); DlogCh4 = (int16)_IQtoIQ15(clarke1.Bs); #endif // (BUILDLEVEL==LEVEL4) // ------------------------------------------------------------------------------ // Call the DATALOG update function. // ------------------------------------------------------------------------------ dlog.update(&dlog); // Enable more interrupts from this timer AdcRegs.ADCINTFLG.bit.ADCINT1 = 1; // Acknowledge interrupt to recieve more interrupts from PIE group 3 PieCtrlRegs.PIEACK.all = PIEACK_GROUP1; } // MainISR Ends Here /**********************************************************/ /********************Offset Compensation*******************/ /**********************************************************/ ////*******CRC16 HESAPLAMA *****//////////// Uint16 CRC16Hesapla(int *p_mes, Uint32 len) { Uint16 i; Uint16 crc = CRC_16_INIT_VAL; for ( i = 0; i < len; i++ ) { CRC_16(crc, p_mes[i]); } return crc; } ///////////////////////////////////////////// interrupt void sciaRxFifoIs(void) { SCI_RECEIVE_MACRO(1, sci_rec1) // All data are received RS422_int_flag = 1; SciaRegs.SCIFFRX.bit.RXFFOVRCLR = 1; // Clear Overflow flag SciaRegs.SCIFFRX.bit.RXFFINTCLR = 1; // Clear Interrupt flag ////////////////////////////////////////////////////////////////////////////////////////////////// // EKU'DEN YKS'YE GELEN EMIR VE REFERANS HIZ BILGILERININ ATANMASI // RS_422_ADRESS_RX = sci_rec1.sci_receive_data[0]; //RDS_422_RECIVER_ADRES Commen_type = sci_rec1.sci_receive_data[1]; //YKS_EMIR_BYTE Ref_Speed_RPM_higByte = sci_rec1.sci_receive_data[2]; //YKS_REFERANS_HIZ_HIGH_BYTE Ref_Speed_RPM_lowByte = sci_rec1.sci_receive_data[3]; //YKS_REFERANS_HIZ_LOW_BYTE CRC16_HIGH_RX = sci_rec1.sci_receive_data[4]; //FROM_EKU_CRC16_HIGH_BYTE CRC16_LOW_RX = sci_rec1.sci_receive_data[5]; //FROM_EKU_CRC16_LOW_BYTE ////////////////////////////////////////////////////////////////////////////////////////////////// SciaRegs.SCIFFRX.bit.RXFFOVRCLR = 1; // Clear Overflow flag SciaRegs.SCIFFRX.bit.RXFFINTCLR = 1; // Clear Interrupt flag PieCtrlRegs.PIEACK.all = PIEACK_GROUP9; } interrupt void QepIEL(void) { #if (CAL_BUL == CAL_BUL0) index_deger++; GpioDataRegs.GPATOGGLE.bit.GPIO8 = 1; // toggle the D2(Red led) #if (BUILDLEVEL==LEVEL4 || BUILDLEVEL==LEVEL4_CAL) if ( Init_IFlag == 0 ) { qep1.CalibratedAngle = EQep1Regs.QPOSILAT; // latch to calibrated angle Init_IFlag++; } // if ( Init_IFlag >= 5 ) // { // lsw = 2; // } Init_IFlag++; #endif #endif /* if ((EQep1Regs.QFLG.bit.IEL ==1) && Init_IFlag==0) // Check the index occurrence {qep1.CalibratedAngle= EQep1Regs.QPOSILAT; Init_IFlag++;}*/ EQep1Regs.QCLR.bit.IEL = 1; // IEL flag i temizlendi EQep1Regs.QCLR.all = 0x0FFF; PieCtrlRegs.PIEACK.all = PIEACK_GROUP5; } interrupt void OffsetISR(void) { // Verifying the ISR IsrTicker++; // DC offset measurement for ADC if ( IsrTicker >= 5000 ) { offsetA = _IQmpy(K1, offsetA) + _IQmpy(K2, _IQ12toIQ(AdcResult.ADCRESULT1)); //Phase A offset offsetB = _IQmpy(K1, offsetB) + _IQmpy(K2, _IQ12toIQ(AdcResult.ADCRESULT2)); //Phase B offset offsetC = _IQmpy(K1, offsetC) + _IQmpy(K2, _IQ12toIQ(AdcResult.ADCRESULT3)); //Phase C offset offsetDC_bara = _IQmpy(K1, offsetDC_bara) + _IQmpy(K2, _IQ12toIQ(AdcResult.ADCRESULT8)); //DC Bara offset } if ( IsrTicker > 20000 ) { EALLOW; PieVectTable.ADCINT1 = &MainISR; EDIS; } // Enable more interrupts from this timer AdcRegs.ADCINTFLG.bit.ADCINT1 = 1; // Acknowledge interrupt to recieve more interrupts from PIE group 1 PieCtrlRegs.PIEACK.all = PIEACK_GROUP1; } //*************** End of Offset Comp. ********************// /**********************************************************/ /***************Protection Configuration*******************/ /**********************************************************/ void HVDMC_Protection(void) { // Configure Trip Mechanism for the Motor control software // -Cycle by cycle trip on CPU halt // -One shot IPM trip zone trip // These trips need to be repeated for EPWM1 ,2 & 3 //=========================================================================== //Motor Control Trip Config, EPwm1,2,3 //=========================================================================== /* EALLOW; // CPU Halt Trip EPwm1Regs.TZSEL.bit.CBC6=0x1; EPwm2Regs.TZSEL.bit.CBC6=0x1; EPwm3Regs.TZSEL.bit.CBC6=0x1; EPwm1Regs.TZSEL.bit.OSHT1 = 1; //enable TZ1 for OSHT EPwm2Regs.TZSEL.bit.OSHT1 = 1; //enable TZ1 for OSHT EPwm3Regs.TZSEL.bit.OSHT1 = 1; //enable TZ1 for OSHT // What do we want the OST/CBC events to do? // TZA events can force EPWMxA // TZB events can force EPWMxB EPwm1Regs.TZCTL.bit.TZA = TZ_FORCE_LO; // EPWMxA will go low EPwm1Regs.TZCTL.bit.TZB = TZ_FORCE_LO; // EPWMxB will go low EPwm2Regs.TZCTL.bit.TZA = TZ_FORCE_LO; // EPWMxA will go low EPwm2Regs.TZCTL.bit.TZB = TZ_FORCE_LO; // EPWMxB will go low EPwm3Regs.TZCTL.bit.TZA = TZ_FORCE_LO; // EPWMxA will go low EPwm3Regs.TZCTL.bit.TZB = TZ_FORCE_LO; // EPWMxB will go low EDIS; // Clear any spurious OV trip EPwm1Regs.TZCLR.bit.OST = 1; EPwm2Regs.TZCLR.bit.OST = 1; EPwm3Regs.TZCLR.bit.OST = 1; */ //************************** End of Prot. Conf. ***************************// } //=========================================================================== // No more. //===========================================================================
您好!
我正在使用具有高压 PM 电机的电机控制器。 如上所述 C 语言主代码、我无法控制使用增强型传感 PM 代码的 PM 电机。 在4级、我认为我找到了特定的转子角度、但我只能轻松地控制高达+/-3500rpm 的电机。 电机的 PI 速度最大和最小限制使我能够以最大9000RPM 的速度驱动电机。 当电机超过3500rpm 时无法控制时、我无法修复该问题。
我 还意识到、在3500rpm 时、主叶巴拉的电流开始缓慢增加。 我尝试通过使用 KP 和 KI 重新调整 PI 参数来降低速度、Id 和 Iq。 我不知道我确切地使用了正确的 Kp 和 Ki 参数
我可以驱动电机270DC、2.01 Ω RLL、3.84mH
电机有4个极对、
有用于1024的编码器
如果未正确估算 QEP 索引相对于相位 A 角度零的初始角度偏移(校准角度)、则可能会出现此问题。 尝试在调试窗口中调整校准角的值、以查看它是否有用。 我建议您再次访问失调电压估算代码、以确保其正确。
interrupt void QepIEL(void) { #if (CAL_BUL == CAL_BUL0) index_deger++; GpioDataRegs.GPATOGGLE.bit.GPIO8 = 1; // toggle the D2(Red led) #if (BUILDLEVEL==LEVEL4 || BUILDLEVEL==LEVEL4_CAL) if ( Init_IFlag == 0 ) { qep1.CalibratedAngle = EQep1Regs.QPOSILAT; // latch to calibrated angle Init_IFlag++; } // if ( Init_IFlag >= 5 ) // { // lsw = 2; // }
您好 Ramesh、
我认为查找校准角的代码是正确的、因为我可以在 main.c 中或通过 QEPIEL 中断找到它。 我尝试在电机运行时更改它、并在调试模式下观察它。 我可以看到、只有电机才能达到4500RPM 的更高速度。
在这种情况下、您可能必须重新调整 PI 参数。 有关设置值的更多信息、请查看以下链接。
您好 Ramesh、
我认为您是对的、我可能需要重新调整 PI 参数。 我已经使用 TI 编写的传感 FOC 算法。 我尝试更改一点点 PI 参数、我意识到电机的行为开始改变。
但是、我看到一些有关电机 PI 参数的情况 、我认为这是荒谬的。 当我更改速度和 Iq PI 参数时、可以在稍高一点的速度4200RPM 下达到该值。 尽管电机速度不会改变、 但 pi_speed.out 开始缓慢增加。 在我看来、随着电机 pi_speed.out 上升、Δ İq _out 开始下降到受控电机下。 这是一个令人困惑的问题。
为什么当电机以稳定速度旋转时、pi.speed.out 会上升? 下图、我的 LEVEL4构建代码也是为了改变 PI 速度、基准速度是 chenge 或 speed.FBK。 我确信参考速度是恒定的、我正在跟踪来自编码器输出的速度.FBK、变化很小。
看起来很奇怪、我怀疑校准角度的精度(电零点和 QEP 指数脉冲之间的偏移角度)。 除此之外、很难看到导致这种情况的原因。
您好 Ramesh、
我意识到在 Clarke 宏感应电流中,不会根据4.125的基极电流进行任何计算。 因为我使用20mR 感应电阻器,而运算放大器增益为20,所以1,65/(20x10^-3*20)等于4.125。 该值需要用于何处?
当我通过与 Clarke.As 和 Clarke.B 相乘来在 Clarke 宏中使用此值时、我可以达到更高速的速度、如6kRPM。
嗯、这是一个调节问题。 确保1.0pu 是 ADC 可以从硬件平台读取的最大值。 如果 ADC 的最大输入电压为3.3V 或3.0V、具体取决于您使用的 MCU、您可以使用电平转换 OPAMP 级将 ADC 输入预偏置为1.65V 或1.5V。 然后、ADC 看到值为3.3V 或3.0V 的分流电流是硬件的基极电流。 希望这对您有所帮助
您好 Ramesh、
我发现问题是在经过一些测试后出现在硬件上。 电路板上 ADC 抗混叠滤波器的截止频率不是很高、以满足高速电流感应的要求。 我更改了它的值并增加了截止频率点、因此我可以高速驱动电机。 感谢您的关注。