Lab#3 - Student Manual_2010-11

22
ELEC443: CONTROL SYSTEMS I Laboratory Instructions Lab Instruction # 3 Position Control of a DC Motor using PD and PID Controllers Course Instructor: Dr. Keyvan Hashtrudi-Zaad Prepared and Modified by: Amir Haddadi Extracted from: Quanser Quarc-Based Position Control Instruction Manual October 2008 Department of Electrical and Computer Engineering Queen's University

description

Lab#3 - Student Manual_2010-11

Transcript of Lab#3 - Student Manual_2010-11

Page 1: Lab#3 - Student Manual_2010-11

ELEC443: CONTROL SYSTEMS I

Laboratory Instructions

Lab Instruction # 3

Position Control of a DC Motorusing PD and PID Controllers

Course Instructor: Dr. Keyvan Hashtrudi-Zaad

Prepared and Modified by: Amir HaddadiExtracted from: Quanser Quarc-Based Position Control Instruction Manual

October 2008

Department of Electrical and Computer Engineering

Queen's University

Page 2: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

1. Objectives

The objective of this experiment is to develop a feedback system that controls the angular position ofthe SRV02-ET rotary servo load shaft, using proportional-derivative (PD) and proportional-integral-derivative (PID) family of controllers to meet a set of time-domain specifications. In this process youwill be introduced to:

● Design a proportional-derivative (PD) compensator that controls the position of the servo loadshaft according to certain time-domain requirements.

● Effect of actuator saturation on PD controller design and performance.● Design a proportional-integral-derivative (PID) control to track a ramp reference signal and

reject constant disturbances.● Simulate the PD and PID controllers using the developed model of the plant and ensure the

specifications are met without any actuator saturation.● Implement the PD and PID controllers on the Quanser SRV02-ET servo module and evaluate

their performance.

2. Prerequisites

In order to successfully carry out this laboratory, the user should be familiar with the following:

● Quanser SRV02-ET module (e.g. actuator, sensors), Quanser UPM power amplifiers, QuanserMultiQ data acquisition card (DAC), terminal board, as described in Lab#1 Instruction Manual.For more information, you are encouraged to refer to the “Quanser SRV02-ET User Manual”available in the laboratory. NOTE: The SRV02-ET module is already connected to the UPMand DAC, and therefore you are not required to wire them.

● Transfer function fundamentals and the transfer function of the SRV02-ET system from inputvoltage to the load shaft angular speed as experimentally obtained in Lab#1. For information onQuanser QuaRC real-time control system, refer to the Lab#1 Instruction Manual or to the“Introduction to QuaRC” document available in the laboratory.

Page 2

Page 3: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

3. Overview of Files

Table 1 below lists and describes the various files supplied with this SRV02-ET Position Controllaboratory.

File Name Description

02 – SRV02 Position Control–Student Manual.pdf

This laboratory guide contains pre-lab and in-lab exercisesdemonstrating how to design and implement a position controlleron the Quanser SRV02-ET rotary plant using QuaRC.

setup_srv02_exp03_pos.m The main MATLAB script that sets the SRV02-ET motor andsensor parameters as well as its configuration-dependent modelparameters. Run this file only once before each experiment.

config_srv02.m Returns the configuration-based SRV02-ET model specificationsRm, kt, km, Kg, eta_g, Beq, Jeq, and eta_m, the sensor calibrationconstants K_POT, K_ENC, and K_TACH, and the UPM limitsVMAX_UPM and IMAX_UPM.

d_model_param.m Calculates the SRV02-ET model parameters K and tau based on thedevice specifications Rm, kt, km, Kg, eta_g, Beq, Jeq, and eta_m.

calc_conversion_constants.m Returns various conversions factors.

s_srv02_pos.mdl Simulink file that simulates a closed-loop PID controller for theSRV02-ET system.

q_srv02_pos.mdl Simulink file that implements a closed-loop PID position controlleron the SRV02-ET system using QuaRC.

Table 1: Files supplied with this SRV02 Position Control laboratory.

4. Pre-Lab Reading and Questions

4.1. PD versus P Controller

Figure 1 shows the block diagram of a PD controller C(s)=Kp+KDs, in a unity feedback system with theplant P(s) representing the transfer function of a DC motor from its voltage input to the angular positionoutput:

( )P sK

( ) s 1 s[1]

where Kp and KD are proportional and derivative controller gains and parameters and K are defined inLab #1.

Page 3

Page 4: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Q1: Find the 2nd-order transfer function of the system in Figure 1 from R(s)=d(s) to Y(s)=(t). Showthat with a proportional controller (assuming kd=0), it is not possible to place the poles of the closed-loop system at any arbitrary location. What is the loci of these poles? Show that with a PD controller, itis possible to put the poles of the closed loop system at any arbitrary location.

As discussed in the lectures, the two disadvantages of PD controllers in forward path are:

● A jump in the reference input appears in the error signal, which is then differentiated by the“Derivative” action of the PD controller, resulting in an impulse (spike) to the motor. A similarundesirable situation can happen when the motor initial angular position is not the same as thereference input at t=0.

● A zero is added to the transfer function of the closed-loop system. The zero can affect thetransient performance of the closed-loop second-order system when the location of the zero withrespect to the j axis is within 4 times the real value of the closed-loop poles.

Figure 1: Block diagram of a PD controlled DC motor, when PD controller is placed in the forward path.

4.1.1. PD Control Implementations:

Figure 2 shows the block diagram of an alternative implementation of the PD controller in which thederivative action is only applied to output, not the error signal. The control voltage to the SRV02-ETmotor in domain is represented as

( )Vm t kp ( )( )d t ( )l t kv

d

d

t( )l t

[2]

where d(t) is the set-point or reference load angle, and l(t) is the measured load shaft angle, and Vm(t)is the SRV02 input voltage. The block diagram of the PD control system is illustrated in Figure 3.Sincethe output does not change instantaneously, a smoother signal can be achieved by taking the derivativeof the output signal. This method has also the advantage of not adding an additional zero in the transferfunction of the system.

Page 4

Page 5: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Remark I: The motor angular velocity needed for the feedback path can be obtained by taking thederivative of the motor angle sensed by the encoder or potentiometer, or directly from the tachometer.

Remark II: In practice, the pure derivative is never used, due to the derivative kick created in thecontrol signal and also undesirable noise amplification due to the derivative action. Thus, it is usuallyreplaced by a first-order high-pass filter.

4.1.2. PD Controller Specifications and Design:

Q2: Find the 2nd-order transfer function of the system in Figure 2 from R(s)=d(s) to Y(s)=(t).n either way, the measured output, Y(s), is supposed to track the reference signal R(s) and the trackinghas to yield to certain specifications.

Figure 2: PD controller with derivative in the feedback loop.

The resulting transfer function of the SRV02-ET transfer function has the same structure of a standardsecond-order system characteristic polynomial

s2

2 n s n2 [3]

where n is the natural undamped frequency and is the damping ratio, which determine the transientperformance of the closed-loop system.

Q3: Find the control gains kp and kv as functions of natural frequency, n, and damping ratio, . to mapthe characteristic equation of the SRV02-ET closed-loop system to the standard characteristicpolynomial.

As explained in lectures and Lab#2, for a 2nd-order under-damped system with no zero, the maximumpercent overshoot and peak time are expressed in terms of the natural frequency and damping ratio as:

Page 5

Page 6: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

PO 100 e

1 2

tp

n 1 2

[4]

Figure 3: Block diagram of SRV02-ET PD position controlled

Generally speaking then, the damping ratio affects the shape of the response while the natural frequencyaffects the speed of the response.

Q4: Using equations [4], express the natural frequency and the damping ratio in terms of thepercentage overshoot and peak time specifications.

Q5: Calculate the minimum damping ratio and natural frequency required to meet the following timedomain specifications: PO=15% and tp=0.15 sec.

Q6: Calculate the maximum overshoot of the response (in radians) given a step set-point of 60 degrees,or d(t)=3.

Q7: Based on the nominal SRV02-ET model parameters, K and , found in Lab #1, calculate thecontrol gains needed to satisfy the above time-domain step response requirements.

Q8: By looking at Figure 2, what is the type of the system with respect to the input R(s)? Use finalvalue theorem to derive the steady-state error to unit step input. What is the steady-state angle?

4.1.3. Controller Gain Limits:

In any control design, another factor to be considered is actuator saturation. This is a nonlinear elementand is represented by a saturation block, as shown in Figure 4. Consider an SRV02-ET type setup

Page 6

Page 7: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

where the PC computes a control voltage. The control voltage is outputted by a digital-to-analogchannel of the data-acquisition device, Vdac(t), and then amplified by a power amplifier by a factor ofKa. The amplified voltage, Vamp(t), is saturated by either the maximum output voltage of the amplifier orthe limits of the motor (whichever is smaller). The input SRV02-ET voltage, Vm(t), is the effectivevoltage being applied to the motor.

Figure 4: Actuator saturation.

The limitations of the actuator must be taken into account when designing a controller. For instance, thevoltage entering the SRV02 motor should never exceed

Vmax 10.0 [ ]V. [5]

Q9: For the 60 degrees reference step given above, calculate the maximum proportional gain. Ignorethe velocity control. Is the kp designed above, to satisfy the specifications, below the maximumproportional gain?

4.2. PD Control Shortcomings

In this section, we will investigate the steady-state error due to a unit step disturbance or a ramp set-point. when using PD controller. As we will investigate, a PD controlled system has a steady state errorto a ramp signal and also is not capable of rejecting disturbance. Therefore, we will utilize a PIDcontroller

4.2.1. Steady-State Effect of Unit Step Disturbance using a PD Controller

Consider Figure 5, when the disturbance D(s) is a unit step signal.

Q10: Calculate the steady-state effect of a unit step disturbance when the input R(s) is zero. What doyou suggest to reduce/eliminate the effect of disturbance?

Page 7

Page 8: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Figure 5: Effect of disturbance on a PD controlled system.

4.2.2. Steady-state Error due to a Ramp Reference using PD Controller

In this section, the steady-state error to a ramp position input the PD controller is evaluated.

Q11: Given the ramp input R(s) = R0/s2, find the transfer function of the error for the closed-loopsystem. Find the steady-state error and evaluate it numerically given a ramp with a slope of R0=1.68rad/sec, the control gains found in Section 4.1.2, and the nominal model parameters derived in Lab #1:K=8.82 and =0.05 .

4.3. PID Control

Adding an integral control term increases the type of the system with respect to both the input anddisturbance, and thus can help to eliminate any steady-state error caused by a ramp set-point or a stepinput disturbance. The proportional-integral-derivative (PID) control command that will be used tocontrol the position of the SRV02-ET is of the form

V mt =k p[d t −lt ]ki∫[d t −lt ] dt−k v [ddtlt ] [6]

where Ki is the integral gain. The PID position control block diagram is shown in Figure 6.

Q12: Find the transfer function of the closed-loop system for the SREV02-ET , that is l(s)/d(s),using the time-domain PID control in Equation [6] or the block diagram in Figure 6. Assume the zeroinitial conditions, thus l(0-) = 0

Page 8

Page 9: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Figure 6: Block diagram of SRV02-ET position control with a PID controller.

4.3.1. Effect of Disturbance on the system using PID control

In this section, the steady-state effect of disturbance on the PID control system is evaluated.

Q13: Find the error transfer function of the output to the disturbance. Evaluate the steady-state effect ofthe unit step disturbance on the output when a PID controller is used.

4.3.2. Ramp Steady-State Error using PID

In this section, the steady-state error to a ramp input when PID controller is used is evaluated.

Q14: Find the transfer function of the SR02-ET closed-loop system from input to error, when PIDcontroller is used. Evaluate the steady-state error when a unit ramp input is applied.

4.3.3. Integral Gain Design

It takes a certain amount of time for the output response to track the ramp reference with zero steady-state error. This is called the “settling time” and it is determined by the value used for the integral gain.In this section, the integral gain is calculated based on the steady-state error that is obtained with the PDcontroller and the amount of voltage there is to spare.

In steady-state, the input ramp response error is constant and does not vary. Therefore, to design anintegral gain the velocity compensation can be neglected. Thus the PI controller

Page 9

Page 10: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

( )Vm t kp ( )( )d t ( )l t ki d

( )d t ( )l t t [7]

is being considered. When in steady-state, the expression can be simplified to

( )Vm t kp ess ki d

0

ti

ess t

.

[8]

The variable ti is the integration time. In the following, we will find the integral gain when taking theerror over 3.5 seconds ti=3.5 sec, based on the proportional gain found in Section 4.1.2, the maximumSRV02-ET voltage [5], the steady-state error yielded with the PD control calculated in Section 4.2.2.

V mt =k p esski ti ess

k i=−V mt k p ess

t iess

k i=28.7v

rad.sec

5. In-Lab Procedures

Students are asked to simulate the closed-loop PD and PID responses. Then, the PD and PID controllersare implemented on the actual SRV02-ET module.

5.1. Position Control Simulation

The s_srv02_pos Simulink diagram shown in Figure 7 is used to simulate the closed-loop positionresponse of the SRV02-ET when using either the PD or PID controllers. The SRV02-ET Model uses aTransfer Fcn block from the Simulink library to simulate the SRV02-ET system. The PID Controlsubsystem contains the PID control detailed in Section 4.3. When the integral gain is set to zero, thecontroller is essentially a PD controller. Before going through the step response exercises in Section5.1.2 and the ramp response questions in Section 5.1.3, go through Section 5.1.1 to configure the labfiles properly.

Page 10

Page 11: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Figure 7: Simulink model used to simulate the SRV02 closed-loop position response.

Lab Report Questions: You need to answer to the questions of the following sections in your post-lab report.

5.1.1. Setup for Position Control Simulation

Follow these steps to configure the lab properly:

1. Load the MATLAB software.

2. Browse through the Current Directory window in MATLAB and find the folder that containsthe SRV02 position controller files, e.g. s_srv02_pos.mdl.

3. Double-click on the s_srv02_pos.mdl file to open the Simulink diagram shown in Figure 7.

4. Double-click on the setup_srv02_exp03_spd.m file to open the setup script for the positioncontrol Simulink models.

5. Configure setup script: The controllers will be run on an SRV02-ET in the low-gearconfiguration with the disc load, as in labs#1 and 2. In order to simulate the SRV02-ETproperly, make sure the script is setup to match this configuration, i.e. theEXT_GEAR_CONFIG should be set to 'LOW' and the LOAD_TYPE should be set to 'DISC'.Also, ensure the ENCODER_TYPE, TACH_OPTION, K_CABLE, UPM_TYPE, andVMAX_DAC parameters are set according to the SRV02 system that is to be used in thelaboratory. Next, set CONTROL_TYPE to 'AUTO_PD'.

6. Run the script by selecting the Debug | Run item from the menu bar or clicking on the Runbutton in the tool bar. The messages shown in Text 1, below, should be generated in theMATLAB Command Window. The model parameters and specifications are loaded but the PIDgains are all set to zero – they need to be changed.

Page 11

Page 12: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

SRV02 model parameters: K = 8.82 rad/s/V tau = 0.0507 sSpecifications: tp = 0.15 s PO = 15 %Calculated PD control gains: kp = 3.44 V/rad kv = 0.032 V.s/radIntegral control gain for triangle tracking: ki = 0 V/rad/s

Text 1: Display message shown in MATLAB Command Window after running setup_srv02_exp03_pos.m.

5.1.2. Simulating Step Response using PD Controller

The closed-loop step position response of the SRV02-ET will be simulated using the PD controller toconfirm that the specifications in an ideal situation are satisfied and to verify that the motor is notsaturated. In addition, the effect of using a high-pass filter instead of a direct derivative is examined.

Follow these steps to simulate the SRV02-ET position response to the PD controller:

1. Open s_srv02_pos.mdl simulink file.

2. Select square in the Signal Type field of the SRV02-ET Signal Generator in order to generate astep reference.

3. Set the Amplitude (rad) gain block to /6 to generate a step with an amplitude of 60 degrees.

4. Inside the PID Control subsystem, set the Manual Switch is to the upward position so theDerivative block is used.

5. Open the load shaft position scope, theta_l (rad), and the motor input voltage scope, Vm (V).

6. Start the simulation. By default, the simulation runs for 5 seconds. The scopes should bedisplaying responses similar to Figures 8 and 9. Note that in the theta_l (rad) scope, the yellowtrace is the set-point position, while the purple trace is the simulated position (generated by theSRV02 Model block). This simulation is the called the Ideal PD response as it uses the PDcompensator with the derivative block.

7. Q1: Generate a MATLAB figure showing the Ideal PD position response and the ideal inputvoltage and attach it to your report. After each simulation run, each scope automatically savestheir response to a variable in the MATLAB workspace. That is, the theta_l (rad) scope savesits response to the variable called data_pos and the Vm (V) scope saves its data to the data_vmvariable. The data_pos variable has the following structure: data_pos(:,1) is the time vector,data_pos(:,2) is the set-point, and data_pos(:,3) is the simulated angle. For the data_vmvariable, data_vm(:,1) is the time and data_vm(:,2) is the simulated input voltage.

8. Q2: Measure the steady-state error, the percentage overshoot, and the peak time of thesimulated response. Does the response satisfy the specifications previously given in terms ofPO, tp, and zero steady state?

Page 12

Page 13: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Figure 8: Ideal PD position response. Figure 9: Ideal PD motor input voltage.

9. When implementing a controller on actual hardware it is generally not advisable to take thedirect derivative of a measured signal. For instance, when taking the derivative of the SRV02-ET encoder or potentiometer signal, any noise or spikes in the signal become amplified, whichthen gets multiplied by a gain and fed into the motor causing damage. To remove any high-frequency component in the velocity signal, a low-pass filter is placed in series with thederivative, i.e. taking the high-pass filter of the measured signal. However, as with anycontroller, the filter must be tuned properly or it have some adverse affects. Go to the PIDControl block and set the Manual Switch block to the downward position in order to enable thehigh-pass filter.

10. Start the simulation. The response in the scopes should still be similar to Figures 8 and 9. Thissimulation is the called the Filtered PD response, as it uses the PD compensator with the high-pass filter block.

11. Q3: Generate a MATLAB figure showing the Filtered PD position and input voltage responsesand attach it to your report.

12. Q4: Measure the steady-state error, peak time, and percentage overshoot. Are the previouslymentioned specifications still satisfied without saturating the actuator? Recall that the peak timeand percentage overshoot should not exceed the values given. Discuss the changes that werenoticed from the ideal response.

13. If the specifications are satisfied without overloading the servo motor, proceed to the nextsection to simulate the ramp response. If not ask your TA if you can proceed to the nextsection.

5.1.3. Simulating Ramp Response using PD and PID Controllers

The closed-loop ramp position response of the SRV02-ET will be simulated using the PD and PID

Page 13

Page 14: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

control systems. It will be verified that the zero steady-state error specifications is met without themotor going into saturation.

Follow these steps to simulated the SRV02-ET position response to the PD controller:

1. Run the setup file in the 'AUTO_PD' mode.

2. Open s_srv02_pos.mdl simulink file.

3. Select triangle in the Signal Type field of the SRV02-ET Signal Generator in order to generate aramp or triangular reference.

4. Set the Amplitude (rad) gain block to /3 to generate a step with an amplitude of 60 degrees.

5. Ensure the Frequency (Hz) field in the Triangle Waveform block is set to 0.4 Hz. This willgenerate a alternative increasing and decreasing ramp signal with the same slope used in thepre-lab exercises, that is R0=1.68 rad/sec . The slope is calculated from the TriangularWaveform amplitude, Amp, and frequency, f, using the expression

R0 4 Amp f [9]

6. Inside the PID Control subsystem, set the Manual Switch is to the downward position so theHigh-Pass Filter block is used.

7. Open the load shaft position scope, theta_l (rad), and the motor input voltage scope, Vm (V).

8. Start the simulation. The scopes should be displaying responses similar to Figures 10 and 11.

9. Q5: Generate a MATLAB figure showing the Ramp PD position response and its correspondinginput voltage trace. Attach the figure to your report.

10. Q6: Measure the steady-state error. Compare the simulation measurement with the steady-stateerror calculated in Pre-Lab.

Figure 10: Ramp response using PD. Figure 11: Input voltage of ramp tracking using PD.

11. Enter the integral gain designed in Section 4.33 in MATLAB. The PID controller will now besimulated.

12. Start the simulation. The Ramp PID response in the scopes should be similar to Figures 12 and

Page 14

Page 15: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

13.13. Q7: Generate a MATLAB figure showing the Ramp PID position response and its

corresponding input voltage. Attach the figure to your report.

Figure 12: PID ramp response. Figure 13: Input voltage using PID control.

14. Q8: Measure the steady-state error. Does the zero steady-state error specification satisfy withoutsaturating the actuator?

15. If the specification is satisfied without saturating the actuator, proceed to the next sectionto begin implementing the controllers on the SRV02-ET. If there is any problem ask your.

The effect of disturbance on PD and PID controllers and also PD and PID using the derivative block inthe feedback loop will be studied on the actual system.

5.2. Position Control Implementation

The q_srv02_pos Simulink diagram shown in Figure 14 is used to do position control experiments inthis laboratory. The SRV02-ET subsystem contains QuaRC blocks that interface with the DC motor andsensors of the SRV02-ET system, as discussed in previous labs. The PID Control subsystemimplements the designed PID controller, except a high-pass filter is used to obtain the velocity signal(as opposed to taking the direct derivative).

Page 15

Page 16: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Figure 14: Simulink model used with QuaRC to run the PD and PID position controllers on the SRV02-ET.

5.2.1. Setup for Position Control Implementation

Before beginning the in-lab exercises on the SRV02-ET module, the q_srv02_pos Simulink diagramand the setup_srv02_exp03_pos.m script must be configured.

Follow these steps to get the system ready for this lab:

1. Setup the SRV02-ET in the low-gear configuration and with the disc load.

2. Load MATLAB.

3. Browse through the Current Directory window in MATLAB and find the folder that containsthe SRV02-ET position control files, e.g. q_srv02_pos.mdl.

4. Double-click on the q_srv02_pos.mdl file to open the Position Control Simulink diagram shownin Figure 14.

5. Configure Sensor: The position of the load shaft can be measured using various sensors. Setthe Pos Src Source block in q_srv02_pos, as shown in Figure 14, as follows:

● 1 to use the potentiometer

● 2 to use to the encoder

Please set the position source block to the potentiometer (1) unless otherwise mentioned.

6. Configure setup script: You will set the parameters in the setup_srv02_exp03_pos.m scriptaccording to your system setup.

5.2.2. Implementing Step Response using PD Controller

In this lab, the angular position of the SRV02-ET load shaft, i.e. the disc load, will be controlled usingthe developed PD controller. Measurements will then be taken to ensure that the specifications are

Page 16

Page 17: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

satisfied. Follow the steps below:

1. Run the setup_srv02_exp03_pos.m script on 'AUTO_PD' mode.

2. Set Signal Type in the SRV02 Signal Generator to square to generate a step reference.

3. Set the Amplitude (rad) gain block to /6 to generate a step with an amplitude of 60 degrees.

4. Open the load shaft position scope, theta_l (rad), and the motor input voltage scope, Vm (V).

5. Build the Simulink diagram and connect to the target.

6. Select QuaRC | Start or press the “Start” button (►) to begin running the controller. The scopesshould be displaying responses similar to Figures 15 and 16. Note that in the theta_l (rad)scope, the yellow trace is the set-point position while the purple trace is the measured position.

7. When a suitable response is obtained, click on the “Stop” (■) button (or QuaRC | Stop from themenu) to stop running the code.

8. Q9: Generate a MATLAB figure showing the PD position response and its input voltage.Attach it to your report. As in the s_srv02_pos Simulink diagram, when the controller is stoppedeach scope automatically saves their response to a variable in the MATLAB workspace. Thusthe theta_l (rad) scope saves its response to the data_pos variable and the Vm (V) scope savesits data to the data_vm variable.

9. Q10: Measure the steady-state error, the percentage overshoot, and the peak time of the SRV02-ET load gear. Does the response satisfy the time-domain specifications?

10. Make sure QuaRC is stopped.

11. Shut off the power of the UPM if no more experiments will be performed on the SRV02 in thissession.

Figure 15: Measured PD step response.

Figure 16: PD control input voltage.

5.2.3. Implementing PD Controller using Tachometer

The previous experiment was performed by taking the derivative of the position signal using a filter. Inthis section, we will use the signal from tachometer to use as the derivative of the position in the PD

Page 17

Page 18: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

control system. Here, we measure the angle by the encoder and use the tachometer data for Derivativecontrol.

Follow the below steps to make the SRV02-ET track a step signal using the PD controller with thetachometer:

1. Run the setup_srv02_exp03_pos.m script when the CONTROL_TYPE in lab configuration isset to 'AUTO_PD'.

2. Open q_srv02_pos_TACH.mdl simulink file.

3. Build the Simulink diagram and connect to the target.

4. Open the load shaft position scope, theta_l (rad), and the motor input voltage scope, Vm (V).

5. Select QuaRC | Start to begin running the controller. After

6. Q11: Generate MATLAB figures showing the measured SRV02-ET position response and itscorresponding input voltage for this case and attach it to your report.

7. Q12: What is the difference between the results of this controller and the case when thederivative filter was used?

5.2.4. Implementing Ramp Response using PD and PID Controllers

Follow the following steps to make the SRV02-ET track a triangular input using the PD and PIDcontrollers:

1. Run the setup_srv02_exp03_pos.m script on 'AUTO_PD' mode.

2. Set Signal Type in the SRV02-ET Signal Generator to triangle in order to generate a ramp ortriangular reference.

3. Set the Amplitude (rad) gain block to /3 to generate a step with an amplitude of 60 degrees.

4. Ensure the Frequency (Hz) field in the Triangle Waveform block is set to 0.4 Hz.

5. Build the Simulink diagram and connect to the target.

6. Open the load shaft position scope, theta_l (rad), and the motor input voltage scope, Vm (V).

7. Select QuaRC | Start to begin running the controller. The scopes should be displaying responsessimilar to Figures 17 and18.

8. Q13: Generate a MATLAB figure showing the Ramp PD position response and itscorresponding input voltage trace. Attach the figure to your report and discuss the results.

9. Q14: Measure the steady-state error and compare it with the steady-state error calculated inPre-Lab.

Page 18

Page 19: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Figure 17: Measured SRV02 PD ramp response.

Figure 18: Input voltage of PD ramp response.

10. Enter the integral gain Ki designed in your pre-lab in MATLAB in order to run the PIDcontroller on the SRV02-ET.

11. Start QuaRC. The Ramp PID response in the scopes should be similar to Figures 19 and 20.

12. Q15: Generate a MATLAB figure showing the measured SRV02-ET Ramp PID positionresponse and its corresponding input voltage. Attach it to your report and discuss the results.

13. Q16: Measure the steady-state error. Is the zero steady-state specification satisfied withoutsaturating the actuator?

Figure 19: Measured SRV02 PID ramp response.

Figure 20: Input voltage from PID ramp control.

5.2.5. Disturbance effect on PD and PID controllers

Follow the below steps to make the SRV02-ET track a triangular disturbance using the PD and PID

Page 19

Page 20: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

controls:

1. Run the setup_srv02_exp03_pos.m script when the CONTROL_TYPE in lab configuration isset to 'AUTO_PD'.

2. Open q_srv02_pos_dist.mdl simulink file.

3. Build the Simulink diagram.

4. Open the load shaft position scope, theta_l (rad), and the motor input voltage scope, Vm (V).

5. Connect to the target and select QuaRC | Start to begin running the controller. The scopesshould be displaying responses similar to Figures 21 and 22.

6. Q17: Generate MATLAB figures showing the measured SRV02-ET position response and itscorresponding input voltage for this case. Attach the figure to your report and discuss theresults.

7. Measure the error signal caused by the disturbance.

8. Enter the correct value for ki . Now you will implement PID controller on the system wheredisturbance exists.

9. Select QuaRC | Start to begin running the controller. The scopes should be displaying responsessimilar to Figures .

10. Q18: Generate MATLAB figures showing the measured SRV02-ET position response and itscorresponding input voltage for this case and attach it to your report.

11. Q19: What is the effect of disturbance on the output when a PID controller is used? Why?

Figure 21: Disturbance effect on a PD controlled system –Output angle signal.

Figure 22: Disturbance effect on a PD controlled system –Motor input voltage.

5.2.6. PD and PID controllers with derivative in the forward path

As discussed in the pre-lab notes, the derivative block for PD and PID controllers are normally

Page 20

Page 21: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

implemented in the feedback loop to avoid the unwanted effect of zero in the closed-loop transferfunction and the high kick that it generates from the differentiation of the error signal. In the finalexperiment of this lab, we will study such effects.

Follow these steps to make the SRV02 track a triangular response using the PD and PID controls:

1. Run the setup_srv02_exp03_pos.m script when the CONTROL_TYPE in lab configuration isset to 'AUTO_PD'.

2. Open q_srv02_pos_FF.mdl simulink file.

3. Build the Simulink diagram.

4. Open the load shaft position scope, theta_l (rad), and the motor input voltage scope, Vm (V).

5. Connect to the target and select QuaRC | Start to begin running the controller. The scopesshould be displaying responses similar to Figures 21 and 22.

6. Q20: Generate MATLAB figures showing the measured SRV02-ET position response and itscorresponding input voltage for this case. Attach the figure to your report and discuss theresults.

7. Q21: Compare the overshoot with the PD control case when the derivative block was in thefeedback.

8. Enter the correct value for ki . Now you will implement PID controller on the system where apulse disturbance exists.

9. Connect to the target and select QuaRC | Start to begin running the controller.

10. Q22: Generate MATLAB figures showing the measured SRV02-ET position response and itscorresponding input voltage for this case, attach them to your report and discuss the results.

11. Q23: Compare the overshoot with the PID control case when the derivative block was in thefeedback.

12. Select QuaRC | Stop.

13. Shut off the power of the UPM if no more experiments will be performed on the SRV02-ET inthis session.

6. Results Summary

Q24: Fill out Table 2, below, with the pre-laboratory and in-laboratory results obtained such as thedesigned PID gains along with the measured peak time, percentage overshoot, and steady-state errorobtained from the simulated and implemented step and ramp responses. Use the results for the casederivative in the feedback loop and no disturbance is considered.

Section Description Symbol Value Unit

Lab#1 Pre-Lab: Model Parameters

Open-Loop Steady-State Gain K rad/(V.s)

Page 21

Page 22: Lab#3 - Student Manual_2010-11

ELEC-443 Lab#3 – Position Control of a DC Motor using PD and PID Controllers

Open-Loop Time Constant s

4.1.2 Pre-Lab: PD Gain Design

Proportional gain kp V/rad

Velocity gain kv V.s/rad

4.1.3 Pre-Lab: Control Gain Limits

Maximum proportional gain kp,max V/rad

4.2.2 Pre-Lab: Ramp Steady-State Error

Steady-state error using PD ess rad

4.3.2 Pre-Lab: Ramp Steady-State Error

Steady-state error using PID ess rad

4.3.3 Pre-Lab: Integral Gain Design

Integral gain ki V/(rad.s)

5.1.2 In-Lab Simulation: Ideal PD Step Response

Peak time tp s

Percentage overshoot PO %

Steady-state error ess rad

5.1.2 In-Lab Simulation: Filtered PD Step Response

Peak time tp s

Percentage overshoot PO %

Steady-state error ess rad

5.1.3 In-Lab Simulation: Ramp Response

PD Steady-state error ess rad

PID Steady-state error ess rad

5.2.2 In-Lab Implementation: PD Step Response

Peak time tp s

Percentage overshoot PO %

Steady-state error ess rad

5.2.4 In-Lab Implementation: Ramp Response

PD Steady-state error ess rad

PID Steady-state error ess rad

Table 2: SRV02-ET Lab#3: Position control results summary.

Page 22