Copyright 2010-2015 Michel Poulin

Last Update: January 2013

 

 

Switch to page no: 1  2  3  4  5  6  7  8

Back to Index

 

Washout Filters Algorithm

 

Introduction

The objective of the motion platform, which primary serves to move the simulator cockpit, is to reproduce similar acceleration sensations to what is felt within an aircraft.  The most common method of motion cueing a flight simulator is to use the classical washout algorithms.  This page will attempt to describe this type of algorithms.

 

The purpose of this Web page is to depict how this can be realized and what was specifically done to get an acceptable motion cues on my own 3DOF motion platform.

 

 

Motion Platform Physical Limitation Aspect

Washout Filter algorithms are used to produce a motion cues within the physical limitations of any specific motion platform.  My motion platform sloping limitation is ± 42 degrees maximum in one DOF at a time without vertical displacement.  Vertical displacement limitation is ± 16.51 cm without rotation.  Since motion cues may need more than one of the three DOFs simultaneously, it is required to allocate an available freedom on each DOF at any given time.  The range allocation could be assigned dynamically during flight, but this technic was not used to avoid false motion cues since the aircraft motion cannot be foreseen in advance and some important acceleration or combined motion might be missed using this method.  This is why a static range allocation on each DOF was used.  However, the static range is software configurable before flight take place.  The actuators stroke range for each DOF is then distributed to have 40% on pitch, 30% on roll and 30% on heave.  This allocation provides now a combined new virtual limitation of ± 21.4 degrees on pitch, ±17.1 degrees on roll and ± 6.5 cm vertical displacement that respect the initial physical limitation.  Doing so, the motion platform has the possibility to simultaneously bank at ±17.1 degrees while its pitch is at ± 20.4 degrees and its heave translation moves at ± 6.5 cm.

 

 

Flight Dynamic

The algorithms described here, use the aircraft dynamic information and compute the Washout filters for a three degree-of-freedom motion system.  Specifically, the dynamic information corresponds to the aircraft 3 axis accelerations and 3 axis rotation speeds (angular rates).  The software uses a washout algorithms that are responsible for calculating the best commanded motion without attempting to extend the motion platform beyond its physical limitations specified above.

 

The following acronyms are used in the following explanation

 

3DOF             Three Degree-of-Freedom (Roll, Pitch and Heave)

ax                    Aircraft body x-axis longitudinal acceleration measured in m/s˛ or feet/s˛

ay                    Aircraft body y-axis lateral acceleration measured in m/s˛ or feet/s˛

az                    Aircraft body z-axis vertical acceleration measured in m/s˛ or feet/s˛

g                      Acceleration created by earth gravity measured in m/s˛ or feet/s˛

Rx                   Rotational angular rate around x-axis measured in degree/s

Ry                   Rotational angular rate around y-axis measured in degree/s

Rz                   Rotational angular rate around z-axis measured in degree/s

hpf_ax                High-pass filtered body x-axis acceleration

lpf_ax                Low-pass filtered body x-axis acceleration

hpf_ay             High-pass filtered body y-axis acceleration

lpf_ay              Low-pass filtered body y-axis acceleration

hpf_az             High-pass filtered body z-axis acceleration

 

The essential FSX inputs information used in the washout filter algorithms are the three aircraft axis accelerations ax, ay, az, and the three aircraft angular rates Rx, Ry, Rz.

 

As a minimum, the software gathers the following FSX variables through the Microsoft “Simconnect.dll” driver provided with Flight Simulator Deluxe edition.

 

In order to tune the washout filters with air craft dynamic performance and ground versus air dynamic influence, two additional FSX variables are used such as aircraft type and the event indicating that aircraft is on ground.

 

 

 

Eight FSX Variables to get from Simconnect.dll

 

 

 

Acceleration Body x

Acceleration Body y

Acceleration Body z

Rotation Velocity Body x

Rotation Velocity Body y

Rotation Velocity Body z

Sim On Ground

Title

 

 

 

For Pitch DOF control, a command is computed by the algorithm which is composed of two components.  The components are the force produced by acceleration ax and the rotation produced by the rotation velocity Ry.  They are then combined together to reproduce the pitch cue felt in aircraft.  The same process using ay and Rx is used to reproduce the roll cue felt in aircraft.  The following paragraphs will focus on the pitch motion cue which applies also on the roll motion cue.

 

 

Washout Filters Algorythm

 

 

https://lh3.googleusercontent.com/-frhfstSeKqA/ULppmtJa86I/AAAAAAAAAnY/CyU_fxvdnsA/s640/washoutFilter.jpg

 

1-Acceleration Converted to Tilt Force Angle

The acceleration ax is initially scaled and then tuned through a low-pass filter and rate limited if required as shown on the illustrated algorithm.  The resulting acceleration is converted to a gravity vector such that the pilot feels a sustained acceleration.  So this gravity vector is used to create the pitch tilt-angle component commonly called “tilt-coordination” which objective is to orient the gravity vector such that the pilot feels a sustained acceleration while the visual display remains constant.  In order to feel the longitudinal acceleration in the body x axis direction (front direction of the aircraft), the simulator’s cockpit will tilt up such that the gravity vector will allow the pilot to feel acceleration in the simulator’s x axis.  In other words, a pushing force on the simmer’s back produced by its own body weight. 

 

As long as the cockpit does not tilt up too far (usually less than 12 degrees) the pilot should not feel the decreasing vertical acceleration (z direction) due to tilting.  Tilting more than twelve degrees may cause a noticeable difference in normal acceleration because the threshold value of acceleration, or the minimum acceleration a pilot can sense, will be reached. The threshold value to be avoided is ranged from 0.17 to 0.28 m/s˛ for linear accelerations according to the literature.

 

Scaling Factor

 

Scaling ax

 

Scaling is used because the acceleration to be felt by pilot is limited by the motion platform physical limitation compared to the large acceleration range that can be felt in real aircraft.

 

During a flight, many events can cause different level of acceleration.  In order to reproduce realistic cue for different event, the maximum aircraft acceleration is scaled down to the platform maximum allowance.  During flight test with the Beech Baron 58 aircraft, the maximum surge acceleration was noticed to be limited at 50 feet/s˛ for the surge and was also dependant of the aircraft position (air or ground).  Since the tilt coordination can provide a maximum of g.Sin (21.4) = 11.7 feet/  (0.36G).  The evidence of scaling requirement is shown.  There is compromise to take. In order to reproduce the whole aircraft acceleration range, scaling is required producing unrealistic acceleration felt but at least the sensation remains there for the whole range.  In order to reproduce accurate acceleration felt, only low acceleration can be reproduced without scaling, so mid to high aircraft acceleration will get truncated (saturated) by the motion platform physical limitation. Below are the scaling equation used on my platform.

 

double ScaleSurgeAir = (Math.Sin(PlatformMaxPitch * Math.PI / 180.0) * (GRAVITY * Ax_Accel2FitRangeA) / surge_limit);

double ScaleSurgeGround = (Math.Sin(PlatformMaxPitch * Math.PI / 180.0) * (GRAVITY * Ax_Accel2FitRangeGround) / surge_limit);

 

In order to adjust the aircraft range of acceleration within the 21.4 degree available on platform, the variable Ax_Accel2FitRangeA can be modified from its default value of 1.  Doing so will reduce the sensibility for lower acceleration.  Note that an exponential factor could also be used to respect full acceleration range and provide more accurate feeling in high or low acceleration end.

 

//Scaling of longitudinal acceleration (surge) Ax

if (ground == 0) surge = surge * ScaleSurgeAir / LPFGainSurgeA; // surge in air.

else if (ground == 1) surge = surge * ScaleSurgeGround / LPFGainSurgeG; // surge on ground.

 

Second Order

Low Pass Filter

 

Low-Pass Filtering ax

 

The filter used in this project is a Bessel second order low-pass filter. The purpose of this filter is to attenuate all high frequency accelerations as much as possible and keep the low frequency accelerations unchanged.  Low-pass filter is used to reproduce the low frequency accelerations sensed in the aircraft for gravity vector computation.  The filter parameters used may differ from ground or air operation.  The cut off frequency was determined by trial and error using graph and flight test.

 

The filter parameters were defined using the following Web site http://www-users.cs.york.ac.uk/~fisher/mkfilter/trad.html.  Thanks to Tony Fisher's Home Page University of York, Computer science Dept.

 

Below is the generic Bessel second order low-pass filter equation and its equivalent C programming.

 

y[n] = (1 * x[n- 2]) + (2 * x[n- 1]) + (1 * x[n- 0]) + ( C1 * y[n- 2]) + (C2 * y[n- 1])

 

Low Pass Filtering of sway

lpf_xv1[0] = lpf_xv1[1];

lpf_xv1[1] = lpf_xv1[2];

lpf_xv1[2] = sway;

lpf_yv1[0] = lpf_yv1[1];

lpf_yv1[1] = lpf_yv1[2];

if (ground == 0) lpf_yv1[2] = (lpf_xv1[0] + lpf_xv1[2]) + (2 * lpf_xv1[1]) + (lpfSwayCoeff1A * lpf_yv1[0]) + (lpfSwayCoeff2A * lpf_yv1[1]);

else if (ground == 1) lpf_yv1[2] = (lpf_xv1[0] + lpf_xv1[2]) + (2 * lpf_xv1[1]) + (lpfSwayCoeff1G * lpf_yv1[0]) + (lpfSwayCoeff2G * lpf_yv1[1]);

 

Tilt Coordinator

 

Vector Calculation

 

As already introduced above, the gravity vector is used to calculate a simulated lateral and longitudinal force.  This method is called tilt-coordination, and utilizes the gravity vector by tilting the platform to a calculated angle such that sustained accelerations are simulated by gravity.

 

//Tilt coordinate angle calculation

tilt_force = (180.0 / Math.PI) * Math.Asin(LPF_yv1[2] / GRAVITY);

 

Rate Limiter

 

Rate Limiter

 

Some undesired acceleration during flight or caused by the Washout filters need to be damped in order to hide a false motion cue to the simulator pilot.  Since the low pass filter cut-out frequency is very low, there is actually no need for additional rate limitation but the rate limiter is also used to limit the sudden acceleration caused during flight crash.  Below is the equivalent C programming of the rate limiter.

 

//Rate Limit Correction (degree/s)

Rate = sway_tilt_force - previous_sway_value;

if (Rate <= RateLimitation && Rate >= - RateLimitation) break; // Within Rate limit

else if (Rate < -RateLimitation) sway_tilt_force = previous_sway_value - RateLimitation; //Rate limitation of falling slew rate

else if (Rate > RateLimitation) sway_tilt_force = previous_sway_value + RateLimitation; //Rate limitation of rising slew rate

previous_sway_value = sway_tilt_force;

 

Ellipse: Σ

Summation

 

The low frequency component of x direction acceleration that is sustainable through tilt coordination is sent to the component summation for the pitch position.  The same way for low frequency component of y direction acceleration that is sustainable through tilt coordination is sent to the component summation for the roll position.

 

 

2 - Rotation Velocity Converted to Angle Position

 

The angular velocity Ry is high-pass filtered to obtain the high frequency component of the aircraft angular motion rate. This angular rate is then converted to an angular position by computing its integral.  In my previous 3DOF Motion Platform software application, the FSX "Plane Pitch Degrees" variable from Simconnect was used, but the objective here is not to follow exactly the aircraft pitch or roll.  Instead, we wish to provide the pilot, a feeling of rotation in the same direction the aircraft is rotating.  Furthermore, we need to remember here that only the highest frequency part of the velocity speed is used, so real aircraft angle cannot be duplicated anyway from its integral.

 

Second Order

High Pass Filter

 

 

High-Pass Filtering

 

The washout filter is used to attenuate as much as possible the low frequency accelerations that cause the motion platform to reach its mechanical limitations, while keeping high frequency accelerations unchanged. The high frequency accelerations last for a small duration of time, and will not drive the motion platform to its physical limits if a proper high-pass filter cut-off frequency is chosen. The filters also serve to bring the motion platform back to its center position after motion cue is performed.  The filter used in this project is a Bessel, second order high-pass filter.  Its generic equation and its equivalent C programming are shown below.

 

yv[2] = (xv[0] + xv[2]) - 2 * xv[1]  + (-C1 * yv[0]) + (C2 * yv[1])

 

//High Pass Filtering the pitch rate

hpf_xv1[0] = hpf_xv1[1];

hpf_xv1[1] = hpf_xv1[2];

hpf_xv1[2] = pitch_rate;

hpf_yv1[0] = hpf_yv1[1];

hpf_yv1[1] = hpf_yv1[2];

hpf_yv1[2] = (hpf_xv1[0] + hpf_xv1[2]) - (2 * hpf_xv1[1]) + (hpfRollCoeff1 * hpf_yv1[0]) + (hpfRollCoeff2 * hpf_yv1[1]);

 

 

ʃ integrator

 

Integral

 

As introduced above, the integral function is used to get the aircraft angle rotation position at any given time from the rotation rate of high frequency change.  So computing the area below the rate curve provides the position angle in real time.  Integrating the high frequency of the rotation rate provides a pseudo aircraft position and most important a rotation feeling.

 

AnglePosition = AnglePosition + 0.5 [AngularRate(n) + AngularRate (n-1)] / ∆t

 

//Integrating the pitch rate to get pitch position angle and rotation feeling

pitch_rate_integral += 0.5 * (hpf_yv1[2] hpf_yv1[1]) * TimeInterval; // cumulative rectangular surface below the curve every sample time period.

 

The integral of the high frequency component of y rotation rate is sent to the components summation for the pitch position.  The same way for high frequency component of the x rotation is sent to the component summation for the roll position.

 

 

3 - Components Summation

 

The rotation movement component calculated in section 2 is added to the tilt-coordination calculated in section 1 to obtain the final angle position command for the motion platform cue. The rotation movement contribution on the motion cue can be adjusted with ratio factor to meet pilot preference.

 

 

4 – Heave Motion Cue

 

Heave takes place along the vertical z axis of the simulator.  Since heave cannot take place continuously, due to high energy required and motion platform limitation, compared to pitch and roll which use gravity vector tilt coordination, low heave frequencies are eliminated using a high pass filter in order to keep impulse vertical acceleration only.  Anyhow, what is mostly interesting to reproduce during flight are the flying events such as turbulence, air pockets, sudden lift following quick pitch, bouncing during landing and taxi on rough surface such as grass, field and gravel.  All these phenomenons are in fact impulse acceleration and this is why a high pass filter is used.

 

On my project, the heave signal computing is straight forward.  A scaling factor is used followed by a Bessel second order high pass filter ended with a rate limiter.

 

The maximum magnitude of the heave acceleration on the Baron 58 is about 220 feet/s2. 

 

This high pass filter controls the speed rate with which the platform heave reacts to changes in aircraft heave acceleration. Setting higher frequency cut-off will hide bouncing during landing but increase taxi feeling on rough surface with proper scaling.  Setting lower frequency cut-off will improve bouncing but will increase average energy required during flight and decrease the return speed to central position.

 

 

Tuning the Washout Filters

                                                                      

DETAILS TO COME SOON

 

Home

 

 

Back

 

 
Titre : Next - Description : Next

TUNNING CHART