Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • aa4cc/edu-ctrl-lab-models/quanser-active-suspension
  • vanekj19/quanser-active-suspension
2 results
Show changes
Commits on Source (12)
Showing
with 6956 additions and 6825 deletions
......@@ -19,22 +19,20 @@ See the video and the documentation.
3. Switch on the [AMPAQ-L2 Amplifier](https://www.quanser.com/products/ampaq-l2-amplifier/) – the switch is on the back side just above the power cable.
4. Check that the green LEDs on the terminal for the [QPID Data Acquisition Device](https://docs.quanser.com/quarc/documentation/qpid.html) should be set on. If not, check that the terminal is connected to the PC (through 3 PCI connectors on the back of the PC that interface to the internal PCI card). Since the PC is also used for controlling some other experiment, somebody mae have disconnected it from our experiment. Other that this connection to the PC, the terminal does not have to be particularly switched on or off. Should you need some more info on this particular DAQ, note that Quanser has already deprecedated it – currently they offer a newer PCIe version – [QPIDe](https://www.quanser.com/products/qpide-data-acquisition-device/).
4. Move the lowest (road-level) stage manually upwards and locate the upper limit (the red LED on the back of the system turns on), move it downwards and locate the lower limit (the red LED on the back of the system turns on), finally position it roughly in between the limit positions and press the limit button on the back side of the experiment (the green LED turns on).
5. Click on the [Simulink Courseware](https://quanserinc.box.com/shared/static/65tv2urk3h0w4a7maoh550e9ucmamuj2.zip) link at the [Active Suspension ](https://www.quanser.com/products/active-suspension/) web page. It will dowload a zip archive. After unzipping there are two subdirectories: `Software` and `Documentation`. Alternatively, you can get these directly at this Gitlab repo.
5. Get the directory [software/quanser_updated](software/quanser_updated) with the code for running the experiment.
9. Within the `Software` subdirectory there is a single m-file. It is named `setup_as.m`. Run it in Matlab. It will set all the parameters needed later.
6. Alternatively you could get the code by clicking on the [Simulink Courseware](https://quanserinc.box.com/shared/static/65tv2urk3h0w4a7maoh550e9ucmamuj2.zip) link at the [Active Suspension ](https://www.quanser.com/products/active-suspension/) web page. It will download a zip archive. After unzipping there are two subdirectories: `Software` and `Documentation`. But we discourage you from doing this because you would then have to make a few changes/updates to their code (see [TROUBLESHOOTING.md](TROUBLESHOOTING.md)). We put this information here just to indicate where the code is originally coming from.
10. Open any of the two simulink models whose names start with `q_`. These are "Hello World!" basic examples for this experiment. One is open-loop, the other contains a controller. The remaining Simulink model starting with `s_` is just for numerical simulation.
7. Launch Matlab (R2021a) and go to the [software/quanser_updated](software/quanser_updated) subdirectory. There is a single m-file, it is named `setup_as.m`, which reveals its purpose – it sets all the parameters needed later. Run it in Matlab.
11. Note that if you want to record the measured data for later analysis (which you will certainly do), the routes that you are familiar with from purely simulation projects may not work here. The reason is that while using the Quanser QUARC system, you are running the Simulink model in [External Mode](https://www.mathworks.com/help/sldrt/ug/simulink-external-mode.html), which prevents from using some Simulink functionality. In particular, if you [use Simulink scope block(s) for logging the data](https://www.mathworks.com/help/sldrt/ug/set-scope-parameters-for-logging-to-file.html), which is a common route, increasing the parameter called `Limit data points to last` will have no impact on how long the sequence of measurements will be stored in Matlab workspace (but do not forget to tick off the `Log data workspace` option and insert the variable name). If you ignore this issue, you may easily leave the lab assured that you stored a minute or two of experimental data only to discover at home that only the last few seconds have been saved. In order to prevent this, the `Duration` parameter needs to be changed somewhere else. Namely, go to manu `Code`, submenu `External Mode Control Panel`. Click on `Signal & Triggering` and change the `Duration` parameter there. If you need more on this, have a look at [the secion on Data Collection in QUARC manual](https://docs.quanser.com/quarc/documentation/quarc_data_collection.html) but if you are happy with logging to the variables in Matlab workspace through the Simulink scope blocks, you should be fine now.
8. Open any of the two simulink models whose names start with `q_`. These are essentially "Hello World!" basic examples for this experiment. One is open-loop, the other contains a controller. The remaining Simulink model starting with `s_` is just for numerical simulation.
12. In the Hardware tab in Simulink, click the green triangle accompanied by "Monitor & Tune" text. This may take a few seconds and then the experiments starts.
9. In the Hardware tab in Simulink, click the green triangle accompanied by "Monitor & Tune" text. It may take a few seconds and then the experiments starts. If nothing happens, check the [TROUBLESHOTING.md](TROUBLESHOOTING.md).
15. In case the experiment fails compiling and running, check that the Quanser block in the diagram is correctly configured to the QPID board (if you downloaded the files from the Quanser website, most probably it will be set to some Q8 board by default). Also, the target should be set (use `Ctrl+E` to get the the menu) to `quanser_win64.tlc` (again, by default after downloading from the web this will probably be `quanser_windows.tlc`, which is a 32-bit version).
10. After the experiment starts running, the green triangle should turn into an icon (black square) for stopping the experiment. But if this does not happen (for whatever reason), the fallback solution for stopping the experiment is the "Stop all" option offered through the small Quanser icon at the bottom right panel in Windows. Ultimately there is the RED BUTTON if nothing else works to stop the experiment, this will switch off the amplifier.
16. After the experiment starts running, the green triangle should turn into an icon (black square) for stopping the experiment. But if this does not happen (for whatever reason), the fallback solution for stopping the experiment is the "Stop all" option offered through the small Quanser icon at the bottom right panel in Windows.
11. Note that if you want to record the measured data for later analysis (which you will certainly do), the routes that you are familiar with from purely simulation projects may not work here. The reason is that while using the Quanser QUARC system, you are running the Simulink model in [External Mode](https://www.mathworks.com/help/sldrt/ug/simulink-external-mode.html), which prevents from using some Simulink functionality. In particular, if you [use Simulink scope block(s) for logging the data](https://www.mathworks.com/help/sldrt/ug/set-scope-parameters-for-logging-to-file.html), which is a common route, increasing the parameter called `Limit data points to last` will have no impact on how long the sequence of measurements will be stored in Matlab workspace (but do not forget to tick off the `Log data workspace` option and insert the variable name). If you ignore this issue, you may easily leave the lab assured that you stored a minute or two of experimental data only to discover at home that only the last few seconds have been saved. In order to prevent this, the `Duration` parameter needs to be changed somewhere else. Namely, in the `HARDWARE` tab, click on the `Control Panel` icon. Click on `Signal & Triggering` and change the `Duration` parameter there. If you need more on this, have a look at [the secion on Data Collection in QUARC manual](https://docs.quanser.com/quarc/documentation/quarc_data_collection.html), but if you are happy with logging to the variables in Matlab workspace through the Simulink scope blocks, you should be fine now.
17. If the experiment seems to be running (sensors are being read) but the actuators seem to be blocked, there is a `Limit switch` button at the back of the experiment. Push it. You may also have to do it after some "wilder" responses during the experiment after the limit switch is engaged.
18. For more, follow the instructions in the documentation.
\ No newline at end of file
18. A bit more (but not really much more) can be found in the laboratory guide and data sheet in the [documentation/quanser](documentation/quanser) directory.
\ No newline at end of file
# Troubleshooting
Make sure that:
- all the three LEDs (J0-J2) on the [QPID Data Acquisition (DAQ) device](https://docs.quanser.com/quarc/documentation/qpid.html) are ON. If they are not, check if all the three PCI connectors are correctly plugged in to the PC (on its back side). Occasionally somebody pulls them out as the PC is shared with some other experiment.
- the green LED on the back side of the experiment is on. If it is off and the red one is on instead, it means that the safety LIMIT switch has been engaged. This can be easily overlooked as the LED is on the back side, but this situation can be easily recognized by seeing the sensors read while the actuators stay still. In order to correct this, move (or make sure that) the lower (road-level) stage is roughly in the middle of its range and then press the LIMIT button on the back side of the experiment (just next to the LEDs).
- the red LEDs on the back side of the amplifier are off. If they are on, the amplifier has been cut off by the safety RED BUTTON. Make sure the button is unlocked (twisting it following the graphical signs on it).
- the QUARC configuration block named [HIL Initialize](https://docs.quanser.com/quarc/documentation/hil_initialize_block.html) in the (upper right corner of the) diagram is correctly configured to the `QPID` board. If you downloaded the files from the Quanser website instead of using the fixed code provided here, most probably it will be set to `Q8` board by default.
- the target is set `quanser_win64.tlc` (again, by default after downloading from the web this will probably be `quanser_windows.tlc`, which is a 32-bit version).
\ No newline at end of file
# Data sets from experiments
## Open-loop experiment
Here we provide the data from the open-loop experiment `software/quanser_updated/q_as_ol.slx`.
Load the data into Matlab workspace using
```matlab
load measured_and_simulated_open_loop_responses.mat
```
Two new data structs then appear in the workspace
- `measured_pos_ol_response`
- `simulated_pos_ol_response`
- `measured_acc_ol_response`
The first two data structures contain (vertical) positions of the three levels/stages:
- `zr` for the road level,
- `zus` for the suspension level,
- `zs` for the car level.
Strictly speaking, just `zr` and `zs` are measured by their dedicated sensors. The absolute position `zus`
is inferred as a difference between `zs` and yet another encoder measurement `zs-zus`.
The third data structs contain just the acceleration of the car level, that is, `d2/dt2 zs`.
Plot these using
```matlab
figure(1)
plot(measured_pos_ol_response.time, measured_pos_ol_response.signals.values)
legend('zr','zus','zs')
xlabel('Time [s]')
ylabel('Measured positions [m]')
grid on
figure(2)
plot(simulated_pos_ol_response.time, simulated_pos_ol_response.signals.values)
legend('zr','zus','zs')
xlabel('Time [s]')
ylabel('Simulated positions [m]')
grid on
figure(3)
plot(measured_acc_ol_response.time, measured_acc_ol_response.signals.values)
legend('d2/dt2 zs')
xlabel('Time [s]')
ylabel('Measured acceleration [m/s2]')
grid on
```
You will get something like the figures below
![figures/measured_pos_ol_response.png](figures/measured_pos_ol_response.png)
![figures/simulated_pos_ol_response.png](figures/simulated_pos_ol_response.png)
![figures/measured_acc_ol_response.png](figures/measured_acc_ol_response.png)
Apparently, the simulation responses do not quite fit the experimental ones. Some optimization-based fitting might be needed here.
\ No newline at end of file
data/figures/measured_acc_ol_response.png

40.8 KiB

data/figures/measured_pos_ol_response.png

47.9 KiB

data/figures/simulated_pos_ol_response.png

50.2 KiB

File added
# Software
- `quanser_original` is the code that can be obtained on the dedicated page on [the product web](https://www.quanser.com/products/active-suspension/) page on Quanser website. Just for archiving purposes here, possibly for use with some older (pre R2021a) release of Matlab and Simulink. **Do not use!**
- `quanser_updated` is the Quanser code after some modifications and upgrades useful or even necessary for our setup. In particular, the data acquisition board was set correctly to our `QPID` DAQ, the configuration file `quanser_win64.tlc` for 64-bit Windows was correctly set, and the Simulink files were saved in the new SLX format (corresponding to R2021a).
\ No newline at end of file
% SETUP_AS
%
% Active Suspension Control Lab:
% Design of a LQR active damping controller
%
% SETUP_AS sets the model parameters and set the controller
% parameters for the Quanser Active Suspension experiment.
%
% Copyright (C) 2013 Quanser Consulting Inc.
% Quanser Consulting Inc.
%
clear all
% ############### USER-DEFINED ACTIVE SUSPENSION CONFIGURATION ###############
%CONTROL TYPE CAN BE SET TO 'AUTO' OR 'MANUAL'.
CONTROL_TYPE = 'AUTO';
% ###############MODEL PARAMETERS###############
ks = 900;% or 1040 Suspension Stiffness (N/m)
kt = 2500;% or 2300
kus = kt;% Tire stiffness (N/m)
ms = 2.45;% or 2.5 Sprung Mass (kg)
mu = 1;% or 1.150
mus = mu;% Unsprung Mass (kg)
bs = 7.5;% Suspension Inherent Damping coefficient (sec/m)
bus = 5;% Tire Inhenrent Damping coefficient (sec/m)
%Set the model parameters of the Active Suspension.
%This section sets the A,B,C and D matrices for the Active Suspension model.
A = [ 0 1 0 -1 ;
-ks/ms -bs/ms 0 bs/ms;
0 0 0 1;
ks/mu bs/mu -kt/mu -(bs+bus)/mu];
B = [0 0 ; 0 1/ms ; -1 0 ; bus/mu -1/mu ];
C = [ 1 0 0 0 ; -ks/ms -bs/ms 0 bs/ms ];
D = zeros(6,2); D(6,2)=1/ms;
if strcmp(CONTROL_TYPE, 'AUTO')
Q = diag([450, 30, 5, 0.01]);
R = 0.01;
K = lqr( A, B(:,2), Q, R )
elseif strcmp(CONTROL_TYPE, 'MANUAL')
disp( [ 'K = [' 0 ' N/m ' 0 ' N/m ' 0 ' N.s/m ' 0 ' N.s/m'] )
disp( ' ' )
disp( 'STATUS: manual mode' )
disp( 'The model parameters of your Active Suspension system have been set.' )
disp( 'You can now design your state-feedback position controller.' )
disp( ' ' )
else
error( 'Error: Please set the type of controller that you wish to implement.' )
end
% SETUP_AS
%
% Active Suspension Control Lab:
% Design of a LQR active damping controller
%
% SETUP_AS sets the model parameters and set the controller
% parameters for the Quanser Active Suspension experiment.
%
% Copyright (C) 2013 Quanser Consulting Inc.
% Quanser Consulting Inc.
%
clear all
% ############### USER-DEFINED ACTIVE SUSPENSION CONFIGURATION ###############
%CONTROL TYPE CAN BE SET TO 'AUTO' OR 'MANUAL'.
CONTROL_TYPE = 'AUTO';
% ###############MODEL PARAMETERS###############
ks = 900;% or 1040 Suspension Stiffness (N/m)
kt = 2500;% or 2300
kus = kt;% Tire stiffness (N/m)
ms = 2.45;% or 2.5 Sprung Mass (kg)
mu = 1;% or 1.150
mus = mu;% Unsprung Mass (kg)
bs = 7.5;% Suspension Inherent Damping coefficient (sec/m)
bus = 5;% Tire Inhenrent Damping coefficient (sec/m)
%Set the model parameters of the Active Suspension.
%This section sets the A,B,C and D matrices for the Active Suspension model.
A = [ 0 1 0 -1 ;
-ks/ms -bs/ms 0 bs/ms;
0 0 0 1;
ks/mu bs/mu -kt/mu -(bs+bus)/mu];
B = [0 0 ; 0 1/ms ; -1 0 ; bus/mu -1/mu ];
C = [ 1 0 0 0 ; -ks/ms -bs/ms 0 bs/ms ];
D = zeros(6,2); D(6,2)=1/ms;
if strcmp(CONTROL_TYPE, 'AUTO')
Q = diag([450, 30, 5, 0.01]);
R = 0.01;
K = lqr( A, B(:,2), Q, R )
elseif strcmp(CONTROL_TYPE, 'MANUAL')
disp( [ 'K = [' 0 ' N/m ' 0 ' N/m ' 0 ' N.s/m ' 0 ' N.s/m'] )
disp( ' ' )
disp( 'STATUS: manual mode' )
disp( 'The model parameters of your Active Suspension system have been set.' )
disp( 'You can now design your state-feedback position controller.' )
disp( ' ' )
else
error( 'Error: Please set the type of controller that you wish to implement.' )
end
File added
File added
File added
% SETUP_AS
%
% Active Suspension Control Lab:
% Design of a LQR active damping controller
%
% SETUP_AS sets the model parameters and set the controller
% parameters for the Quanser Active Suspension experiment.
%
% Copyright (C) 2013 Quanser Consulting Inc.
% Quanser Consulting Inc.
%
clear all
% ############### USER-DEFINED ACTIVE SUSPENSION CONFIGURATION ###############
%CONTROL TYPE CAN BE SET TO 'AUTO' OR 'MANUAL'.
CONTROL_TYPE = 'AUTO';
% ###############MODEL PARAMETERS###############
ks = 900;% or 1040 Suspension Stiffness (N/m)
kt = 2500;% or 2300
kus = kt;% Tire stiffness (N/m)
ms = 2.45;% or 2.5 Sprung Mass (kg)
mu = 1;% or 1.150
mus = mu;% Unsprung Mass (kg)
bs = 7.5;% Suspension Inherent Damping coefficient (sec/m)
bus = 5;% Tire Inhenrent Damping coefficient (sec/m)
%Set the model parameters of the Active Suspension.
%This section sets the A,B,C and D matrices for the Active Suspension model.
A = [ 0 1 0 -1 ;
-ks/ms -bs/ms 0 bs/ms;
0 0 0 1;
ks/mu bs/mu -kt/mu -(bs+bus)/mu];
B = [0 0 ; 0 1/ms ; -1 0 ; bus/mu -1/mu ];
C = [ 1 0 0 0 ; -ks/ms -bs/ms 0 bs/ms ];
D = zeros(6,2); D(6,2)=1/ms;
if strcmp(CONTROL_TYPE, 'AUTO')
Q = diag([450, 30, 5, 0.01]);
R = 0.01;
K = lqr( A, B(:,2), Q, R )
elseif strcmp(CONTROL_TYPE, 'MANUAL')
disp( [ 'K = [' 0 ' N/m ' 0 ' N/m ' 0 ' N.s/m ' 0 ' N.s/m'] )
disp( ' ' )
disp( 'STATUS: manual mode' )
disp( 'The model parameters of your Active Suspension system have been set.' )
disp( 'You can now design your state-feedback position controller.' )
disp( ' ' )
else
error( 'Error: Please set the type of controller that you wish to implement.' )
end