Open Access
Issue
Wuhan Univ. J. Nat. Sci.
Volume 26, Number 6, December 2021
Page(s) 513 - 520
DOI https://doi.org/10.1051/wujns/2021266513
Published online 17 December 2021

© Wuhan University 2021

Licence Creative CommonsThis is an Open Access article distributed under the terms of the Creative Commons Attribution License (https://creativecommons.org/licenses/by/4.0), which permits unrestricted use, distribution, and reproduction in any medium, provided the original work is properly cited.

0 Introduction

The purpose of the washout filter is to provide the motion cues representing realistic human perception, beside the motion must proceed within the bounds of the simulator workspace. Three approaches to develop motion cueing algorithm (MCA) have been put forward, which are designed to “trick” a person into believing that driver is experiencing cues similar to those in a real flight. Conrad et al[1] proposed the classical MCA in the first place. The scheme has simple structure, fast execution and feedback speed[2], but it also has several shortcomings, e.g. the key one is a fixed scheme of the classical washout filters as a result of inappropriate weight- tuning of the associated parameters[3]. The adaptive MCA is the second method. Bowles et al[4] developed a modification of the coordinated adaptive MCA. The third method is the optimal MCA which was developed by Sivan et al[5] and later implemented by Reid et al[6]. There are two types of optimal MCA, linear and nonlinear. Note that both algorithms are designed based on the same principles and concepts. The major differences are in real-time implementation of washout filters for the solution to the Riccati equation. No matter what kind of platform used as the simulator, the limited workspace is a key issue in designing the MCA. The approach to the input signal within the threshold has linear and non-linear scaling based on the MCA, to replace the value of the input signal with a threshold value for signals that exceed the threshold[7]. Asadi et al[8] proposed a non-linear scaling method based on genetic algorithms and optimal MCA to overcome problems pertaining to select nonlinear scaling parameters based on trial- and-error and inefficient usage of the platform workspace, and to reduce the sensation error between the simulator and aircraft, while satisfying the constraints imposed by the platform boundaries, but it neglects the factor that the motion cueing is significantly different from high and low amplitude signal, and the solution of the Riccati equation is obtained offline for optimal MCA. Luo et al[9] and Chen et al[10] proposed a variable input, the third-order polynomial method and Hermite function reduction method in combination with classical MCA, respectively. Although the two modification methods have achieved satisfactory results, they are also constrained by the adaptability of the classical MCA filter. The adaptive MCA is concerned, because the classical MCA generated some extra oscillations in some rotational input cases, and this method tries to eliminate the difference of the gravity vector between in the aircraft and in the simulator. It was noted in this study that the difference could not be eliminated since the simulator usually rotates an angle smaller than the aircraft does and the simulator translational acceleration could not be sustained for a long time [11,12].

In this paper, the nonlinear optimal MCA was adopted and the center of simulator rotation was re-defined. The pilot’s head as the center of simulator rotation was chosen to avoid any cross-coupling from simulator rotation to pilot’s head translational motion. The method of nonlinear scaling and limiting is adopted to deal with the input signal.

1 Redesign of Nonlinear Optimal MCA

1.1 Pilot Station

The nonlinear optimal MCA input signals are the actual aircraft’s longitudinal acceleration and pitch angle velocity. The following is the equations for computing translational accelerations at the pilot station which are implemented in the “Translation to PS (pilot’s station)” block.axPSA=axAARSx(q2+r2)+RSy(pqr˙)+RSz(prq˙)ayPSA=ayAA+RSx(pq+r˙)RSy(p2+r2)+RSz(qrp˙)ayPSA=azAA+RSx(prr˙)+RSy(qr+p˙)RSz(p2+q2)(1)where aPSA=[axPSA,ayPSA,azPSA], aAA=[axAA,ayAA,azAA], RS=[RSx,RSy,RSz], ωAA=[p,q,r], ω˙AA=[p˙,q˙,r˙], a represents the acceleration, x, y, z are the coordinate directions, p, q, r are the attitude angles, A represents the aircraft coordinate, PS represents the pilot’s station, and S represents the simulator.

The structure of nonlinear optimal MCA is shown in Fig. 1. The inertial reference frame FrI is earth-fixed with xI aligned with the gravity vector g, and its origin is placed at the center of the fixed platform motion-base. xI, yI point forward and the right hand side with respect to the simulator driver. The simulator reference frame FrS has its origin at the centroid of the simulator payload platform, the centroid of the upper bearing attachment points. The origin is fixed with respect to the simulator payload platform. xS points forward and zS points downward with respect to the simulator cockpit, and yS points toward the pilot’s right hand side. The x-y plane is parallel to the floor of the cockpit. Zaychik[13] proposed modification to the original nonlinear algorithm, which position the PS at the location of the pilot’s head. The essence of applying nonlinear washout filters at the PS location as opposed to the centroid of the upper joint bearings of the motion platform is, in fact, the shift of FrS from the motion platform to wherever the PS is located. Nonlinear optimal MCA[14,15] can make better use of the motion platform workspace, the design requirements in motion simulation can be solved by adjusting the cost function in the optimization process, and the displacement and acceleration performance of motion platform can be greatly improved by eliminating false cues and presenting a smooth motion perception. However, an inappropriate scaling and limiting in MCA could cause the effect that the motion platform workspace is too conservative, which severely restricts the advantage of the nonlinear optimal MCA. To deal with the problem, Asadi et al[16] and Mohammadi et al[17] presented the MCA based on model prediction and fuzzy adaptive control. Basically, this MCA includes washout filters and scaling and limiting units, and the scaling and limiting module has a critical impact during motion washout.

thumbnail Fig. 1 Nonlinear optimal MCA

uA: the aircraft input signal; us: the simulator motion input signal; e: pilot sensation error; FrI: the inertial reference frame; FrS: the simulator reference frame; FrPS: the pilot’s head reference frame; RI: radius vector from the inertial reference frame to the simulator reference frame; RS: radius vector from the simulator reference frame to the pilot’s head reference frame; xI, zI represent the inertial reference frame coordinate directions; xS, zS represent the simulator reference frame coordinate directions; xPS, zPS represent the pilot’s head reference frame coordinate directions

1.2 Nonlinear Optimal MCA

The input uS is given in Eq. (2), ax is the x directions acceleration in the inertial reference frame FrI, θ˙ represents pitch angular velocity:uS=[θ˙ax]=[u1u2](2)

The human vestibule system that consists of the semicircular canals and otolith organs can sense translational and rotational movements. The semicircular canals can detect roll, pitch and yaw angular velocity beyond sense threshold. The mathematical model of semicircular canals model is given as:θ˙^=GSCCs2s2+T1s+T0u1(3)where θ˙^ is the sensed angular velocity, s is the Laplace variable, T0, T1 are described as follows:T0=1τ1τa, T1=τ1+τaτ1τa

In addition, τ1, τa are the parameters of the semicircular canals model, GSCC is the angular velocity threshold that scales the response to threshold units.

In an attempt to produce the desired motion cues that most closely represent the perceptual behavior of the aircraft pilot, the confirming case of the integrated perceptual model will be incorporated into the perceptual channel. The visual delay was also neglected since it has only a small effect on the perceptual response. The perceptual input u=uS for a simulator pilot, and u=uA for the aircraft pilot. Therefore, u=uS-uA can be considered as input to the cueing algorithm. The additional state due to the optokinetic influence must be added to these equations[18]:θ˙^OK=T2s+T2(θ˙^Aθ˙^S)(4)where T2 relates to the time constant.

The semicircular canals state equations become{X˙SCC=ASCCXSCC+BSCCuθ˙PE=CSCCXSCC+DSCCu(5)where XSCC is the state vector of semicircular canals model, θ˙PE is the state vector of sensed angular velocity, and ASCC, BSCC, CSCC, and DSCC show the semicircular canals model as one set of state equations.

A SCC = [ T 1 1 0 T 0 0 0 T 2 0 T 2 ] ,   B S C C = [ G S C C T 1 G SCC T 0 G SCC T 2 0 0 0 ] , C SCC = [ 1 0 1 ] ,   D SCC = [ G S C C 0 ]

The otolith organs can detect lateral, longitudinal and vertical linear acceleration and motion. It transmits information in regard to sense applied specific forces on the human body, responding to linear acceleration or tilting of the head, with consideration of the gravity vector. However, it cannot differentiate translational acceleration from gravity or tilt[19]. The specific force stimulus isf^x(s)=GOTOKOTO'(s+A0)(s+B0)(s+B1)fx(s)(6)where fx(s) is the stimulus-specific force, f^x(s) is the sensed specific force along the x-axis of the head, GOTO, KOTO', B0, B1 and A0 are the calculated parameters for a static sensitivity, long time constant, short time constant, and lead operator, respectively.

For the center of rotation head-specific force equation is as follows:fx=ax+gθ+RSzθ¨(7)Eq. (7) can be transformed into the Laplace domain:fx(s)=u2(s)+(g1sRSzs)u1(s)(8)The output of the optokinetic influence becomes:f^xOK=T2s+T2(f^Af^S)(9)

The state space representation for the mathematical models of the otolith organs is:{X˙OTO=AOTOXOTO+BOTOuf^xPE=COTOXOTO+DOTOu(10)where AOTO, BOTO, COTO, and DOTO show the otolith models as one set of state equationsAOTO=[00000T21a000001000000000T20001a000000T2],BOTO=[cdace00T2GOTORSz000fhaf0],COTO=[100101], DOTO=[GOTOK'OTORSz0]

The representations in Eqs. (5) and (10) can be integrated to arrange a single representation for the human perceptual model:{X˙V=AVXV+BVuyPE=CVXV+DVu(11)where X˙V and yPE are the combined states vector and the sensed responses, respectively. AV, BV, CV, and DV represent the vestibular models as one set of state equations:AV=[ASCC00AOTO], BV=[BSCCBOTO],CV=[CSCC00COTO], DV=[DSCCDOTO]

The vestibular state error is defined as Xe where XS and XA are the vestibular states for simulator and aircraft, respectively. Then the pilot sensation error Xe= XA-XS can be calculated in the form:{X˙e=AVXe+BVuS-BVuAe=CVXe+DVue-DVuA(12)where uS and uA represent the simulator and aircraft input, respectively, as shown in Fig. 1.

The aircraft input uA consists of filtered noise, and can be represented as:{X˙n=γXn+γwuA=Xn(13)where Xn is the filtered white noise state, and γ is the break frequency for a given degree of freedom.

By combining Eqs. (11), (12), and (13), we can obtain the desired system equation:{X˙=AX+BuS+HWy=[eXd]T=CX+DuS(14)where X=[XeXdXn]T, Xd is motion platform states, y is the desired output, and A=[AV0-BV0Ad000-γ], B=[BVBd0], H=[00γ], C=[CV00I-DV0], D=[DV0], Ad=[0100], Bd=[01].

The cost function is augmented with an additional term e2αt proposed by Anderson.{X˙=(A'+αI)X+Bu'+HWJ'=E{t0t1e2αt(XTR'1X+u'TR2u')dt}(15)where u'=uS+R2-1R12TX, R1=R1-R12R2-1R12T, R1=CTGC, R12=CTGD, R2=R+DTGD, G=diag[Q,Rd].

When u=-R2-1RTP(α)X, the cost function is minimized, where P(α) is the solution of the algebraic Riccati equationR1-P(α)BR2-1BTP(α)+(A'+αI)TP(α)+P(α)(A'+αI)=0(16)

Eq. (16) can be substituted into Eq. (15) by solving for uSuS=-[R2-1(BTP(α)+R12T)]X(17)

By defining a matrix K, uS=-K(α)XK(α)=R2-1(BTP(α)+R12), X=[XeXdXn]T, we can obtain:uS=-[K1(α)K2(α)][XeXd]-K3(α)uA(18)and the Riccati equation solution P(α) can be partitioned asP(α)=[P11(α)P12(α)P13(α)P21(α)P22(α)P23(α)P31(α)P32(α)P33(α)](19)K is given in Eq. (18) and results inK1(α)=R2-1[BVTP11+BdTP21+DVTQCV]K2(α)=R2-1[BVTP12+BdTP22]K3(α)=R2-1[BVTP11+BdTP23-DVTQCV](20)where, by symmetry, P12=P21T.

As uA=Xn, the state corresponding to Xn is removed from[X˙eX˙d]=[AV0-BV0Ad0][XeXduA]+[BVBd]uS(21)Substitution of (20) into (21)[X·eX·d]=[AV-BVK1(α)-BVK2(α)-BdK1(α)Ad-BdK2(α)][XeXd]+[-BV(I+K3(α))-BdK3(α)]uA(22)

A nonlinear control law is chosen to make α dependent upon the system states:α=XdTQ2Xd(23)where Q2 is a weighting matrix that is at least positive semi-definite. The feedback matrix K(α) is then determined by solving the Riccati equation of Eq. (15) in real time as a function of α.

1.3 Nonlinear Scaling and Limiting

In the structure of the washout algorithm, no matter how classical, adaptive or optimal the MCA, they all have a scaling and limiting module to ensure that the washout signal conforms to the characteristics of the simulated actual movement, and the driver can drive a real aircraft in the simulator. Usually, there are two types: linear and nonlinear[20], such as third-order polynomial method, equal scaling and limiting method. The common problem pertaining to the scaling and limiting module is their tuning process, which is based on trial-and-error. This is a sub-optimal process that affects the generated motions, makes the simulator motion conservative, and produces false motion cues. For instance, the third-order polynomial method that Telban proposed[7] does not limit the local extreme point. When input signal monotonously increases or decreases within a large amplitude range, it is easy to cause the result that output signal fall into the local extreme value and lead to signal distortion[10]. This paper proposes a scaling & limiting strategy to deal with input signal, and the formula is shown in Eq. (24),ytran={kl×yin,|yin|<ylyin,|yin|<yuku×(yinyu)+yu,|yin|>yu(24)where yin,yl, yu are the input signal, lower and upper scaling boundary, respectively. kl, ku are the motion perception boundary parameters. The general selection range should be between 1-2 for the lower motion perception scaling boundary factor kl. The most appropriate upper motion perception scaling boundary factor ku for most commercial simulators is chosen empirically as 0.5 in both the translational and rotational motion channels[21]. ytran is the transformed input acceleration, and it is limited within the maximum acceleration range of the motion platform to protect the safety of motion simulation.

2 Simulation Analysis

In this paper, in order to verify the reliability of the method, nonlinear optimal MCA is adopted in the longitudinal and pitch directions, and its structure is shown in Fig. 2.

Pilot’s station vector RS=[0.01, 0.25, 1.75] in meters. Longitudinal acceleration is shown in Fig. 3. In order to observe the influence of the coordinated tilt acceleration, the pitch angular velocity is set as zero in the pitch direction. The solid line represents the actual input acceleration, and the dotted line represents the acceleration after non-linear scaling and limiting. The nonlinear scaling and limiting acceleration is determined by Eq. (24), and yl, yu are 1 m/s2, 3 m/s2, the parameter kl, ku are 1.35, 0.5, respectively. The original signal is as large as possible in the range of the low amplitude, so that the driver can feel the movement in advance. To ensure the fidelity of simulation acceleration, the original signal is maintained in the range of the medium amplitude. Especially, the scaling and limiting should be paid attention in the range of the high amplitude. The appropriate parameter can not only prevent the movement platform from exceeding the limit of the workspace, but also ensure the movement characteristics of the washout signal.

thumbnail Fig. 2 Longitudinal and pitch nonlinear optimal MCA

aAA: aircraft acceleration; aPSA: pilot’s head vestibule acceleration in simulator; aAI: acceleration after nonlinear scaling & limiting; PS: pilot station; LSI: transformation matrix from simulator into inertial frame; TS: transformation matrix from angular velocity to Euler angle rates; β˙A: angular velocity after TS; β˙SR: angular velocity after nonlinear scaling & limiting; β˙ST: washout angular velocity after tilt rate limit; β˙S: the sum of washout angular velocity; βS: washout angular displacement; s: Laplace variable; S¨I: washout acceleration in the inertial frame; S˙I: washout velocity in the inertial frame; SI: washout displacement in the inertial frame; K(α): the feedback matrix

Pilot’s station vector RS=[0.01, 0.25, 1.75] in meters. Longitudinal acceleration is shown in Fig. 3. In order to observe the influence of the coordinated tilt acceleration, the pitch angular velocity is set as zero in the pitch direction. The solid line represents the actual Input acceleration, and the dotted line represents the acceleration after non-linear scaling and limiting. The nonlinear scaling and limiting acceleration is determined by Eq. (24), and yl, yu are 1 m/s2, 3 m/s2, the parameter kl, ku are 1.35, 0.5, respectively. The original signal is as large as possible in the range of the low amplitude, so that the driver can feel the movement in advance. To ensure the fidelity of simulation acceleration, the original signal is maintained in the range of the medium amplitude. Especially, the scaling and limiting should be paid attention in the range of the high amplitude. The appropriate parameter can not only prevent the movement platform from exceeding the limit of the workspace, but also ensure the movement characteristics of the washout signal.

thumbnail Fig. 3 Longitudinal acceleration signal

Figure 4 shows the sense acceleration of the longitudinal direction after the nonlinear optimal MCA, nonlinear scaling and limiting. The chain line is the pilot’s perceived acceleration in the aircraft, which is the actual perceived acceleration. The dotted line is the washout sensory acceleration by the improved nonlinear optimal MCA. The solid line is the unimproved nonlinear optimal MCA. That is, the driver’s sensory center is in the center of the motion platform, and the scaling and limiting module is linear scaling. The washout acceleration is evaluated by the human vestibular model, then the sense acceleration is obtained. Therefore, it can be seen that the improved washout algorithm is closer to the actual movement sense as a whole, while the nonlinear optimal MCA with linear scaling and limiting has certain errors in the range of the low- and high-amplitude.

thumbnail Fig. 4 Sense acceleration

The washout displacement of the algorithm is shown in Fig. 5 under linear and nonlinear conditions. On the whole, the longitudinal washout displacement of nonlinear method for motion platform is upper than the linear in the range of 0-1.5 s, and the maximum washout displacement does not exceed the linear method. It indicates that the improved method has the higher feedback speed in the motion simulation performance, and the safety of workspace is guaranteed. About at 2.5 s, they all reach the maximum washout displacement of the motion platform. The maximum washout displacement of the linear method is 0.38 m, and the nonlinear method is 0.36 m, so the improved method is more capable of using a smaller motion space to achieve the same motion simulation, to ensure the safety of motion platform. In the final stage of the motion simulation, the motion platform can be restored to the neutral position more quickly so that the sufficient time and workspace can be provided for the next movement.

thumbnail Fig. 5 Washout displacement of the algorithm under linear and nonlinear conditions

As shown in Fig. 6, both linear and nonlinear methods represent the washout sensory angular velocity. The two horizontal lines are the upper and lower thresholds of the semicircular canal±0.062 8 rad/s. The core of the MCA is to use the principle of tilt coordination to simulate continuous acceleration, but it cannot exceed the semicircular canal threshold, otherwise the washout process will inevitably be perceived for the occurrence of tilt coordination. To avoid this as much as possible during the motion simulation process, in the conventional processing measure, the angular velocity limiter is added into tilt coordination channel to ensure tilt angular velocity within the semicircular canal threshold. Although this method can avoid the occurrence of false cue, it will simultaneously lead to the filter of the angular velocity signal beyond the semicircular canal threshold. The part of the simulation continuous acceleration cannot be duplicated beyond the semicircular canal threshold. Therefore, the nonlinear control strategy is adopted to ensure the washout sense angular velocity within the threshold. Finally, the sense angular velocity tends to zero, which can be used for the next movement and provide adequate time preparation.

thumbnail Fig. 6 Sense angular velocity

3 Conclusion

The MCA has responsibility for duplicating the actual flight status, but the aircraft motions can be transformed into the simulator motions within the motion platform’s physical limitations. In designing the MCA, the scaling and limiting units play a major role in keeping the motions with the physical constraints of the simulator. The scaling and limiting module should be used along with washout filters to reduce the magnitude of the translational and rotational motion signals uniformly across all frequencies for all kinds of MCA, so as to decrease the effects due to workspace limitations in reproducing the simulator motions, and enhancing realism of motion sensation. In this article, by establishing a mathematical model of the nonlinear optimal MCA, PS is considered, the control strategy of nonlinear scaling and limiting is designed. The simulation results indicate that the proposed method is able to accurately duplicate motions in a simulator platform. The washout displacement and sense angular velocity signal are in conformity with shape-following criteria. And the proposed method can reduce the sensation error of motion washout process with higher fidelity and higher efficiency in platform usage without violating the physical limitations of the simulator, to eliminate the false cues occurrence. Nevertheless, there are still shortcomings to overcome, such as, how the scaling factor further improve the adaptability in the nonlinear scaling module? How can the scaling boundary division impact on the motion perception in the MCA? The researchers will have an interest in future research.

References

  1. Conrad B, Schmidt S F. Motion Drive Signals for Piloted Flight Simulators [EB/OL]. [2021-08-15]. https://ntrs.nasa.gov/archive/nasa/casi.ntrs.nasa.gov/19700017803.pdf. [Google Scholar]
  2. Nehaoua L, Amouri A, Arioui H. Classic and adaptive washout comparison for a low cost driving simulator [C]// Proceedings of the 20th IEEE International Symposium on Intelligent Control and the 13th Mediterranean Conference on Control and Automation. Piscataway: IEEE, 2005: 586-591. [Google Scholar]
  3. Asadi H, Mohammadi A, Mohamed S, et al. A particle swarm optimization-based washout filter for improving simulator motion fidelity [C]// Proceedings of the 2016 IEEE International Conference on Systems, Man, and Cybernetics (SMC). New York: IEEE, 2016: 1963-1968. [Google Scholar]
  4. Bowles R L, Parrish R V, Dieudonne J E. Coordinated adaptive washout for motion simulators [J]. Journal of Aircraft, 1975, 12(1): 44-50. [Google Scholar]
  5. Sivan R, Ish-Shalom J, Huang J K. An optimal control approach to the design of moving flight simulators [J]. IEEE Transactions on Systems, Man and Cybernetics, 1982, 12(6): 818-827. [Google Scholar]
  6. Reid L D, Nahon M A. Flight Simulation Motion-base Drive Algorithms: Part 1—Developing and Testing the Equations[EB/OL]. [2021-08-15]. http://repository.tudelft.nl/assets/uuid:45b071c0-0568-4e8f-948f-dfa52d350665/296.pdf. [Google Scholar]
  7. Telban R, Wu W, Cardullo F M. Motion cuing algorithm development: Initial investigation and redesign of the algorithms [EB/OL]. [2021-08-15]. https://ntrs.nasa.gov/archive/nasa/casi.ntrs.nasa.gov/20000041705.pdf. [Google Scholar]
  8. Asadi H, Chee P L. A genetic algorithm-based nonlinear scaling method for optimal MCA in driving simulator [J]. Proc IMechE Part I: Journal of Systems and Control Engineering, 2018, 232(8): 1025-1038. [CrossRef] [Google Scholar]
  9. Luo Z H, Wei Y D, Zhou X J. Research on variable input MCA for Stewart platform vehicle simulator [J]. Journal of Zhejiang University (Engineering Science), 2013, 47(2): 238-243(Ch). [Google Scholar]
  10. Chen W, Jiang G H, Chao J G. Signal scaling strategies for motion-base spaceflight simulators [J]. Journal of Beijing University of Aeronautics and Astronautics, 2012, 38(3): 324-329. [Google Scholar]
  11. Wu W. Development of Cueing Algorithm for the Control of Simulator Motion Systems [D]. New York: Binghamton University, 1997. [Google Scholar]
  12. Wu W, Cardullo F. Is there an optimum motion cueing algorithm? [C]//AIAA Modeling and Simulation Technologies Conference. Reston: AIAA, 1997: 3506. [Google Scholar]
  13. Zaychik K B, Cardullo F M. Nonlinear Motion Cueing Algorithm: Filtering at Pilot Station and Development of the Nonlinear Optimal Filters for Pitch and Roll [EB/OL]. [2021- 08-06]. https://ntrs.nasa.gov/citations/20120008933.pdf. [Google Scholar]
  14. Telban R J, Cardullo F M, Houck J A. A nonlinear, human-centered approach to motion cueing with a neurocomputing solver [C]// AIAA Modeling and Simulation Technologies Conference and Exhibit. Reston: AIAA, 2002: 4692. [Google Scholar]
  15. Pahlevaninezhad M, Das P, Drobnik J, et al. A nonlinear optimal control approach based on the control-Lyapunov function for an AC/DC converter used in electric aircrafts [J]. IEEE Transactions on Industrial Informatics, 2012, 8(3): 596-614. [Google Scholar]
  16. Asadi H, Mohamed S, Nahavandi S. Incorporating human perception with the motion washout filter using fuzzy logic control [J]. IEEE/ASME Transactions on Mechatronics, 2015, 20(6): 3276-3284. [Google Scholar]
  17. Mohammadi A, Asadi H, Mohamed S, et al. Optimizing model predictive control horizons using genetic algorithm for motion cueing algorithm [J]. Expert Systems with Applications, 2018, 92: 73-81. [CrossRef] [Google Scholar]
  18. Telban R J, Cardullo F M. MCA development: Human centered linear and nonlinear approaches [EB/OL]. [2021-09-06]. https://ntrs.nasa.gov/citations/20050180246.pdf. [Google Scholar]
  19. Hosman R, van der Vaart J C.Vestibular Models and Thresholds of Motion Perception: Results of Tests in a Flight Simulator [R]. Delft: Delft University of Technology, 1978. [Google Scholar]
  20. Zhu D Y, Duan S L, Shang J Q, et al. A novel nonlinear scaling method for optimal motion cueing algorithm in flight simulator [J]. Wuhan University Journal of Natural Sciences, 2020, 25(5): 452-460. [Google Scholar]
  21. Nahon M A, Reid L D. Simulator motion-drive algorithms—A designer’s perspective [J]. J Guid ContrDynam, 1990, 13(2): 356-362. [NASA ADS] [CrossRef] [Google Scholar]

All Figures

thumbnail Fig. 1 Nonlinear optimal MCA

uA: the aircraft input signal; us: the simulator motion input signal; e: pilot sensation error; FrI: the inertial reference frame; FrS: the simulator reference frame; FrPS: the pilot’s head reference frame; RI: radius vector from the inertial reference frame to the simulator reference frame; RS: radius vector from the simulator reference frame to the pilot’s head reference frame; xI, zI represent the inertial reference frame coordinate directions; xS, zS represent the simulator reference frame coordinate directions; xPS, zPS represent the pilot’s head reference frame coordinate directions

In the text
thumbnail Fig. 2 Longitudinal and pitch nonlinear optimal MCA

aAA: aircraft acceleration; aPSA: pilot’s head vestibule acceleration in simulator; aAI: acceleration after nonlinear scaling & limiting; PS: pilot station; LSI: transformation matrix from simulator into inertial frame; TS: transformation matrix from angular velocity to Euler angle rates; β˙A: angular velocity after TS; β˙SR: angular velocity after nonlinear scaling & limiting; β˙ST: washout angular velocity after tilt rate limit; β˙S: the sum of washout angular velocity; βS: washout angular displacement; s: Laplace variable; S¨I: washout acceleration in the inertial frame; S˙I: washout velocity in the inertial frame; SI: washout displacement in the inertial frame; K(α): the feedback matrix

In the text
thumbnail Fig. 3 Longitudinal acceleration signal
In the text
thumbnail Fig. 4 Sense acceleration
In the text
thumbnail Fig. 5 Washout displacement of the algorithm under linear and nonlinear conditions
In the text
thumbnail Fig. 6 Sense angular velocity
In the text

Current usage metrics show cumulative count of Article Views (full-text article views including HTML views, PDF and ePub downloads, according to the available data) and Abstracts Views on Vision4Press platform.

Data correspond to usage on the plateform after 2015. The current usage metrics is available 48-96 hours after online publication and is updated daily on week days.

Initial download of the metrics may take a while.