Next Article in Journal
A New Top-Mounted Shear-Hinge Structure Based on Modal Theory and Rubber-Pad Damping Theory
Previous Article in Journal
Horizontally Layered and Vertically Encased Geosynthetic Reinforced Stone Column: An Experimental Analysis
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Performance Evaluation of a Quadcopter by an Optimized Proportional–Integral–Derivative Controller

Department of Electrical Engineering, University of Da-Yeh University, No.168, University Rd., Dacun, Changhua 515006, Taiwan
*
Author to whom correspondence should be addressed.
Appl. Sci. 2023, 13(15), 8663; https://doi.org/10.3390/app13158663
Submission received: 24 May 2023 / Revised: 21 July 2023 / Accepted: 22 July 2023 / Published: 27 July 2023
(This article belongs to the Topic UAV Remote Sensing of Cyber-Physical System)

Abstract

:
This paper presents an analysis of a quadcopter’s stability and its sensors’ data reading using an IMU (inertial measurement unit). Firstly, the angular velocity and acceleration data are read by an Stm® development board embedded with an Stm32f401ccu6 microcontroller. The altitude of the measurement instrument platform was determined using an MS5611 barometric pressure sensor combined with a temperature sensor. The quadcopter’s control was achieved by connecting a brushless DC motor to the Stm® board, which received four PWM (pulse-width modulation) signals via the output port. An electronic governor was utilized to control the brushless DC motor, while a pre-existing remote control was designated as the transmitter. The quadcopter receiver received a 2.4 GHz signal from the transmitter using the BLE (Bluetooth low-energy) protocol, which was used to ensure the simultaneous operation of the four brushless DC motors. Finally, a PID (proportional–integral–derivative) controller was employed for parameter adjustment. The collected PID parameter program was developed in the Simulink software as a simulation platform, allowing for the execution of the Simulink model on the Stm® MCU. The Stm® module facilitates monitoring of the performance of the UAV (unmanned aerial vehicle) and enables immediate parameter adjustments to ensure flight stability. This research aims to reduce calculation errors in sensor and controller usage and improve the efficacy of the remote machine module for future industrial applications.

1. Introduction

Recently, the application of UAVs (unmanned aerial vehicles) has been widely launched in distinct markets. According to a report about market forces, the revenue that comes from the wide application of UAVs is expected to exceed USD 8.5 billion by 2027. Additionally, UAV-based architectures have been explored for the development and implementation of next-generation technologies such as 5G, V2X (vehicle-to-everything) communications, etc. [1]. Such technologies have been applied in the industrial, agriculture, transportation, and entertainment fields, and even in the current war. The application of UAVs has gradually become a core research theme in environmental detection, and the research of aerial vehicles is most popular with aerial QA (quadrotor aircraft). Moreover, the study in [2] aimed to optimize the autonomous performance (i.e., both longitudinal and lateral) and endurance of the quadrotor-type aerial vehicle simultaneously, depending on the autopilot gain coefficients and battery weight. In [3], the authors explain that the purpose of their research was to investigate the impacts of UV (ultrasonic vibration) and tool-pin profiles on the mechanical properties and microstructural behavior of AA7075-T651 and AA6061-T6 joints. The reason that quadcopter aircraft can obtain a balance between two vehicles is due to the flight principle and materials cost. The quadcopter performs altitude calculations based on the sensors configured on the flight controller. Moreover, it is calculated by a three-axis gyroscope and a three-axis accelerometer to achieve directional monitoring of various data (e.g., angular rate, acceleration, etc.) of the quadcopter. However, there have been many critical issues, including hardware and software, which could be addressed in the deployment of the UAV. The study in [4] investigated viscous cementitious mortars for AAM (aerial additive manufacturing); it also assessed workability and buildability. A robotic arm representing UAV movement in three-dimensional space moved a lightweight deposition device to extrude multiple layers. In fact, the discussion of the PID (proportional–integral–derivative) algorithm for precisely and accurately controlling the UAV was an important research event. The PID algorithm can more effectively improve the speed control of these types of motors. Based on the previously described facts and the experimental function, we were motivated to provide a self-making and self-designing version of the PID controller. Finally, the study underwent some manual tests that support a determination of the efficacy of an in-depth controller with a PID regulator plus a direction controller equipped with an Stm® MCU (micro control unit) modular. The main objective, and effective target, was to achieve satisfactory control performance compared to other controllers. Seriously speaking, there are many existing works describing studies that were carried out that arrived at relevant results from the experimental simulation of UAVs. In report [5], authors describe in-depth research based on a quadcopter UAV model that is widely used in society, including for agricultural pesticide-spraying UAVs and defense-industry detection UAVs. Moreover, the important architecture of this UAV includes a flight controller, electronic governor, and motor. Quadcopter UAVs need to be lightweight and maneuverable, as these characteristics are advantageous [6]. Hence, the motor selected was a brushless DC motor. Compared to a brushed DC motor, the brushless DC is superior, although the cost is higher, because the brush introduces friction with the rotor inside. On the other hand, the produced sparks could result in increased maintenance costs [7]. The literature detailing the PID controller of brushless DC motors is described to help this study on the characteristics of brushless DC motors. The motor needs to convert DC into a three-phase alternating current and promote the permanent magnet in the motor structure and the stator for angle commutation. Furthermore, it needs to be energized in order, as far as the rotational moment is generated. Paper [8] proposed a concept called electron commutation, that is, a circuit of the electronic governor, realized according to the electronic commutation, adjusts the speed and direction of the motor in real time according to a change in the control signal. According to the paper discussed above, the quadcopter UAV needs not only have four brushless DC motors, but also four electronic governors. Certainly, the control center is responsible for integration, that is, the flight controller is based on the work of [8] using Stm32F407VGT6 for flight-controller development. In addition, the MCU uses an ARM-M4 processor, and the main frequency can reach up to 168 MHz. The single-chip system has high performance, which is suitable as a flight chip, and this component is similar to our human brain. Besides, it is responsible for each foreign message and signal action for the quadcopter UAV flight controller.
In fact, the MCU is required to be equipped with a gyroscope and an accelerometer, and to use the data from these sensors to determine the angular velocity of the UAV. The law of conservation of angular momentum can be evaluated according to the obtained data when the vehicle is subjected to external forces. If the angular momentum changes, the total angular momentum will not change in any way under such conditions. This concept can be applied to UAV aircraft. In report [9], the gyroscope and accelerometer use MPU6050 components to measure the angle and angular velocity of this UAV. From the pieces of knowledge according to the above description, one can calculate the external force on the UAV by measuring the angle and angular velocity of the UAV [10,11]. It could also follow up on the IMU (inertial measurement unit system) to know the error value of this application product. It is convenient to compare the error value with the target value, and let the quadcopter UAV compare this error value. The action of correcting the PID controller is an important indicator of the feedback system, through this value back to the input.
The current article proposed a basic Optimized PID architecture shown in Figure 1, which runs the tool Simulink in Matlab@, and is designed by the first-order differential equation. Such an equation can be used to verify the PID control algorithm and to eliminate the error, for example, K p , K i , and, K d . Accordingly, it is worth knowing that the above-mentioned parameters of K p , K i , and K d could be adaptively adjusted by following up with the UAV location. Typically, the order of the control steps is first to adjust the proportional value k P which is followed by the integral stage k i modification, and the correction of the derivative parameter k P will be carried out in the end, if necessary.
Therefore, the proposed algorithms of the PID controller can be declared to have optimized performance, which can be noted as the main contributions of the investigation. For this reason, the commonly used and powerful PID control concept is used to filter the transformed error variables, that is, to optimize the performance of a UAV. A composite learning algorithm consisting of a neural network and a perturbation observer is incorporated to handle the error-induced nonlinear terms as the flight safety progresses [12]. A successful solution for eliminating path deviation in multi-terrain robots has been proposed and implemented in [13]. The deviation is almost negligible after the implementation of the proposed algorithm, and it provides fusing wheel encoder and inertial measuring unit (IMU) data for PID control using the ROS (robot operating system) packages. The work in [14] proposed an NLPID (nonlinear PID) controller to stabilize the translational and rotational motion of a 6-DOF (degree of freedom) UAV quadrotor system and force it to track a given trajectory with minimum energy and error, except in the previous discussion of the PID controller which has the three parameters that can be adjusted according to the MPU6050 return angular speed and rate [15].
Generally, the motor speed is controlled by the PID controller in order to ensure that the quadcopter UAV PID is stably controlled. In [16], where the use of Ziegler–Nichols oscillation tuning rules is described, the use of closed-loop testing to obtain critical point information that is needed to determine the PID controller is detailed. The work presented in [17] illustrates a quadcopter equipped with PID controllers for stabilization requirements and that are used to regulate its four basic motions: roll, pitch, yaw angles, and altitude. The quadcopter was originally equipped with sensors and software to estimate and control the orientation of the quadcopter. In addition, an APE (adaptive perturbation estimator) was based on a DSC (dynamic sliding control) applying the PID for a UAV, as demonstrated in [18]. The presented controller is used to significantly remove the negative effects of uncertainties/perturbations to improve the stabilization control performance of a UAV.
In general, the basis of the PID controller is ultimately defined by a feedback system. However, due to the non-linear and physical parameters of multi-rotor UAVs, the attitude control system of the UAV will be designed as a cascade structure of PID control. In general, the controller consists of three attitude angles; these are Yaw (YAW), Pitch (PITCH), Roll (ROLL), which are arranged on the X, Y, and Z axis, respectively. The Z-axis of the fuselage is surrounded, and the attitude control is the basis of the quadrotor UAV PID control method. The basic knowledge of cascade PID is supplemented to facilitate future design. A multi-rotor UAV simulation model created in Matlab@Simulink that presented the results of the first stage is discussed in [19]. In the previous report, a quadcopter mechanical model was developed based on Simscape Multibody library elements. In addition, an angular position and flight altitude control model based on PID controllers was designed using the standard Simulink libraries.
It is assumed that stability, controllability, and even causality are normally the critical conditions of a control system. On the other hand, based on the constrains that motivated the investigation of the quadcopter and the data readings of the sensor analyzed by the IMU, the overall results obtained follow the methodologies proposed in this article. Recently, the PID is not efficient as mentioned by many other studies, such as in the discussion articles [20,21,22], when the environment faces external disturbances and parametric variations. However, the scenario considered in the current article points out that the use of PID was focused on the practice experiment without too much mathematical analysis. That is, the motivation for the proposed “optimized PID” is to try to give contributions on the following points:
  • Try to obtain the most stable conditions of the UAV by adjusting the four parameters, kP, ki, kd, of a PID controller.
  • Trying to obtain the best results from a PID controller that can implicitly control the roll, pitch, and the yaw of a quadrotor.
  • Attempt to implement the proposed “optimized PID” with some experimental tools (Proteus®, Matlab/Simulink®, and MCU IDE) for validating the obtained results. It is believed that these results from the experimental simulation will be of interest to beginners (even senior scientists) in terms of stability and control for a PID controller.
  • The use of devices with data-driven edge computing concepts has been discussed in the proposed methodologies. It is believed that edge computing techniques will become the main trend for embedded technologies in UAVs, even a 6-DOF UAV Quadrotor.
Then, the contribution of the article aims at firstly the angular velocity and acceleration data read by the Stm® development board embedded with an MPU6050 [23], and the altitude at which the measurement instrument platform is located by the MS5611 barometric pressure and temperature sensor. Then, in the edge device, a brushless DC motor attached to the Stm® controller is adapted to 4 PWM (pulse-width modulation) signals via the output port. To control the brushless DC motor, an off-the-shelf BLDC (brushless DC) motor is assigned as a transmitter to the electronic controller.
The rest of this paper is organized into five sections, which are described as follows. After the introductory section, the methodologies including hardware and software employed in the UAV are discussed in Section 2. The detailed implementation of the relevant techniques and the progress and results are presented in Section 3 and Section 4, respectively. Finally, a brief conclusion is given in Section 4.

2. The Statement of Methodologies

It is believed that the critical research points addressed in UAVs include many issues. For practical reasons, a common speed control structure is applied in the PID controller. The mathematical model and speed control of the BLDC (brushless DC) motor have been proposed and validated using fuzzy logic and PID controller [24,25]. Specifically, in order to achieve better performance the BLDC motor requires a control drive that facilitates the control of its speed and torque. Therefore, a suitable control driver system is required to control the speed and torque to obtain better performance for the BLDC motors. Under the considered condition, an optimized PID controller is probably the best candidate. It is a complex task to design the structure of a BLDC motor as it depends on many issues such as project selection, modeling, simulation, etc. In terms of the speed frame of the BLDC motor, a variety of modern control solutions have been proposed [26]. The main features of a conventional PID controller algorithm are that it is easily adjustable, has steady operation and has a simple design, which makes it widely used for controlling systems. In most cases, a different finding is seen in terms of practical experience where the volatility of well-structured prototypes, and different units of nonlinearity and low variability have been at work. In general, the parameters are not easily tuned for a PID controller; hence, obtaining the optimal position under the examined circumstances is challenging [27]. This study proposes a PID controller by making some changes to it, which can increase the control speed of the BLDC motor.
For example, there are different types of motors, different requirements for power supply, and even different controllers that are included in the areas of the hardware [25]. Moreover, there are the events of the control method, the different application scenarios, operating modes, etc. These are included in the software aspects. Thereafter, in the following subsection, both the hardware and software key issues are going to be addressed and explored in advance.

2.1. Software Architecture

At the beginning, the simple expression for the operation of a PID controller is introduced herein. As the basic PID architecture is shown in Figure 1, the PID controller is the most suitable controller circuit for the BLDC motor. It is well known that the PID controller mainly consists of three blocks with their corresponding circuits, and they are proportional, integral, and derivative blocks. As the name suggests, each block of the circuit is used to perform different mathematical operations. The PID diagram shown in Figure 1 clearly shows how the reference source, PID controller, driver circuit, sensors, converter circuit, inverter circuit, display scope, and motor are connected. In the theoretical discussion, the basic frequency transferring performance H ( s ) of the PID controller can be expressed as
H ( s ) = K p + K i s 1 + K d s
where K p , K i , and K d have been defined in the previous section; these are, proportional gain coefficient, the integral gain coefficient, and the derivative gain coefficient, respectively. The s is the complex frequency. Normally, the time derivative output, H ( s ) , of the controller for controlling the plant is equal to K p times the magnitude of the error pulse K d times the derivative of the time function error signal e r r ( t ) and K i times the integral, which generates the results that can be represented as
h ( t ) = K p e r r ( t ) + K i e r r ( t ) d t + K d d [ e r r ( t ) ] / d t
where the e r r ( t ) denotes the error values that occur in each parameter of the proportional, integral and derivative components. Typically, a closed-loop PID controller is used for industrial applications. Its applications are wide due to its simplicity and excellent performance; in many cases, its efficiency is more than 95%. The overall performance of the proposed optimized PID controller could be evaluated by appropriately adjusting the parameter values of K p , K i , and K d . Certainly, the error occurring in Equation (2) can be modified according to the feedback signals from the control center of a UAV on the duty of flight. The so-called optimization of a quadcopter which is able to be obtained by an optimized PID, and the analyzed results will be implemented in a later section.
In this study, the Stm® IDE device of the EC (edge computing) device is used as the main integrated development platform, which has a beginner’s learning program and supports C/C++. In addition, the advantage of the MCU is that there are many developers who build libraries embedded in the Stm® development environment for convenience when compared to other MCU modulars. Moreover, the development time cost for the Stm® modular is much lower, although the performance is much lower than other MCUs; this article focuses on it because of the advantages mentioned previously. To adjust the PID controller parameters, this paper uses the Matlab/Simulink® software platform as the test data platform and determines whether the PID controller matches the objective function according to the waveform diagram shown in Figure 2. Accordingly, the program flowchart for the PID controller program will first be written to the Stm32f401ccu6 development board. Then, the Stm32f401ccu6 will be issued. The three initial values of yaw (YAW), pitch (PITCH), and roll (ROLL) are given at a setpoint from the operator via the HMI, as shown in Figure 2. The gain constants (P, I, D) mentioned in the flowchart are used for error correction. Error correction can be achieved by performing multiple tunings. Proportional gain helps reduce the rise time; at the same time, there is a sudden increase in the overshoot which leads to the instability of the system. Tracking and correcting the error by using different tuning methods such as P, PI, PD, and PID provide effective results. Similarly, integral gain may lead to lessen in the steady-state error but lead to an increase in oscillations; differential gain can lead to an increase in the steady state error but at the same time reduce the overshoots.

2.2. Hardware Architecture

A fact that needs to be improved here is the current proposed optimized PID architecture, which is adaptively suitable for embedding in a quadcopter, especially for a UAV. It is a first step that will become an auxiliary means of machine learning to promote the performance of a PID to approach the most optimized level. On the other hand, the proposed algorithm will apply the machine learning technologies to develop the next-generation PID. In fact, the application of modeling and control method with machine learning in the development of a controller with PID have been widely adopted [28]. In the following, a test platform of optimized PID proposed in this article is shown in Table 1. The Stm32f401ccu6 embedded with three 16-bit A/D (analog-to-digital) converters for the gyroscope and accelerometer is contained in the architecture. The measurable range of the gyroscope is from ±250°, ±500°/, ±1000°, to ±2000°/s, and the accelerometer can measure between ±2, ±4, ±8, ±16 g. The above-mentioned controllable range is to track fast and slow movements more accurately. Otherwise, the remote control part uses FLYSKY’s remote control because its own remote control uses the IBUS protocol. When compared to other protocols (such as SBUS), it has the advantage of being able to transmit several channels of data at the same time.
Furthermore, the quadcopter UAV requires more channels than other thematic UAVs; hence, the FLYSKY controller was chosen, as shown in the hardware architecture diagram in Figure 3. In summary, the UAV’s propeller hardware circuit is completed and installed in a design platform that is provided by the Stm32f401ccu6 modular. It can be easily seen that there are four 30A motor drivers being driven to control the three parameters of yaw (YAW), pitch (PITCH), and roll (ROLL), respectively.

3. Implementation of the Relevant Techniques

The comprehensive review in [16] provides the state-of-the-art embedded sensors, communication technologies, computing platforms, and machine learning techniques used in autonomous UAVs. Based on the existing program and hardware circuit of the electronic governor shown in Figure 2, the hardware-related circuit is shown in Figure 4. The circuit is output by the ATMega328P MCU for three-phase PWM, the single chip will be interrupted by the two pins, the pins are officially defined as a priority, the 32th pin of this circuit diagram represents the two pins, this pin is used in the rotation position of the induction motor, and the 12, 14, and 16 pins of the circuit diagram are input to the high level, and 13, 15, and 17 are low. The speed pin is PWM output, and the 26 pin is PWM The input pin passes the high potential signal to the IC with the serial number 7407, and in order not to burn the MCU, such a triode gate is used to convert the level, and this schematic is called IRF3205 [29]. This device is an N-channel MOSFET, and the voltage at its output pin is controlled by the ATMega328P MOSFET. The switching state provides enough current and voltage to drive the motor, and the low on-resistance of the IRF3205 component also reduces motor noise and interference, allowing the motor to rotate stably. The road PWM signal is followed by the electronic governor, and it will not only read the PWM signal value but also write into the generation of electronic commutation and inform the brushless DC motor. Thus, the motor generates angular commutation and then lets the motor carry out speed-regulation action. However, at present, the ascent principle of the quadrotor UAV is based on the motor to drive the propeller rotation, and then the air resistance produces a downward reaction force. This reaction force is going to generate four different directions of rotation for the embedded motors. On the other hand, two pairs of motors rotate in opposite directions, respectively. The top-right and bottom-right motors are marked with No. 1, and No. 2, and the upper-left and lower-right motors are called No. 3 and No. 4, respectively. Motors No. 1 and No. 2 rotate counterclockwise, and motors No. 3 and No. 4 rotate clockwise to achieve the ascending flight principle of a quadcopter UAV. Specifically, the control system uses a commercial version of the remote control. Since this version of the remote control is more mature and the control of the drone has a certain danger, using a remote control with a more stable signal is necessary. The Stm32f401ccu6 modular uses the Read channel function to read the specified channel of the receiver. Once the command has been received, the function is converted to the given range according to the number of the specified channel. The channel is initialized when it is closed and maintains the stability of the channel output PWM signal. The channels of the receiver are the first channel that presents the mean of the “aileron” used to control the roll axis of the quadcopter. This command is received by the Stm32f401ccu6 modular and the lateral movement control signal of the right stick of the remote control. In addition, the second channel is the lifting channel; although this term and the throttle channel conflict, their essential concept is different. That is, the pitch axis is in the form of the pitch axis as in the definition of the quadcopter. The pitch axis is the axis that rotates back and forth around the ride when the quadcopter UAV performs a lifting motion.
Normally, to keep the speed of the left and right rotor propellers unchanged, the speed of the front rotor propeller can be reduced. It is also possible to increase the speed of the rear propeller. The two methods suggested above can be used simultaneously. Anyway, the aforementioned statement is also applied to the pitch motion. The simulation of the basic PID operation is carried out in the tool Proteus® Ver. 8.9 [30], which provides all the components used in the circuit used. In the following, the description to the fact of the action used the methods of “trial and error” is necessary, because most of the simulation is implemented practically. However, there is an oscilloscope equipped to measure the real-time signals between the transmitter and the receiver embedded in the controller based on the Stm® MCU.
The third channel is the throttle channel which is the key to the vertical flight control of the quadcopter UAV. As the name suggests, it is used to increase or decrease the speed of the four brushless DC motors simultaneously. Accordingly, the lift generated by the four rotors could make the body rise or fall. Therefore, to achieve climbing or falling, the fourth channel is proposed to be subjected to the steering gear. The principle of the fourth channel is able to overcome the influence of the reverse torque. In general, two of the four rotor propellers rotate clockwise and the other two rotate counterclockwise. The two diagonal propellers on the diagonal rotate in the same direction. Following the experimental motivation, this paper uses the remote control to control four brushless DC motors simultaneously through the Stm® modular with Stm32f401ccu6, in adjusting the balance of the retort, hovering, and other phenomena by the PID controller.

4. Detailed Discussions and Results

The discussion of the implementation of the proposed improved PID methods is going to be described in this section. In addition, the full hardware skeleton is also introduced. The results of the simulation are also presented.
As shown in Figure 5, which includes six main hardware parts for the hardware skeleton of the developed UAV, there is a receiver with #FS-IA6B, a battery with 3200 mah BETA LIPO, four brushless DC motors with A2212/15T/930KV, a flight controller with Stm32f401ccu6, a gyroscope/accelerometer with MEMS MPU6050 sensor, and an electronic governor with 30A ZMR, and so on. Hence, the configuration of the UAV is organized by the above-mentioned parts plus a remote control referred to as FLYSKY-16X.
In this article, the Java code developed is uploaded to the Stm32f401ccu6 development platform. The data are simulated using Matlab®/Simulink for wave patterns, and the Serial Receive module is deployed to receive the simulated code [31]. As the statement has been announced in the introductory section, the PID architecture proposed in Figure 5 in fact has a linear behavior of the PID. However, the outcomes from the simulation have actually revealed that the proposed method has good performance in terms of accuracy, robustness, finite time convergence, and the robustness of flight activity when it is compared with other PID structure [32]. The previously mentioned proposed PID performance can be proved with the results which were obtained later.
The connection diagram for the overall system flow of PID to control a quadrotor UAV is shown in Figure 6. The waveform type uses an integer of 32 bytes, and the flight controller outputs a PWM data response signal, as shown in Figure 7. This module receives the remote control signal from the flight controller to send the PWM signal. It is obvious that the stability of the generated PWM signals is well achieved for the PID controller. That is, the previous statement could be explained by the phenomena that occur on the X axis and Y axis, which represent the scales of amplitude and time, respectively. The amplitude always occurs as approximately 1018 during the duration of 0 to 5 s, and can remain in a stable state for a long time. The above fact has verified the optimized PID’s functionality.
Moreover, the simulation of the motor speed response waveform of the Stm® Stm32f401ccu6 is also evaluated. In the deployment, the three online measured degrees, YAW, PITCH, and ROLL, are monitored by the Stm32f401ccu6 as the block shown in Figure 6. In the surveillant system, these three values are calculated and shown in Figure 8. For example, the roll, pitch, and yaw are displayed as “1370”, “448” and “-24”, respectively. The “positive” and “negative” values illustrated in Figure 8 could correspond to indicate the “forward” and “reverse” directions. The data are helpful in the process of designing the PID controller in the future. On the other hand, the data are useful for recognizing that the quadrotor UAV can be operated under normal control. At the same time, the UAV could arrive at the correct local position and flight direction according to the message shown in Figure 8, which was sent back to the control center.
Certainly, it is worth trying to compare the response outputs via a PWM signal generated by the proposed PID controller with the other techniques discussed in [15]. Seriously, the PWN signals are generated in a firmly fixed way, as shown in Figure 7, which means that there is no doubt that the PWM signal is always kept stable from the starting point of the flight controller to the end. Accordingly, the PWM signals generated from the so-called “optimized PID” controller can cause the UAV to operate and work rigidly. Thus, the aforementioned fact has consistently outperformed the performance shown in article [15]. Moreover, the three parameters, which include k P , k i , and k d , are relevant to a PID controller. The comparative item defined as “rise time” occurs at different scenarios of the PID models which are divided as PID-1, PID-2, and PID-3. The comparative results are demonstrated in Table 2 where the three parameters of ( k P ,   k i ,   k d ) are assumed as ( 1 ,   0.0 ,   0.0 ) , ( 1 ,   1 / 300 ,   0.0 ) , and ( 0.1 ,   1 / 100 ,   0 ) , respectively. Finally, it is obvious to understand that the “Rise time” of the three different PID models can be adjusted and obtained as corresponding to values of 0.0180, 0.0180, and 0.0352 s. Actually, in Table 2, the “rise time” generated from the proposed “Optimized PID” with three different PID models is compared with the outcomes from article [15].
Eventually, the validation of the performance evaluated on the proposed optimized PID could be certified with quantification. A feasible first-order continuous system with time delay and the transfer function of 1 / ( 60 s + 1 ) is applied to the explain the behavior for the proposed optimized PID shown in Figure 1. The characteristic equation can be calculated by making the denominator expressed in the transfer function equal to zero, that is, ( 60 s + 1 ) = 0 . According to the previous discussion, the PID can mainly provide feedback on the changing signal depending on the error values measured from the output of the controller. Typically, the order of the control steps is as follows: adjust the k P value, then the k i factor, and finally the parameter of k P .
There are 12 figures included in Table 3 where the simulation of the optimal PID controller proposed in this article is carried out by adjusting different PID parameter values. In order to limit the size of the text, only some of the plots obtained in the simulation section will be explained in this article. For example, in graph (a) shown in Table 3, the yellow and green curves denote the control signal as “after PID regulation” and “without PID regulation”, respectively. It is clear to see that the stability of the controller can be quickly researched under conditions without k i values. On the other hand, the speed of stability for a PID controller is definitely not dominated by the value of k d . Additionally, plot (c) shown in Table 3 tells that k i should decrease since the larger value of k i will lead to divergence of the control signal.

5. Conclusions

In this article, the stability of the quadcopter and the data readings of the sensor have been analyzed using the IMU. The results from the simulation tools not only include the proposed improvement of the PID control way, but the performance evaluation of the developed UAV is also presented. On the other hand, this paper has learned through the development of the flight controller of quadcopter UAV. Through surround sensing and reading the data of roll, pitch, and yaw, numerical computation have been carried out to help UAV communication system integration. The integration of the combination of signal processing and communication is a difficult problem. Even in the era of AI (artificial intelligence) technology breakthroughs, quadcopter UAV autonomous flight technology still needs to be developed further through AI algorithms to implement more accurate hovering, trajectory flight, and obstacle avoidance. The various flight control algorithms of machine vision technology can deeply understand the mystery of drones through this research. Thus, the evaluation of the schemes proposed in the study suggests that much more stable controllability and a reduction in the response time of the UAV system are achievable.

Author Contributions

Formal analysis, J.I.-Z.C. and H.-Y.L.; investigation, J.I.-Z.C. and H.-Y.L.; visualization and resources, H.-Y.L.; project administration, J.I.-Z.C.; supervision, J.I.-Z.C.; writing—original draft, H.-Y.L.; writing—review and editing, J.I.-Z.C. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Informed consent was obtained from all subjects involved in the study.

Data Availability Statement

The datasets generated during and/or analyzed during the current study are available from the corresponding author on reasonable request.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Drone Market Outlook in 2021. Available online: https://www.businessinsider.com/drone-industry-analysis-market-trends-growth-forecasts (accessed on 22 February 2023).
  2. Şahin, H.; Kose, O.; Oktay, T. Simultaneous Autonomous System and Powerplant Design for Morphing Quadrotors. Aircr. Eng. Aerosp. Technol. 2022, 94, 1228–1241. [Google Scholar] [CrossRef]
  3. Yuvaraj, K.P.; Joshua, J.G.S.; Shanmugam, A. Impact of Ultrasonic Vibration Power and Tool Pin Profile on Mechanical and Microstructural Behaviour of Friction Stir Welded Dissimilar Aluminium Alloy Joints. Aircr. Eng. Aerosp. Technol. 2023, 95, 685–696. [Google Scholar]
  4. Dams, B.; Chen, B.; Shepherd, P.; Ball, R.J. Development of Cementitious Mortars for Aerial Additive Manufacturing. Appl. Sci. 2023, 13, 641. [Google Scholar] [CrossRef]
  5. Koca, Y.B.; Aslan, Y.; Gökçe, B. Speed Control Based PID Configuration of a DC Motor for An Unmanned Agricultural Vehicle. In Proceedings of the 2021 8th International Conference on Electrical and Electronics Engineering (ICEEE), Antalya, Turkey, 9–11 April 2021; Volume 117–120. [Google Scholar]
  6. Mahmud, M.; Islam, M.R.; Motakabber, S.M.A.; Satter, M.D.A.; Afroz, K.E.; Ahasan Habib, A.K.M. Control Speed of BLDC Motor using PID. In Proceedings of the 2022 IEEE 18th International Colloquium on Signal Processing & Applications (CSPA), Selangor, Malaysia, 12 May 2022; Volume 11. [Google Scholar]
  7. Gadekar, K.; Joshi, S.; Mehta, H. Performance Improvement in BLDC Motor Drive Using Self-Tuning PID Controller. In Proceedings of the 2020 Second International Conference on Inventive Research in Computing Applications (IRCA), Coimbatore, India, 15–17 July 2020; pp. 1162–1166. [Google Scholar]
  8. Ömürlü, V.E.; Gurkan, B. STM32F407VG Microprocessor Based Flight Controller Design Experimented on a Quadrotor. In Proceedings of the 2019 6th International Conference on Electrical and Electronics Engineering (ICEEE), Istanbul, Turkey, 16–17 April 2019. [Google Scholar] [CrossRef]
  9. Hsieh, S.T.; Lin, C.L. Fall Detection Algorithm Based on MPU6050 and Long-Term Short-Term Memory Network. In Proceedings of the 2020 International Automatic Control Conference (CACS), Hsinchu, Taiwan, 4–7 November 2020; Volume 1. [Google Scholar]
  10. Li, Z.; Su, Z.; Yang, T. Design of Intelligent Mobile Robot Positioning Algorithm Based on IMU/Odometer/Lidar. In Proceedings of the 2019 International Conference on Sensing, Diagnostics, Prognostics, and Control (SDPC), Beijing, China, 15–17 August 2019. [Google Scholar] [CrossRef]
  11. Chi, H.; Zhu, Z. Research on Ackerman Driverless Vehicle Control Strategy Based on IMU Steering Calibration and Inverted Parabolic Speed Control. In Proceedings of the 2021 IEEE International Conference on Consumer Electronics and Computer Engineering (ICCECE), Guangzhou, China, 15–17 January 2021. [Google Scholar] [CrossRef]
  12. Yu, Z.; Zhang, Y.; Jiang, B. PID-type Fault-tolerant Prescribed Performance Control of Fixed-wing UAV. J. Syst. Eng. Electron. 2021, 32, 1053–1061. [Google Scholar]
  13. Kannan, M.R.; Deepak, N.; Katta, N.; Vamsi, G.; Kumar, A.P. PID Based Locomotion of Multi-terrain Robot Using ROS Platform. In Proceedings of the 2020 Fourth International Conference on Inventive Systems and Control (ICISC), Coimbatore, India, 8–10 January 2020; pp. 751–756. [Google Scholar]
  14. Aws, A.N.; Kasim, I.I. Nonlinear PID Controller Design for a 6-DOF UAV Quadrotor System. Eng. Sci. Technol. Int. J. 2019, 22, 1087–1097. [Google Scholar]
  15. Say, M.F.Q.; Sybingco, E.; Bandala, A.A.; Vicerra, R.R.P.; Chua, A.Y. A Genetic Algorithm Approach to PID Tuning of a Quadcopter UAV Model. In Proceedings of the 2021 IEEE/SICE International Symposium on System Integration (SII), Fukushima, Japan, 11–14 January 2021. [Google Scholar]
  16. Budnyaev, V.A.; Filippov, I.F.; Vertegel, V.V.; Dudnikov, S.Y. Simulink-based Quadcopter Control System Model. In Proceedings of the 2020 1st International Conference Problems of Informatics, Electronics, and Radio Engineering (PIERE), Novosibirsk, Russia, 10–11 December 2020. [Google Scholar] [CrossRef]
  17. Ayele, B.T. Controlling Quadcopter Altitude Using PID-Control System. Int. J. Eng. Res. Technol. (IJERT) 2019, 8, 195–200. [Google Scholar]
  18. Thanh, H.L.N.N.; Choong, H.L.; Sung, K.H. Adaptive Perturbation Estimator based Dynamic Control using PID Sliding Manifold for a Quadcopter UAV. In Proceedings of the 2021 International Conference on Advances in Electrical, Computing, Communication and Sustainable Technologies (ICAECT), Bhilai, India, 19–20 February 2021. [Google Scholar]
  19. Dubey, Y.; Shinde, M.; Sheikh, R.; Upadhye, P.; Hulke, H.; Suneja, D. Stabilization of Flight Controller for Unmanned Aerial Vehicle. In Proceedings of the 2021 International Conference on Artificial Intelligence and Smart Systems (ICAIS), Coimbatore, India, 25–27 March 2021. [Google Scholar] [CrossRef]
  20. Sankaranarayanan, V.N.; Yadav, R.D.; Swayampakula, R.K.; Ganguly, S.; Roy, S. Robustifying Payload Carrying Operations for Quadrotors Under Time-Varying State Constraints and Uncertainty. IEEE Robot. Autom. Lett. 2022, 7, 4885–4892. [Google Scholar] [CrossRef]
  21. Ganguly, S.; Sankaranarayanan, V.N.; Suraj, B.V.S.G.; Dev Yadav, R.; Roy, S. Efficient Manoeuvring of Quadrotor under Constrained Space and Predefined Accuracy. In Proceedings of the 2021 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Prague, Czech Republic, 27 September–1 October 2021; pp. 6352–6357. [Google Scholar] [CrossRef]
  22. Sankaranarayanan, V.N.; Roy, S. Introducing Switched Adaptive Control for Quadrotors for Vertical Operations. Optim. Control. Appl. Methods 2020, 41, 1875–1888. [Google Scholar] [CrossRef]
  23. Wilson, A.N.; Kumar, A.; Jha, A.; Cenkeramaddi, L.R. Embedded Sensors, Communication Technologies, Computing Platforms and Machine Learning for UAVs: A Review. IEEE Sensors J. 2022, 22, 1807–1826. [Google Scholar] [CrossRef]
  24. Jasim, M.H. Tuning of a PID Controller by Bacterial Foraging Algorithm for Position Control of DC Servo Motor. Eng. Technol. J. 2018, 36, 287–294. [Google Scholar] [CrossRef]
  25. Rajkumar, M.V.; Ranjhitha, G.; Pradeep, M.; PK, M.F.; Sathishkumar, R. Fuzzy Based Speed Control of Brushless DC Motor Fed Electric Vehicle. Int. J. Innov. Stud. Sci. Eng. Technol. (IJISSET) 2017, 3, 12–17. [Google Scholar]
  26. Singirala, M.; Krishna, D.; Kumar, T.A. Improving Performance Parameters of PM BLDC Motor Using Fuzzy Sliding Mode Controller. Int. J. Recent Technol. Eng. (IJRTE) 2019, 8. [Google Scholar]
  27. Available online: https://www.Stm.cc/ (accessed on 22 March 2023).
  28. Available online: https://www.infineon.com/cms/en/product/power/mosfet/n-channel/irf3205/ (accessed on 22 January 2023).
  29. Available online: https://www.labcenter.com/ (accessed on 22 January 2023).
  30. Zhou, L.; Pljonkin, A.; Singh, P.K. Modeling and PID Control of Quadrotor UAV Based on Machine Learning. J. Intell. Syst. 2022, 31, 1112–1122. [Google Scholar] [CrossRef]
  31. Wang, S.; Chen, J.; He, X. An Adaptive Composite Disturbance Rejection for Attitude Control of the Agricultural Quadrotor UAV. ISA Trans. 2022, 129, 564–579. [Google Scholar] [CrossRef] [PubMed]
  32. Fortuna, L.; Frasca, M.; Buscarino, A. Optimal and Robust Control: Advanced Topics with MATLAB®, 2nd ed.; CRC Press: Boca Raton, FL, USA, 2021. [Google Scholar]
Figure 1. Basic Optimized PID architecture proposed in the article simulated with Matlab@Simulink.
Figure 1. Basic Optimized PID architecture proposed in the article simulated with Matlab@Simulink.
Applsci 13 08663 g001
Figure 2. Basic algorithm of PID operation flow.
Figure 2. Basic algorithm of PID operation flow.
Applsci 13 08663 g002
Figure 3. UAV’s propeller hardware circuit diagram.
Figure 3. UAV’s propeller hardware circuit diagram.
Applsci 13 08663 g003
Figure 4. Basic PID architecture simulated in the tool of Proteus®.
Figure 4. Basic PID architecture simulated in the tool of Proteus®.
Applsci 13 08663 g004
Figure 5. The brand-new UAV proposed in this article.
Figure 5. The brand-new UAV proposed in this article.
Applsci 13 08663 g005
Figure 6. The overall system flow of PID for controlling a quadrotor UAV.
Figure 6. The overall system flow of PID for controlling a quadrotor UAV.
Applsci 13 08663 g006
Figure 7. The flight controller outputs a response signal.
Figure 7. The flight controller outputs a response signal.
Applsci 13 08663 g007
Figure 8. The reading data from the quadcopter of yaw, pitch, and roll.
Figure 8. The reading data from the quadcopter of yaw, pitch, and roll.
Applsci 13 08663 g008
Table 1. UAV hardware components.
Table 1. UAV hardware components.
CategoryProduct Name
Flight controllerStm32f401ccu6 Development board
Gyroscope/accelerometerMEMS Stm32f401ccu6 Sensor
Electronic governor30A ZMR Simon Brushless ESC
Brushless DC motorA2212/15T/930KV
Remote controlFLYSKY FS-I6X
ReceiverFS-IA6B
RackF450 V2 Shen PCB Carbon fiber reinforced nylon arm
Power supplyModel aircraft lithium battery 3200 mah BEAT LIPO
Propeller1045 10/inch
Table 2. The comparative results of “Rise time” for three different PID models.
Table 2. The comparative results of “Rise time” for three different PID models.
ArticlesParametersPID-1PID-2PID-3
[15](kP, ki, kd)(4.1302, 89.8994, 0.0511)(2.9055, 22.8899, 0.0208)(2.5865, 20.9157, 0.0106)
“Rise Time” (s)0.02280.04150.0479
Proposed(kP, ki, kd)(1, 0.0, 0.0)(1, 1/300, 0.0)(0.1, 1/100, 0.0)
“Rise Time” (s)0.1800.1800.352
Table 3. The simulation results from the optimal PID controller proposed in this article.
Table 3. The simulation results from the optimal PID controller proposed in this article.
Fixed ValueVariated Values
PID-1

kP = 1
kd = 0
ki = 0 (a)ki = 5 (b) ki = 1/10 (c)
Applsci 13 08663 i001Applsci 13 08663 i002Applsci 13 08663 i003
PID-2

ki = 1/300
kP = 1
kd = 0 (d) kd = 1/10 (e)kd = 10 (f)
Applsci 13 08663 i004Applsci 13 08663 i005Applsci 13 08663 i006
PID-3

kP = 0.1
kd = 0
ki = 1/100 (g) ki = 1/200 (h) ki = 1/300 (i)
Applsci 13 08663 i007Applsci 13 08663 i008Applsci 13 08663 i009
PID-4

ki = 1/300
kP = 0.1
kd = 5 (j) kd = 10 (k) kd = 100 (l)
Applsci 13 08663 i010Applsci 13 08663 i011Applsci 13 08663 i012
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Chen, J.I.-Z.; Lin, H.-Y. Performance Evaluation of a Quadcopter by an Optimized Proportional–Integral–Derivative Controller. Appl. Sci. 2023, 13, 8663. https://doi.org/10.3390/app13158663

AMA Style

Chen JI-Z, Lin H-Y. Performance Evaluation of a Quadcopter by an Optimized Proportional–Integral–Derivative Controller. Applied Sciences. 2023; 13(15):8663. https://doi.org/10.3390/app13158663

Chicago/Turabian Style

Chen, Joy Iong-Zong, and Hsin-Yu Lin. 2023. "Performance Evaluation of a Quadcopter by an Optimized Proportional–Integral–Derivative Controller" Applied Sciences 13, no. 15: 8663. https://doi.org/10.3390/app13158663

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop