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.

CCS/CCSTUDIO-C2000: How to give filtered signal to PID controller as reference ?

Part Number: CCSTUDIO-C2000

Tool/software: Code Composer Studio

I need to give filtered signal to my pid1 controller as my reference rk. AdcBufFiltered is my filtered signal.i'm using CCSv6.

LPF.c
#include "DSP28x_Project.h"     // Device Headerfile and Examples Include File
#include "DCL.h"               // Digital control library
#include "IQmathLib.h"
// ADC start parameters
#if (CPU_FRQ_150MHZ)     // Default - 150 MHz SYSCLKOUT
  #define ADC_MODCLK 0x3 // HSPCLK = SYSCLKOUT/2*ADC_MODCLK2 = 150/(2*3)   = 25.0 MHz
#endif

#define ADC_CKPS   0x1   // ADC module clock = HSPCLK/2*ADC_CKPS   = 25.0MHz/(1*2) = 12.5MHz
#define ADC_SHCLK  0xf   // S/H width in ADC module periods                        = 16 ADC clocks
#define AVG        50  // Average sample limit
#define ZOFFSET    0x00  // Average Zero offset
#define BUF_SIZE   50  // Sample buffer size


typedef volatile struct {
float Kp; // proportional gain
float Ki; // integral gain
float Kd; // derivative gain
float Kr; // set point weight
float c1; // D filter coefficient 1
float c2; // D filter coefficient 2
float d2; // D filter storage 1
float d3; // D filter storage 2
float i10; // I storage
float i14; // sat storage
float Umax; // upper saturation limit
float Umin; // lower saturation limit
} PID2 ;

#define PID1_DEFAULTS { 0.0587f, \
	    	0.001f, \
			0.0f, \
			1.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.9f, \
			0.1f \
}

#define PID2_DEFAULTS { 0.0439f, \
	    	0.000538f, \
			0.0f, \
			1.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			3.0f, \
			0.2f \
}


#define PID3_DEFAULTS { -0.0259f, \
	    	0.00192f, \
			0.0f, \
			1.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.0f, \
			0.9f, \
			0.1f \
}
//pid parameters

PID pid1 = PID1_DEFAULTS; //current  control fuel cell
PID pid2 = PID2_DEFAULTS; //voltage  control bidirectional outer loop
PID pid3 = PID3_DEFAULTS ;// cureent control bidirectional inner current loop


//#define eps  0.01		//for error comparison
//#define MAX  1			//for current saturation
//#define MIN  0.1			//for current saturation
//#define Kp   0.1
//#define Kd   0.0
//#define Ki   0.005

void InitEPwm1Example(void);
void InitEPwm2Example(void);
void InitEPwm3Example(void);

interrupt void cpu_timer0_isr(void);

#define AdcBufLen 50
#define AdcFsVoltage	_IQ(3.0)		// ADC full scale voltage

// global variables
_iq AdcBuf[AdcBufLen];					// ADC results buffer
_iq AdcBufFiltered[AdcBufLen];			// filtered ADC results buffer
_iq xBuffer[5] = {0,0,0,0,0};			// filter sample buffer
// filter coefficients
_iq coeffs[5] = {_IQ(0.0357),_IQ(0.2411),_IQ(0.4465),_IQ(0.2411),_IQ(0.0357)};


// Global variable for this Program
Uint16 SampleTable[BUF_SIZE];
Uint16 SampleTable1[BUF_SIZE];
//Uint16 coeff[BUF_FILT];
Uint16 SampleTable2[BUF_SIZE];
Uint16 SampleTable3[BUF_SIZE];
Uint16 SampleTable4[BUF_SIZE];
Uint16 SampleTable5[BUF_SIZE];
Uint16 SampleTable6[BUF_SIZE];
Uint16 i=0;

float d,d1,I_sensor_FC,Vsensor_FC, Vsensor_Load,Vsensor_Batt, I_sensor_Batt, I_sensor_Load, factor_dc=28.2 ,factor_bidir=2.991;
float IDC_offset=0,IDC1_offset=0,VDC2_offset=0,VDC_offset=0,VDC1_offset=0,ILbatt=0,ILfc=0,Iload=0, sum=0,IDC2_offset=0;
float rk=0, yk=0, lk=1, uk, rk1=60, yk1=0, lk1=1, uk1, rk2=1, yk2=0, lk2=1,b, uk2, duty=0, a[10];
int p, z=0;
float Vo=0,Vin_batt=0,ek=0,ek1=0,ek2=0,VFC=0;
float voltage_ref=60,current_ref=0.5;
float Boost_factor=26.75;
  _iq IQssfir(_iq*, _iq*, Uint16);
//pid constant
//float Iref=0.7, Iact=0;
//float pre_err=0, integral=0, error=0, derivative, output
//float Ki=0.05,Kp=0,Kd=0;
//float t=0.01;		//100ms loop time
//float MAX=1,MIN=0;
//float eps=0.01;
int j;




main()
{
// Step 1. Initialize System Control:
// PLL, WatchDog, enable Peripheral Clocks
// This example function is found in the DSP2833x_SysCtrl.c file.






	InitSysCtrl();

// Specific clock setting for this example
   EALLOW;
   SysCtrlRegs.HISPCP.all = ADC_MODCLK;	// HSPCLK = SYSCLKOUT/ADC_MODCLK
   EDIS;

// Step 2. Initialize GPIO:
// This example function is found in the DSP2833x_Gpio.c file and
// illustrates how to set the GPIO to it's default state.
   InitEPwm1Gpio();
   InitEPwm2Gpio();
   InitEPwm3Gpio();
   EALLOW;
   GpioCtrlRegs.GPBMUX1.bit.GPIO34 = 0;    // GPIO pin
   GpioCtrlRegs.GPBDIR.bit.GPIO34 = 1;     // Output pin
   EDIS;

// Step 3. Clear all interrupts and initialize PIE vector table:
// Disable CPU interrupts
   DINT;

// Initialize the PIE control registers to their default state.
// The default state is all PIE interrupts disabled and flags
// are cleared.
// This function is found in the DSP2833x_PieCtrl.c file.
   InitPieCtrl();

// Disable CPU interrupts and clear all CPU interrupt flags:
   IER = 0x0000;
   IFR = 0x0000;

// Initialize the PIE vector table with pointers to the shell Interrupt
// Service Routines (ISR).
// This will populate the entire table, even if the interrupt
// is not used in this example.  This is useful for debug purposes.
// The shell ISR routines are found in DSP2833x_DefaultIsr.c.
// This function is found in DSP2833x_PieVect.c.
   InitPieVectTable();

   EALLOW;  // This is needed to write to EALLOW protected registers
   PieVectTable.TINT0 = &cpu_timer0_isr;

   EDIS;    // This is needed to disable write to EALLOW protected registers

// Step 4. Initialize all the Device Peripherals:
// This function is found in DSP2833x_InitPeripherals.c
// InitPeripherals(); // Not required for this example
   InitCpuTimers();   // For this example, only initialize the Cpu Timers
   InitAdc();  // For this example, init the ADC

   #if (CPU_FRQ_150MHZ)
// Configure CPU-Timer 0, 1, and 2 to interrupt every second:
// 150MHz CPU Freq, 1 second Period (in uSeconds)
   ConfigCpuTimer(&CpuTimer0, 150, 20);
   #endif

   EALLOW;
   SysCtrlRegs.PCLKCR0.bit.TBCLKSYNC = 0;
   EDIS;

///********************** A - Initialize ADC and ePWM **********************///////

   InitEPwm1Example();
   InitEPwm2Example();
   InitEPwm3Example();
   EALLOW;
   SysCtrlRegs.PCLKCR0.bit.TBCLKSYNC = 1;
   EDIS;

   CpuTimer0Regs.TCR.all = 0x4001; // Use write-only instruction to set TSS bit = 0

// Specific ADC setup for this example:
   AdcRegs.ADCTRL2.bit.SOC_SEQ1 = 1;	// start ADC by software
   AdcRegs.ADCTRL1.bit.ACQ_PS = ADC_SHCLK;
   AdcRegs.ADCTRL3.bit.ADCCLKPS = ADC_CKPS;
   AdcRegs.ADCTRL1.bit.SEQ_CASC = 1;        // 1  Cascaded mode
   AdcRegs.ADCMAXCONV.all = 0x0006;       // Setup 7 conv's on SEQ1
   AdcRegs.ADCCHSELSEQ1.bit.CONV00 = 0x0;
   AdcRegs.ADCCHSELSEQ1.bit.CONV01 = 0x1;
   AdcRegs.ADCCHSELSEQ1.bit.CONV02 = 0x2;
   AdcRegs.ADCCHSELSEQ1.bit.CONV03 = 0x3;
   AdcRegs.ADCCHSELSEQ2.bit.CONV04 = 0x4;
   AdcRegs.ADCCHSELSEQ2.bit.CONV05 = 0x5;
   AdcRegs.ADCCHSELSEQ2.bit.CONV06 = 0x6;

   AdcRegs.ADCTRL1.bit.CONT_RUN = 1;       // Setup continuous run


// Step 5. User specific code, enable interrupts:
   IER |= M_INT1;
   IER |= M_INT3;

   // Enable TINT0 in the PIE: Group 1 interrupt 7
      PieCtrlRegs.PIEIER1.bit.INTx7 = 1;

      // Enable EPWM INTn in the PIE: Group 3 interrupt 1-3
         PieCtrlRegs.PIEIER3.bit.INTx1 = 1;
         PieCtrlRegs.PIEIER3.bit.INTx2 = 1;
         PieCtrlRegs.PIEIER3.bit.INTx3 = 1;

      // Clear SampleTable
         for (i=0; i<BUF_SIZE; i++)
         {
           SampleTable[i] =0;
           SampleTable1[i]=0;
           SampleTable2[i]=0;
           SampleTable3[i]=0;
           SampleTable4[i]=0;
           SampleTable5[i]=0;
           SampleTable6[i]=0;

         }

         AdcRegs.ADCTRL2.all = 0x2000;


     // Enable global Interrupts and higher priority real-time debug events:
        EINT;   // Enable Global interrupt INTM
        ERTM;   // Enable Global realtime interrupt DBGM


      // Step 6. IDLE loop. Just sit and loop forever (optional):
      for(;;);

 }

interrupt void cpu_timer0_isr(void)
{
   GpioDataRegs.GPBSET.bit.GPIO34 = 1;  // Set GPIO34 for monitoring
   CpuTimer0.InterruptCount++;

///********************** B - Sense the output voltages and inductor currents  **********************///////

   while (AdcRegs.ADCST.bit.INT_SEQ1== 0) {} // Wait for interrupt
   AdcRegs.ADCST.bit.INT_SEQ1_CLR = 1;
   SampleTable[i] =((AdcRegs.ADCRESULT0>>4));               //FC Current Sensing
   SampleTable1[i] =((AdcRegs.ADCRESULT1>>4));             // Battery current Sensing
   SampleTable2[i] =((AdcRegs.ADCRESULT2>>4));             //  Sensing
   SampleTable3[i] =((AdcRegs.ADCRESULT3>>4));             //  Battry Voltage Sensing
   SampleTable4[i] =((AdcRegs.ADCRESULT4>>4));           //  Load current Sensing
   SampleTable5[i] =((AdcRegs.ADCRESULT5>>4));           //  Load voltage Sensing
   SampleTable6[i] =((AdcRegs.ADCRESULT6>>4));
   //z =((AdcRegs.ADCRESULT3>>4));
   // Write your code here
   	  I_sensor_FC =SampleTable[i]*7.326007326e-4-IDC_offset; // Current sensor output = ADC * 3/4095 - IDC_offset ,IDC_offset=-0.1333
      I_sensor_Batt = SampleTable1[i]*7.326007326e-4- IDC1_offset;//IDC1_offset=-0.116
      I_sensor_Load = SampleTable4[i]*7.326007326e-4- IDC2_offset;//IDC_offset=-0.13
      Vsensor_Batt= SampleTable3[i]*7.326007326e-4-VDC_offset; // Voltage sensor output = ADC * 3/4095 - VDC_offset
      Vsensor_Load= SampleTable5[i]*7.326007326e-4-VDC1_offset;
      Vsensor_FC= SampleTable6[i]*7.326007326e-4-VDC2_offset;

      //IL=(Isensor_out-2.46)*7.5583; //current sensor measurement
      //IL=((I_sensor_new-2.43)/0.13);
   // IL=(I_sensor_new)*factor_bidir; //bidirectional current output

     ILfc=((I_sensor_FC-1.5)/0.05);//Fuel cell input current
     ILbatt=((I_sensor_Batt-1.5)/0.05);//battry input current
     Iload=((I_sensor_Load-1.5)/0.05);//Load current
     Vin_batt =(  Vsensor_Batt*26.667);//Battery Voltage
     Vo=( Vsensor_Load* 29.1);//output voltage
     VFC=( Vsensor_FC* 29.1);

    //fuel cell current current control




      yk=ILfc;
        ek=rk-yk;
      uk = DCL_runPID(&pid1,rk,yk,lk); //� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)

           	d = uk;
           	if(d<=0.3)
           	      		{
           	      	    	d = 0.3;					                      // Lower limit for duty ratio
           	      	    }
           	      	if(d>=0.7)
           	      	 	{
           	      	    	d = 0.7;										 // Upper limit for duty ratio
           	      	 	}

// Outer voltage loop
 yk1=Vo;
 rk1=voltage_ref;
 ek1=rk1-yk1;
 uk1 = DCL_runPID(&pid2,rk1,yk,lk1); //� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)

   if(uk1<=-5)
         		{
         	    	uk1 = -4;
         		}			                      // Lower limit for duty ratio
         	if(uk1>=5)
         	 	{
         	    	uk1 = 4;										 // Upper limit for duty ratio
         	 	}

    yk2=ILbatt;
   	rk2=uk1;//current ref
	ek2=rk2-yk2;
    uk2= DCL_runPID(&pid3,rk2,yk2,lk2); //� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)

d1=uk2;

  // d =0.5 ;
      	if(d1<=0.3)
      		{
      	    	d1 = 0.3;
      		}			                      // Lower limit for duty ratio
      	if(d1>=0.7)
      	 	{
      	    	d1 = 0.7;										 // Upper limit for duty ratio
      	 	}

      	//Update duty ratio to compare register


      	 EPwm1Regs.CMPA.half.CMPA = d*10000;//duty pulse of fuel cell boost pin no.-01
      	// TBPRD = fCPU / ( 2 * fPWM *CLKDIV * HSPCLKDIV)

      	 EPwm2Regs.CMPA.half.CMPA = d1*10000;//duty pulse of batt-bidir pin no.-03

      	 PieCtrlRegs.PIEACK.all = PIEACK_GROUP1;
      	 GpioDataRegs.GPBCLEAR.bit.GPIO34 = 1;


      	 static Uint16 index=0;
      	AdcBuf[index] = _IQmpy(AdcFsVoltage, _IQ16toIQ((_iq)AdcRegs.ADCRESULT2));
    	//AdcBuf[index] =  Vsensor_Batt;
      	/*** Call the filter function ***/
      		xBuffer[0] = AdcBuf[index];				// Add the new entry to the delay chain
      		AdcBufFiltered[index] = (IQssfir(xBuffer, coeffs, 5)/16777216.0);
      		rk=AdcBufFiltered[index];
      		 //yk=AdcBufFiltered[index];
      		index++;									// Increment the index
      		if(index == AdcBufLen) index = 0;			// Rewind the pointer to beginning
      		// Reinitialize for next ADC sequence
      	  	AdcRegs.ADCTRL2.bit.RST_SEQ2 = 1;   	// Reset SEQ1
      	  	AdcRegs.ADCST.bit.INT_SEQ2_CLR = 1;		// Clear INT SEQ1 bit
      	  	//PieCtrlRegs.PIEACK.all = 1;   			// Acknowledge interrupt to PIE

   }



void InitEPwm1Example()
{

   EPwm1Regs.TBPRD = 10000;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
   EPwm1Regs.TBPHS.half.TBPHS = 0x0000;           // Phase is 0
   EPwm1Regs.TBCTR = 0x0000;                      // Clear counter

   // Setup TBCLK
   EPwm1Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
   EPwm1Regs.TBCTL.bit.PHSEN = TB_DISABLE;        // Disable phase loading
   	   	   	   	  // EPwm1Regs.TBCTL.bit.PRDLD = TB_SHADOW;
   	   	   	   	  // EPwm1Regs.TBCTL.bit.SYNCOSEL = TB_CTR_ZERO; // Sync down-stream module
   EPwm1Regs.TBCTL.bit.HSPCLKDIV = TB_DIV1;       // Clock ratio to SYSCLKOUT
   EPwm1Regs.TBCTL.bit.CLKDIV = TB_DIV1;

   EPwm1Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
   EPwm1Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
   EPwm1Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
   EPwm1Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;

   // Setup compare
   //EPwm1Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
   //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially

   // Set actions
   EPwm1Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
   EPwm1Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up

   EPwm1Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
   EPwm1Regs.AQCTLB.bit.CAD = AQ_SET;

//      //Dead band setting
      EPwm1Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
      EPwm1Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
      EPwm1Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
      EPwm1Regs.DBRED = 1; // RED = 10 TBCLKs

}

void InitEPwm2Example()
{

   EPwm2Regs.TBPRD = 10000;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
   EPwm2Regs.TBPHS.half.TBPHS =TB_DISABLE;           // Phase is dissable
   EPwm2Regs.TBCTR = 0x0000;                      // Clear counter

   // Setup TBCLK
   EPwm2Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
   EPwm2Regs.TBCTL.bit.PHSEN =TB_DISABLE;        // Disable phase loading

   EPwm2Regs.TBCTL.bit.SYNCOSEL = TB_CTR_ZERO; // Sync down-stream module

   //EPwm2Regs.TBCTL.bit.PHSDIR = TB_DOWN; // Count DOWN on sync (=120 deg)
   EPwm2Regs.TBCTL.bit.PRDLD = TB_SHADOW;
   //EPwm2Regs.TBCTL.bit.SYNCOSEL = 1;  //TB_SYNC_IN; // sync flow-through

   EPwm2Regs.TBCTL.bit.HSPCLKDIV = TB_DIV1;       // Clock ratio to SYSCLKOUT
   EPwm2Regs.TBCTL.bit.CLKDIV = TB_DIV1;

   EPwm2Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
   EPwm2Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
   EPwm2Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
   EPwm2Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;

   // Setup compare
   //EPwm2Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
   //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially

   // Set actions
   EPwm2Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
   EPwm2Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up

   EPwm2Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
   EPwm2Regs.AQCTLB.bit.CAD = AQ_SET;

//      // Dead band setting
      EPwm2Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
      EPwm2Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
      EPwm2Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
      EPwm2Regs.DBRED = 1; // RED = 10 TBCLKs

}

void InitEPwm3Example()
{

   EPwm3Regs.TBPRD = 624;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
   EPwm3Regs.TBPHS.half.TBPHS = 155;             // when phase =3, pd = 0 ; when phase = 3+ 155-dutycycle+dutycycleaux
   EPwm3Regs.TBCTR = 0x0000;                     // Clear counter

   // Setup TBCLK
   EPwm3Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
   EPwm3Regs.TBCTL.bit.PHSEN = TB_ENABLE;        // Disable phase loading

   	   	          EPwm3Regs.TBCTL.bit.PHSDIR = TB_DOWN; // Count DOWN on sync (=120 deg)
      	  	  	  EPwm3Regs.TBCTL.bit.PRDLD = TB_SHADOW;
                  EPwm3Regs.TBCTL.bit.SYNCOSEL = 1;  //TB_SYNC_IN; // sync flow-through

   	   	   	   	   //EPwm2Regs.TBCTL.bit.PRDLD = TB_SHADOW;
   	   	   	   	   //EPwm3Regs.TBCTL.bit.SYNCOSEL = 0; // Sync down-stream module
   EPwm3Regs.TBCTL.bit.HSPCLKDIV = TB_DIV4;       // Clock ratio to SYSCLKOUT
   EPwm3Regs.TBCTL.bit.CLKDIV = TB_DIV4;

   EPwm3Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
   EPwm3Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
   EPwm3Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
   EPwm3Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;

   // Setup compare
   //EPwm3Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
   //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially

   // Set actions
   EPwm3Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
   EPwm3Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up

   EPwm3Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
   EPwm3Regs.AQCTLB.bit.CAD = AQ_SET;

//      // Dead band setting
      EPwm3Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
      EPwm3Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
      EPwm3Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
      EPwm3Regs.DBRED = 1; // RED = 10 TBCLKs

}

 //===========================================================================
// No more.
//===========================================================================

  • Hello Ananda,

    You should take a look at the DCL - Digital Control Library - www.ti.com/.../C2000-DIGITAL-CONTROL-LIBRARY .

    HTH,
    John W.
  • My filtered signal is in the array format of length 50.And i want that signal convert into float rk ,which is my reference to pid. I can't write rk=AdcBufFiltered[index]. then rk is choose any value from the array.how to resolve that problem.
  • It looks like the filtered signal is in IQ format, so you can use the IQ to float conversion from that library:

    rk=_IQtoF(AdcBufFiltered[index]);

    You should also typecast the ADC results to float. Your first assignment, the current sensor reading, would look like this:

    I_sensor_FC =(float) SampleTable[i] * 7.326007326e-4 - IDC_offset;

    On last thing; where you are assigning float constants it's better to place an 'f' at the end to make it unambiguous to the compiler. For example:

    float IDC_offset=0.0f, ...

    Regards,

    Richard
  • Filter.c
    //File: Filter.c
    //* Description: Contains IQmath filter for C28x workshop labs
    //* Devices: TMS320F2812, TMS320F2811, TMS320F2810
    //* Author: Technical Training Organization (TTO), Texas Instruments
    //* Function List:
    //*   _iq fir(_iq *x, _iq *a, Uint16 n)
    //* History:
    //*   11/10/03 - original (based on DSP281x header files v1.00)                   // ( and IQmath v1.4d)
    //* Notes: none
    /**********************************************************************/
    #include "DSP2833x_Device.h"
    #include "IQmathLib.h"
    
    
    /**********************************************************************
    * Function: IQssfir()
    * Description: IQmath n-tap single-sample FIR filter.
    *
    *         y(k) = a(0)*x(k) + a(1)*x(k-1) + ... + a(n-1)*x(k-n+1)
    *
    * DSP: TMS320F2812, TMS320F2811, TMS320F2810
    * Include files: DSP281x_Device.h, IQmathLib.h
    * Function Prototype: _iq IQssfir(_iq*, _iq*, Uint16)
    * Useage: y = IQssfir(x, a, n);
    * Input Parameters: x = array of input and delay chain (global IQ format)
    *                   a = array of coefficients (global IQ format)
    *                   n = number of coefficients
    * Return Value: y = result
    * Notes:
    * 1) This is just a simple filter example, and completely unoptimized.
    *    The goal with the code was clarity and simplicity, not efficiency.
    * 2) The filtering is done from last tap to first tap.  This allows
    *    more efficient delay chain updating.
    **********************************************************************/
    _iq IQssfir(_iq *x, _iq *a, Uint16 n)
    {
    
    Uint16 i;								// general purpose
    _iq y;									// result
    _iq *xold;								// delay line pointer
    
    /*** Setup the pointers ***/
    	a = a + (n-1);						// a points to last coefficient
    	x = x + (n-1);						// x points to last buffer element
    	xold = x;							// xold points to last buffer element
    
    /*** Last tap has no delay line update ***/
    	y = _IQmpy(*a--, *x--);
    
    /*** Do the other taps from end to beginning ***/
    	for(i=0; i<n-1; i++)
    	{
    		y = y + _IQmpy(*a--, *x);		// filter tap
    		*xold-- = *x--;					// delay line update
    	}
    
    /*** Finish up ***/
    	return(y);
    
    } //end IQssfir()
    
    
    /*** end of file ***/
    
    LPF2.c
    /*
     * LPF2.c
     *
     *  Created on: Feb 14, 2019
     *      Author: Ananda
     */
    
    
    
    #include "DSP28x_Project.h"     // Device Headerfile and Examples Include File
    #include "DCL.h"               // Digital control library
    #include "IQmathLib.h"
    // ADC start parameters
    #if (CPU_FRQ_150MHZ)     // Default - 150 MHz SYSCLKOUT
      #define ADC_MODCLK 0x3 // HSPCLK = SYSCLKOUT/2*ADC_MODCLK2 = 150/(2*3)   = 25.0 MHz
    #endif
    
    #define ADC_CKPS   0x1   // ADC module clock = HSPCLK/2*ADC_CKPS   = 25.0MHz/(1*2) = 12.5MHz
    #define ADC_SHCLK  0xf   // S/H width in ADC module periods                        = 16 ADC clocks
    #define AVG        50  // Average sample limit
    #define ZOFFSET    0x00  // Average Zero offset
    #define BUF_SIZE   50  // Sample buffer size
    
    
    typedef volatile struct {
    float Kp; // proportional gain
    float Ki; // integral gain
    float Kd; // derivative gain
    float Kr; // set point weight
    float c1; // D filter coefficient 1
    float c2; // D filter coefficient 2
    float d2; // D filter storage 1
    float d3; // D filter storage 2
    float i10; // I storage
    float i14; // sat storage
    float Umax; // upper saturation limit
    float Umin; // lower saturation limit
    } PID2 ;
    
    #define PID1_DEFAULTS { 0.0587f, \
    	    	0.001f, \
    			0.0f, \
    			1.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.9f, \
    			0.1f \
    }
    
    #define PID2_DEFAULTS { 0.0439f, \
    	    	0.000538f, \
    			0.0f, \
    			1.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			3.0f, \
    			0.2f \
    }
    
    
    #define PID3_DEFAULTS { -0.0259f, \
    	    	0.00192f, \
    			0.0f, \
    			1.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.9f, \
    			0.1f \
    }
    //pid parameters
    
    PID pid1 = PID1_DEFAULTS; //current  control fuel cell
    PID pid2 = PID2_DEFAULTS; //voltage  control bidirectional outer loop
    PID pid3 = PID3_DEFAULTS ;// cureent control bidirectional inner current loop
    
    
    //#define eps  0.01		//for error comparison
    //#define MAX  1			//for current saturation
    //#define MIN  0.1			//for current saturation
    //#define Kp   0.1
    //#define Kd   0.0
    //#define Ki   0.005
    
    void InitEPwm1Example(void);
    void InitEPwm2Example(void);
    void InitEPwm3Example(void);
    
    interrupt void cpu_timer0_isr(void);
    
    #define AdcBufLen 50
    #define AdcFsVoltage	_IQ(3.0)		// ADC full scale voltage
    
    // global variables
    _iq AdcBuf[AdcBufLen];					// ADC results buffer
    _iq AdcBufFiltered[AdcBufLen];			// filtered ADC results buffer
    _iq xBuffer[5] = {0,0,0,0,0};			// filter sample buffer
    // filter coefficients
    _iq coeffs[5] = {_IQ(0.0357),_IQ(0.2411),_IQ(0.4465),_IQ(0.2411),_IQ(0.0357)};
    //_iq rk[AdcBufLen];
    
    
    // Global variable for this Program
    Uint16 SampleTable[BUF_SIZE];
    Uint16 SampleTable1[BUF_SIZE];
    //Uint16 coeff[BUF_FILT];
    Uint16 SampleTable2[BUF_SIZE];
    Uint16 SampleTable3[BUF_SIZE];
    Uint16 SampleTable4[BUF_SIZE];
    Uint16 SampleTable5[BUF_SIZE];
    Uint16 SampleTable6[BUF_SIZE];
    Uint16 i=0;
    
    float d,d1,I_sensor_FC,Vsensor_FC, Vsensor_Load,Vsensor_Batt, I_sensor_Batt, I_sensor_Load, factor_dc=28.2 ,factor_bidir=2.991;
    float IDC_offset=0.0f,IDC1_offset=0.0f,VDC2_offset=0.0f,VDC_offset=0.0f,VDC1_offset=0.0f,ILbatt=0.0f,ILfc=0.0f,Iload=0.0f, sum=0.0f,IDC2_offset=0.0f;
    float yk=0.0f, lk=1.0f, uk, rk1=60.0f, yk1=0.0f, lk1=1.0f, uk1, rk2=1.0f, yk2=0.0f, lk2=1.0f,b, uk2, duty=0.0f, a[10];
    float rk=0.0f;
    int p, z=0;
    float Vo=0.0f,Vin_batt=0.0f,ek=0.0f,ek1=0.0f,ek2=0.0f,VFC=0.0f;
    float voltage_ref=60.0f,current_ref=0.5f;
    float Boost_factor=26.75f;
      _iq IQssfir(_iq*, _iq*, Uint16);
    //pid constant
    //float Iref=0.7, Iact=0;
    //float pre_err=0, integral=0, error=0, derivative, output
    //float Ki=0.05,Kp=0,Kd=0;
    //float t=0.01;		//100ms loop time
    //float MAX=1,MIN=0;
    //float eps=0.01;
    int j;
    
    
    
    
    main()
    {
    // Step 1. Initialize System Control:
    // PLL, WatchDog, enable Peripheral Clocks
    // This example function is found in the DSP2833x_SysCtrl.c file.
    
    
    
    
    
    
    
    	InitSysCtrl();
    
    // Specific clock setting for this example
       EALLOW;
       SysCtrlRegs.HISPCP.all = ADC_MODCLK;	// HSPCLK = SYSCLKOUT/ADC_MODCLK
       EDIS;
    
    // Step 2. Initialize GPIO:
    // This example function is found in the DSP2833x_Gpio.c file and
    // illustrates how to set the GPIO to it's default state.
       InitEPwm1Gpio();
       InitEPwm2Gpio();
       InitEPwm3Gpio();
       EALLOW;
       GpioCtrlRegs.GPBMUX1.bit.GPIO34 = 0;    // GPIO pin
       GpioCtrlRegs.GPBDIR.bit.GPIO34 = 1;     // Output pin
       EDIS;
    
    // Step 3. Clear all interrupts and initialize PIE vector table:
    // Disable CPU interrupts
       DINT;
    
    // Initialize the PIE control registers to their default state.
    // The default state is all PIE interrupts disabled and flags
    // are cleared.
    // This function is found in the DSP2833x_PieCtrl.c file.
       InitPieCtrl();
    
    // Disable CPU interrupts and clear all CPU interrupt flags:
       IER = 0x0000;
       IFR = 0x0000;
    
    // Initialize the PIE vector table with pointers to the shell Interrupt
    // Service Routines (ISR).
    // This will populate the entire table, even if the interrupt
    // is not used in this example.  This is useful for debug purposes.
    // The shell ISR routines are found in DSP2833x_DefaultIsr.c.
    // This function is found in DSP2833x_PieVect.c.
       InitPieVectTable();
    
       EALLOW;  // This is needed to write to EALLOW protected registers
       PieVectTable.TINT0 = &cpu_timer0_isr;
    
       EDIS;    // This is needed to disable write to EALLOW protected registers
    
    // Step 4. Initialize all the Device Peripherals:
    // This function is found in DSP2833x_InitPeripherals.c
    // InitPeripherals(); // Not required for this example
       InitCpuTimers();   // For this example, only initialize the Cpu Timers
       InitAdc();  // For this example, init the ADC
    
       #if (CPU_FRQ_150MHZ)
    // Configure CPU-Timer 0, 1, and 2 to interrupt every second:
    // 150MHz CPU Freq, 1 second Period (in uSeconds)
       ConfigCpuTimer(&CpuTimer0, 150, 20);
       #endif
    
       EALLOW;
       SysCtrlRegs.PCLKCR0.bit.TBCLKSYNC = 0;
       EDIS;
    
    ///********************** A - Initialize ADC and ePWM **********************///////
    
       InitEPwm1Example();
       InitEPwm2Example();
       InitEPwm3Example();
       EALLOW;
       SysCtrlRegs.PCLKCR0.bit.TBCLKSYNC = 1;
       EDIS;
    
       CpuTimer0Regs.TCR.all = 0x4001; // Use write-only instruction to set TSS bit = 0
    
    // Specific ADC setup for this example:
       AdcRegs.ADCTRL2.bit.SOC_SEQ1 = 1;	// start ADC by software
       AdcRegs.ADCTRL1.bit.ACQ_PS = ADC_SHCLK;
       AdcRegs.ADCTRL3.bit.ADCCLKPS = ADC_CKPS;
       AdcRegs.ADCTRL1.bit.SEQ_CASC = 1;        // 1  Cascaded mode
       AdcRegs.ADCMAXCONV.all = 0x0006;       // Setup 7 conv's on SEQ1
       AdcRegs.ADCCHSELSEQ1.bit.CONV00 = 0x0;
       AdcRegs.ADCCHSELSEQ1.bit.CONV01 = 0x1;
       AdcRegs.ADCCHSELSEQ1.bit.CONV02 = 0x2;
       AdcRegs.ADCCHSELSEQ1.bit.CONV03 = 0x3;
       AdcRegs.ADCCHSELSEQ2.bit.CONV04 = 0x4;
       AdcRegs.ADCCHSELSEQ2.bit.CONV05 = 0x5;
       AdcRegs.ADCCHSELSEQ2.bit.CONV06 = 0x6;
    
       AdcRegs.ADCTRL1.bit.CONT_RUN = 1;       // Setup continuous run
    
    
    // Step 5. User specific code, enable interrupts:
       IER |= M_INT1;
       IER |= M_INT3;
    
       // Enable TINT0 in the PIE: Group 1 interrupt 7
          PieCtrlRegs.PIEIER1.bit.INTx7 = 1;
    
          // Enable EPWM INTn in the PIE: Group 3 interrupt 1-3
             PieCtrlRegs.PIEIER3.bit.INTx1 = 1;
             PieCtrlRegs.PIEIER3.bit.INTx2 = 1;
             PieCtrlRegs.PIEIER3.bit.INTx3 = 1;
    
          // Clear SampleTable
             for (i=0; i<BUF_SIZE; i++)
             {
               SampleTable[i] =0;
               SampleTable1[i]=0;
               SampleTable2[i]=0;
               SampleTable3[i]=0;
               SampleTable4[i]=0;
               SampleTable5[i]=0;
               SampleTable6[i]=0;
    
             }
    
             AdcRegs.ADCTRL2.all = 0x2000;
    
    
         // Enable global Interrupts and higher priority real-time debug events:
            EINT;   // Enable Global interrupt INTM
            ERTM;   // Enable Global realtime interrupt DBGM
    
    
          // Step 6. IDLE loop. Just sit and loop forever (optional):
          for(;;);
    
     }
    
    interrupt void cpu_timer0_isr(void)
    {
       GpioDataRegs.GPBSET.bit.GPIO34 = 1;  // Set GPIO34 for monitoring
       CpuTimer0.InterruptCount++;
    
    ///********************** B - Sense the output voltages and inductor currents  **********************///////
    
       while (AdcRegs.ADCST.bit.INT_SEQ1== 0) {} // Wait for interrupt
       AdcRegs.ADCST.bit.INT_SEQ1_CLR = 1;
       SampleTable[i]  = ((AdcRegs.ADCRESULT0>>4));               //FC Current Sensing
       SampleTable1[i] = ((AdcRegs.ADCRESULT1>>4));             // Battery current Sensing
       SampleTable2[i] = ((AdcRegs.ADCRESULT2>>4));             //  Sensing
       SampleTable3[i] = ((AdcRegs.ADCRESULT3>>4));             //  Battry Voltage Sensing
       SampleTable4[i] = ((AdcRegs.ADCRESULT4>>4));           //  Load current Sensing
       SampleTable5[i] = ((AdcRegs.ADCRESULT5>>4));           //  Load voltage Sensing
       SampleTable6[i] = ((AdcRegs.ADCRESULT6>>4));
       //z =((AdcRegs.ADCRESULT3>>4));
       // Write your code here
       	  I_sensor_FC	 =(float) SampleTable[i]*7.326007326e-4-IDC_offset; 		// Current sensor output = ADC * 3/4095 - IDC_offset ,IDC_offset=-0.1333
          I_sensor_Batt  =(float) SampleTable1[i]*7.326007326e-4- IDC1_offset;		//IDC1_offset=-0.116
          I_sensor_Load  =(float) SampleTable4[i]*7.326007326e-4- IDC2_offset;		//IDC_offset=-0.13
          Vsensor_Batt	 =(float) SampleTable3[i]*7.326007326e-4-VDC_offset; 		// Voltage sensor output = ADC * 3/4095 - VDC_offset
          Vsensor_Load	 =(float) SampleTable5[i]*7.326007326e-4-VDC1_offset;
          Vsensor_FC	 =(float) SampleTable6[i]*7.326007326e-4-VDC2_offset;
    
          //IL=(Isensor_out-2.46)*7.5583; //current sensor measurement
          //IL=((I_sensor_new-2.43)/0.13);
       // IL=(I_sensor_new)*factor_bidir; //bidirectional current output
    
         ILfc		=(float) ((I_sensor_FC-1.5)/0.05);				//Fuel cell input current
         ILbatt		=(float) ((I_sensor_Batt-1.5)/0.05);			//battry input current
         Iload		=(float) ((I_sensor_Load-1.5)/0.05);			//Load current
         Vin_batt 	=(float) (Vsensor_Batt*26.667);					//Battery Voltage
         Vo			=(float) (Vsensor_Load* 29.1);					//output voltage
         VFC		=(float) (Vsensor_FC* 29.1);					//Fuelcell voltage
    
        //fuel cell current current control
         yk=ILfc;
         	 	 	 ek=rk-yk;
               		      uk = DCL_runPID(&pid1,rk,yk,lk); 			//� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)
    
               		           	d = uk;
               		           	if(d<=0.3)
               		           	      		{
               		           	      	    	d = 0.3;					                      // Lower limit for duty ratio
               		           	      	    }
               		           	      	if(d>=0.7)
               		           	      	 	{
               		           	      	    	d = 0.7;										 // Upper limit for duty ratio
               		           	      	 	}
    
    
    
    
    
    
    // Outer voltage loop
     yk1=Vo;
     rk1=voltage_ref;
     ek1=rk1-yk1;
     uk1 = DCL_runPID(&pid2,rk1,yk,lk1); //� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)
    
       if(uk1<=-5)
             		{
             	    	uk1 = -4;
             		}			                      // Lower limit for duty ratio
             	if(uk1>=5)
             	 	{
             	    	uk1 = 4;										 // Upper limit for duty ratio
             	 	}
    
        yk2=ILbatt;
       	rk2=uk1;//current ref
    	ek2=rk2-yk2;
        uk2= DCL_runPID(&pid3,rk2,yk2,lk2); //� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)
    
    d1=uk2;
    
      // d =0.5 ;
          	if(d1<=0.3)
          		{
          	    	d1 = 0.3;
          		}			                      // Lower limit for duty ratio
          	if(d1>=0.7)
          	 	{
          	    	d1 = 0.7;										 // Upper limit for duty ratio
          	 	}
    
          	//Update duty ratio to compare register
    
    
          	 EPwm1Regs.CMPA.half.CMPA = d*10000;//duty pulse of fuel cell boost pin no.-01
          	// TBPRD = fCPU / ( 2 * fPWM *CLKDIV * HSPCLKDIV)
    
          	 EPwm2Regs.CMPA.half.CMPA = d1*10000;//duty pulse of batt-bidir pin no.-03
    
          	 PieCtrlRegs.PIEACK.all = PIEACK_GROUP1;
          	 GpioDataRegs.GPBCLEAR.bit.GPIO34 = 1;
    
    
          	 static Uint16 index=0;
          	AdcBuf[index] = _IQmpy(AdcFsVoltage, _IQ16toIQ((_iq)AdcRegs.ADCRESULT2));
        	//AdcBuf[index] =  Vsensor_Batt;
          	/*** Call the filter function ***/
          		xBuffer[0] = AdcBuf[index];				// Add the new entry to the delay chain
          		AdcBufFiltered[index] = (IQssfir(xBuffer, coeffs, 5)/16777216.0);
          		rk=_IQtoF(AdcBufFiltered[index]);
          		       		 //yk=AdcBufFiltered[index];
          		index++;									// Increment the index
          		if(index == AdcBufLen) index = 0;			// Rewind the pointer to beginning
          		// Reinitialize for next ADC sequence
          	  	AdcRegs.ADCTRL2.bit.RST_SEQ2 = 1;   	// Reset SEQ1
          	  	AdcRegs.ADCST.bit.INT_SEQ2_CLR = 1;		// Clear INT SEQ1 bit
          	  	//PieCtrlRegs.PIEACK.all = 1;   			// Acknowledge interrupt to PIE
    
       }
    
    
    
    void InitEPwm1Example()
    {
    
       EPwm1Regs.TBPRD = 10000;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
       EPwm1Regs.TBPHS.half.TBPHS = 0x0000;           // Phase is 0
       EPwm1Regs.TBCTR = 0x0000;                      // Clear counter
    
       // Setup TBCLK
       EPwm1Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
       EPwm1Regs.TBCTL.bit.PHSEN = TB_DISABLE;        // Disable phase loading
       	   	   	   	  // EPwm1Regs.TBCTL.bit.PRDLD = TB_SHADOW;
       	   	   	   	  // EPwm1Regs.TBCTL.bit.SYNCOSEL = TB_CTR_ZERO; // Sync down-stream module
       EPwm1Regs.TBCTL.bit.HSPCLKDIV = TB_DIV1;       // Clock ratio to SYSCLKOUT
       EPwm1Regs.TBCTL.bit.CLKDIV = TB_DIV1;
    
       EPwm1Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
       EPwm1Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
       EPwm1Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
       EPwm1Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;
    
       // Setup compare
       //EPwm1Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
       //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially
    
       // Set actions
       EPwm1Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
       EPwm1Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up
    
       EPwm1Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
       EPwm1Regs.AQCTLB.bit.CAD = AQ_SET;
    
    //      //Dead band setting
          EPwm1Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
          EPwm1Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
          EPwm1Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
          EPwm1Regs.DBRED = 1; // RED = 10 TBCLKs
    
    }
    
    void InitEPwm2Example()
    {
    
       EPwm2Regs.TBPRD = 10000;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
       EPwm2Regs.TBPHS.half.TBPHS =TB_DISABLE;           // Phase is dissable
       EPwm2Regs.TBCTR = 0x0000;                      // Clear counter
    
       // Setup TBCLK
       EPwm2Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
       EPwm2Regs.TBCTL.bit.PHSEN =TB_DISABLE;        // Disable phase loading
    
       EPwm2Regs.TBCTL.bit.SYNCOSEL = TB_CTR_ZERO; // Sync down-stream module
    
       //EPwm2Regs.TBCTL.bit.PHSDIR = TB_DOWN; // Count DOWN on sync (=120 deg)
       EPwm2Regs.TBCTL.bit.PRDLD = TB_SHADOW;
       //EPwm2Regs.TBCTL.bit.SYNCOSEL = 1;  //TB_SYNC_IN; // sync flow-through
    
       EPwm2Regs.TBCTL.bit.HSPCLKDIV = TB_DIV1;       // Clock ratio to SYSCLKOUT
       EPwm2Regs.TBCTL.bit.CLKDIV = TB_DIV1;
    
       EPwm2Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
       EPwm2Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
       EPwm2Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
       EPwm2Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;
    
       // Setup compare
       //EPwm2Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
       //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially
    
       // Set actions
       EPwm2Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
       EPwm2Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up
    
       EPwm2Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
       EPwm2Regs.AQCTLB.bit.CAD = AQ_SET;
    
    //      // Dead band setting
          EPwm2Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
          EPwm2Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
          EPwm2Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
          EPwm2Regs.DBRED = 1; // RED = 10 TBCLKs
    
    }
    
    void InitEPwm3Example()
    {
    
       EPwm3Regs.TBPRD = 624;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
       EPwm3Regs.TBPHS.half.TBPHS = 155;             // when phase =3, pd = 0 ; when phase = 3+ 155-dutycycle+dutycycleaux
       EPwm3Regs.TBCTR = 0x0000;                     // Clear counter
    
       // Setup TBCLK
       EPwm3Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
       EPwm3Regs.TBCTL.bit.PHSEN = TB_ENABLE;        // Disable phase loading
    
       	   	          EPwm3Regs.TBCTL.bit.PHSDIR = TB_DOWN; // Count DOWN on sync (=120 deg)
          	  	  	  EPwm3Regs.TBCTL.bit.PRDLD = TB_SHADOW;
                      EPwm3Regs.TBCTL.bit.SYNCOSEL = 1;  //TB_SYNC_IN; // sync flow-through
    
       	   	   	   	   //EPwm2Regs.TBCTL.bit.PRDLD = TB_SHADOW;
       	   	   	   	   //EPwm3Regs.TBCTL.bit.SYNCOSEL = 0; // Sync down-stream module
       EPwm3Regs.TBCTL.bit.HSPCLKDIV = TB_DIV4;       // Clock ratio to SYSCLKOUT
       EPwm3Regs.TBCTL.bit.CLKDIV = TB_DIV4;
    
       EPwm3Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
       EPwm3Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
       EPwm3Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
       EPwm3Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;
    
       // Setup compare
       //EPwm3Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
       //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially
    
       // Set actions
       EPwm3Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
       EPwm3Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up
    
       EPwm3Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
       EPwm3Regs.AQCTLB.bit.CAD = AQ_SET;
    
    //      // Dead band setting
          EPwm3Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
          EPwm3Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
          EPwm3Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
          EPwm3Regs.DBRED = 1; // RED = 10 TBCLKs
    
    }
    
     //===========================================================================
    // No more.
    //===========================================================================
    
    
    
    LPF2.c
    /*
     * LPF2.c
     *
     *  Created on: Feb 14, 2019
     *      Author: Ananda
     */
    
    
    
    #include "DSP28x_Project.h"     // Device Headerfile and Examples Include File
    #include "DCL.h"               // Digital control library
    #include "IQmathLib.h"
    // ADC start parameters
    #if (CPU_FRQ_150MHZ)     // Default - 150 MHz SYSCLKOUT
      #define ADC_MODCLK 0x3 // HSPCLK = SYSCLKOUT/2*ADC_MODCLK2 = 150/(2*3)   = 25.0 MHz
    #endif
    
    #define ADC_CKPS   0x1   // ADC module clock = HSPCLK/2*ADC_CKPS   = 25.0MHz/(1*2) = 12.5MHz
    #define ADC_SHCLK  0xf   // S/H width in ADC module periods                        = 16 ADC clocks
    #define AVG        50  // Average sample limit
    #define ZOFFSET    0x00  // Average Zero offset
    #define BUF_SIZE   50  // Sample buffer size
    
    
    typedef volatile struct {
    float Kp; // proportional gain
    float Ki; // integral gain
    float Kd; // derivative gain
    float Kr; // set point weight
    float c1; // D filter coefficient 1
    float c2; // D filter coefficient 2
    float d2; // D filter storage 1
    float d3; // D filter storage 2
    float i10; // I storage
    float i14; // sat storage
    float Umax; // upper saturation limit
    float Umin; // lower saturation limit
    } PID2 ;
    
    #define PID1_DEFAULTS { 0.0587f, \
    	    	0.001f, \
    			0.0f, \
    			1.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.9f, \
    			0.1f \
    }
    
    #define PID2_DEFAULTS { 0.0439f, \
    	    	0.000538f, \
    			0.0f, \
    			1.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			3.0f, \
    			0.2f \
    }
    
    
    #define PID3_DEFAULTS { -0.0259f, \
    	    	0.00192f, \
    			0.0f, \
    			1.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.0f, \
    			0.9f, \
    			0.1f \
    }
    //pid parameters
    
    PID pid1 = PID1_DEFAULTS; //current  control fuel cell
    PID pid2 = PID2_DEFAULTS; //voltage  control bidirectional outer loop
    PID pid3 = PID3_DEFAULTS ;// cureent control bidirectional inner current loop
    
    
    //#define eps  0.01		//for error comparison
    //#define MAX  1			//for current saturation
    //#define MIN  0.1			//for current saturation
    //#define Kp   0.1
    //#define Kd   0.0
    //#define Ki   0.005
    
    void InitEPwm1Example(void);
    void InitEPwm2Example(void);
    void InitEPwm3Example(void);
    
    interrupt void cpu_timer0_isr(void);
    
    #define AdcBufLen 50
    #define AdcFsVoltage	_IQ(3.0)		// ADC full scale voltage
    
    // global variables
    _iq AdcBuf[AdcBufLen];					// ADC results buffer
    _iq AdcBufFiltered[AdcBufLen];			// filtered ADC results buffer
    _iq xBuffer[5] = {0,0,0,0,0};			// filter sample buffer
    // filter coefficients
    _iq coeffs[5] = {_IQ(0.0357),_IQ(0.2411),_IQ(0.4465),_IQ(0.2411),_IQ(0.0357)};
    //_iq rk[AdcBufLen];
    
    
    // Global variable for this Program
    Uint16 SampleTable[BUF_SIZE];
    Uint16 SampleTable1[BUF_SIZE];
    //Uint16 coeff[BUF_FILT];
    Uint16 SampleTable2[BUF_SIZE];
    Uint16 SampleTable3[BUF_SIZE];
    Uint16 SampleTable4[BUF_SIZE];
    Uint16 SampleTable5[BUF_SIZE];
    Uint16 SampleTable6[BUF_SIZE];
    Uint16 i=0;
    
    float d,d1,I_sensor_FC,Vsensor_FC, Vsensor_Load,Vsensor_Batt, I_sensor_Batt, I_sensor_Load, factor_dc=28.2 ,factor_bidir=2.991;
    float IDC_offset=0.0f,IDC1_offset=0.0f,VDC2_offset=0.0f,VDC_offset=0.0f,VDC1_offset=0.0f,ILbatt=0.0f,ILfc=0.0f,Iload=0.0f, sum=0.0f,IDC2_offset=0.0f;
    float yk=0.0f, lk=1.0f, uk, rk1=60.0f, yk1=0.0f, lk1=1.0f, uk1, rk2=1.0f, yk2=0.0f, lk2=1.0f,b, uk2, duty=0.0f, a[10];
    float rk=0.0f;
    int p, z=0;
    float Vo=0.0f,Vin_batt=0.0f,ek=0.0f,ek1=0.0f,ek2=0.0f,VFC=0.0f;
    float voltage_ref=60.0f,current_ref=0.5f;
    float Boost_factor=26.75f;
      _iq IQssfir(_iq*, _iq*, Uint16);
    //pid constant
    //float Iref=0.7, Iact=0;
    //float pre_err=0, integral=0, error=0, derivative, output
    //float Ki=0.05,Kp=0,Kd=0;
    //float t=0.01;		//100ms loop time
    //float MAX=1,MIN=0;
    //float eps=0.01;
    int j;
    
    
    
    
    main()
    {
    // Step 1. Initialize System Control:
    // PLL, WatchDog, enable Peripheral Clocks
    // This example function is found in the DSP2833x_SysCtrl.c file.
    
    
    
    
    
    
    
    	InitSysCtrl();
    
    // Specific clock setting for this example
       EALLOW;
       SysCtrlRegs.HISPCP.all = ADC_MODCLK;	// HSPCLK = SYSCLKOUT/ADC_MODCLK
       EDIS;
    
    // Step 2. Initialize GPIO:
    // This example function is found in the DSP2833x_Gpio.c file and
    // illustrates how to set the GPIO to it's default state.
       InitEPwm1Gpio();
       InitEPwm2Gpio();
       InitEPwm3Gpio();
       EALLOW;
       GpioCtrlRegs.GPBMUX1.bit.GPIO34 = 0;    // GPIO pin
       GpioCtrlRegs.GPBDIR.bit.GPIO34 = 1;     // Output pin
       EDIS;
    
    // Step 3. Clear all interrupts and initialize PIE vector table:
    // Disable CPU interrupts
       DINT;
    
    // Initialize the PIE control registers to their default state.
    // The default state is all PIE interrupts disabled and flags
    // are cleared.
    // This function is found in the DSP2833x_PieCtrl.c file.
       InitPieCtrl();
    
    // Disable CPU interrupts and clear all CPU interrupt flags:
       IER = 0x0000;
       IFR = 0x0000;
    
    // Initialize the PIE vector table with pointers to the shell Interrupt
    // Service Routines (ISR).
    // This will populate the entire table, even if the interrupt
    // is not used in this example.  This is useful for debug purposes.
    // The shell ISR routines are found in DSP2833x_DefaultIsr.c.
    // This function is found in DSP2833x_PieVect.c.
       InitPieVectTable();
    
       EALLOW;  // This is needed to write to EALLOW protected registers
       PieVectTable.TINT0 = &cpu_timer0_isr;
    
       EDIS;    // This is needed to disable write to EALLOW protected registers
    
    // Step 4. Initialize all the Device Peripherals:
    // This function is found in DSP2833x_InitPeripherals.c
    // InitPeripherals(); // Not required for this example
       InitCpuTimers();   // For this example, only initialize the Cpu Timers
       InitAdc();  // For this example, init the ADC
    
       #if (CPU_FRQ_150MHZ)
    // Configure CPU-Timer 0, 1, and 2 to interrupt every second:
    // 150MHz CPU Freq, 1 second Period (in uSeconds)
       ConfigCpuTimer(&CpuTimer0, 150, 20);
       #endif
    
       EALLOW;
       SysCtrlRegs.PCLKCR0.bit.TBCLKSYNC = 0;
       EDIS;
    
    ///********************** A - Initialize ADC and ePWM **********************///////
    
       InitEPwm1Example();
       InitEPwm2Example();
       InitEPwm3Example();
       EALLOW;
       SysCtrlRegs.PCLKCR0.bit.TBCLKSYNC = 1;
       EDIS;
    
       CpuTimer0Regs.TCR.all = 0x4001; // Use write-only instruction to set TSS bit = 0
    
    // Specific ADC setup for this example:
       AdcRegs.ADCTRL2.bit.SOC_SEQ1 = 1;	// start ADC by software
       AdcRegs.ADCTRL1.bit.ACQ_PS = ADC_SHCLK;
       AdcRegs.ADCTRL3.bit.ADCCLKPS = ADC_CKPS;
       AdcRegs.ADCTRL1.bit.SEQ_CASC = 1;        // 1  Cascaded mode
       AdcRegs.ADCMAXCONV.all = 0x0006;       // Setup 7 conv's on SEQ1
       AdcRegs.ADCCHSELSEQ1.bit.CONV00 = 0x0;
       AdcRegs.ADCCHSELSEQ1.bit.CONV01 = 0x1;
       AdcRegs.ADCCHSELSEQ1.bit.CONV02 = 0x2;
       AdcRegs.ADCCHSELSEQ1.bit.CONV03 = 0x3;
       AdcRegs.ADCCHSELSEQ2.bit.CONV04 = 0x4;
       AdcRegs.ADCCHSELSEQ2.bit.CONV05 = 0x5;
       AdcRegs.ADCCHSELSEQ2.bit.CONV06 = 0x6;
    
       AdcRegs.ADCTRL1.bit.CONT_RUN = 1;       // Setup continuous run
    
    
    // Step 5. User specific code, enable interrupts:
       IER |= M_INT1;
       IER |= M_INT3;
    
       // Enable TINT0 in the PIE: Group 1 interrupt 7
          PieCtrlRegs.PIEIER1.bit.INTx7 = 1;
    
          // Enable EPWM INTn in the PIE: Group 3 interrupt 1-3
             PieCtrlRegs.PIEIER3.bit.INTx1 = 1;
             PieCtrlRegs.PIEIER3.bit.INTx2 = 1;
             PieCtrlRegs.PIEIER3.bit.INTx3 = 1;
    
          // Clear SampleTable
             for (i=0; i<BUF_SIZE; i++)
             {
               SampleTable[i] =0;
               SampleTable1[i]=0;
               SampleTable2[i]=0;
               SampleTable3[i]=0;
               SampleTable4[i]=0;
               SampleTable5[i]=0;
               SampleTable6[i]=0;
    
             }
    
             AdcRegs.ADCTRL2.all = 0x2000;
    
    
         // Enable global Interrupts and higher priority real-time debug events:
            EINT;   // Enable Global interrupt INTM
            ERTM;   // Enable Global realtime interrupt DBGM
    
    
          // Step 6. IDLE loop. Just sit and loop forever (optional):
          for(;;);
    
     }
    
    interrupt void cpu_timer0_isr(void)
    {
       GpioDataRegs.GPBSET.bit.GPIO34 = 1;  // Set GPIO34 for monitoring
       CpuTimer0.InterruptCount++;
    
    ///********************** B - Sense the output voltages and inductor currents  **********************///////
    
       while (AdcRegs.ADCST.bit.INT_SEQ1== 0) {} // Wait for interrupt
       AdcRegs.ADCST.bit.INT_SEQ1_CLR = 1;
       SampleTable[i]  = ((AdcRegs.ADCRESULT0>>4));               //FC Current Sensing
       SampleTable1[i] = ((AdcRegs.ADCRESULT1>>4));             // Battery current Sensing
       SampleTable2[i] = ((AdcRegs.ADCRESULT2>>4));             //  Sensing
       SampleTable3[i] = ((AdcRegs.ADCRESULT3>>4));             //  Battry Voltage Sensing
       SampleTable4[i] = ((AdcRegs.ADCRESULT4>>4));           //  Load current Sensing
       SampleTable5[i] = ((AdcRegs.ADCRESULT5>>4));           //  Load voltage Sensing
       SampleTable6[i] = ((AdcRegs.ADCRESULT6>>4));
       //z =((AdcRegs.ADCRESULT3>>4));
       // Write your code here
       	  I_sensor_FC	 =(float) SampleTable[i]*7.326007326e-4-IDC_offset; 		// Current sensor output = ADC * 3/4095 - IDC_offset ,IDC_offset=-0.1333
          I_sensor_Batt  =(float) SampleTable1[i]*7.326007326e-4- IDC1_offset;		//IDC1_offset=-0.116
          I_sensor_Load  =(float) SampleTable4[i]*7.326007326e-4- IDC2_offset;		//IDC_offset=-0.13
          Vsensor_Batt	 =(float) SampleTable3[i]*7.326007326e-4-VDC_offset; 		// Voltage sensor output = ADC * 3/4095 - VDC_offset
          Vsensor_Load	 =(float) SampleTable5[i]*7.326007326e-4-VDC1_offset;
          Vsensor_FC	 =(float) SampleTable6[i]*7.326007326e-4-VDC2_offset;
    
          //IL=(Isensor_out-2.46)*7.5583; //current sensor measurement
          //IL=((I_sensor_new-2.43)/0.13);
       // IL=(I_sensor_new)*factor_bidir; //bidirectional current output
    
         ILfc		=(float) ((I_sensor_FC-1.5)/0.05);				//Fuel cell input current
         ILbatt		=(float) ((I_sensor_Batt-1.5)/0.05);			//battry input current
         Iload		=(float) ((I_sensor_Load-1.5)/0.05);			//Load current
         Vin_batt 	=(float) (Vsensor_Batt*26.667);					//Battery Voltage
         Vo			=(float) (Vsensor_Load* 29.1);					//output voltage
         VFC		=(float) (Vsensor_FC* 29.1);					//Fuelcell voltage
    
        //fuel cell current current control
         yk=ILfc;
         	 	 	 ek=rk-yk;
               		      uk = DCL_runPID(&pid1,rk,yk,lk); 			//� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)
    
               		           	d = uk;
               		           	if(d<=0.3)
               		           	      		{
               		           	      	    	d = 0.3;					                      // Lower limit for duty ratio
               		           	      	    }
               		           	      	if(d>=0.7)
               		           	      	 	{
               		           	      	    	d = 0.7;										 // Upper limit for duty ratio
               		           	      	 	}
    
    
    
    
    
    
    // Outer voltage loop
     yk1=Vo;
     rk1=voltage_ref;
     ek1=rk1-yk1;
     uk1 = DCL_runPID(&pid2,rk1,yk,lk1); //� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)
    
       if(uk1<=-5)
             		{
             	    	uk1 = -4;
             		}			                      // Lower limit for duty ratio
             	if(uk1>=5)
             	 	{
             	    	uk1 = 4;										 // Upper limit for duty ratio
             	 	}
    
        yk2=ILbatt;
       	rk2=uk1;//current ref
    	ek2=rk2-yk2;
        uk2= DCL_runPID(&pid3,rk2,yk2,lk2); //� Reference input current: r(k) � Feedback input: y(k) � Saturation input: l(k) � Control output: u(k)
    
    d1=uk2;
    
      // d =0.5 ;
          	if(d1<=0.3)
          		{
          	    	d1 = 0.3;
          		}			                      // Lower limit for duty ratio
          	if(d1>=0.7)
          	 	{
          	    	d1 = 0.7;										 // Upper limit for duty ratio
          	 	}
    
          	//Update duty ratio to compare register
    
    
          	 EPwm1Regs.CMPA.half.CMPA = d*10000;//duty pulse of fuel cell boost pin no.-01
          	// TBPRD = fCPU / ( 2 * fPWM *CLKDIV * HSPCLKDIV)
    
          	 EPwm2Regs.CMPA.half.CMPA = d1*10000;//duty pulse of batt-bidir pin no.-03
    
          	 PieCtrlRegs.PIEACK.all = PIEACK_GROUP1;
          	 GpioDataRegs.GPBCLEAR.bit.GPIO34 = 1;
    
    
          	 static Uint16 index=0;
          	AdcBuf[index] = _IQmpy(AdcFsVoltage, _IQ16toIQ((_iq)AdcRegs.ADCRESULT2));
        	//AdcBuf[index] =  Vsensor_Batt;
          	/*** Call the filter function ***/
          		xBuffer[0] = AdcBuf[index];				// Add the new entry to the delay chain
          		AdcBufFiltered[index] = (IQssfir(xBuffer, coeffs, 5)/16777216.0);
          		rk=_IQtoF(AdcBufFiltered[index]);
          		       		 //yk=AdcBufFiltered[index];
          		index++;									// Increment the index
          		if(index == AdcBufLen) index = 0;			// Rewind the pointer to beginning
          		// Reinitialize for next ADC sequence
          	  	AdcRegs.ADCTRL2.bit.RST_SEQ2 = 1;   	// Reset SEQ1
          	  	AdcRegs.ADCST.bit.INT_SEQ2_CLR = 1;		// Clear INT SEQ1 bit
          	  	//PieCtrlRegs.PIEACK.all = 1;   			// Acknowledge interrupt to PIE
    
       }
    
    
    
    void InitEPwm1Example()
    {
    
       EPwm1Regs.TBPRD = 10000;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
       EPwm1Regs.TBPHS.half.TBPHS = 0x0000;           // Phase is 0
       EPwm1Regs.TBCTR = 0x0000;                      // Clear counter
    
       // Setup TBCLK
       EPwm1Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
       EPwm1Regs.TBCTL.bit.PHSEN = TB_DISABLE;        // Disable phase loading
       	   	   	   	  // EPwm1Regs.TBCTL.bit.PRDLD = TB_SHADOW;
       	   	   	   	  // EPwm1Regs.TBCTL.bit.SYNCOSEL = TB_CTR_ZERO; // Sync down-stream module
       EPwm1Regs.TBCTL.bit.HSPCLKDIV = TB_DIV1;       // Clock ratio to SYSCLKOUT
       EPwm1Regs.TBCTL.bit.CLKDIV = TB_DIV1;
    
       EPwm1Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
       EPwm1Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
       EPwm1Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
       EPwm1Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;
    
       // Setup compare
       //EPwm1Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
       //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially
    
       // Set actions
       EPwm1Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
       EPwm1Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up
    
       EPwm1Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
       EPwm1Regs.AQCTLB.bit.CAD = AQ_SET;
    
    //      //Dead band setting
          EPwm1Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
          EPwm1Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
          EPwm1Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
          EPwm1Regs.DBRED = 1; // RED = 10 TBCLKs
    
    }
    
    void InitEPwm2Example()
    {
    
       EPwm2Regs.TBPRD = 10000;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
       EPwm2Regs.TBPHS.half.TBPHS =TB_DISABLE;           // Phase is dissable
       EPwm2Regs.TBCTR = 0x0000;                      // Clear counter
    
       // Setup TBCLK
       EPwm2Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
       EPwm2Regs.TBCTL.bit.PHSEN =TB_DISABLE;        // Disable phase loading
    
       EPwm2Regs.TBCTL.bit.SYNCOSEL = TB_CTR_ZERO; // Sync down-stream module
    
       //EPwm2Regs.TBCTL.bit.PHSDIR = TB_DOWN; // Count DOWN on sync (=120 deg)
       EPwm2Regs.TBCTL.bit.PRDLD = TB_SHADOW;
       //EPwm2Regs.TBCTL.bit.SYNCOSEL = 1;  //TB_SYNC_IN; // sync flow-through
    
       EPwm2Regs.TBCTL.bit.HSPCLKDIV = TB_DIV1;       // Clock ratio to SYSCLKOUT
       EPwm2Regs.TBCTL.bit.CLKDIV = TB_DIV1;
    
       EPwm2Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
       EPwm2Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
       EPwm2Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
       EPwm2Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;
    
       // Setup compare
       //EPwm2Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
       //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially
    
       // Set actions
       EPwm2Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
       EPwm2Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up
    
       EPwm2Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
       EPwm2Regs.AQCTLB.bit.CAD = AQ_SET;
    
    //      // Dead band setting
          EPwm2Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
          EPwm2Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
          EPwm2Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
          EPwm2Regs.DBRED = 1; // RED = 10 TBCLKs
    
    }
    
    void InitEPwm3Example()
    {
    
       EPwm3Regs.TBPRD = 624;                        // Set timer period = 16/150M *468 = 50us ; f=20kHz
       EPwm3Regs.TBPHS.half.TBPHS = 155;             // when phase =3, pd = 0 ; when phase = 3+ 155-dutycycle+dutycycleaux
       EPwm3Regs.TBCTR = 0x0000;                     // Clear counter
    
       // Setup TBCLK
       EPwm3Regs.TBCTL.bit.CTRMODE = TB_COUNT_UP; // Count up
       EPwm3Regs.TBCTL.bit.PHSEN = TB_ENABLE;        // Disable phase loading
    
       	   	          EPwm3Regs.TBCTL.bit.PHSDIR = TB_DOWN; // Count DOWN on sync (=120 deg)
          	  	  	  EPwm3Regs.TBCTL.bit.PRDLD = TB_SHADOW;
                      EPwm3Regs.TBCTL.bit.SYNCOSEL = 1;  //TB_SYNC_IN; // sync flow-through
    
       	   	   	   	   //EPwm2Regs.TBCTL.bit.PRDLD = TB_SHADOW;
       	   	   	   	   //EPwm3Regs.TBCTL.bit.SYNCOSEL = 0; // Sync down-stream module
       EPwm3Regs.TBCTL.bit.HSPCLKDIV = TB_DIV4;       // Clock ratio to SYSCLKOUT
       EPwm3Regs.TBCTL.bit.CLKDIV = TB_DIV4;
    
       EPwm3Regs.CMPCTL.bit.SHDWAMODE = CC_SHADOW;    // Load registers every ZERO
       EPwm3Regs.CMPCTL.bit.SHDWBMODE = CC_SHADOW;
       EPwm3Regs.CMPCTL.bit.LOADAMODE = CC_CTR_ZERO;
       EPwm3Regs.CMPCTL.bit.LOADBMODE = CC_CTR_ZERO;
    
       // Setup compare
       //EPwm3Regs.CMPA.half.CMPA = dutycycle_initial;                 // Set initial d = 0.5 intially
       //EPwm1Regs.CMPB  = dutycycle_initial;                 // Set initial d = 0.5 intially
    
       // Set actions
       EPwm3Regs.AQCTLA.bit.PRD = AQ_SET;             // Set PWM1A when tmr = Period
       EPwm3Regs.AQCTLA.bit.CAU = AQ_CLEAR;           // Clear PWM1A when tmr = Compare value when count up
    
       EPwm3Regs.AQCTLB.bit.CAU = AQ_CLEAR;          // Set PWM1B on Zero
       EPwm3Regs.AQCTLB.bit.CAD = AQ_SET;
    
    //      // Dead band setting
          EPwm3Regs.DBCTL.bit.OUT_MODE = DB_FULL_ENABLE; // enable Dead-band module
          EPwm3Regs.DBCTL.bit.POLSEL = DB_ACTV_HIC; // Active Hi complementary
          EPwm3Regs.DBFED = 1; // FED = 10 TBCLKs 10*16/150M = 1.0666uS
          EPwm3Regs.DBRED = 1; // RED = 10 TBCLKs
    
    }
    
     //===========================================================================
    // No more.
    //===========================================================================
    
    
    
    IQmathLib.hwhen i use this line rk = _IQtoF(AdcBufFilter[index]); i got errors as follows,

    Description Resource Path Location Type

    unresolved symbol __IQ24toF, first referenced in ./LPF1.obj EV1 C/C++ Problem

    Description Resource Path Location Type

    <a href="file:/c:/ti/ccsv7/tools/compiler/dmed/HTML/10234.html">#10234-D</a>  unresolved symbols remain EV1 C/C++ Problem

    Description Resource Path Location Type

    #10010 errors encountered during linking; "EV1.out" not built EV1 C/C++ Problem

    I attached file LPF2.c which is main file and filter.c and IQmathlib.h file .

  • It sounds like you haven't linked IQmath.lib. Check section 3.5 of the IQ math Quick Start guide.

    Which device are you using?

    Regards,

    Richard
  • Yeah I hadn't link that IQmath.lib .Even if i link that I got some new error as follows,

    Description Resource Path Location Type
    <a href="file:/c:/ti/ccsv7/tools/compiler/dmed/HTML/16008.html">#16008-D</a> file "../IQmath.lib<IQ24toF.obj>" specifies ISA revision "C2800", which is not compatible with ISA revision "C28FPU32" specified in a previous file or on the command line EV1 C/C++ Problem.

    I'm using Delfino f28335 of c2000 famiy.

  • I think this is because you've built for the FPU32 but are linking the fixed point version of IQmath.  Try linking "IQmath_fpu32.lib" instead of "IQmath.lib".  Both are in the \lib sub-directory in C2000Ware.

    Regards,

    Richard

  • Hello Ananda,

    Just wondering - were you able to resolve your issue?

    Did Richard's last reply do the trick for you?

    Thanks,
    John W.
  • yeah problem is resolve.

    Thanks.