CHAPTER 5 DIGITAL REALIZATION OF PID CONTROLLER AND INVERSE PARK S TRANSFORMATION

Size: px
Start display at page:

Download "CHAPTER 5 DIGITAL REALIZATION OF PID CONTROLLER AND INVERSE PARK S TRANSFORMATION"

Transcription

1 43 CHAPTER 5 DIGITAL REALIZATION OF PID CONTROLLER AND INVERSE PARK S TRANSFORMATION 5. INTRODUCTION Proportional Integral Derivative (PID) controller is one of the most common types of feedback controllers that are used in dynamic systems (Gopal 2003). This controller has been widely used in many different areas, such as aerospace, process control, manufacturing, robotics, automation and transportation systems. Implementation of PID controllers has gone through several stages of evolution from early mechanical and pneumatic designs to microprocessor-based systems. Recently, FPGAs have become an alternative solution for the realization of digital control systems. FPGA based controllers offer advantages such as high speed, complex functionality and low power consumption which were previously dominated by general-purpose microprocessor systems (Samet et al 998). These are attractive features from the embedded system design point of view. Previous work has reported the use of FPGAs in digital feedback control systems, such as Pulse Width Modulation (PWM) inverters (Jung et al 999), control of induction motors (Ferreira et al 2003), AC/DC converters (Zumel et al 2002) and variablespeed drives (Ricci and Le-Huy 2002). Another advantage of FPGA-based platforms is their capability to execute concurrent operations, allowing parallel architectural design of digital controllers (Zumel et al 2002).

2 44 Conventional implementation of FPGA-based controllers has not focused much on optimal use of hardware resources. These designs usually require a large number of multipliers and adders, and do not efficiently utilize the memory-rich characteristics of FPGAs. In the previous work (Chen et al 2000), the multiplier-based PID controller block takes up as much as 740 logic cells (LCs) or 64% utilization of the chip. Each LC contains a four-input Look-Up Table (LUT), a programmable flip-flop (FF) with a synchronous enable, a carry chain, and a cascade chain (Altera 2007). In the first part of this chapter, the design and digital realization of an efficient PID controller with anti-windup is presented. Based on the LUT scheme, the proposed PID controller reduces the cost of the FPGA design by enabling the chip to accommodate more logic and arithmetic functions while requiring less power consumption. Second part of the chapter discusses the digital realization of inverse Park s transformation using COordinate Rotation DIgital Computer (CORDIC) algorithm. 5.2 CONVENTIONAL PID CONTROLLER Controllers are often used to stabilize or improvise the response of a control system. The output of PID controllers will change the response of a system to a change in measurement or set point. A PID loop always adds its result to the current output, so that it effortlessly floats to a new steady output level. In digital control systems, simply increasing the number of bits can increase the accuracy of a digital compensator. The use of digital systems is cost effective even for small control systems. Another advantage offered by digital control is the flexibility of modifying the controller characteristics or of adapting the controller if plant dynamics change with operating conditions.

3 45 The general PID controller expression is, de( t) c( t) K e( t) K e( t) dt K (5.) p c r dt where c(t) = output of the controller, e(t) = error signal, K p = proportional gain, K c = K p /T i = integral gain, K r = K p.t d = derivative gain, T i = integral time constant and T d = derivative time constant. A proportional control (K p ) will have the effect of reducing the rise time. An integral control (K c ) will have the effect of eliminating the steadystate error, summing even a small error over time, produces a drive signal large enough to move the system towards a smaller error but it may make the transient response worse. A derivative control (K r ) will have the effect of increasing the stability of the system, reducing the overshoot and ringing and also improving the transient response. The PID controller, being a suitable combination, helps to get the output in a short time, with minimal overshoot and little error. Referring to Figure 5., the controller compares a measured value from a process (Vsensor) with a set point value (Vset). The error signal (Verror) is used to calculate a correction to the input variable of the process so that the correction will remove error in the output.

4 46 Figure 5. General block diagram of PID controller 5.2. Integrator wind up Integrator wind up is a phenomenon of interaction between integral action and saturation. For a control system with wide range of operating conditions, it may happen that the control variable may reach the actuator limits. When this happens, the feedback loop is broken and the system runs as an open loop system because the actuator will remain at its limit, independent of the process output. The integrator continually integrates the error signal, which may become very large or colloquially it winds up. If the controlled process has a positive gain and if a positive set-point change occurs, then controller will try to reduce the error between set point and the output, which is initially positive. The integral component will sum these positive errors to generate the necessary integral action. An overshoot occurs, whereupon the errors become negative. However, the direction of the control signal will not change to compensate if the sum of the positive errors occurred earlier, but dominates in which case the overshoot becomes prolonged. The direction of control action will change, only when the contribution of negative errors cancels the accumulated positive errors sufficiently. This phenomenon is known as integral windup or reset windup.

5 Concept of anti-windup Integrator windup can be avoided by making sure that the integral is kept at a proper value when the actuator saturates, so that the actuator avoids bouncing several times between high and low values and the controller is ready to resume action. This is accomplished by a technique called anti wind-up. There are four methods for dealing with windup in a controller:. Conditional Integration: If the controller output is saturated and input and output are of the same sign, then set integrator input to zero. 2. Limited Integration: If the integrator is saturated and controller input is of the same sign, then set integrator input to zero. 3. Tracking Anti Wind-up: If the controller output is saturated, reduce the integrator input by some constant times the difference between unsaturated and saturated controller output.

6 48 4. Modified Tracking Anti Wind-up: Limit integrator input by a constant times the sum of integral output (I(k)) and saturated proportional and derivative output (P(k) + D(k)) so that if either of those two components exceeds the limit, the integrator is off. In this work modified tracking anti-windup approach is followed. 5.3 DIGITAL PID CONTROLLER MODELING AND SIMULATION In a PID controller, the three different signal paths (P, I and D elements) are fed by input as shown in Figure 5.. To implement a continuous time control law given in Equation (5.) in a digital computer, the three paths are discretized as shown in Equations (5.2) to (5.4). The digital PID controller based on Equations (5.2) to (5.4) is shown in Figure 5.2. P(k) = K p.e(k) (5.2) I(k) = K i.(e(k)+e(k-)]+i(k-)) (5.3) D(k) = K d.(e(k) e(k -)) (5.4) T where K d = K r /T s, K i = K s c and T s is the sampling period. In Figure 5.2, 2 r(k) is the reference, f(k) is the feedback and c(k) is the output.

7 49 Figure 5.2 Block diagram of the proposed digital PID controller with anti-windup The anti-windup phenomenon in this controller is realized on the basis of actuator model. The actuator routes out the appropriate signal based on following criteria:. When the actuator reaches the saturation, the integral is cut off and the PD signal serves as the controller output. 2. When the input to the actuator goes below minimum, the controller output assumes the minimum value of zero. 3. When the actuator is in the linear region, the PID signal becomes the controller output. The controller output thus obtained is given to the process for further manipulations.

8 Derivation of controller constants The general PID controller expression in s domain is, G(s) K c K p K rs (5.5) s Equation (5.5) can be approximated as G(s) k(s a) s 2 (5.6) where K p = 2ak, K c = ka 2 and K r =k. The possible set of values of k and a, which satisfies maximum overshoot of less than 0% and above 5% and settling time (2% tolerance) of less than 2.6 seconds coupled with a plant having a transfer function,.2 g(s), are determined as 2.2 and 0.9 respectively s.86s 2.5s using Matlab script. Figure 5.3 shows these results and their corresponding overshoot and settling time as 7.72% and 2.29 seconds respectively. From these values of k and a, K p, K c and K r are calculated as 3.96,.782 and 2.2 respectively (Equation (5.6)). Further K p, K i and K d used in Equations (5.2) to (5.4) are calculated as 4, and 2200 (T s = ms) respectively. These values of K p, K i and K d are used to implement the digital PID controller. Figure 5.4 shows the step response of a system for three different cases namely, the system as uncompensated, compensated only for peak overshoot and compensated for peak overshoot and settling time constraints. The plant taken for this purpose is given in Equation (5.7), as

9 5.2 h(s) s.86s 2.5s (5.7) Figure 5.3 Result of Matlab script to calculate PID coefficients 5.4 DIGITAL REALIZATION OF PID CONTROLLER The rounded off controller constants determined from Matlab script are used to implement the PID controller in FPGA. Figure 5.5 shows the flowchart used for the digital realization of PID controller. The following points briefly discuss the algorithm adopted in the flowchart: The position of the motor is continuously monitored and taken as feedback signal. An optical encoder is used for this purpose.

10 52 The output of the optical encoder is read by the FPGA and by using suitable calibration the current speed of the motor will be calculated. The current speed will be compared with the reference speed using the comparator and the error will be found. Then the proportional and integral action will be calculated based on the error and the proportional and integral constants like K p and K i respectively. After the integral action is calculated, it will be checked for saturation. Here since a 6-bit PWM is proposed to be used if the value is exceeding or if it is negative then the integral output is reset. Then the PI action is calculated and again checked for saturation. If the value exceed then it will be saturated to 65536, otherwise if the value is negative the PI action is forced to zero. Figure 5.4 Step response of PID controller Simulink environment

11 53 Start read the output of the sensor and calculate the current speed read the reference speed False if ref_speed >= current_speed True error = current_speed - ref_speed dir = error = ref_speed - current_speed dir = 0 p_action = kp * error d_action = kd * (error - prev_error) i_action = ki * (error + prev_error) + prev_i_action prev_i_action = i_action prev_error = error i_action >= i_action <= 0 False Cont_ cont True Figure 5.5 Flowchart VHDL coding for the PID controller

12 54 cont cont_ i_action_mod = 0 i_action_mod = i_action control_action = p_action + d_action + i_action_mod False control_action >= True control_action <= 0 False flag = 0 True control_action_saturated = 0 flag = control_action_saturated = flag = flag == 0 False True control_action_saturated = control_action control_action_saturated to the next module end Figure 5.5 (contd.,) Flowchart VHDL coding for the PID controller The simulation result as obtained from Quartus II simulation is shown in Figure 5.6. In Figure 5.6, where control_action_saturated is the output variable. This will saturate to if the integrator gets into wind-up phenomenon. The signal max_hall_voltage (0 volts) is a constant used to store the maximum sensor voltage from the hall sensor when the machine is running at its rated speed which is given in the variable max_speed_srm

13 55 (4000 rpm). The current speed of the machine is calculated from the feed back signal namely fb_hall_voltage (7 volts). The speed at which the motor is expected to run is given in ref_speed (3000 rpm). The output of the PID controller is 0,836 which is to be fed as input to the next module of the complete control algorithm. The result is confirming to the analytical result as per the flowchart. Figure 5.6 PID controller simulation in Quartus II software 5.5 RESULT ANALYSIS The space, speed and power results obtained from the simulation and synthesis of digital anti-windup PID controller are compared with similar results proposed by Yuen Fong Chan et al (2007) in Table 5. and Samet et al (998) in Table 5.2. In Tables 5. and 5.2, the equivalent Logic Elements (LEs) are calculated based on the fact (Xilinx 2006) that each Xilinx s Configurable Logic Block (CLB) contains two Slices and Each Slice contains two 4 input LUTs (Logic Cells). The Logic Cell of Xilinx FPGA and Logic Element of Altera consists of one 4 input LUT each with minor difference in other logic. Hence the equation is each CLB is equivalent to 4.5 LEs (Altera 2007) and so each slice is equivalent to 2.25 LEs. A DPS block in an Altera

14 56 FPGA is a 9-bit by 9-bit multiplier. Figures 5.7 to 5.9 show the reports generated for the PID Controller program from the Quartus II software after the compilation, power analysis and timing analysis respectively. The space, power and speed results as can be found in Figures 5.7 to 5.9 are used for the comparison of the proposed architecture with earlier implementations. Figure 5.7 PID controller - Compilation report summary Figure 5.8 PID controller - Power analyzer report summary

15 57 Figure 5.9 PID controller Timing analyzer report summary Based on the comparison carried out in Table 5., the proposed architecture uses the lowest hardware resources and executes faster. This architecture which is inherently a parallel architecture was developed on a top-down modular approach using LUTs in the FPGA. Also this architecture was developed with structural style of modeling of the algorithm and was realized in an FPGA which has product-based logic. Due to these reasons, the proposed model could result in the best solution while the multiplier based architecture makes maximum use of hardware resources since it is based on the hardware multipliers present in the Spartan series of Xilinx FPGAs. Distributed Arithmatic (DA) based architecture is a bit serial computation algorithm that performs multiplication (using LUTs) has comparatively lower speed of execution due to the serial computation. For industrial control applications, speed and space demand suggests the proposed model with the added advantage of lowest power consumption. Table 5. Comparison of proposed PID controller with Yuen Fong Chan et al s proposals PID Controller Components Clock frequency Speed Power DA-based (6 bit) Multiplier-based (6 bit) Proposed model (32 bit) 437 Slices = 983 LEs 47 Slices = 258 LEs 47 ALUTs and nine 9-bit DSP blocks 47 MHz 36 ns 456 mw 5 MHz 67 ns 765 mw 50 MHz ns mw

16 58 Samet et al (998) have proposed three different architectures as listed in Table 5.2 for the digital realization of the PID controller without antiwindup compensation. They have used the form as given in Equation (5.8) while Yuen Fong Chan et al (2007) realized the PID controller in the same form as followed in this thesis work but in bit serial approach and multiplier based approach. The comparison of Samet et al proposals also suggests the proposed architecture to be a better solution for industrial control loop applications. C(k) C(k ) Ki Ki Kp Kd e(k) Kp 2Kd e(k ) Kde(k 2)) (5.8) 2 2 Table 5.2 Comparison of proposed PID controller with Samet et al s proposals PID Controller Components Hardware approach Speed Features Parallel architecture 52 CLBs = 2304 LEs Combinatorial operators 220 ns Faster execution Serial Architecture 76 CLBs = 792 LEs Two sequential logic operators 3360 ns Lower hardware resource Mixed Architecture 225 CLBs = 03 LEs Combinatorial operators with storage managed by FSM 660 ns Improved speed and cost reduction Proposed model 47 ALUTs and nine 9-bit DSP blocks Combinatorial operators in LUT approach ns High speed and lowest hardware resource

17 59 Masmoudi et al (997) have reported in their work, a PID controller that executes in.5 sec. This large time of execution is because the author tried out various approximations to obtain less space (with 3 multipliers and 7 adders). Another work reported by Jianyong Niu (2006) uses 383 LEs for a PI controller with 6-bit inputs and 32-bit output in an FPGA. The drawbacks of this work are, derivative action and anti wind-up phenomenon of the controller are not included. Lima et al (2006) have proposed a high end methodology for FPGA based PID controller implementation which offers advantages compared to custom-logic based designs. This methodology will be explored in the future works. The comparisons above conclude that the proposed architecture occupies less hardware resource, less power consumption and executes faster and is more suitable for control loops in industrial applications. 5.6 INVERSE PARK S TRANSFORMATION The Transformation of coordinates from the three phase balanced - - -q coordinate system (rotor reference frame). The inverse Park s transformation converts the two phase d-q - shows the transformation of d-q coordinate system into - system. These three transformations are used in the vector control of the AC machines such that the stator currents of the induction machine are separated into flux and torque-producing components and so facilitating the independent control of speed and torque as in DC motor control (Vas 998). Equations (5.9) and (5.0) are used for the inverse Park s transformation.

18 60 i = i d * cos - i q * sin (5.9) i = i d * sin + i q * cos (5.0) Figure 5.0 Transformation of d-q co-ordinate system into - co-ordinate system 5.7 CORDIC ALGORITHM CORDIC is an iterative algorithm for the calculation of rotation of two dimensional vectors in linear, circular and hyperbolic coordinate system, using only add and shift operations. The CORDIC algorithm has become a widely used approach for elementary functional evaluation when the silicon area is a primary constraint. Algorithm was written to calculate the sine and cosine values using shifts and adds, which was digitally implemented by Jack Volder called CORDIC. Through proper selection of scale factor, arc tangent radix and initial conditions, it is possible to determine the family of iterative equations involving shifts and adds to calculate trigonometric functions in a deterministic way (Andraka 998).

19 6 The trigonometric functions are based on vector rotations. CORDIC algorithm is of two operating modes, vectoring mode (VM) and rotation mode (RM). Its current applications are in the fields of digital signal processing, image processing, filtering, matrix algebra, etc.,. Different versions of CORDIC algorithm have been developed in order to increase the speed of computation of trigonometric functions. The speed enhancements in the algorithm have been achieved in diverse and creative ways (Jason Todd Arbaugh 2004). This work uses the classic CORDIC algorithm that utilizes small LUT and standard arithmetic functional units to perform calculations CORDIC algorithm for trigonometric functions Trigonometric functions are often used in embedded applications like filtering, motion control and waveform synthesis. For waveforms with few output points per cycle (for example one output point per degree), a lookup table will often suffice and indeed this method is optimal in that, it offers a reasonable compromise between speed and the need to use the microcontroller s memory efficiently. For waveforms with many output points per cycle (consider a waveform with 4096 points per cycle), the lookup table approach is often unfeasible because of the memory requirements. In the case of a waveform with 4096 output points per cycle, the lookup table alone would occupy at least 4kB of Flash and more often the table would take 8kB of memory. This precludes the use of such a lookup table approach on the lowest cost microcontrollers with their limited Flash memory.

20 62 It would appear from the above that, where many points are required on a waveform, it would be more practical to compute points on the waveform in real time when required and output them as they are computed. The CORDIC algorithm often offers the most elegant solution to the problem and it is astounding in its simplicity of implementation, efficiency and elegance. Inverse Park s Transformation involves the computations of sine and cosine values which is computed using CORDIC algorithm Mathematical background of CORDIC algorithm The CORDIC algorithm is used for finding out the position of the vector after rotation. With this basic principle of vector rotation, CORDIC algorithm can be efficiently used to calculate the values of sine and cosine functions. The unit vector, shown in Figure 5., y (Cos, Sin -x (, 0) x -y

21 63 Now consider a random unit vector with an initial rotation of angle i, y i ), then i (5.) i (5.2) the direction of rotation, the head of the vector will be at the summation (pos The new locations (x i+, y i+ ) are then found out from Equations (5.3) and (5.4). i + (5.3) i+ (5.4) Using the additive angle formulae for cosine and sine for rotating the vector in either direction and using Equations (5.) and (5.2), it is arrived that x y i i cos sin sin cos x y i i (5.5) Equation (5.5) is the standard two dimensional rotational equations which can be used to rotate any vector or group of vectors, with any initial rotation -2 ).

22 64 it becomes n, x y i i cos sin n n sin cos n n... cos sin sin cos. x y i i (5.6) The storage is reduced to a ROM table with n entries for sine and cosine values and makes the implementation of algorithm feasible. Now for each sub rotation Equation (5.6) involves 4 multiplications and 2 additions. The execution time is small for two additions when compared to four multiplications. Thereby Equation (5.6) could be rewritten to arrive at Equation (5.7) which reduces the number of multiplications to two. x y i i cos n tan n tan n... cos tan tan x y i i (5.7) The subsets of angles are to be selected for each sub rotation in order to minimize the calculation. In binary multiplication, multiplying by power of 2 is done easily by shifting the binary number to the correct number of positions to the left. It is possible to break the rotation into many steps, each of decreasing size and such that tan step) in each step The first eight steps of the set of rotations are shown in Table 5.3 to demonstrate the feasibility of this method. If the rotation steps are added up, it may be seen that the maximum total rotation is almost 00. Since the rotation

23 65 may be in a clockwise or counter clockwise direction, it is clear that these steps may be used to approximate any angle between (approximately) +00 and -00. Further, the decreasing size of the steps indicates that the approximation may be made arbitrarily accurate by increasing the number of steps of rotation. A small lookup table is used to store t step. The size of this table increases with log2 N where N is the number of steps of rotation. Table 5.3 The first eight rotational steps in the CORDIC algorithm ½ 0, ¼ / / / / / tan (2 -n ) so that a simple look up table as shown in Table 5.3 could be used and the value can be iteratively calculated with simple shift and add i is used to represent the sign of the current angle. For positive angle, the rotation is in negative direction while for negative angle, rotation i are {, 0,-}. With suitable substitution, Equation (5.7) becomes

24 66 x y i i n n cos(tan (2 ) n...cos(tan (2 ) n 2 2 n ) 2 2 ) x y i i (5.8) Let the scale factor K i = cos(tan - (2 -i i =0, K=. Equation (5.8) can now be written as i values x y i i K n... K n 2 n n 2 n ) ) x y i i (5.9) The value of K i in Equation (5.9) depends only on the number of steps used to approximate the total angle. If four steps are used to approximate the angle then K i is calculated as given in Equation (5.20). K i = cos( tan - (2-0 )) * cos(tan - (2 - )) * cos(tan - (2-2 )) * cos(tan - (2-3 )) = (5.20) number of steps. The same sequence may be used to calculate the value of K i for any To calculate the vector or angle iteratively, CORDIC algorithm uses the system of Equations (5.2) to (5.23) x i+ = x i i (2 -i ) y i (5.2) y i+ = y i + i (2 -i ) x i (5.22) z i+ = z i i (tan - (2 -i )) (5.23) i values are selected during each iteration of equations for values of residue angle z i i = for z i i = - for z i < 0.

25 67 As the rotation mode is used in this work, the value of angle z i is checked for each iteration. When z i becomes zero, the iteration is completed. In the case of vectoring mode, the value of y i is checked for each iteration and the iteration gets completed when y i becomes zero. 5.8 SIMULATION OF INVERSE PARK S TRANSFORMATION The following sections discuss the simulation procedures and results obtained from C coding, Matlab script and VHDL coding Simulation in C The realization of Inverse Park s Transformation using CORDIC algorithm is implemented using C language. The angle beta and the values of currents i d and i q are given - (2 -i ) is calculated and stored in an array of arctan table for every iteration. Then depending upon the sign of the residual angle, the values of sine and cosine are calculated. For normalization, the sine and cosine values are multiplied with a constant of K= (using 8 steps for the approximation of the angle).then the values of the currents i a and i b are calculated using the Equations (5.24) and (5.25). i a = x i+* i d - y i+* i q (5.24) i b =y i+* i d + x i+* i q (5.25) Figure 5.2 shows the flowchart for the implementation of inverse Park s transformation in C language.

26 68 START get the values of beta,id,iq initialize i=0 if i<000 False True arctantable[i]=atan(2 -i ) i=i+ False if i<000 True x i+ =x i +y i *2 -i y i+ =y i -x i *2 -i z i+=z i +arctantable[i] i=i+ True If beta<0 False x i+ =x i -y i *2 -i y i+ =y i +x i *2 -i z i+=z i -arctantable[i] i=i+ Normalize the result i a = x i+* i d - y i+* i q i b =y i+* i d + x i+* i q STOP Figure 5.2 Flowchart - Inverse Park s transformation in C

27 69 following: In Figure 5.2 the algorithm adopted is briefly described in the LUT for arctangent function is prepared with 000 values. The iterative algorithm given by Equations (5.2) to (5.23) is performed for 000 iterations with the input values of i d, i q and beta Simulation in Matlab Inverse Park s Transformation calculates i and i current values (stator reference frame) from the input currents i d and i q (rotor reference frame). The formula is implemented in Matlab script. The implemented algorithm for finding out the inverse Park s transformation is explained with the help of the block diagram as shown in Figure 5.3. The Matlab script includes the following functions for finding the inverse Park s transformation. InvPark, the main function takes i d, i q and theta as inputs. This main function calls cordic function which is used to carry out the CORDIC algorithm for the given theta value in 6 bits word length. The final values of this function as XD, YD and ZD which are respectively the cosine, sine and the residual angle are used to calculate the i and i values. CORDIC Cordic takes inputs as angle and i for iterations. It calls functions DtoB, RShift, BinSub, BinAdd and BtoD. K0 is the constant value calculated from K0=K0 *sqrt(+2 -(2i) ), with K0 initially assumed to be.0.

28 70 DtoB DtoB converts the decimal value to the binary value of 6 bits. X0, Y0, Z0 and Arctan values are calculated in binary from values.0/k0, 0.0, theta* /80 and atan(2 -i ) respectively. Rshift Rshift shifts the 6 bit data input to this function by i bits. This forms the binary shifting in the main equation. Xshift and Yshift are from the binary shifting of X i.2 -i and Y i.2 -i. Figure 5.3 Block diagram for inverse Park s transformation in Matlab

29 7 BinSub and BinAdd BinSub and BinAdd functions are used for subtracting and adding the X0, Y0, Z0, Yshift, Xshift and Arctan values as per the values of LSB of Z0. The values are stored in X, Y and Z respectively. When the number of iterations are completed the values are stored in X0,Y0 and Z0 from X,Y and Z respectively. BtoD BtoD function is used to convert the binary values into decimal. The X0,Y0 and Z0 values are converted into decimal and stored as XD,YD and ZD. i These functions are called by the main function InvPark and i and values are calculated using the formula given by i = XD.i d YD.i q i = YD.i d + XD.i q Simulation using VHDL Figure 5.4 shows the block diagram for inverse Park s transformation as realized using VHDL coding.

30 72 SC_CORPROC id iq X i P2R_CORDIC X i+ P2R_CORDIC Y i PIPE Y i+ X 0 Y 0 ia ib Figure 5.4 Block diagram for inverse Park s transformation in digital realization The whole algorithm is partitioned into three segments and each is coded in VHDL individually and finally integrated to get the complete algorithm. SC_CORPROC The angle program. The normalization constant is defined in this file. The sine and cosine values are calculated by the component P2R_CORDIC which takes angle as input. Then the inverse park s transformation is calculated and ia and ib values are found out. Table 5.4 lists the input and output ports used in the design.

31 73 P2R_CORDIC In this, a generate function is used which creates a shift register like structure to calculate the consecutive iterative values of sine and cosine functions. The current value obtained from P2R_CORDICPIPE is used in the calculation of the next value. P2R_CORDICPIPE This file stores the arctangent values in LUT form. The shifting and adding operations involved in CORDIC algorithm are performed in this file. Then the current value of sine and cosine is calculated and passed to P2R_CORDIC. Table 5.4 List of input/output ports for sine/cosine CORDIC core Port Width Direction Description CLK Input System Clock ENA Input Clock enable signal Ain 6 Input Angle input Sin 6 Output Sine output Cos 6 Output Cosine output All CORDIC Processor cores are built around three fundamental blocks, the pre-processor, the post-processor and the actual CORDIC core. The CORDIC core is built using a pipeline of CordicPipe blocks. Each CordicPipe block represents a single step in the iteration processes. Because of the arctan table used in the CORDIC algorithm, it converges in the range

32 74 of to + radians. To use the CORDIC algorithm over the entire 2 range, the input needs to be manipulated to fit in the to + radians range. This is handled by the pre-processor. The post-processor corrects this and places the CORDIC core s results in the correct quadrant. The CORDIC core is the heart of the CORDIC Processor Core. It performs the actual CORDIC algorithm. All iterations are performed in parallel, using a pipelined structure. Because of the pipelined structure, the core can perform a CORDIC transformation in each clock cycle. Thus ensures the highest throughput possible. Each pipe or iteration step is performed by the CordicPipe core. It contains the arctan table for each iteration and the logic needed to manipulate the X, Y and Z values. 5.9 SIMULATION RESULTS The following tables list the results obtained from the simulation of C, Matlab and VHDL codes Results of C Tables 5.5 and 5.6 show the results obtained for two sets of inputs. Figure 5.5 shows a sample snapshot of the result screen.

33 75 Table 5.5 Results from C for id=iq= id=iq= ia ib d e g r e e s Table 5.6 Results from C for id=iq=2 id=iq=2 sin cos ia ib d e g r e e s

34 76 Figure 5.5 Simulation result in C Results of Matlab Tables 5.7 and 5.8 show the results obtained for two sets of inputs. Figure 5.6 shows a sample snapshot of the result screen. Table 5.7 Results from Matlab for id=iq= id=iq= ia ib d e g r e e s

35 77 Table 5.8 Results from Matlab for id=iq=2 id=iq=2 sin cos ia ib d e g r e e s Figure 5.6 Simulation result in Matlab

36 Results of VHDL Table 5.9 shows the sine and cosine values obtained from CORDIC realization and Tables 5.0 and 5. list the results obtained for two sets of inputs. Table 5.9 sine and cosine values from VHDL 0 deg 30 deg 45 deg 60 deg 90 deg sin (hex format) cos (hex format) 0x0CC 0x3FFC 0x5A82 0x6EDC 0x8000 0x8000 0x6EDD 0x5A83 0x4000 0x0CC sin (decimal) cos (decimal) Table 5.0 Results from VHDL for id=iq= ia ib Angle Equi valent Actual Calcu lated Equi valent Actual Calculated

37 79 Table 5. Results from VHDL for id=iq=2 ia ib Angle Equi Calcu Actual valent lated Equivalent Actual Calculated Figures 5.7 to 5.9 display the simulation results obtained using Quartus II software for three different input angles. Figure 5.7 o

38 80 o o

39 8 5.0 COMPARATIVE ANALYSIS OF RESULTS The simulation results shown in Figures 5.7 to 5.9 handle the data in 6 bit format. To demonstrate the interpretation of results, sample calculation of the value of sin30 o is as explained below: 360 o 30 o o * (decimal) 555(hex format) Hence angle input is given as 555 in hexadecimal format. The core calculates the following value of sine for Zi=546: sin : 6380 (in decimal) = 3FFC (in hex format) The outputs represent values in the to + range. The results can be derived as follows: * Therefore the value of sin30 o obtained through the VHDL code is Similar interpretation is done for the cosine value and the output currents which are 6 bits wide. Table 5.2 lists a sample comparison of the results obtained from the three simulations with the theoretical values.

40 82 o Results Sine cosine ia ib Theory Matlab C VHDL Figures 5.20 to 5.22 show the compilation report summary, timing analyzer report summary and power analyzer report summary of the VHDL code. Figure 5.20 Compilation report Inverse Park s transformation

41 83 Figure 5.2 Timing analyzer report Inverse Park s transformation Figure 5.22 Power analyzer report Inverse Park s transformation From the compilation report, the total Logic Elements (LEs) used for the design is 907 with eight 9-bit DSP blocks. This is less compared to the conventional LUT based approach which normally requires large hardware resources, especially memory blocks, for the same accuracy (Chris Dick et al 2004, Kadam et al 2002). From the timing and power analyzer reports the design executes in 4.65 ns and dissipates mw. Ghariani et al (998) have reported in their work that CORDIC based Park s Transformation takes 3 sec for the execution. Hence the time of execution for the proposed design is less.

42 84 Results of FPGA based Park s transformation by Kharrat et al (2000), as shown in Table 5.3, reveal that the proposed architecture is a high speed and low cost design. Table 5.3 Results of Kharrat et al s (2000) proposals Approach Hardware resource Execution Time Remarks LUT based (28 points) 756 CLBs = 3402 LEs 520 ns Accuracy depends on the number of points LUT & Linear Interpolation method 092 CLBs = 494 LEs 782 ns Needs extra manipulation along with LUT for accuracy Mathematical Series based 648 CLBs = 296 LEs 52 ns Precision depends on the value of angle input and sine and cosine values are well defined only around zero CORDIC (rotation mode) 224 CLBs = 008 LEs 289 ns Minimum delay time and area with acceptable precision 5. CONCLUSION Resource savings are important in order to embed several PID controllers and other system components in the same FPGA. Resource savings are also an important factor in order to reduce the power dissipation and energy consumption which are important goals for embedded systems. In addition, due to the flexibility of using LUTs in FPGAs, the design method can be used to implement other algorithms such as adaptive control schemes. For the next generation of FPGAs in which A/D converters (ADCs) and D/A

43 85 converters (DACs) are built into the chip, the proposed PID controller architecture is more efficient in terms of hardware resources, power consumption and control performance when compared with the standard microcontroller Intellectual Property (IP) cores. This is due to the fact that custom-made logic can obviously outperform the general purpose microcontrollers. In the second part of this chapter, it is shown that VHDL results are as accurate as that of C and Matlab and it also confirms to the theoretical results with the major advantages of speed and space in digital realization of inverse Park s Transformation. Moreover, since the logic occupied compared to conventional LUT based approach is less the speed of execution is faster. In this work only inverse Park s transformation has been realized using CORDIC algorithm. The same may be extended to Park s transformation to make the optimal use of the limited hardware resources available in an FPGA for the complete vector control realization.

High speed all digital phase locked loop (DPLL) using pipelined carrier synthesis techniques

High speed all digital phase locked loop (DPLL) using pipelined carrier synthesis techniques High speed all digital phase locked loop (DPLL) using pipelined carrier synthesis techniques T.Kranthi Kiran, Dr.PS.Sarma Abstract DPLLs are used widely in communications systems like radio, telecommunications,

More information

EFFICIENT FPGA IMPLEMENTATION OF 2 ND ORDER DIGITAL CONTROLLERS USING MATLAB/SIMULINK

EFFICIENT FPGA IMPLEMENTATION OF 2 ND ORDER DIGITAL CONTROLLERS USING MATLAB/SIMULINK EFFICIENT FPGA IMPLEMENTATION OF 2 ND ORDER DIGITAL CONTROLLERS USING MATLAB/SIMULINK Vikas Gupta 1, K. Khare 2 and R. P. Singh 2 1 Department of Electronics and Telecommunication, Vidyavardhani s College

More information

Rotation of Coordinates With Given Angle And To Calculate Sine/Cosine Using Cordic Algorithm

Rotation of Coordinates With Given Angle And To Calculate Sine/Cosine Using Cordic Algorithm Rotation of Coordinates With Given Angle And To Calculate Sine/Cosine Using Cordic Algorithm A. Ramya Bharathi, M.Tech Student, GITAM University Hyderabad ABSTRACT This year, 2015 make CORDIC (COordinate

More information

CHAPTER 4 DDS USING HWP CORDIC ALGORITHM

CHAPTER 4 DDS USING HWP CORDIC ALGORITHM 90 CHAPTER 4 DDS USING HWP CORDIC ALGORITHM 4.1 INTRODUCTION Conventional DDFS implementations have disadvantages in area and power (Song and Kim 2004b). The conventional implementation of DDS is a brute-force

More information

CHAPTER III THE FPGA IMPLEMENTATION OF PULSE WIDTH MODULATION

CHAPTER III THE FPGA IMPLEMENTATION OF PULSE WIDTH MODULATION 34 CHAPTER III THE FPGA IMPLEMENTATION OF PULSE WIDTH MODULATION 3.1 Introduction A number of PWM schemes are used to obtain variable voltage and frequency supply. The Pulse width of PWM pulsevaries with

More information

Implementing Logic with the Embedded Array

Implementing Logic with the Embedded Array Implementing Logic with the Embedded Array in FLEX 10K Devices May 2001, ver. 2.1 Product Information Bulletin 21 Introduction Altera s FLEX 10K devices are the first programmable logic devices (PLDs)

More information

Hardware Realization of Embedded Control Algorithm on FPGA

Hardware Realization of Embedded Control Algorithm on FPGA COMPUTATION TOOLS 1 : The Fifth International Conference on Computational Logics, Algebras, Programming, Tools, and Benchmarking Hardware Realization of Embedded Control Algorithm on FPGA Róbert Krasňanský,

More information

DYNAMICALLY RECONFIGURABLE PWM CONTROLLER FOR THREE PHASE VOLTAGE SOURCE INVERTERS. In this Chapter the SPWM and SVPWM controllers are designed and

DYNAMICALLY RECONFIGURABLE PWM CONTROLLER FOR THREE PHASE VOLTAGE SOURCE INVERTERS. In this Chapter the SPWM and SVPWM controllers are designed and 77 Chapter 5 DYNAMICALLY RECONFIGURABLE PWM CONTROLLER FOR THREE PHASE VOLTAGE SOURCE INVERTERS In this Chapter the SPWM and SVPWM controllers are designed and implemented in Dynamic Partial Reconfigurable

More information

CHAPTER 4 ANALYSIS OF LOW POWER, AREA EFFICIENT AND HIGH SPEED MULTIPLIER TOPOLOGIES

CHAPTER 4 ANALYSIS OF LOW POWER, AREA EFFICIENT AND HIGH SPEED MULTIPLIER TOPOLOGIES 69 CHAPTER 4 ANALYSIS OF LOW POWER, AREA EFFICIENT AND HIGH SPEED MULTIPLIER TOPOLOGIES 4.1 INTRODUCTION Multiplication is one of the basic functions used in digital signal processing. It requires more

More information

VECTOR CONTROL SCHEME FOR INDUCTION MOTOR WITH DIFFERENT CONTROLLERS FOR NEGLECTING THE END EFFECTS IN HEV APPLICATIONS

VECTOR CONTROL SCHEME FOR INDUCTION MOTOR WITH DIFFERENT CONTROLLERS FOR NEGLECTING THE END EFFECTS IN HEV APPLICATIONS VECTOR CONTROL SCHEME FOR INDUCTION MOTOR WITH DIFFERENT CONTROLLERS FOR NEGLECTING THE END EFFECTS IN HEV APPLICATIONS M.LAKSHMISWARUPA 1, G.TULASIRAMDAS 2 & P.V.RAJGOPAL 3 1 Malla Reddy Engineering College,

More information

Design and Simulation of PID Controller using FPGA

Design and Simulation of PID Controller using FPGA IJSTE - International Journal of Science Technology & Engineering Volume 2 Issue 10 April 2016 ISSN (online): 2349-784X Design and Simulation of PID Controller using FPGA Ankur Dave PG Student Department

More information

Chapter 10 Digital PID

Chapter 10 Digital PID Chapter 10 Digital PID Chapter 10 Digital PID control Goals To show how PID control can be implemented in a digital computer program To deliver a template for a PID controller that you can implement yourself

More information

Digital Logic, Algorithms, and Functions for the CEBAF Upgrade LLRF System Hai Dong, Curt Hovater, John Musson, and Tomasz Plawski

Digital Logic, Algorithms, and Functions for the CEBAF Upgrade LLRF System Hai Dong, Curt Hovater, John Musson, and Tomasz Plawski Digital Logic, Algorithms, and Functions for the CEBAF Upgrade LLRF System Hai Dong, Curt Hovater, John Musson, and Tomasz Plawski Introduction: The CEBAF upgrade Low Level Radio Frequency (LLRF) control

More information

Method We follow- How to Get Entry Pass in SEMICODUCTOR Industries for 2 nd year engineering students

Method We follow- How to Get Entry Pass in SEMICODUCTOR Industries for 2 nd year engineering students Method We follow- How to Get Entry Pass in SEMICODUCTOR Industries for 2 nd year engineering students FIG-2 Winter/Summer Training Level 1 (Basic & Mandatory) & Level 1.1 continues. Winter/Summer Training

More information

ASIC Implementation of High Throughput PID Controller

ASIC Implementation of High Throughput PID Controller ASIC Implementation of High Throughput PID Controller 1 Chavan Suyog, 2 Sameer Nandagave, 3 P.Arunkumar 1,2 M.Tech Scholar, 3 Assistant Professor School of Electronics Engineering VLSI Division, VIT University,

More information

AREA EFFICIENT DISTRIBUTED ARITHMETIC DISCRETE COSINE TRANSFORM USING MODIFIED WALLACE TREE MULTIPLIER

AREA EFFICIENT DISTRIBUTED ARITHMETIC DISCRETE COSINE TRANSFORM USING MODIFIED WALLACE TREE MULTIPLIER American Journal of Applied Sciences 11 (2): 180-188, 2014 ISSN: 1546-9239 2014 Science Publication doi:10.3844/ajassp.2014.180.188 Published Online 11 (2) 2014 (http://www.thescipub.com/ajas.toc) AREA

More information

FPGA Implementation of Digital Modulation Techniques BPSK and QPSK using HDL Verilog

FPGA Implementation of Digital Modulation Techniques BPSK and QPSK using HDL Verilog FPGA Implementation of Digital Techniques BPSK and QPSK using HDL Verilog Neeta Tanawade P. G. Department M.B.E.S. College of Engineering, Ambajogai, India Sagun Sudhansu P. G. Department M.B.E.S. College

More information

Evaluation of CORDIC Algorithm for the processing of sine and cosine functions

Evaluation of CORDIC Algorithm for the processing of sine and cosine functions International Journal of Business and Management Invention ISSN (Online): 2319 8028, ISSN (Print): 2319 801X Volume 6 Issue 3 March. 2017 PP 50-54 Evaluation of CORDIC Algorithm for the processing of sine

More information

DESIGN OF INTELLIGENT PID CONTROLLER BASED ON PARTICLE SWARM OPTIMIZATION IN FPGA

DESIGN OF INTELLIGENT PID CONTROLLER BASED ON PARTICLE SWARM OPTIMIZATION IN FPGA DESIGN OF INTELLIGENT PID CONTROLLER BASED ON PARTICLE SWARM OPTIMIZATION IN FPGA S.Karthikeyan 1 Dr.P.Rameshbabu 2,Dr.B.Justus Robi 3 1 S.Karthikeyan, Research scholar JNTUK., Department of ECE, KVCET,Chennai

More information

Design of Adjustable Reconfigurable Wireless Single Core

Design of Adjustable Reconfigurable Wireless Single Core IOSR Journal of Electronics and Communication Engineering (IOSR-JECE) e-issn: 2278-2834,p- ISSN: 2278-8735. Volume 6, Issue 2 (May. - Jun. 2013), PP 51-55 Design of Adjustable Reconfigurable Wireless Single

More information

A HARDWARE DC MOTOR EMULATOR VAGNER S. ROSA 1, VITOR I. GERVINI 2, SEBASTIÃO C. P. GOMES 3, SERGIO BAMPI 4

A HARDWARE DC MOTOR EMULATOR VAGNER S. ROSA 1, VITOR I. GERVINI 2, SEBASTIÃO C. P. GOMES 3, SERGIO BAMPI 4 A HARDWARE DC MOTOR EMULATOR VAGNER S. ROSA 1, VITOR I. GERVINI 2, SEBASTIÃO C. P. GOMES 3, SERGIO BAMPI 4 Abstract Much work have been done lately to develop complex motor control systems. However they

More information

CHAPTER 4 FUZZY BASED DYNAMIC PWM CONTROL

CHAPTER 4 FUZZY BASED DYNAMIC PWM CONTROL 47 CHAPTER 4 FUZZY BASED DYNAMIC PWM CONTROL 4.1 INTRODUCTION Passive filters are used to minimize the harmonic components present in the stator voltage and current of the BLDC motor. Based on the design,

More information

CHAPTER 4 FUZZY LOGIC CONTROLLER

CHAPTER 4 FUZZY LOGIC CONTROLLER 62 CHAPTER 4 FUZZY LOGIC CONTROLLER 4.1 INTRODUCTION Unlike digital logic, the Fuzzy Logic is a multivalued logic. It deals with approximate perceptive rather than precise. The effective and efficient

More information

Optimal Control System Design

Optimal Control System Design Chapter 6 Optimal Control System Design 6.1 INTRODUCTION The active AFO consists of sensor unit, control system and an actuator. While designing the control system for an AFO, a trade-off between the transient

More information

Current Rebuilding Concept Applied to Boost CCM for PF Correction

Current Rebuilding Concept Applied to Boost CCM for PF Correction Current Rebuilding Concept Applied to Boost CCM for PF Correction Sindhu.K.S 1, B. Devi Vighneshwari 2 1, 2 Department of Electrical & Electronics Engineering, The Oxford College of Engineering, Bangalore-560068,

More information

Tirupur, Tamilnadu, India 1 2

Tirupur, Tamilnadu, India 1 2 986 Efficient Truncated Multiplier Design for FIR Filter S.PRIYADHARSHINI 1, L.RAJA 2 1,2 Departmentof Electronics and Communication Engineering, Angel College of Engineering and Technology, Tirupur, Tamilnadu,

More information

CORDIC Algorithm Implementation in FPGA for Computation of Sine & Cosine Signals

CORDIC Algorithm Implementation in FPGA for Computation of Sine & Cosine Signals International Journal of Scientific & Engineering Research, Volume 2, Issue 12, December-2011 1 CORDIC Algorithm Implementation in FPGA for Computation of Sine & Cosine Signals Hunny Pahuja, Lavish Kansal,

More information

An Optimized Direct Digital Frequency. Synthesizer (DDFS)

An Optimized Direct Digital Frequency. Synthesizer (DDFS) Contemporary Engineering Sciences, Vol. 7, 2014, no. 9, 427-433 HIKARI Ltd, www.m-hikari.com http://dx.doi.org/10.12988/ces.2014.4326 An Optimized Direct Digital Frequency Synthesizer (DDFS) B. Prakash

More information

Nicolò Antonante Kristian Bergaplass Mumba Collins

Nicolò Antonante Kristian Bergaplass Mumba Collins Norwegian University of Science and Technology TET4190 Power Electronics for Renewable Energy Mini-project 19 Power Electronics in Motor Drive Application Nicolò Antonante Kristian Bergaplass Mumba Collins

More information

Design of stepper motor position control system based on DSP. Guan Fang Liu a, Hua Wei Li b

Design of stepper motor position control system based on DSP. Guan Fang Liu a, Hua Wei Li b nd International Conference on Machinery, Electronics and Control Simulation (MECS 17) Design of stepper motor position control system based on DSP Guan Fang Liu a, Hua Wei Li b School of Electrical Engineering,

More information

CHAPTER 6 CURRENT REGULATED PWM SCHEME BASED FOUR- SWITCH THREE-PHASE BRUSHLESS DC MOTOR DRIVE

CHAPTER 6 CURRENT REGULATED PWM SCHEME BASED FOUR- SWITCH THREE-PHASE BRUSHLESS DC MOTOR DRIVE 125 CHAPTER 6 CURRENT REGULATED PWM SCHEME BASED FOUR- SWITCH THREE-PHASE BRUSHLESS DC MOTOR DRIVE 6.1 INTRODUCTION Permanent magnet motors with trapezoidal back EMF and sinusoidal back EMF have several

More information

Hardware Implementation of Automatic Control Systems using FPGAs

Hardware Implementation of Automatic Control Systems using FPGAs Hardware Implementation of Automatic Control Systems using FPGAs Lecturer PhD Eng. Ionel BOSTAN Lecturer PhD Eng. Florin-Marian BÎRLEANU Romania Disclaimer: This presentation tries to show the current

More information

REALIZATION OF FPGA BASED Q-FORMAT ARITHMETIC LOGIC UNIT FOR POWER ELECTRONIC CONVERTER APPLICATIONS

REALIZATION OF FPGA BASED Q-FORMAT ARITHMETIC LOGIC UNIT FOR POWER ELECTRONIC CONVERTER APPLICATIONS 17 Chapter 2 REALIZATION OF FPGA BASED Q-FORMAT ARITHMETIC LOGIC UNIT FOR POWER ELECTRONIC CONVERTER APPLICATIONS In this chapter, analysis of FPGA resource utilization using QALU, and is compared with

More information

FPGA implementation of Induction Motor Vector Control using Xilinx System Generator

FPGA implementation of Induction Motor Vector Control using Xilinx System Generator 6th WSEAS International Conference on CIRCUITS, SYSTEMS, ELECTRONICS,CONTROL & SIGNAL PROCESSING, Cairo, Egypt, Dec 29-31, 2007 252 FPGA implementation of Induction Motor Vector Control using Xilinx System

More information

Mohd Ahmer, Mohammad Haris Bin Anwar and Amsal Subhan ijesird, Vol. I (XI) May 2015/422

Mohd Ahmer, Mohammad Haris Bin Anwar and Amsal Subhan ijesird, Vol. I (XI) May 2015/422 Implementation of CORDIC on FPGA using VHDL to compare word serial & pipelined architecture. Mohd Ahmer 1, Mohammad Haris Bin Anwar 2, Amsal Subhan 3 Lecturer 1, Lecturer 2 M.Tech. Student 3 Department

More information

Computer Architecture Laboratory

Computer Architecture Laboratory 304-487 Computer rchitecture Laboratory ssignment #2: Harmonic Frequency ynthesizer and FK Modulator Introduction In this assignment, you are going to implement two designs in VHDL. The first design involves

More information

Model-Based Design for Medical Applications. Rob Reilink, M.Sc Ph.D

Model-Based Design for Medical Applications. Rob Reilink, M.Sc Ph.D Model-Based Design for Medical Applications using HDL Coder Rob Reilink, M.Sc Ph.D DEMCON Profile 6 locations HIGHTECH SYSTEMS MEDICAL SYSTEMS EMBEDDED SYSTEMS INDUSTRIAL SYSTEMS & VISION OPTOMECHATRONIC

More information

INTRODUCTION. In the industrial applications, many three-phase loads require a. supply of Variable Voltage Variable Frequency (VVVF) using fast and

INTRODUCTION. In the industrial applications, many three-phase loads require a. supply of Variable Voltage Variable Frequency (VVVF) using fast and 1 Chapter 1 INTRODUCTION 1.1. Introduction In the industrial applications, many three-phase loads require a supply of Variable Voltage Variable Frequency (VVVF) using fast and high-efficient electronic

More information

Techniques for Implementing Multipliers in Stratix, Stratix GX & Cyclone Devices

Techniques for Implementing Multipliers in Stratix, Stratix GX & Cyclone Devices Techniques for Implementing Multipliers in Stratix, Stratix GX & Cyclone Devices August 2003, ver. 1.0 Application Note 306 Introduction Stratix, Stratix GX, and Cyclone FPGAs have dedicated architectural

More information

Single Chip FPGA Based Realization of Arbitrary Waveform Generator using Rademacher and Walsh Functions

Single Chip FPGA Based Realization of Arbitrary Waveform Generator using Rademacher and Walsh Functions IEEE ICET 26 2 nd International Conference on Emerging Technologies Peshawar, Pakistan 3-4 November 26 Single Chip FPGA Based Realization of Arbitrary Waveform Generator using Rademacher and Walsh Functions

More information

Section 1. Fundamentals of DDS Technology

Section 1. Fundamentals of DDS Technology Section 1. Fundamentals of DDS Technology Overview Direct digital synthesis (DDS) is a technique for using digital data processing blocks as a means to generate a frequency- and phase-tunable output signal

More information

The Comparative Study of FPGA based FIR Filter Design Using Optimized Convolution Method and Overlap Save Method

The Comparative Study of FPGA based FIR Filter Design Using Optimized Convolution Method and Overlap Save Method International Journal of Recent Technology and Engineering (IJRTE) ISSN: 2277-3878, Volume-3, Issue-1, March 2014 The Comparative Study of FPGA based FIR Filter Design Using Optimized Convolution Method

More information

FPGA Implementation of Adaptive Noise Canceller

FPGA Implementation of Adaptive Noise Canceller Khalil: FPGA Implementation of Adaptive Noise Canceller FPGA Implementation of Adaptive Noise Canceller Rafid Ahmed Khalil Department of Mechatronics Engineering Aws Hazim saber Department of Electrical

More information

FPGA Implementation of Wallace Tree Multiplier using CSLA / CLA

FPGA Implementation of Wallace Tree Multiplier using CSLA / CLA FPGA Implementation of Wallace Tree Multiplier using CSLA / CLA Shruti Dixit 1, Praveen Kumar Pandey 2 1 Suresh Gyan Vihar University, Mahaljagtapura, Jaipur, Rajasthan, India 2 Suresh Gyan Vihar University,

More information

CORDIC Based Digital Modulator Systems

CORDIC Based Digital Modulator Systems ISSN (Online) : 239-8753 ISSN (Print) : 2347-67 An ISO 3297: 27 Certified Organization Volume 3, Special Issue 5, July 24 Technology [IC - IASET 24] Toc H Institute of Science & Technology, Arakunnam,

More information

Effective Teaching Learning Process for PID Controller Based on Experimental Setup with LabVIEW

Effective Teaching Learning Process for PID Controller Based on Experimental Setup with LabVIEW Effective Teaching Learning Process for PID Controller Based on Experimental Setup with LabVIEW Komal Sampatrao Patil & D.R.Patil Electrical Department, Walchand college of Engineering, Sangli E-mail :

More information

Modeling & Simulation of PMSM Drives with Fuzzy Logic Controller

Modeling & Simulation of PMSM Drives with Fuzzy Logic Controller Vol. 3, Issue. 4, Jul - Aug. 2013 pp-2492-2497 ISSN: 2249-6645 Modeling & Simulation of PMSM Drives with Fuzzy Logic Controller Praveen Kumar 1, Anurag Singh Tomer 2 1 (ME Scholar, Department of Electrical

More information

CHAPTER 4 FIELD PROGRAMMABLE GATE ARRAY IMPLEMENTATION OF FIVE LEVEL CASCADED MULTILEVEL INVERTER

CHAPTER 4 FIELD PROGRAMMABLE GATE ARRAY IMPLEMENTATION OF FIVE LEVEL CASCADED MULTILEVEL INVERTER 87 CHAPTER 4 FIELD PROGRAMMABLE GATE ARRAY IMPLEMENTATION OF FIVE LEVEL CASCADED MULTILEVEL INVERTER 4.1 INTRODUCTION The Field Programmable Gate Array (FPGA) is a high performance data processing general

More information

CHAPTER 3 WAVELET TRANSFORM BASED CONTROLLER FOR INDUCTION MOTOR DRIVES

CHAPTER 3 WAVELET TRANSFORM BASED CONTROLLER FOR INDUCTION MOTOR DRIVES 49 CHAPTER 3 WAVELET TRANSFORM BASED CONTROLLER FOR INDUCTION MOTOR DRIVES 3.1 INTRODUCTION The wavelet transform is a very popular tool for signal processing and analysis. It is widely used for the analysis

More information

CHAPTER 3 VOLTAGE SOURCE INVERTER (VSI)

CHAPTER 3 VOLTAGE SOURCE INVERTER (VSI) 37 CHAPTER 3 VOLTAGE SOURCE INVERTER (VSI) 3.1 INTRODUCTION This chapter presents speed and torque characteristics of induction motor fed by a new controller. The proposed controller is based on fuzzy

More information

S.Nagaraj 1, R.Mallikarjuna Reddy 2

S.Nagaraj 1, R.Mallikarjuna Reddy 2 FPGA Implementation of Modified Booth Multiplier S.Nagaraj, R.Mallikarjuna Reddy 2 Associate professor, Department of ECE, SVCET, Chittoor, nagarajsubramanyam@gmail.com 2 Associate professor, Department

More information

Abstract: PWM Inverters need an internal current feedback loop to maintain desired

Abstract: PWM Inverters need an internal current feedback loop to maintain desired CURRENT REGULATION OF PWM INVERTER USING STATIONARY FRAME REGULATOR B. JUSTUS RABI and Dr.R. ARUMUGAM, Head of the Department of Electrical and Electronics Engineering, Anna University, Chennai 600 025.

More information

INF3430 Clock and Synchronization

INF3430 Clock and Synchronization INF3430 Clock and Synchronization P.P.Chu Using VHDL Chapter 16.1-6 INF 3430 - H12 : Chapter 16.1-6 1 Outline 1. Why synchronous? 2. Clock distribution network and skew 3. Multiple-clock system 4. Meta-stability

More information

Hydraulic Actuator Control Using an Multi-Purpose Electronic Interface Card

Hydraulic Actuator Control Using an Multi-Purpose Electronic Interface Card Hydraulic Actuator Control Using an Multi-Purpose Electronic Interface Card N. KORONEOS, G. DIKEAKOS, D. PAPACHRISTOS Department of Automation Technological Educational Institution of Halkida Psaxna 34400,

More information

Abstract of PhD Thesis

Abstract of PhD Thesis FACULTY OF ELECTRONICS, TELECOMMUNICATION AND INFORMATION TECHNOLOGY Irina DORNEAN, Eng. Abstract of PhD Thesis Contribution to the Design and Implementation of Adaptive Algorithms Using Multirate Signal

More information

CHAPTER 4 PID CONTROLLER BASED SPEED CONTROL OF THREE PHASE INDUCTION MOTOR

CHAPTER 4 PID CONTROLLER BASED SPEED CONTROL OF THREE PHASE INDUCTION MOTOR 36 CHAPTER 4 PID CONTROLLER BASED SPEED CONTROL OF THREE PHASE INDUCTION MOTOR 4.1 INTRODUCTION Now a day, a number of different controllers are used in the industry and in many other fields. In a quite

More information

3KDVH 6LQH *HQHUDWRU ZLWK 9DULDEOH3KDVH&RQWURO

3KDVH 6LQH *HQHUDWRU ZLWK 9DULDEOH3KDVH&RQWURO Digital Motor Control Library 3KDVH 6LQH *HQHUDWRU ZLWK 9DULDEOH3KDVH&RQWURO Component Name: 2-Phase Sine Generator with Variable Phase Control 2-Phase Sine Generator with Variable Phase Control 0 Inputs

More information

Fan in: The number of inputs of a logic gate can handle.

Fan in: The number of inputs of a logic gate can handle. Subject Code: 17333 Model Answer Page 1/ 29 Important Instructions to examiners: 1) The answers should be examined by key words and not as word-to-word as given in the model answer scheme. 2) The model

More information

Embedded Control Project -Iterative learning control for

Embedded Control Project -Iterative learning control for Embedded Control Project -Iterative learning control for Author : Axel Andersson Hariprasad Govindharajan Shahrzad Khodayari Project Guide : Alexander Medvedev Program : Embedded Systems and Engineering

More information

AutoBench 1.1. software benchmark data book.

AutoBench 1.1. software benchmark data book. AutoBench 1.1 software benchmark data book Table of Contents Angle to Time Conversion...2 Basic Integer and Floating Point...4 Bit Manipulation...5 Cache Buster...6 CAN Remote Data Request...7 Fast Fourier

More information

Speed Control of BLDC Motor Using FPGA

Speed Control of BLDC Motor Using FPGA Speed Control of BLDC Motor Using FPGA Jisha Kuruvilla 1, Basil George 2, Deepu K 3, Gokul P.T 4, Mathew Jose 5 Assistant Professor, Dept. of EEE, Mar Athanasius College of Engineering, Kothamangalam,

More information

Reconfigurable Hardware Implementation and Analysis of Mesh Routing for the Matrix Step of the Number Field Sieve Factorization

Reconfigurable Hardware Implementation and Analysis of Mesh Routing for the Matrix Step of the Number Field Sieve Factorization Reconfigurable Hardware Implementation and Analysis of Mesh Routing for the Matrix Step of the Number Field Sieve Factorization Sashisu Bajracharya MS CpE Candidate Master s Thesis Defense Advisor: Dr

More information

Switch Mode Power Conversion Prof. L. Umanand Department of Electronics System Engineering Indian Institute of Science, Bangalore

Switch Mode Power Conversion Prof. L. Umanand Department of Electronics System Engineering Indian Institute of Science, Bangalore Switch Mode Power Conversion Prof. L. Umanand Department of Electronics System Engineering Indian Institute of Science, Bangalore Lecture - 30 Implementation on PID controller Good day to all of you. We

More information

Chapter 4 Design of a Digital Tri-mode Controller

Chapter 4 Design of a Digital Tri-mode Controller Chapter 4 Design of a Digital Tri-mode Controller As described in section.4, digital control is not new in the field of Power Electronics. It is often associated with DP or other micro-processors. Generally

More information

Reference. Wayne Wolf, FPGA-Based System Design Pearson Education, N Krishna Prakash,, Amrita School of Engineering

Reference. Wayne Wolf, FPGA-Based System Design Pearson Education, N Krishna Prakash,, Amrita School of Engineering FPGA Fabrics Reference Wayne Wolf, FPGA-Based System Design Pearson Education, 2004 CPLD / FPGA CPLD Interconnection of several PLD blocks with Programmable interconnect on a single chip Logic blocks executes

More information

Chapter 5: Signal conversion

Chapter 5: Signal conversion Chapter 5: Signal conversion Learning Objectives: At the end of this topic you will be able to: explain the need for signal conversion between analogue and digital form in communications and microprocessors

More information

FIR_NTAP_MUX. N-Channel Multiplexed FIR Filter Rev Key Design Features. Block Diagram. Applications. Pin-out Description. Generic Parameters

FIR_NTAP_MUX. N-Channel Multiplexed FIR Filter Rev Key Design Features. Block Diagram. Applications. Pin-out Description. Generic Parameters Key Design Features Block Diagram Synthesizable, technology independent VHDL Core N-channel FIR filter core implemented as a systolic array for speed and scalability Support for one or more independent

More information

CHAPTER 2 CURRENT SOURCE INVERTER FOR IM CONTROL

CHAPTER 2 CURRENT SOURCE INVERTER FOR IM CONTROL 9 CHAPTER 2 CURRENT SOURCE INVERTER FOR IM CONTROL 2.1 INTRODUCTION AC drives are mainly classified into direct and indirect converter drives. In direct converters (cycloconverters), the AC power is fed

More information

Pre-distortion. General Principles & Implementation in Xilinx FPGAs

Pre-distortion. General Principles & Implementation in Xilinx FPGAs Pre-distortion General Principles & Implementation in Xilinx FPGAs Issues in Transmitter Design 3G systems place much greater requirements on linearity and efficiency of RF transmission stage Linearity

More information

A LOW-COST SOFTWARE-DEFINED TELEMETRY RECEIVER

A LOW-COST SOFTWARE-DEFINED TELEMETRY RECEIVER A LOW-COST SOFTWARE-DEFINED TELEMETRY RECEIVER Michael Don U.S. Army Research Laboratory Aberdeen Proving Grounds, MD ABSTRACT The Army Research Laboratories has developed a PCM/FM telemetry receiver using

More information

Step vs. Servo Selecting the Best

Step vs. Servo Selecting the Best Step vs. Servo Selecting the Best Dan Jones Over the many years, there have been many technical papers and articles about which motor is the best. The short and sweet answer is let s talk about the application.

More information

Sensors and Sensing Motors, Encoders and Motor Control

Sensors and Sensing Motors, Encoders and Motor Control Sensors and Sensing Motors, Encoders and Motor Control Todor Stoyanov Mobile Robotics and Olfaction Lab Center for Applied Autonomous Sensor Systems Örebro University, Sweden todor.stoyanov@oru.se 13.11.2014

More information

Design and synthesis of FPGA for speed control of induction motor

Design and synthesis of FPGA for speed control of induction motor International Journal of Physical Sciences ol. 4 (11), pp. 645-650, November, 2009 Available online at http://www.academicjournals.org/ijps ISSN 1992-1950 2009 Academic Journals Full Length Research Paper

More information

Sno Projects List IEEE. High - Throughput Finite Field Multipliers Using Redundant Basis For FPGA And ASIC Implementations

Sno Projects List IEEE. High - Throughput Finite Field Multipliers Using Redundant Basis For FPGA And ASIC Implementations Sno Projects List IEEE 1 High - Throughput Finite Field Multipliers Using Redundant Basis For FPGA And ASIC Implementations 2 A Generalized Algorithm And Reconfigurable Architecture For Efficient And Scalable

More information

STUDY ON THE REALIZATION WITH FPGA OF A MULTICARRIER MODEM

STUDY ON THE REALIZATION WITH FPGA OF A MULTICARRIER MODEM STUDY ON THE REALIZATION WITH FPGA OF A MULTICARRIER MODEM Galia Marinova 1 and Claude Fernandes 2 1 Technical University of Sofia, Telecommunications Faculty, Sofia, Bulgaria, gim@tu-sofia.bg 2 CNAM-Paris,

More information

Design of NCO by Using CORDIC Algorithm in ASIC-FPGA Technology

Design of NCO by Using CORDIC Algorithm in ASIC-FPGA Technology Advance in Electronic and Electric Engineering. ISSN 2231-1297, Volume 3, Number 9 (2013), pp. 1109-1114 Research India Publications http://www.ripublication.com/aeee.htm Design of NCO by Using CORDIC

More information

IMPLEMENTATION OF QALU BASED SPWM CONTROLLER THROUGH FPGA. This Chapter presents an implementation of area efficient SPWM

IMPLEMENTATION OF QALU BASED SPWM CONTROLLER THROUGH FPGA. This Chapter presents an implementation of area efficient SPWM 3 Chapter 3 IMPLEMENTATION OF QALU BASED SPWM CONTROLLER THROUGH FPGA 3.1. Introduction This Chapter presents an implementation of area efficient SPWM control through single FPGA using Q-Format. The SPWM

More information

Module 5. DC to AC Converters. Version 2 EE IIT, Kharagpur 1

Module 5. DC to AC Converters. Version 2 EE IIT, Kharagpur 1 Module 5 DC to AC Converters Version 2 EE IIT, Kharagpur 1 Lesson 38 Other Popular PWM Techniques Version 2 EE IIT, Kharagpur 2 After completion of this lesson, the reader shall be able to: 1. Explain

More information

An Optimized Wallace Tree Multiplier using Parallel Prefix Han-Carlson Adder for DSP Processors

An Optimized Wallace Tree Multiplier using Parallel Prefix Han-Carlson Adder for DSP Processors An Optimized Wallace Tree Multiplier using Parallel Prefix Han-Carlson Adder for DSP Processors T.N.Priyatharshne Prof. L. Raja, M.E, (Ph.D) A. Vinodhini ME VLSI DESIGN Professor, ECE DEPT ME VLSI DESIGN

More information

PID Implementation on FPGA for Motion Control in DC Motor Using VHDL

PID Implementation on FPGA for Motion Control in DC Motor Using VHDL IOSR Journal of VLSI and Signal Processing (IOSR-JVSP) Volume 6, Issue 3, Ver. II (May. -Jun. 2016), PP 116-121 e-issn: 2319 4200, p-issn No. : 2319 4197 www.iosrjournals.org PID Implementation on FPGA

More information

Keywords Double boost DC to DC Converter, integral-proportional control, PWM, ADC, FPGA. Fig1. Double Boost DC-DC converter Model

Keywords Double boost DC to DC Converter, integral-proportional control, PWM, ADC, FPGA. Fig1. Double Boost DC-DC converter Model Volume 3, Issue 9, September 2013 ISSN: 2277 128X International Journal of Advanced Research in Computer Science and Software Engineering Research Paper Available online at: www.ijarcsse.com FPGA Implementation

More information

Design of double loop-locked system for brush-less DC motor based on DSP

Design of double loop-locked system for brush-less DC motor based on DSP International Conference on Advanced Electronic Science and Technology (AEST 2016) Design of double loop-locked system for brush-less DC motor based on DSP Yunhong Zheng 1, a 2, Ziqiang Hua and Li Ma 3

More information

Channelization and Frequency Tuning using FPGA for UMTS Baseband Application

Channelization and Frequency Tuning using FPGA for UMTS Baseband Application Channelization and Frequency Tuning using FPGA for UMTS Baseband Application Prof. Mahesh M.Gadag Communication Engineering, S. D. M. College of Engineering & Technology, Dharwad, Karnataka, India Mr.

More information

Digital Control of MS-150 Modular Position Servo System

Digital Control of MS-150 Modular Position Servo System IEEE NECEC Nov. 8, 2007 St. John's NL 1 Digital Control of MS-150 Modular Position Servo System Farid Arvani, Syeda N. Ferdaus, M. Tariq Iqbal Faculty of Engineering, Memorial University of Newfoundland

More information

An Energy Scalable Computational Array for Energy Harvesting Sensor Signal Processing. Rajeevan Amirtharajah University of California, Davis

An Energy Scalable Computational Array for Energy Harvesting Sensor Signal Processing. Rajeevan Amirtharajah University of California, Davis An Energy Scalable Computational Array for Energy Harvesting Sensor Signal Processing Rajeevan Amirtharajah University of California, Davis Energy Scavenging Wireless Sensor Extend sensor node lifetime

More information

A New High Speed Low Power Performance of 8- Bit Parallel Multiplier-Accumulator Using Modified Radix-2 Booth Encoded Algorithm

A New High Speed Low Power Performance of 8- Bit Parallel Multiplier-Accumulator Using Modified Radix-2 Booth Encoded Algorithm A New High Speed Low Power Performance of 8- Bit Parallel Multiplier-Accumulator Using Modified Radix-2 Booth Encoded Algorithm V.Sandeep Kumar Assistant Professor, Indur Institute Of Engineering & Technology,Siddipet

More information

COMBINATIONAL and SEQUENTIAL LOGIC CIRCUITS Hardware implementation and software design

COMBINATIONAL and SEQUENTIAL LOGIC CIRCUITS Hardware implementation and software design PH-315 COMINATIONAL and SEUENTIAL LOGIC CIRCUITS Hardware implementation and software design A La Rosa I PURPOSE: To familiarize with combinational and sequential logic circuits Combinational circuits

More information

A COMPARISON ANALYSIS OF PWM CIRCUIT WITH ARDUINO AND FPGA

A COMPARISON ANALYSIS OF PWM CIRCUIT WITH ARDUINO AND FPGA A COMPARISON ANALYSIS OF PWM CIRCUIT WITH ARDUINO AND FPGA A. Zemmouri 1, R. Elgouri 1, 2, Mohammed Alareqi 1, 3, H. Dahou 1, M. Benbrahim 1, 2 and L. Hlou 1 1 Laboratory of Electrical Engineering and

More information

FPGA high efficiency, low noise pulse frequency vector modulation Part II

FPGA high efficiency, low noise pulse frequency vector modulation Part II FPGA high efficiency, low noise pulse frequency vector modulation Part II Dr. Giulio Corradi, Diego Quagreda, Dr. Roberto Raffaetà, Xilinx - October 23, 2012 Part I MODULAR FOC From a practical standpoint

More information

VLSI Implementation of Digital Down Converter (DDC)

VLSI Implementation of Digital Down Converter (DDC) Volume-7, Issue-1, January-February 2017 International Journal of Engineering and Management Research Page Number: 218-222 VLSI Implementation of Digital Down Converter (DDC) Shaik Afrojanasima 1, K Vijaya

More information

Multiplier Design and Performance Estimation with Distributed Arithmetic Algorithm

Multiplier Design and Performance Estimation with Distributed Arithmetic Algorithm Multiplier Design and Performance Estimation with Distributed Arithmetic Algorithm M. Suhasini, K. Prabhu Kumar & P. Srinivas Department of Electronics & Comm. Engineering, Nimra College of Engineering

More information

CHAPTER 4 CONTROL ALGORITHM FOR PROPOSED H-BRIDGE MULTILEVEL INVERTER

CHAPTER 4 CONTROL ALGORITHM FOR PROPOSED H-BRIDGE MULTILEVEL INVERTER 65 CHAPTER 4 CONTROL ALGORITHM FOR PROPOSED H-BRIDGE MULTILEVEL INVERTER 4.1 INTRODUCTION Many control strategies are available for the control of IMs. The Direct Torque Control (DTC) is one of the most

More information

Digital Integrated CircuitDesign

Digital Integrated CircuitDesign Digital Integrated CircuitDesign Lecture 13 Building Blocks (Multipliers) Register Adder Shift Register Adib Abrishamifar EE Department IUST Acknowledgement This lecture note has been summarized and categorized

More information

Appendix B. Design Implementation Description For The Digital Frequency Demodulator

Appendix B. Design Implementation Description For The Digital Frequency Demodulator Appendix B Design Implementation Description For The Digital Frequency Demodulator The DFD design implementation is divided into four sections: 1. Analog front end to signal condition and digitize the

More information

Vector Arithmetic Logic Unit Amit Kumar Dutta JIS College of Engineering, Kalyani, WB, India

Vector Arithmetic Logic Unit Amit Kumar Dutta JIS College of Engineering, Kalyani, WB, India Vol. 2 Issue 2, December -23, pp: (75-8), Available online at: www.erpublications.com Vector Arithmetic Logic Unit Amit Kumar Dutta JIS College of Engineering, Kalyani, WB, India Abstract: Real time operation

More information

for amateur radio applications and beyond...

for amateur radio applications and beyond... for amateur radio applications and beyond... Table of contents Numerically Controlled Oscillator (NCO) Basic implementation Optimization for reduced ROM table sizes Achievable performance with FPGA implementations

More information

DMCode-MS(BL) MATLAB Library

DMCode-MS(BL) MATLAB Library Technosoft is a Third Party of Texas Instruments supporting the TMS320C28xx and TMS320F24xx DSP controllers of the C2000 family To help you get your project started rapidly, Technosoft offers the DMCode-MS(BL)

More information

Design and implementation of Open & Close Loop Speed control of Three Phase Induction Motor Using PI Controller

Design and implementation of Open & Close Loop Speed control of Three Phase Induction Motor Using PI Controller Design and implementation of Open & Close Loop Speed control of Three Phase Induction Motor Using PI Controller Ibtisam Naveed 1, Adnan Sabir 2 1 (Electrical Engineering, NFC institute of Engineering and

More information

SPIRO SOLUTIONS PVT LTD

SPIRO SOLUTIONS PVT LTD VLSI S.NO PROJECT CODE TITLE YEAR ANALOG AMS(TANNER EDA) 01 ITVL01 20-Mb/s GFSK Modulator Based on 3.6-GHz Hybrid PLL With 3-b DCO Nonlinearity Calibration and Independent Delay Mismatch Control 02 ITVL02

More information

DEPARTMENT OF ELECTRICAL AND ELECTRONIC ENGINEERING BANGLADESH UNIVERSITY OF ENGINEERING & TECHNOLOGY EEE 402 : CONTROL SYSTEMS SESSIONAL

DEPARTMENT OF ELECTRICAL AND ELECTRONIC ENGINEERING BANGLADESH UNIVERSITY OF ENGINEERING & TECHNOLOGY EEE 402 : CONTROL SYSTEMS SESSIONAL DEPARTMENT OF ELECTRICAL AND ELECTRONIC ENGINEERING BANGLADESH UNIVERSITY OF ENGINEERING & TECHNOLOGY EEE 402 : CONTROL SYSTEMS SESSIONAL Experiment No. 1(a) : Modeling of physical systems and study of

More information