Abstract

A methodology for the experimental modelling of the electric actuators of a multirotor is presented in this work. These actuators are usually brushless DC motors which are driven by electronic speed controllers in an open loop. The duty cycle of a PWM signal, generated by the electronic control unit, is the input of the electronic controller. However, during the control design procedure for the multirotor, it is important to account with a model of the actuators as its dynamical features define the closed-loop performance of the overall aircraft. Hence, a procedure, based on low-cost electronic components, to obtain approximated transfer functions of the actuators of a multirotor is presented. Moreover, as the proposed signal processing algorithms are simple, the computational capabilities of the required embedded system are also low. Given that different control schemes require different information from the actuator, two models were obtained: a duty cycle vs. angular velocity transfer function and a duty cycle vs. consumed current transfer function. The effectivity of the proposal is validated with experimental results on common electric actuators of a multirotor.

1. Introduction

Several research and application projects have been developed based on the capabilities of an unmanned aerial vehicle (UAV). From agriculture [1] to noninvasive landmine detection [2], the wide range of disciplines impacted by these aircrafts is impressive and increasing. However, the performance of the UAV is determined by the effectiveness of the automatic control algorithm implemented in it, which allows the vehicle to develop a specific required task. There are some control schemes for UAVs that do not need the knowledge of the dynamic model of the vehicle or any of its subsystems [3]. However, most of the controllers used for this type of vehicles require a total or partial knowledge of their dynamical characteristics. In particular, those controllers oriented to increase the robustness of the system’s closed-loop behavior by means of sliding modes control [4, 5], adaptive control [6, 7], or neural networks [8]. Therefore, a lot of efforts have been done to obtain or identify a model for these systems [9] or their actuators [1012]. The most common actuators for commercial UAVs are brushless direct current (BLDC) motors for their light weight, energy consumption, and speed/torque ratio. In [13, 14], respective methodologies to the model identification of these type of actuators were developed and applied in real-time experiments. Usually, the performance of controlling and monitoring a UAV rely in the accuracy of the actuators dynamical model. Due to that, a methodology for their experimental approximation is presented in this work, which is based on the obtaining of a transfer function identification. First, the standard closed-loop control scheme for UAVs is presented and the role of the actuator, and its controller is explained. Then, the actuator model and configuration are defined. After that, the experimental setup and results are outlined. Finally, some conclusions and future work are described.

1.1. Closed-Loop Controllers for UAVs

A standard closed-loop control scheme for UAVs is depicted in Figure 1. In particular, the scheme represents the elements of a controller for a quadrotor, but it can easily be extended for any multirotor.

The scheme is composed by the vehicle, the actuators (usually BLDC motors), the drivers, the actuator controller, and the UAV controller. The latter receives a reference vector , which describes the desired behavior for the vehicle, and generates the desired angular velocities of the propellers , , which are the inputs of the actuator controllers. After that, the actuator controllers generate the duty cycle of the PWM signals injected to the drivers of the actuators. These, in turn, generate the three-phase voltages injected to the actuators to set the actual angular velocities of the propellers , which are the inputs of the vehicle.

There are two options for the actuator controller: open loop or closed loop. The former determines signals based on a calibration process which stablishes a relation between the duty cycle and the generated angular velocity for each actuator. The second option requires the measurement of the current angular velocity of the actuator, represented by the dashed line in Figure 1. Evidently, the open loop option is simpler and cheaper, but the closed-loop option offers the possibility to enhance the transient response, steady-state error, and robustness of the overall system. In any case, obtaining the dynamical model for the actuators results in great benefits in the performance of the overall control scheme.

Moreover, for a model-based UAV controller design, it is necessary to define a dynamical model for the UAV which considers the state of the vehicle as where are the 3D coordinates and are the Euler angles of the vehicle. Analyzing the torques and forces on the vehicle generated by the propellers at angular speeds , , , and , the dynamics for the position and the attitude of the vehicle results in the form [9, 15]. where , , are the moments of inertia of the vehicle, and its mass; is the gravitational acceleration, , , and , , , are given by with as the distance from the center of mass of the vehicle and the center of the propeller, as the thrust factor, and as the drag factor of the actuators.

On the other hand, there are diverse flight modes for a UAV, i.e., manual mode, altitude hold, GPS position hold, return to home, waypoint tracking, and stabilize mode, among others. The difference between these flight modes can be defined by the reference vector sent to the UAV controller. For instance, if the waypoint tracking mode is set, then the UAV controller receives the reference where correspond to the coordinates of the waypoint and defines the desired yaw angle. Else, if a stabilize mode is used, the reference vector is defined as , i.e., the desired attitude and altitude of the vehicle are specified.

1.2. Actuators Dynamical Model and Configuration

The electric motors used in most of the commercial multirotor vehicles are brushless DC motors with electronic speed controllers (ESC) in an open loop. This type of motors comes in one-, two-, or three-phase configurations, being the latter the most common version [16] and the one used in this work. In order to actuate these motors, an electronic commutator sequentially energizes the stator coils, generating a rotating electric field that drags the rotor around with it. Thus, electrical revolutions equate to one mechanical revolution, where is the number of magnet pairs. In the case of 3-phase motors, three Hall-effect sensors are commonly embedded in the stator to indicate the relative positions of stator and rotor to the controller, so it can energize the windings in the correct sequence and at the correct time. The Hall-effect sensors are usually mounted on the nondriving end of the unit, as shown in Figure 2.

All electric motors generate a voltage potential due to the movement of the windings through the associated magnetic field. This potential is known as an electromotive force (EMF), and it gives rise to a current in the windings with a magnetic field that opposes the original change in the magnetic flux; in other words, EMF tends to resist the rotation of the motor and is, therefore, referred to as back EMF.

The standard dynamical model for the 3-phase BLDC motor is composed of two parts: the electrical and the mechanical. The electrical part is defined by the following differential equations: where , , and are the voltage inputs, corresponding to the three phases of the motor, , , and are the phases currents, and , , are the back EMF of each phase. It is assumed that the stator phases are balanced; hence, the phase resistance , the self-inductance , and the mutual inductance are equal for the three phases, and the equation is fulfilled. Also, it is considered that the back EMFs are trapezoidal and given by where is the back EMF constant of the motor, is the electrical angle of the rotor which is related to the mechanical angle of the rotor with where is the number of poles of the motor. The terms , , and are the standard trapezoidal functions of the motor defined as in [17]. The mechanical part of the motor is described by the equations. where is the rotor inertia, is the friction coefficient, is the load torque, and is the generated electric torque which is defined as

Finally, by means of equations (1)–(4), a complete dynamical model for the BLDC motor results as where the output of the motor is the angular velocity which corresponds also to the angular velocity of the propeller. The parameters of the equations (6) are extremely difficult to characterize as the current and voltages for the three phases must be measured, in addition to the angular velocity and position of the rotor. Hence, we proposed to obtain an approximated model of the BLDC motor by means of two transfer functions. The first relates the duty cycle applied to the motor with its current consumption and it is defined as . The latter relates the duty cycle applied to the motor with its angular velocity it is defined as . These relationships are depicted in Figure 3.

Therefore, the proposed methodology considers the identification of these two transfer functions by introducing test inputs signals to the real BLDC motor and monitoring the consumed current and angular velocity of the rotor. The sensors required for this procedure are inexpensive and will be described in detail in the following section. It is worth to note that for a control scheme that is not based on a model of the actuator, i.e., PID, the consumed current information could appear useless. Nonetheless, some model-based controllers, i.e., backstepping and block control, would need the knowledge of this variable. In addition, the consumed current can be used to monitor the performance of the rotor, the energy cost of a task with the multirotor, and a possible actuator fault.

1.3. Experimental Setup

In order to inject test signals to the real BLDC motor, a Pixhawk flight controller board is used, altogether with the ArduPilot ArduCopter base code. Hence, a current and an angular speed sensor are necessary to capture these variables of the motor generated by the test input signal. To this end, a daughter board platform is used due to the lack of user-oriented functions in ArduCopter, the timing limitations of the scheduler tasks, and the reduced ADC and input-capture ports of the Pixhawk board. This secondary board is based on an ATMEGA328/P microcontroller running at 16 MHz, which provides numerous 10-bit ADC precision ports and voltage level detection pins.

The speed controllers used in the vehicle can support up to 12 A when driving the BLDC motors. Therefore, the same current rate, or higher, needs to be measured in the motors during flight. Therefore, an ACS712ELCTR-20A-T is used which is a low-profile SOIC8 current sensor that can be attached to the UAV, without compromising the weight load that it can support. Basically, the sensors are linear Hall-effect devices with a copper conduction path that generates a magnetic field that is sensed by the Hall integrated circuit (IC) and converted to a proportional voltage signal. The device has a response time of 5  and can operate with a 5 V supply voltage, which is suitable for embedded systems and suits in the UAV circuitry. The sensor mounted in the vehicle and its interconnection with the other elements of the testing system is depicted in Figure 4.

On the other hand, the angular velocity sensor for the motors is implemented by means of a black and white-striped band attached to the brushless motor and a CNY70 sensor to capture the reflectance of the stripes transitions during the rotation of the axle of the motor. The time between transitions is measured and, using that, the angular velocity is computed. The mounting of this sensor on the vehicle and its interconnection with the daughter board are shown in Figure 5.

This electronic instrumentation setup provides the current consumption and angular velocity measurements during the testing of the BLDC motor to obtain the approximated transfer function, as described in the following section. It is worth to note that all the components of the experimental setup are low cost and commonly found in any electronics provider. Furthermore, the complexity of the implemented algorithms during the experiments is also low which impacts in the cost and requirements of the daughter board. The components of the overall testing system and the vehicle is depicted in Figure 6.

2. Simulation Results

The proposed methodology was proved by means of simulations and real-time experiments, and their results was analyzed and discussed in the following sections. The overall process consists of two stages: a model identification and a model validation.

2.1. Model Identification

First, the dynamical model of a BLDC motor, given by equation (7), was implemented in Simulink using the parameters of Table 1.

Then, a simulation experiment of the system was carried out for 8 s. During this period, the duty cycle of the PWM input signal for the BLDC motor was variant according to the following behavior: for 4 s, and for 4 s. The resulting angular velocity and consumed current of the motor are depicted in Figure 7. It is worth to note the high frequency components in the current signal as it is characterized by a faster response.

After that, the data obtained from the previous simulation is used with the identification toolbox from MATLAB in order to obtain a transfer function for the angular velocity and the consumed current . The resulting transfer functions are defined by

The poles for the angular velocity and current systems are and , respectively.

2.2. Model Validation

Once the models for the BLDC motor are obtained, a test signal is introduced in the transfer functions and in the system (7) for comparison purposes. The simulation experiments were carried out for 8 s, and the duty cycle of the PWM input signal for the systems was variant according to the following behavior: for 2 s, for 4 s, and for 2 s. These duty cycle values are different from the values used during the identification stage in order to validate the accuracy of the obtained transfer functions. The results of these simulations are shown in Figure 8 where the angular velocity and current for the transfer function and the original model are depicted. It can be noted that the performance is satisfactory in terms of settling time and steady-state error.

3. Experimental Results

After the simulation experiments, a real-time implementation of the proposed methodology was carried out using a commercial version of a BLDC motor for a drone with a standard 6030 propeller. The selected motor is the MT2204-2300KV motor from EMAX [18] which is shown in Figure 9.

3.1. Model Identification

As described in the former sections, the first step of the proposed methodology is to introduce test signals to the real BLDC motor and to obtain the responses for the angular velocity and the current consumption. For that purpose, the ESC is injected with a PWM signal of a 100% duty cycle for a period, and, later, the duty cycle is decreased to 50%. This will permit us to observe both possible step transient behaviors. The current consumption and angular speed responses to the experiment are displayed in Figures 10 and 11, respectively. It can be noticed that the angular speed signal does not have the first overdamping that is seen in the current consumption. This is due to the time constant of the variables as the current is characterized by a significant lower time constant than the angular speed, i.e., it can achieve a faster response.

After that, the data of both responses is imported to the MATLAB [19] environment as an input for the system identification toolbox which is used to obtain an approximated transfer function of a system based on the knowledge of the input (duty cycle) and output (current consumption and angular velocity) of an experiment. In addition, the toolbox permits to define the number of poles and zeros of the transfer function to be approximated, and, for comparison purposes, several combinations were tested. In that regard, 100 iterations for the fitting process were executed for each zero/pole combination. The six most accurate transfer function approximations are listed in Tables 2 and 3 for the angular speed and current consumption, correspondingly. The best approximated model, in terms of accuracy, corresponded to 2 zeros and 2 poles for the angular speed, and to 4 poles and 4 zeros for the current consumption. The obtained transfer functions were used in the model validation process which will be described in the following section.

3.2. Model Validation

In order to validate the approximation of the obtained transfer function with respect to the real motor, the control scheme described in Figure 1 was implemented in a commercial UAV. The UAV controller was designed using the backstepping control technique [15] considering velocity sensors for the actuators. In addition, the well-known PID controller for the angular velocity of the studied BLDC motor was developed and implemented. It is defined by the following equation: where is the angular velocity error variable and the parameters , , and are the control gains which were tuned heuristically.

The closed-loop response of the output of the motor is shown in Figure 12 which demonstrates that the control objective is fulfilled. It can be noted that the performance of the control scheme is better in steady state than in the transient. In addition, Figure 13 shows the comparison between the measured angular velocity and the output of the obtained transfer function for the angular velocity. Consistently with the simulation results presented in Figure 8, the best performance of the approximated transfer function is appreciated in the steady-state part of the response. This is due to the limited capabilities of a transfer function to capture the dynamical behavior of a complex system as a BLDC motor. As the implemented controller is based on the two transfer functions obtained by means of the proposed methodology, they show the effectiveness of the proposed methodology.

4. Results Analysis and Discussion

The performance presented in both stages of the simulation results were satisfactory as the feasibility of the presented methodology was demonstrated. Particularly, the steady-state response showed that the obtained transfer functions correspond to good approximations of the BLDC motor behavior in terms of angular velocity and consumed current. Furthermore, the experimental results demonstrated a satisfactory performance. The validation stage was carried out during the flight of the UAV with a standard UAV controller based on the backstepping technique. It permitted to evaluate the methodology in a more realistic manner than only introducing test signals to a single BLDC motor.

However, the transient response is characterized by a considerable error. This would decrease the bandwidth of the whole solution for applications as fault detection of actuators during flight time, or adaptive control scheme based on the obtained transfer functions. A good option to alleviate this could be to append to the methodology the characterization of some fundamental parameters of the motor.

5. Conclusions and Future Work

A methodology for the obtaining of a dynamical model approximation for actuators of a UAV was presented. The considered actuator is a 3-phase BLDC motor as it is the most common type of actuator for this type of vehicles. The methodology requires the implementation and instrumentation of a current and an angular velocity sensor which are inexpensive. In addition, the complexity of the algorithms implemented in the required daughter board is low. The methodology is easy and straightforward and can be applied for any type of electrical motor used as actuator for UAVs. The experimental results showed the effectiveness of the presented proposal.

On the other hand, the presented results correspond to an ongoing project developed by the authors. Hence, the next steps for the work consider the implementation of the actuator’s controller based on the obtained models, the inclusion of parameters identification, and a fault detection algorithm based on the implemented sensors and the obtained transfer functions. To this end, an extension of the proposed model would be interesting in order to improve the error between the model and the real motor during the transient response.

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 is no conflict of interest regarding the publication of this paper.

Acknowledgments

This work was supported by the National Council of Science and Technology of México under grants no. 335335 and no. 261774.