Abstract

The tilt trirotor unmanned aerial vehicle (UAV) is a novel aircraft that has broad application prospects in transportation. However, the development progress of the aircraft is slow due to the complicated control system and the high cost of the flight experiment. This work attempts to overcome the problem by developing a hardware-in-the-loop (HIL) simulation system based on a heavily developed and commercially available flight simulator X-Plane. First, the tilt trirotor UAV configuration and dynamic model are presented, and the parameters are obtained by conducting identification experiments. Second, taking the configuration of the aircraft into account, a control scheme composed of the mode transition strategy, hierarchical controller, and control allocation is proposed. Third, a full-scale flight model of the prototype is designed in X-Plane, and an interface program is completed for connecting the autopilot and X-Plane. Then, the HIL simulation system that consists of the autopilot, ground control station, and X-Plane is developed. Finally, the results of the HIL simulation and flight experiments are presented and compared. The results show that the HIL simulation system can be an efficient tool for verifying the performance of the proposed control scheme for the tilt trirotor UAV. The work contributes to narrowing the gap between theory and practice and provides an alternative verification method for the tilt trirotor UAV.

1. Introduction

Tiltrotor UAV is an aircraft that has three flight modes including hover, transition, and forward. Therefore, it enjoys many advantages, such as long endurance, high mobility, and less site limitation [1, 2]. In the hover mode, it can vertically takeoff and land (VTOL), so that there is no need for a runway. In the forward mode, long-distance transportation can be achieved due to its long endurance and high cruise speed. Due to these advantages, a tiltrotor UAV has received considerable attention in recent decades [3, 4]. It can be applied to aerial photography, target identification and localization, environmental protection, and so on. It is worthwhile to mention that the tiltrotor UAV may perform an impressive role in the field of urban air traffic [5]. Airbus has proposed a tilt-wing aircraft named Vahana for the urban air mobility passenger transportation mission [6]. Besides, Uber has taken an interest in the urban air traffic based on the VTOL aircraft [7]. However, the development progress of tiltrotor UAV is slow because of the high cost and risk of flight experiments. Few mature platforms can be applied for engineering applications [8].

At present, many countries such as the United States, Korea, Israel, and China are devoted to developing the tiltrotor UAV for its outstanding advantages. The Eagle Eye developed by the United States is one of the successful tiltrotor UAVs in operation. However, there are several serious accidents caused by the complexity of the control system and aerodynamic model, and the aircraft has not come into extensive use [9]. Korea designed a tiltrotor UAV named Smart UAV, which is configured similar to the Eagle Eye. Although many experiments with the Smart UAV have been carried out, the aircraft is still in the test stage [10, 11]. Israel Aircraft Industries designed a tilt trirotor UAV named Panther. The rear rotor can tilt for the control of yaw motion. Note that Panther is the first tilt trirotor UAV, which has been delivered to the army as equipment [12]. The VTOL aircraft FireFLY6 developed by Birds Eye View Aerobotics has six propellers. The two rotors fixed at the rear of the aircraft are only for hovering and remain off during forwarding flight. The other rotors in the front are driven by the same servo and can synchronously tilt 90 degrees for mode transition [13]. Panther and FireFLY6 are two typical aircrafts that have been applied in practice; however, the cruise efficiency and flight stability are still needed to be improved.

The development of the tiltrotor UAV suffers from various difficulties including the control scheme and verification method. More and more research works are published to solve the two problems. Kang et al. built the mathematical model of the tiltrotor UAV, and a neural network controller was designed for stable flight control. The control performance under turbulent wind conditions was validated through the nonlinear simulation [14]. Papachristos et al. proposed an explicit model predictive control scheme relying on constrained multiparametric optimization, and the effectiveness of the scheme was demonstrated based on a tri-tiltrotor equipped with rotor-tilting mechanisms [15]. Yucel et al. designed a tiltrotor UAV named TURAC using a cheap, rapid, and easily reproducible prototyping methodology. Mathematical and CFD analyses were performed to optimize the design. The low-cost prototyping methodology was verified by ground and flight experiments [16, 17]. Many control algorithms are proposed for a tiltrotor UAV, while few efficient verification methods are developed.

Due to the cost of designing a prototype and high risk for conducting a flight experiment, most of the advanced algorithms proposed for the tiltrotor UAV are validated by software simulation. It is well known that the effectiveness of simulation relies on the accurate mathematical model, which is difficult to be obtained. The HIL simulation with a high degree of accuracy as an actual flight contributes to verifying the control scheme and improving development efficiency. The most realistic flight simulator X-Plane is widely used for developing and testing flight control scheme [18]. Adriano et al. developed a HIL simulation system that consists of an academic autopilot and X-Plane to verify and optimize the hardware. The fixed-wing attitude control scheme was proposed and verified by the HIL simulation, in which X-Plane was used to simulate the aircraft dynamics, sensors, and actuators [19, 20]. Sergio et al. designed a quadrotor using Plane Maker provided by the X-Plane flight simulator and proposed a novel approach to design an attitude controller for the quadrotor according to the learning algorithm. The simulation system composed of Simulink and X-Plane was built to investigate and verify the control algorithm [21]. Zhang et al. developed a test system, including autopilot and X-Plane, to validate the control structure and narrow the gap between the theory and practice. The results show that the autopilot that passed the validation in HIL simulation can be directly applied to the real flight [22]. Due to the variable structure of the tilt trirotor UAV during flight, the aerodynamic model is too complex to be acquired. However, the tilt trirotor UAV with unique configuration can be designed with the help of Plane Maker, and the aircraft model imported into the X-Plane flight simulator is capable of simulating real flight with a high degree of accuracy. It is evident that HIL simulation based on X-Plane is an effective, rapid, and low-cost method to develop and verify control schemes for a tilt trirotor UAV.

In this paper, the motivation is to provide an efficient method for verifying the performance of the hardware and software designs of the control scheme for a tilt trirotor UAV. The X-Plane-based HIL simulation system that contributes to developing and verifying the control scheme of the aircraft is presented. First, we design a tilt trirotor UAV with three rotors, two servos, elevator, and aileron. For the designed aircraft, the control principle and mathematical model are presented. The critical parameters as the moment of inertia, mass, and coefficients of the rotor are obtained through the identification experiments. Second, in order to achieve stable control of the aircraft in different modes, a complete control scheme that consists of the mode transition strategy, hierarchical controller, and control allocation is developed. The control scheme is coded using C programming language and embedded in the autopilot designed for HIL simulation and flight experiment. Third, the advantages of the X-Plane flight simulator are illustrated in detail. According to the tilt trirotor UAV parameters, the 3-dimension (3D) full-scale model used to simulate actual flight dynamics is developed using Plane Maker. And then, the HIL simulation system that consists of the autopilot, ground control station, and X-Plane is developed. Finally, the HIL simulation and flight experiment results are presented and compared to illustrate the reliability of the HIL simulation system. The control scheme validated by the HIL simulation can be directly moved on to the flight experiment, and only control gains need to be adjusted. Based on the HIL simulation system, the risk and cost of the flight experiment can be reduced; meanwhile, the development efficiency is improved.

The remaining sections are arranged as follows. In Section 2, the configuration and control principle of the tilt trirotor UAV are demonstrated, and then, a serial of identification experiments is conducted. Section 3 details the control scheme of the aircraft. In Section 4, the accurate full-scale 3D flight model based on the prototype is designed using Plane Maker, and then, the HIL simulation system is developed. In Section 5, the results of the HIL simulation and flight experiment are presented. In Section 6, the conclusion and future research work are outlined.

2. Tilt Trirotor UAV

The designed tilt trirotor UAV is a novel aircraft with a unique structure. To further understand the aircraft, we briefly describe the configuration and dynamic model of the tilt trirotor UAV. Then, the parameter identification is completed by conducting different experiments.

2.1. Model Description

As shown in Figure 1, the tilt trirotor UAV is equipped with three rotors, two servos, elevator, and aileron. The tilt trirotor UAV has three flight modes, including hover, transition, and forward modes. Two front rotors are able to be tilted by using servos and poles, so that the aircraft can fly under different modes. Note that the two tilting servos are embedded in the nacelles. The two front rotors are able to tilt from to with respect to the vertical axis, and the rear rotor is installed vertically. The right rotor and rear rotor rotate in counter-clockwise while the left in clockwise.

Taking the hierarchical control structure into account, position control is achieved by adjusting the attitude of the aircraft. In the hover mode, three rotors and two servos are used to control attitude. The different thrusts between the left and right rotors are used to control the roll motion. The rear rotor can compensate for the moment generated by two front rotors to stabilize the pitch. The yaw moment is created by the difference of tilting angles between the two front rotors. In the forward mode, the elevator and aileron are used for pitch and roll control, respectively. The aircraft is designed without the rudder, so the yaw motion is achieved by adjusting the thrust of two front rotors, and the rear rotor remains off in the forward mode. The principle of flight control in the hover and forward modes are shown in Figure 2.

The tilting angles of two rotors are denoted by and , respectively. The thrust of the rotor is influenced by the rotation speed . The symbol represents the angle of aileron deflection, and the angle of elevator deflection is represented by . The mathematical model of the tilt trirotor UAV that contains kinematic equations, navigation equations, force equations, and moment equations is expressed as follows [23, 24]:where is defined as

In these expressions, the position of the center of gravity in the world frame is expressed as , denotes the linear velocity of the aircraft in the body frame, denotes the mass, represents the rotational angular velocity, is the Euler angle, and is the inertial matrix with respect to the body frame. The rotation matrix from the body frame to the world frame is , and denotes the transformation matrix from the body frame to the world frame. The force and moment imposed on the aircraft are denoted using and , and these force and moment are generated by the rotors, wings, and surfaces. It should be pointed out that the aerodynamics of the tilt trirotor UAV is difficult to be obtained; however, the mathematical model is an important part of the simulation. To efficiently tackle this issue, the X-Plane flight simulator is introduced to provide dynamics of the aircraft; to this end, parameters of the prototype should be acquired for designing a 3D flight model.

2.2. Parameter Identification

In this section, the parameter identification and related work of the tilt trirotor UAV are presented. On the one hand, constant parameters including the moment of inertia and coefficients of the rotor are obtained. On the other hand, the method used for estimating the tilting angle is demonstrated.

The compound-pendulum method and bifilar torsion pendulum method are used for measuring the moment of inertia of the aircraft [25, 26]. According to the methods described above, the measurement of the oscillation period is the most important part. To obtain the oscillation period, the autopilot with sensors is introduced to the experiment. The oscillation period can be obtained by recording the change of attitude. The partial results are shown in Figure 3.

Three groups of experiments are conducted for different axes, respectively, and the accurate period is obtained by calculating the average of three measurements. According to the value of the oscillation period, the moment of inertia with respect to three axes can be acquired as follows:

The rotor is one of the most important actuators for the tilt trirotor UAV. In our work, the rotor of the aircraft is composed of a inch propeller and a motor. A novel intelligent ergometer that can record the value of force, moment, and rotation speed is applied to test the rotor. The test system that contains a rotor, ergometer, lithium battery, and computer is shown in Figure 4.

Assuming that the air density is constant, there is a linear relationship between the thrust and the square of rotation speed. The thrust and torque can be calculated by the following equation [27].

Data are acquired after the test of the rotor, and thrust coefficient and torque coefficient can be obtained by using the least square method. According to the specification of the motor and propeller, the maximum thrust that a rotor can provide is around . The curve-fitting results are shown in Figure 5, and then, the value of rotor coefficients are given as follows:

The yaw control is achieved by adjusting the tilting angle of the rotor. Taking the structure of the tilting mechanism into account, it is difficult to install a sensor for measuring the tilting angle. Therefore, a utility approach should be proposed to estimate the tilting angle for flight control. In the practical application, the function relation between the angle and command should be built first, and then, we can estimate the tilting angle online according to the command. The calibration is divided into two steps. In the first step, an angle measuring instrument is fixed in the rotor, the tilting angle is changed by adjusting the output command of the autopilot, and the value of tilting angle corresponding to different commands is recorded. Due to the existence of installation error, two rotors are calibrated separately. The measurement process is presented in Figure 6.

In the second step, by fitting the recorded data, the function expression of the tilting angle and command is acquired. The fitting results are shown in Figure 7, and the function can be acquired as in equation (6). It is evident that the two rotors have a different tilting angle when given the same command. This problem is caused by the installation error and can be solved based on the result of calibration. The contributions of equation (6) contain two aspects. On the one side, the decoupled control allocation algorithm can be designed based on the estimation of the tilting angle. On the other side, the precise control of the tilting angle is achieved without the angle sensor. It is noteworthy that the commands and are solved from the desired tilting angles, and then, the two front rotors can be driven by the servos to the desired angles, respectively. In the real flight, the tilting angle error can be limited to no more than 2 degrees by using the estimation method:

It should be mentioned that, for building the accurate mathematical model in the X-Plane, parameters such as wingspan and rotor position are also obtained. According to the model described above, the control scheme and a full-scale 3D flight model are developed.

3. Control Design

The control scheme consists of the mode transition strategy, hierarchical controller, and control allocation. Considering the existence of the hover, transition, and forward modes, the mode transition strategy is designed for achieving safety mode conversion. The tilt trirotor UAV is an underactuated system, and a hierarchical controller using PID is developed to control position and attitude. The control allocation is proposed to provide the mapping from the virtual control commands to the manipulated inputs of the aircraft. For the tilt trirotor UAV, the three parts described above are necessary for flight control.

3.1. Mode Transition Strategy

The altitude and attitude are the key factors for stable mode transition. The control system aims to stabilize the altitude and attitude in flight. As a matter of fact, it is difficult to obtain the accurate aerodynamic model in the transition mode, so that the airspeed should be increased as quickly as possible to ensure flight safety. A phased mode transition strategy is designed according to the mode transition command and flight airspeed. To illustrate the transition process clearly, the transition from the hover mode to the forward mode is called the conversion phase, and the transition from the forward mode to the hover mode is called the reconversion phase.

The conversion phase is completed with the increase of the airspeed. First, after receiving the conversion command, the two front rotors tilt forward to an angle within seconds. With the tilting angle increasing, the airspeed increases, and the wings start generating lift. Second, if the airspeed achieves in which the aerodynamic can compensate a part of the gravity, all rotors are shut down; meanwhile, two front rotors tilt forward to the horizontal position within seconds. Finally, the aircraft enters into the forward mode and cruises at . In this work, the reconversion phase is a relatively simple process. After receiving the reconversion command, the two front rotors are shut down and tilted backward to the vertical position within seconds. And then, the aircraft enters into the hover mode and begins to decelerate flight. Note that and should be set small enough to ensure the stable of the transition flight. Conversion and reconversion phases are shown in Figure 8.

3.2. Hierarchical Controller

Due to the tilt trirotor UAV is an underactuated system, a PID-based hierarchical controller is introduced to achieve the position and attitude control. In terms of hover and forward modes, two controllers are applied, respectively. Note that the hover controller is also used in the transition mode. Figure 9 shows a block diagram of the flight control system.

For the hover controller, the outer loop is used for the position control, and it receives the desired position from the navigator and outputs the desired thrust vector in the world frame. According to the inverse transformation and desired yaw angle , the desired pitch angle and roll angle can be solved; besides, the virtual thrust in the body frame is obtained [28]. The inner loop attitude controller receives the desired angles and provides the virtual control torque . The virtual thrust and control torque are inputs of the allocator, and then, the control inputs of actuators can be obtained based on the control allocation algorithm. For the forward controller, the outer loop position controller is composed of the longitude control and lateral control. navigation logic is used for the lateral control; then, the desired yaw angle and roll angle can be obtained based on the desired position and current position [29]. The longitude control is completed based on the total energy control method; the desired pitch angle and virtual thrust are acquired according to the altitude and airspeed [30]. The attitude controller in different flight modes has two loops including an angular loop and an angular rate loop. The angular loop uses the P controller to produce the desired angular rate for the angular rate loop. And then, the virtual control torque is provided by the angular rate loop, which is based on the PID controller.

3.3. Control Allocation

In this section, the control allocation algorithm that provides the mapping from the control inputs to the manipulated inputs of the aircraft is presented [31]. It should be pointed out that the control allocation under the forward mode is the same as the traditional fixed-wing. So that we focus only on the control allocation for the hover controller. The tilt trirotor UAV has four virtual control inputs , and , where is directly linked to roll control, is used for pitch control, is related to yaw control, and the altitude is controlled by . There are five actuators including three rotors and two servos that can be used for flight control. It is known that the change of rotation speed is much faster than the change of the tilting angle. According to the response speed of actuators, the calculation of actual outputs can be divided into two parts.

For the first part, the rotation speeds of three rotors are acquired by , and . The right rotor, the left rotor, and the rear rotor are labeled by 1, 2, and 3, respectively. To calculate rotation speeds from the virtual commands, the tilting angles are determined based on the equation (6).where

The vector denotes the position of the rotor in the body frame. Since the matrix is a square matrix, the keypoint to obtain the rotation speed is to verify the reversibility of the matrix . Taking the symmetry of the aircraft into account, we have and . In this manner, the determinant of matrix can be written as

For the hover mode and transition mode, the tilting angles are limited to . Considering the differential control of two front rotors, we have . Then, we can conclude that

According to the above derivation, the reversibility of is proved, so that the rotation speed can be obtained by

For the second part, there are two tilting angles that need to be determined based on . The yaw control of the aircraft is achieved by the differential tilting angles generated by two front servos. Considering the fact that the yaw motion can be adjusted effectively by tilting the two front rotors in opposite directions. From this point of view, the tilting angles are given as follows:where is a small constant that depends on the maximum tilting angle and the corresponding yaw moment, is an original angle, which is relevant to flight modes, and in the hover mode. The proposed control allocation is very useful for the aircraft without the tilting angle sensor; besides, it is easy to be applied in real flight.

4. HIL Simulation System

X-Plane is a commercially available flight simulator written by Laminar Research, that can be installed on computers running Windows, Linux, or Mac OS. In this work, X-Plane is applied to provide the model of the tilt trirotor UAV and simulate its dynamics. The advantages and communication interface are illustrated, and then, a full-scale 3D flight model is designed.

4.1. X-Plane Flight Simulator

The flight simulator X-Plane is chosen because of its ability to predict the aircraft’s flying qualities with high accuracy. This is performed by using the blade element theory. The aircraft is divided into many small elements, and the forces acting on each element are calculated several times per second. Compared to the other flight simulators such as Flight Gear and FSX, X-Plane is more flexible and advanced. Moreover, it is the only flight simulator that has obtained certification from the Federal Aviation Administration (FAA), which makes the simulation results more credible [32]. Numerous companies as Cessna, Cirrus, and Boeing have purchased X-Plane as an engineering tool; in addition, many researchers have applied X-Plane to develop and test control schemes. X-Plane provides Plane Maker and Airfoil Maker to enable users to create the aircraft and airfoils as easily as possible. The benefits of using X-Plane are(a)Realistic simulation environment: Laminar Research claims that using the blade element theory to calculate the forces on the aircraft is more accurate than the stability derivative method. The cloud cover, rain, wind, thermals, microburst, and fog can be simulated in X-Plane. The certification from the FAA allows researchers to achieve high levels of confidence in simulation results. The results of many papers have verified that the simulation based on X-Plane has a high degree of accuracy as an actual flight.(b)Database of aircraft models: thousands of manned and unmanned vehicle models are freely available for download at the X-Plane forum. Although not necessarily certified, these models provide quick starting points for testing. Most important of all, Plane Maker makes it possible for researchers to design their aircraft model, so that the particular aircraft such as the tilt trirotor UAV can be developed and tested.(c)Communication: X-Plane can communicate with external processes via User Datagram Protocol (UDP). The UDP protocol is well suited for simulating because there is no check as delivery, detection, or error correction; it is possible to achieve high-speed data traffic. X-Plane accepts control signals to drive actuators and outputs flight information. Note that X-Plane is capable of outputting all the navigation data necessary to perform a simulation and allows users to adjust the update rate from 1 to 99 packets per second.

The data packet of X-Plane that has 41 bytes follows a standard format [33]. The first four bytes denote the characters “DATA,” which indicates that this is a data package. The fifth byte is a code “I,” and it is used for internal policy. The remaining 36 bytes are divided into nine groups: the first group of four bytes presents a label to identify the set of data, and the other eight groups denote the data need to be sent. The first byte of the group is the sign bit, which tells whether the number is positive or negative. To further illustrate the data packet, a packet that contains Euler angles is shown in Figure 10. The packet is labeled 17 in X-Plane (version 10.42), and the values of the Euler angles are selected. Not all the groups are filled with data in practice, and the detailed information can be acquired from the manual.

4.2. Design of the Flight Model

The 3D model of the tilt trirotor UAV is performed using Plane Maker, which allows the user to create nearly any type of aircraft [34]. The program provides a graphical interface to design an aircraft according to the physical specifications (weight, engine power, wingspan, wing area, control surfaces, and the center of gravity). And then, X-Plane is capable of predicting how that aircraft will fly. Based on Plane Maker, we can edit the fuselage cross section at a maximum of 20 locations along the fuselage length, with up to nine points at each cross section. This allows for much more accurate modeling of the fuselage than simply stating the radius and length, as is the case in most software which can only model simple bodies of revolution.

To build an accurate X-Plane model, useful information such as dimensions and weight of the aircraft is measured as shown in Table 1, and then, the designing process is divided into three parts. First, the fuselage is the basic frame for adding other parts, and it is relatively simple to be modeled based on the prototype. Second, wings and control surfaces are designed according to the airfoil and actual parameters. Finally, the rotor consists of a motor, and a propeller is modeled. For the motor, the value of input such as provides 1500 watts of power to the aircraft, and the motor turns off when given 0. Figure 11 shows the prototype and X-Plane model. It should be mentioned that the X-Plane model has three rotors, two servos, elevator, and aileron. Therefore, it is able to drive actuators as the prototype does when given the same command.

4.3. HIL Simulation System Setup

The HIL simulation system consists of a dedicated autopilot, X-Plane simulator, and ground control station. The diagram of the HIL simulation system for the tilt trirotor UAV is shown in Figure 12. An open-source ground control station named QGroundControl that can parse and package the UDP packet is applied. We have completed the secondary development of the QGroundControl, so that it can be used to connect with the tilt trirotor UAV in the X-Plane environment. The control scheme is embedded and realized in the autopilot using the C programming language. The autopilot hardware is placed inside the simulation loop in order to test and validate both the hardware and control scheme, and it receives the states of the aircraft simulated by X-Plane and outputs control commands. The control commands are sent to the X-Plane and used to control rotation speeds, surfaces, and tilting angles of the flight model. Note that all state information necessary for flight control can be provided by X-Plane.

The autopilot shown in Figure 12 is developed for the control of the tilt trirotor UAV. The autopilot embedded two ARM Cortex-M4 microcontrollers, working up to 168 MHz of clock rate. In addition, a triaxial gyro, triaxial accelerator, triaxial magnetic field meter, barometric altimeter, and airspeed meter are integrated into the autopilot. The autopilot linked with an external GPS module can be applied to perform the predefined mission in the flight experiment. The interface resource of the autopilot contains 1 serial peripheral interface (SPI), 1 S-bus (RC receiver), 2 CAN BUS, 4 serial ports, and 16 PWM outputs. In HIL simulation, a serial port is used to communicate with the ground control station, and the RC receiver transmits manual control signals to the autopilot through the S-bus port.

It should be pointed out that the X-Plane is capable of providing a realistic simulation environment. Moreover, the autopilot and ground control station used in HIL simulation is the same as the flight experiment. Based on HIL simulation, we can test both the autopilot and control scheme. The autopilot that passed the validation in HIL simulation can be directly moved on to the prototype, and the flight experiment can be conducted with minimum modification.

5. Results

In this section, the mode transition flight is conducted in the HIL simulation environment to verify and improve the control scheme. And then, the flight experiment using the same autopilot and control scheme is carried out. The effectiveness of the control scheme and HIL simulation system are demonstrated by comparing the results of the simulation and experiment.

5.1. HIL Simulation Results

In order to verify the control scheme and test the HIL simulation system, we set an oblong airline flight mission, in which the mode transition process can be demonstrated clearly. After receiving the takeoff command, the aircraft is capable of carrying out the mission automatically. The predefined oblong airline contains fifteen waypoints. The aircraft switches the mode and completes the mission as shown in Figure 8. In the first waypoint, the aircraft receives the conversion command and switches the flight mode by tilting two front rotors. And then, the aircraft conducts the mission under the forward mode. When the aircraft arrives at the fourteenth waypoint, it receives the reconversion command and enters into the hover mode. Finally, the aircraft flies to the fifteenth waypoint and lands under the hover mode.

Mode transition flight is the most important part of the flight mission. The key parameters for mode transition in HIL simulation are shown in Table 2. Based on the mode transition strategy mentioned earlier, the conversion phase is completed by tilting two front rotors as shown in Figure 13. It is noteworthy that we mainly focus on the conversion phase due to the reconversion phase is a relatively simple process.

To further present the flight mission, the trajectory of the aircraft in HIL simulation is shown in Figure 14. The flight mission consists of fifteen waypoints, in which waypoint 1 and waypoint 14 are introduced for mode transition. The aircraft takes off and flies to waypoint 1 under the hover mode, and then, it enters into the conversion phase based on the conversion strategy. It enters into the forward mode while the airspeed reaches and flies from waypoint 2 to waypoint 13 under the forward mode. After arriving at waypoint 14, the altitude decreases to , and the aircraft enters into the hover mode according to the reconversion strategy. In the last stage of the flight mission, the flight performance of the hover mode is demonstrated. Due to the airspeed is still large while entering into the hover mode, the aircraft begins to decelerate flight under the influence of the aerodynamic. After the airspeed decreases to less than , the aircraft flies to the last waypoint and lands. It should be mentioned that the whole flight is conducted automatically within , and we just provide the takeoff command by remote control.

The airspeed and altitude are shown in Figure 15. The yellow shaded areas denote the conversion and reconversion phases. Note that the cruise airspeed in the forward mode is set to , which is obtained based on the aerodynamic analysis and flight test of the prototype. It should be pointed out that the conversion phase costs about from to , the time used for tilting to angle is , the aircraft uses about to accelerate to with tilting angle , and then, the two rotors tilt to the horizontal position within . The reconversion phase is completed within . Due to the low airspeed when entering into the forward mode, the altitude of the aircraft decreases about 5 meters at first, and then, it climbs and accelerates with enough thrust under the forward mode. There are two peaks in the airspeed curve between and . The aircraft needs to turn left and reduce altitude significantly when getting through waypoints 11 and 12, so the curve of the airspeed and altitude has fluctuations. Around , the reconversion phase is completed, and then, the aircraft begins to decelerate by increasing the pitch angle under the hover mode, and the increasing of the altitude around is caused by the aerodynamics. After the airspeed decreases to , the aircraft flies to the last waypoint with velocity less than .

The roll angle, pitch angle, and yaw angle of the aircraft in HIL simulation are shown in Figure 16. The aircraft has achieved a good attitude control performance with the hierarchical controller. It is obvious that the desired pitch angle between and is about , which is the maximum desired pitch angle in the hover mode. Therefore, the aircraft is capable of decelerating with a positive pitch angle. The control input signals of the two front tilting servos are shown in Figure 17. The pulse width modulation (PWM) signals are used to drive actuators, and the range is (duty cycle ). The differential control of the tilting angles for yaw motion in the hover mode and transition mode is demonstrated clearly. Note that the two rotors tilt forward simultaneously in the conversion phase. However, the two rotors tilt backward to the vertical position directly in the reconversion phase. In the hover mode, there exists a constant differential angle for dealing with the torque generated by the rear rotor.

The HIL simulation results illustrate that the proposed control scheme is useful for the control of the tilt trirotor UAV. The attitude and altitude of the aircraft in the transition mode are two key factors to describe the control performance. Figure 16 shows that the attitude is able to track the reference angle accurately in the transition mode. Moreover, the altitude fluctuation after the reconversion phase is limited to . The proposed HIL simulation system contributes to testing and validating both the autopilot and control scheme.

5.2. Flight Experiment Results

Based on the autopilot and control scheme that passed validation in HIL simulation, a flight experiment is conducted to further demonstrate the effectiveness of the HIL simulation system and control scheme. The autopilot and the ground control station used in HIL simulation are directly applied for the flight experiment. The parameters for the mode transition in the flight experiment are the same as HIL simulation shown in Table 2, and only some gains of the hierarchical controller are adjusted to improve the control performance. To present the realistic of the HIL simulation with X-Plane, a flight mission similar to the one used in HIL simulation is designed for the flight experiment.

Considering the importance of the mode transition in the whole flight, the mode transition process of the tilt trirotor UAV in the air is recorded by a camera fixed on the aircraft. By comparing Figures 18 and 13, we can conclude that the mode transition strategy can be carried out effectively both in the HIL simulation and flight experiment. Figure 19 shows the 3D trajectory of the aircraft in the flight experiment. It is obvious that the trajectory is similar to the one generated by HIL simulation because of the similar flight mission. The airspeed and altitude of the aircraft in the flight experiment are shown in Figure 20. The whole flight is completed within . The conversion and reconversion phases are covered by the yellow shaded area. The conversion phase consumes about from to ; is used for tilting two front rotors from the vertical position to the angle . Under the tilting angle, the aircraft accelerates to within about , and then, the two rotors tilt forward to the horizontal position within . Around , the reconversion phase is completed within . The conversion phase consumes less time in real flight than in HIL simulation. The varying tendencies of airspeed and altitude are similar to the curves depicted in Figure 15. However, two main differences can be pointed out clearly. On the one side, due to the increasing of the airspeed, the altitude increases significantly around . On the other side, the airspeed is generally bigger than during the hover mode. It is noteworthy that the airspeed meter used in the experiment has an error when working in the low airspeed case. Meanwhile, the value of the airspeed meter is also influenced by the gust in the flight experiment.

The attitude of the aircraft in the flight experiment is shown in Figure 21. It should be mentioned that the pitch angle is not tracked well during the conversion phase; however, the changing of the pitch is relatively smooth. For decelerating flight between and , the desired pitch angle is provided by the outer loop position controller. The control input signals of the tilting servos are shown in Figure 22; note that the curves match the results depicted in Figure 17.

As shown in the results of the flight experiment, the predefined flight mission can be conducted well using the proposed mode transition strategy, hierarchical controller, and control allocation. Besides, the results of the flight experiment are remarkably similar to the results of HIL simulation. The flight experiment not only demonstrates the effectiveness of the control scheme but also verifies the reliability of the developed HIL simulation system. The control scheme and autopilot that passed the validation in HIL simulation can be easily applied to the flight experiment. The extra work required is to adjust the control gains of the controller based on the platform.

6. Conclusions

This paper presents the design and implementation of the HIL simulation system for the tilt trirotor UAV that contains advantages of helicopter and fixed-wing. In this paper, several parameter identification experiments are completed based on the developed prototype to obtain the parameters of the aircraft. The control scheme that consists of the mode transition strategy, hierarchical controller, and control allocation is proposed for the control of the tilt trirotor UAV. And then, a full-scale 3D flight model that can simulate actual flight dynamics is designed according to the acquired parameters. In order to improve efficiency and reduce the risk of the flight experiment, the HIL simulation system including the autopilot, ground control station, and X-Plane is developed. The HIL simulation and flight experiment results are presented and compared to demonstrate the performance of the control scheme. The HIL simulation system has a high degree of accuracy as an actual flight. Based on the developed HIL simulation system, defects or problems can be found and modified before the flight experiment, so that the workload and risk of the flight experiment are reduced. The work provides an alternative verification method for the development of the tilt trirotor UAV and can be used as a guide for those who want to research the novel aircraft with a special configuration. In the future work, we will pay more attention on the improvement of the control system based on HIL simulation.

Data Availability

The data used to support the findings of this study are available from the corresponding author upon request.

Conflicts of Interest

The authors declare that there are no conflicts of interest regarding the publication of this paper.

Acknowledgments

This work was supported by the National Natural Science Foundation of China (grant nos. 62003356 and 61973309).