Abstract
Increasing the flight endurance of unmanned aerial vehicles (UAVs) has received attention recently. To solve this problem, two research topics have generally appeared: Shortest-path planning (SPP) and remaining-flying-range estimation. In this work, energy-efficient path planning by considering the distance between waypoint nodes, the minimum and maximum speed of the UAV, the weight of the UAV, and the angle between two intersecting edges is proposed. The performances of energy-efficient path planning (EEPP) and generic shortest-path planning are compared using extended-Kalman-filter-based state-of-charge and state-of-power estimation. Using this path-planning tool and considering energy consumption during flight operation, two different path plans can be obtained and compared in advance so that the operator can decide which path to choose by consulting a comparison chart. According to the experimental results, the EEPP algorithm results in 0.96% of improved SOC leftover and 11.03 () of lowered SOP compared to the SPP algorithm.
1. Introduction
As unmanned aerial vehicle (UAV) technology matures, the longtime flight endurance capability of UAVs is gaining attention [1,2]. Because the energy density () of the battery pack (in particular, Li-ion) is closely correlated with the overall flight time of the UAV, it is recommended to choose cells possessing as high an energy density as possible [3,4]. However, in contrast to electric vehicles (EVs), the operation times of electric aircraft, including the UAV, drastically decrease as the system weights increase. Hence, technology development for increasing UAV flight time has been delayed for a long time.
Lately, the EV industry has been growing quickly, and automotive industry researchers have focused their attention on accurately predicting the energy leftover so that the driving range can be extended. Accurate energy leftover monitoring (state of charge (SOC) estimation in the EV industry), aims to extend the driving range, and it is related to shortest-path planning (SPP), which is essential to saving energy. Both accurate SOC estimation and SPP should ultimately enhance the fuel economy of EVs, and the same philosophy applies to UAVs.
There have been numerous studies regarding path planning. Chang et al. proposed a method to achieve an effective delivery route for trucks carrying delivery drones with moving shift-weights-based K-means clustering and traveling-salesman-problem modeling [5]. Rubio et al. presented adaptive path planning for multiple UAVs using evolutionary computation combined with market-based cooperation strategies [6].
Further, there has been research regarding the accurate estimation of the remaining driving or flying range. Oliva et al. suggested a model-based approach by combining unscented filtering and Markov chains to predict the remaining driving range (RDR) [7]. Ondruska et al. proposed the efficient computation of RDR confidence level using a feature-based linear regression framework with a varying probabilistic attainability map in real-time [8]. Ferreira et al. presented an interaction method between a driver and EV to estimate EV range using a regression-model-based data mining approach [9].
Unlike the previously listed works, this study contributes to the energy-efficient path planning (EEPP) of the UAV to ultimately increase the flight endurance compared with the general SPP. To verify the improved fuel efficiency, the concept of the extended Kalman filter (EKF)-based SOC estimation method is adopted. To mimic cell behavior, a physics-based equivalent circuit model (ECM) is used [10,11,12,13].
The overall mission hierarchy to achieve an energy-efficient path proposed in this paper is as follows.
First, with the given satellite map, the EEPP algorithm generates the most energy-efficient path with step-by-step processes; (1) obstacle detection, (2) extract obstacle, (3) obstacle separation, (4) add buffer zone, (5) Voronoi, (6) filter out useless candidates, (7) 1D optimal control, and (8) SPP or EEPP selection. Here, the format of the output path has both Euclidean and GPS coordinates. In contrast to the SPP algorithm, which uses Dijkstra algorithm, the EEPP algorithm uses three step-by-step processes; (1) find all trajectory candidates, (2) calculate total unit energy consumption (UEC) of all trajectory candidates, and (3) find a trajectory having the minimum UEC.
Second, either flight simulation with equivalent circuit model (ECM) of the Li-Ion battery pack or the flight experiment with a real Li-Ion battery pack is performed using the previously obtained energy-efficient path and gives out the voltage and current profiles of each cell.
Third, a battery state estimator uses the voltage and current profiles of cells to calculate the SOC. In particular, the battery state estimator uses the EKF to calculate the SOC.
The flow of this paper is as follows: In Section 2, the overall mission hierarchy, including four subparts (path planning, flight simulation, flight experiment, and battery state estimation), is described. In Section 3, the path planning, including the SPP and EEPP algorithms, is explained. Section 4 covers the mathematical formulation of the UAV and battery pack. Section 5 presents the simulation and experimental setups, while Section 6 shows the simulation and experiment results. Section 7 contains the conclusion of this paper and describes future works.
2. Mission Hierarchy
Figure 1 depicts the overall mission hierarchy to achieve the most energy-efficient path and corresponding estimated SOC value.
Figure 1.
Mission hierarchy.
First, using a Google Earth satellite photograph, and the takeoff and landing locations, the most energy-efficient path is determined by the path-planning part. Here, the path is saved in both the Cartesian system unit, , and the geographic coordinate system unit, .
Second, the achieved path is utilized for the indoor flight simulation and outdoor flight experiment to calculate the cell open-circuit voltage (OCV), , and load current, , data.
Third, the achieved cell voltage and current data are utilized for the battery state estimation to calculate the SOC. Both and are calculated to compare results.
With the achieved SOC value, one can finally determine whether the EEPP algorithm results in an energy-efficient path.
3. Path Planning
Figure 2 displays a magnified version of the path-planning part of Figure 1. This part results in either the shortest path or energy-efficient path. The detailed description of each subpart is given elsewhere [14].
Figure 2.
Flowchart of path planning.
3.1. SPP
The Dijkstra algorithm is used for the SPP algorithm, which utilizes the weights of each edge between nodes to calculate the minimum sum of the total distance from the start node to the goal node [15].
The overall flowchart of the SPP algorithm is shown in Figure 3.
Figure 3.
Flowchart of shortest-path planning (SPP) algorithm.
3.2. EEPP
In contrast to the general SPP algorithm, which only accounts for the distance between nodes, the EEPP algorithm calculates the energy-efficient path by considering factors including the distance between nodes, the minimum and maximum speed of the UAV, and the weight of the UAV as shown in Figure 4.
Figure 4.
Analysis of flight path using the Dubins path method [18,19,20].
The overall amount of battery consumption of the UAV, , would be
where is the battery consumption during takeoff (), is the battery consumption during hovering (), is the battery consumption during acceleration (), is the battery consumption during normal flight (), is the battery consumption during deceleration (), is the battery consumption during the circular flight (), and is the battery consumption during landing ().
Because the takeoff and landing occur in a short period and the amount of battery consumption is insignificant compared with the total consumption, and are assumed to be zero, and Equation (1) becomes
If there are number of edges in the given path,
From the equation of a single rotor helicopter in hover [16,17], the required hovering power of the UAV can be derived as
where is the mass of the UAV (), is the gravitational acceleration (), is the fluid density of air (), is the total area of the spinning rotor disk (), and is the number of rotors (no unit).
The required power for the acceleration can be derived as
where is the maximum acceleration (), and is the time taken for the acceleration ().
The required power for the deceleration can be derived as
where is the minimum acceleration (), and is the time taken for the deceleration (). Here, with assumptions that and , one can conclude .
The required power for the normal (constant speed) flight can be derived as
Here, is the maximum velocity (), and is the time taken for the normal flight ().
The required power for the circular flight can be derived as
where is the minimum velocity (), and is the time taken for the circular flight ().
The unknown value, , in Equation (5) can be calculated as
The unknown value, , in Equation (7) can be calculated as
therefore,
where is the intersection angle of two edges, which satisfies .
Because
the unknown value, , in Equation (8) can be calculated as
where is the waypoint (no unit), is the distance in which the UAV accelerates or decelerates (), and is the distance at which the UAV flies in a circular motion ().
If Equations (4)–(13) are combined into Equation (3), then
To calculate the total unit energy consumption (UEC) (), , Equation (14) is converted as
where .
The overall flowchart of the EEPP algorithm is shown in Figure 5.
Figure 5.
Flowchart of the energy-efficient path planning (EEPP) algorithm.
4. Mathematical Modeling of the UAV and Battery Pack
4.1. UAV
The configuration and governing control inputs of the quadrotor are described in Figure 6, where , , and represent earth coordinates, , , and represent quadrotor coordinates, and represents a thrust force generated by the i-th rotor in the indicated direction.
Figure 6.
Quadrotor configuration.
To extract current and voltage profiles along the predetermined path obtained from the previous section, an enhanced quadrotor dynamic model can be represented as
where is the total upward thrust of the UAV (), b is the thrust factor, and is the i-th rotor speed (), is the lever length from the center of gravity (CG) to rotors (), d is the drag factor, and , , and are torques applied on the UAV’s body along x-, y-, and z-axes () [21,22].
Here, , , , and can be calculated using proportional–integral–derivative (PID) controllers as
where , , and are PID controller gains, , , and are roll, pitch, and yaw angles (), uppercase letter * represents reference data, and is the UAV weight ().
The full quadrotor UAV dynamic model can be written as
Here, is the rotor inertia ().
Using the fact that power can be calculated by multiplying the thrust and velocity, one can calculate the required propulsive thrust power from the total upward thrust in Equation (15) as
Then, the load current can be calculated using
where is the terminal voltage (), and is the load current ().
The above equations are used for the operation of flight simulation, as shown in Figure 7.
Figure 7.
Flowchart of the EEPP algorithm.
4.2. Battery Pack
4.2.1. ECM
By using the two-ladder battery ECM and impedance voltage response, as shown in Figure 8, the can be determined as
where is the OCV voltage (), is the resistor (), is the voltage across the i-th RC-network (), is the time constant (), which is calculated as in which is the resistor () and is the capacitor () of the i-th ladder, and is the time ().
Figure 8.
Battery modeling; (a) two-ladder battery equivalent circuit model (ECM); (b) impedance voltage response.
4.2.2. TBLI Parameter Identification
The ECM parameters, including , , , , and , are extracted at SOC 10% intervals using the high-performance pulse characterization current pattern, as shown in Appendix A [12]. Here, the table-based linear interpolation (TBLI) method is used to determine ECM parameters corresponding to varying SOC values. Although , , , , and are the functions of the SOC, C-rate, and temperature, only the SOC variance effect is considered in this research.
4.2.3. SOC and SOP State Estimation
The SOC estimation is performed using the EKF for each cell. For the EKF algorithm application, Equation (21) and SOC calculation based on current integration method are fused and converted into the discrete-time state space model as
where is the SOC (), is 0.1 s, and and are system and measurement noises (), respectively. Here, the term can be calculated as where is the initial battery capacity (), is the battery efficiency (assumed as 1), and is the current battery capacity ().
With an initial estimation vector, , and covariance vector, , the estimation vector and covariance vector can be propagated using
The Kalman gain, , can be calculated as
With the updated Kalman gain, , and updated measurement, , the updated estimation vector, , can be calculated as
and the updated covariance vector, , can be calculated as
The final SOC value of the battery pack is conservatively chosen as the minimum value of each cell as
where is the SOC (%) of a battery pack at the k-th time step.
Regarding the state of power (SOP) estimation, the maximum discharging current, , can be calculated as
where is the C-rate of the cell (no unit).
The maximum discharging current considering the SOC, , can be calculated as
where is the standard deviation of the cell SOCs (), is the minimum SOC (), is the battery efficiency (assumed as one), and is the time flown from the beginning (). Here, was used for the 99.7% confidence interval of the cell SOC estimation values.
The maximum discharging current considering the cell voltage, , can be calculated as
where is the open-circuit voltage (OCV) (V), and is the minimum cell voltage (V). Here, and .
With the previously found , , and , one can calculate as
and can calculate as
Then, the maximum power that each cell could perform, , is calculated as
and compared with the maximum power that each cell performs during the discharging process, , as
where the total initial resistance of each cell, , can be calculated as
Figure 9 presents the flowchart of the battery state estimation [23].
Figure 9.
Flowchart of battery state estimation.
5. Simulation and Experimental Setups
5.1. Simulation Setup
All simulations were performed with a quadrotor vehicle with initial system properties , , , , , , , , , and , where , , , , , , and are initial position, attitude, angular velocity, velocity, acceleration, minimum flight altitude, and normal flight altitude, respectively. Also, the time step used in MATLAB/Simulink is 0.01 s, installed in a desktop with the following system specifications; Intel Core i5-4590 CPU 3.40- processor, 64-bit operating system, and 4.00- RAM. Every simulation flight was performed with a fully charged 4s 3300- battery pack.
5.2. Experiment Setup
All experiments were performed with the parts shown in Figure 1—a PX4 Pro powered F450 quadrotor, shown in Figure 10a; Pixhawk 2.1 flight controller, as in Figure 10b; QGroundControl (QGC), shown in Figure 10c; Pixhawk 2.1 Here + RTK, as in Figure 10d; eLogger V4 voltage and current data logging system, as shown in Figure 10e; and a 4s 3300- battery pack, shown in Figure 10f—for the outdoor autopilot experiment with a previously achieved energy-efficient path. In particular, the Pixhawk 2.1 Here + RTK is used for the centimeter-level autopilot path following accuracy.
Figure 10.
Flight experiment parts: (a) F450 quadrotor, (b) Pixhawk 2.1, (c) QGroundControl (QGC), (d) Pixhawk 2.1 Here+ RTK, (e) eLogger V4, and (f) 4s 3300- battery pack.
The overall experiment setup is presented in Figure 11. On the day of the experiment, the wind speed was approximately 2 .
Figure 11.
Flight experiment setup.
For the experiment, the SPP and EEPP trajectories represented as the Cartesian system unit, , obtained from the path-planning algorithm shown in Figure 2 are converted into the geographic coordinate system unit, . The detailed description can be found in previous work [24].
In particular, the waypoint list of is saved as a text file following the Pixhawk waypoint file format, as depicted in Table 1 [25]. For the waypoints lists of SPP and EEPP trajectories, see Appendix B.
Table 1.
Waypoint file format.
6. Simulation and Experimental Results
6.1. Simulation Result
From the flight simulation, the obtained current and voltage profiles are shown in Figure 12. Here, negative current represents discharging.
Figure 12.
Current and voltage profiles (simulation): (a) Current profile and (b) voltage profile.
Energy consumption comparison results of the SPP and EEPP algorithms are listed in Table 2 and Figure 13.
Table 2.
Comparison result (simulation).
Figure 13.
State of charge (SOC) and state of power (SOP) comparison (simulation): (a) SOC and (b) SOP.
The percentage difference between the actual values of SPP and EEPP is shown in Table 3 and Figure 14. According to the result, the SOC leftover is larger and the SOP peak is lower when using SPP.
Table 3.
Comparison results in percentage (simulation).
Figure 14.
The comparison results in percentage (simulation).
6.2. Experimental Result
From the flight experiment, the obtained current and voltage profiles are shown in Figure 15.
Figure 15.
Current and voltage profiles (experiment): (a) Current profile and (b) voltage profile.
Energy consumption comparison results of the SPP and EEPP algorithms are shown in Table 4 and Figure 16.
Table 4.
Energy consumption comparison (experiment).
Figure 16.
SOC and SOP comparison (experiment): (a) SOC and (b) SOP.
The percentage difference between the actual values of SPP and EEPP is shown in Table 5 and Figure 17. According to the result, the SOC leftover is larger and the SOP peak is lower when using EEPP.
Table 5.
Comparison result in percentage (experiment).
Figure 17.
The comparison results in percentage (experiment).
The overall reference, simulation, and experiment flight trajectories of the SPP and EEPP algorithms are drawn on Google Earth, as shown in Figure 18. Here, yellow polygons represent imaginary obstacles that the UAV should avoid. The blue line represents the reference trajectory that the UAV should follow. The red line represents the simulation flight trajectory. The green line represents the experiment flight trajectory.
Figure 18.
Reference, simulation, and experiment flight trajectories of: (a) SPP algorithm (2D), (b) EEPP algorithm (2D), (c) SPP algorithm (3D), and (d) EEPP algorithm (3D).
7. Conclusions
In this work, the EEPP algorithm is proposed and its performance is compared to the generic SPP algorithm using EKF-filter-based SOC estimation. Using the proposed path planning tool, two different path plans can be obtained and compared in advance. According to the experimental results, the EEPP algorithm results in an energy-efficient path.
Regarding the SOC, 0.96% is saved when using the EEPP algorithm, and this implies that the fuel economy is improved. Regarding the SOP, 11.03 ( is lowered, and this implies that the internal shock of the battery pack is reduced. Although the rate of improved fuel economy and internal shock of the battery pack is not as good in this study, these two key factors can be enhanced in mission planning with longer trajectories. Here, the difference between simulation and experiment results appears to be caused by factors such as environmental effects and a less mature quadrotor simulation model.
In the future, instead of 2D path planning, 3D path planning with an enhanced EEPP algorithm are planned to greatly improve the fuel economy of the UAV. Also, rather than the offline method presented here, the development of online real-time energy-efficient path planning based on the probabilistic method is planned.
Acknowledgments
This work was supported by the JeonNam TechnoPark (JNTP) through the project (B0080802000131).
Conflicts of Interest
The author declares no conflict of interest.
Appendix A
Figure A1.
ECM parameter values: (a) R0; (b) R1; (c) C1; (d) R2; (e) C2.
Appendix B
Figure A2.
Waypoint list of SPP and EEPP trajectories: (a) SPP; (b) EEPP.
References
- Kim, K.; Kim, T.; Lee, K.; Kwon, S. Fuel Cell System with Sodium Borohydride as Hydrogen Source for Unmanned Aerial Vehicles. J. Power Sources 2011, 196, 9069–9075. [Google Scholar] [CrossRef]
- Gao, X.; Hou, Z.; Guo, Z.; Fan, R.; Chen, X. The Equivalence of Gravitational Potential and Rechargeable Battery for High-Altitude Long-Endurance Solar-Powered Aircraft on Energy Storage. Energy Convers. Manag. 2013, 76, 986–995. [Google Scholar] [CrossRef]
- Khaligh, A.; Li, Z. Battery, Ultracapacitor, Fuel Cell, and Hybrid Energy Storage Systems for Electric, Hybrid Electric, Fuel Cell, and Plug-In Hybrid Electric Vehicles: State of the Art. IEEE Trans. Veh. Technol. 2010, 59, 2806–2814. [Google Scholar] [CrossRef]
- Noorden, R.A. Better Battery—Chemists are Reinventing Rechargeable Cells to Drive Down Costs and Boost Capacity. Nature 2014, 507, 26–28. [Google Scholar] [PubMed]
- Chang, Y.S.; Lee, H.J. Optimal Delivery Routing with Wider Drone-Delivery Areas Along a Shorter Truck-Route. Expert Syst. Appl. 2018, 104, 307–317. [Google Scholar] [CrossRef]
- Rubio, J.C.; Vagners, J.; Rysdyk, R. Adaptive Path Planning for Autonomous UAV Oceanic Search Missions. In Proceedings of the AIAA 1st Intelligent Systems Technical Conference, Chicago, IL, USA, 20–22 September 2004. [Google Scholar]
- Oliva, J.A.; Weihrauch, C.; Bertram, T. A Model-Based Approach for Predicting the Remaining Driving Range in Electric Vehicles. In Proceedings of the Annual Conference of the Prognostics and Health Management Society, New Orleans, LA, USA, 14–17 October 2013. [Google Scholar]
- Ondruska, P.; Posner, I. Probabilistic Attainability Maps: Efficiently Predicting Driver-Specific Electric Vehicle Range. In Proceedings of the IEEE Intelligent Vehicles Symposium Proceedings, Dearborn, MI, USA, 8–11 June 2014. [Google Scholar]
- Ferreira, J.C.; Monteiro, V.; Afonso, J.L. Dynamic Range Prediction for an Electric Vehicle. In Proceedings of the EVS27 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium, Barcelona, Spain, 17–20 November 2013. [Google Scholar]
- Plett, G.L. Battery Management Systems, II: Equivalent-Circuit Methods, 2nd ed.; Artech House Publishers: Norwood, MA, USA, 2014. [Google Scholar]
- Sharma, O.P. Analysis and Parameter Estimation of Li-Ion Batteries Simulations for Electric Vehicles. In Proceedings of the American Control Conference, San Francisco, CA, USA, 29 June–21 July 2011. [Google Scholar]
- Thanagasundram, S.; Arunachala, R.; Makinejad, K.; Teutsch, T.; Jossen, A. A Cell Level Model for Battery Simulation. In Proceedings of the European Electric Vehicle Congress, Brussels, Belgium, 20–22 November 2012. [Google Scholar]
- Plett, G.L. Extended Kalman Filtering for Battery Management Systems of LiPB-based HEV Battery Packs–Part 3. State and Parameter Estimation. J. Power Sources 2004, 134, 277–292. [Google Scholar] [CrossRef]
- Jung, S.; Ariyur, K.B. Robustness for Scalable Autonomous UAV Operations. Int. J. Aeronaut. Space Sci. 2017, 18, 767–779. [Google Scholar] [CrossRef]
- Jung, S.; Ariyur, K.B. Scalable Autonomy for UAVs. In Proceedings of the AIAA Infotech@Aerospace, St. Louis, MO, USA, 29–31 March 2011. [Google Scholar]
- Leishman, J.G. Principles of Helicopter Aerodynamics, 2nd ed.; Cambridge University Press: Cambridge, UK, 2002. [Google Scholar]
- Dorling, K.; Heinrichs, J.; Messier, G.G.; Magierowski, S. Vehicle Routing Problems for Drone Delivery. IEEE Trans. Syst. Man Cybern. Syst. 2017, 47, 70–85. [Google Scholar] [CrossRef]
- Dubins, L.E. On Curves of Minimal Length with a Constraint on Average Curvature and with Prescribed Initial and Terminal Positions and Tangent. Am. J. Math. 1957, 79, 497–516. [Google Scholar] [CrossRef]
- Tsourdos, A.; White, B.; Shanmugavel, M. Cooperative Path Planning of Unmanned Aerial Vehicles, 1st ed.; John Wiley & Sons: Chichester, UK, 2011. [Google Scholar]
- Jung, S.; Ariyur, K.B. Enabling Operational Autonomy for UAVs with Scalability. AIAA J. Aerosp. Inf. Syst. 2013, 10, 516–529. [Google Scholar]
- Robotics, P.C. Vision and Control: Fundamental Algorithms in MATLAB; Springer: Berlin/Heidelberg, Germany, 2011. [Google Scholar]
- Jung, S.; Ariyur, K.B. Strategic Cattle Roundup using Multiple Quadrotor UAVs. Int. J. Aeronaut. Space Sci. 2017, 18, 315–326. [Google Scholar] [CrossRef]
- Jung, S.; Jeong, H. Extended Kalman Filter-Based State of Charge and State of Power Estimation Algorithm for Unmanned Aerial Vehicle Li-Po Battery Pack. Energies 2017, 10, 1237. [Google Scholar] [CrossRef]
- Steven, B.L.; Lewis, F.L. Aircraft Control and Simulation; John Wiley & Sons: New York, NY, USA, 2003. [Google Scholar]
- QGroundControl—Waypoint Protocol. Available online: https://goo.gl/SqVVzd (accessed on 28 June 2018).
© 2019 by the author. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (http://creativecommons.org/licenses/by/4.0/).