Next Article in Journal
Methods for Continuous Blood Pressure Estimation Using Temporal Convolutional Neural Networks and Ensemble Empirical Mode Decomposition
Next Article in Special Issue
Cooperative Localization Based on Augmented State Belief Propagation for Mobile Agent Networks
Previous Article in Journal
Low Computing Leakage, Wide-Swing Output Compensation Circuit for Linearity Improvement in SRAM Multi-Row Read Computing-in-Memory
Previous Article in Special Issue
A 3D Range-Only SLAM Algorithm Based on Improved Derivative UKF
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Adaptive Cruise Predictive Control Based on Variable Compass Operator Pigeon-Inspired Optimization

1
Bio-Inspired Autonomous Flight Systems(BAFS) Research Group, School of Automation Science and Electrical Engineering, Beihang University, Beijing 100083, China
2
Beijing Specialized Machinery Institute, Beijing 100143, China
*
Author to whom correspondence should be addressed.
Electronics 2022, 11(9), 1377; https://doi.org/10.3390/electronics11091377
Submission received: 22 February 2022 / Revised: 6 April 2022 / Accepted: 16 April 2022 / Published: 26 April 2022
(This article belongs to the Collection Advance Technologies of Navigation for Intelligent Vehicles)

Abstract

:
A vehicle adaptive cruise system can control the speed and the safe distance between vehicles rapidly and effectively, which is an integral part of an intelligent driver assistance system. Adaptive cruise predictive control algorithms based on variable compass operator pigeon-inspired optimization (PIO) and PSO are proposed to improve the time response characteristics of multi-objective adaptive cruise system predictive control. Firstly, a longitudinal kinematic model of an adaptive cruise system was established and linearly discretized. Secondly, the multi-objective optimal cost function and parameter constraints were designed by integrating factors such as distance error, relative speed, acceleration and impact, and a mathematical model of the adaptive cruise predictive control optimization problem was constructed. Finally, PIO and PSO were used to solve the optimal control law for MPC and simulated by Matlab. The results show that the adaptive cruise system can reach a steady state quickly with the control laws of PIO or PSO. However, due to the global optimization and fast convergence characteristic, variable compass operator PIO has better time response characteristics.

1. Introduction

A vehicle adaptive cruise control system can control the speed and the safe distance between vehicles rapidly and effectively, which is an integral part of intelligent driver assistance systems. The common methods of adaptive cruise control systems include optimal control [1], sliding mode variable structure control [2], fuzzy neural network control [3], model predictive control [4] and multi-mode switching control [5], among others. The adaptive cruise control method can improve safety and fuel economy of a vehicle system [6]. A method of eco-ACC has been designed to reduce energy consumption and increase the life of the battery [7]. The performance of five typical policies in adaptive cruise control (ACC) systems has been analyzed, namely, the constant spacing policy, constant time headway, traffic flow stability, constant safety factor and human driving behavior spacing policies [8]. Several scholars have conducted studies on the stability of vehicle adaptive cruise [9,10,11,12]. When the number in a convoy reaches a certain size, the ACC system is prone to oscillation during frequent acceleration and deceleration. An adaptive optimal control was proposed to ensure tracking performance and stability [13]. In addition, a sliding mode was introduced and the chattering problem was overcome and achieved better results [14]. A sliding mode control strategy based on neural network has been proposed [15]. With the rapid development of communication technology, many scholars have conducted studies on the CACC method [16]. A distributed nonlinear consensus delay-dependent control algorithm for a connected vehicle platoon has been provided [17]. Deep learning has been used in automatic driving and longitudinal motion control [18]. Model predictive control (MPC) can effectively solve the problem of multiple optimization objectives and constraints and compensate for uncertainties such as model time variation and disturbances, which have become a hot spot for research and application in recent years [19]. Many scholars have solved the multi-objective optimization problems of ACC based on model predictive control algorithms. Compared with traditional LQR or fuzzy control algorithms, MPC significantly improves the control accuracy and energy-saving of ACC [20,21,22]. A bi-directional hierarchical adaptive cruise control method with reduced collision probability has been proposed in a MPC framework [23,24]. A distributed model predictive control (DMPC) algorithm to reduce the steady-state errors has been proposed [25]. Based on a particle swarm optimization algorithm, the safety, economy, comfort and tracking ability of convoys during deceleration has been effectively improved [26]. Combining MPC and particle swarm optimization (PSO), multi-objective optimization including driving stability, safety and economy has been verified [27,28].
With the advantage of global optimization and fast convergence characteristic, PIO and PSO are suitable for solving the optimal control law of adaptive cruise predictive control. In order to improve the time response characteristics of adaptive cruise system predictive control under the constantly changing speed of the leading vehicle, this paper studies a vehicle adaptive cruise predictive control algorithm based on variable compass operator pigeon-inspired optimization. A longitudinal kinematic model of the adaptive cruise system is established, the multi-objective optimization cost function and multi-parameter constraints are designed, the predictive control optimization mathematical model is constructed, and the optimal control law is solved based on variable compass operator pigeon-inspired optimization. Finally, the feasibility and superiority of the algorithm are verified through simulation.

2. Longitudinal Kinematic Model of Adaptive Cruise

The longitudinal kinematics relationship of the adaptive cruise is shown in Figure 1, where x f and x p are the current positions of the vehicle and the front vehicle, respectively; d is the actual distance; d d e s is the desired distance; v f and v p are the speeds of the vehicle and the front vehicle, respectively; a f and a p are the accelerations of the vehicle and the front vehicle, respectively; Δ d is the distance error; Δ v is the relative speed between the front vehicle and the current vehicle; a f d e s is the expected acceleration of the current vehicle; d 0 is the minimum safe distance after stopping.
The linear discrete state-space equation for an adaptive cruise following system is established [29,30], as shown in Equation (1).
{ x ( k + 1 ) = A ¯ x ( k ) + B ¯ u ( k ) + G ¯ v ( k ) y ( k ) = C ¯ x ( k )
where A ¯ = [ 1 T s t h T s 0 0 T s 0 0 1 T s / T L ] , B ¯ = [ 0 0 T s K L / T L ] , G ¯ = [ 0 T s 0 ] , C ¯ = [ 1 0 0 0 1 0 0 0 1 ] , x = [ Δ d Δ v a f ] T , u = a f d e s , v = a p , t h is the time-distance, K L is the system gain, T L is the time constant and T s is the sampling period.

3. Multi-Objective Adaptive Cruise Predictive Control Algorithm

Prediction Control Algorithm

Assuming that the current moment is t , the multi-objective optimization function is established as Equation (2).
J ( y , u , Δ u ) = k = t t + N 1 [ y ( k + 1 | t ) ] T w y [ y ( k + 1 | t ) ] + k = t t + N 1 [ u ( k | t ) ] T w E a [ u ( k | t ) ] + k = t t + N 1 [ Δ u ( k | t ) ] T w Δ E a [ Δ u ( k | t ) ]
where N is the length of prediction time, w y is the weight coefficients of system output, w E a is the weight coefficients of control, and w Δ E a is the weight coefficients of control incremental.
In order to predict system output y ( t ) from the time t to t + N 1 , the output y ( t ) , y ( t + 1 ) , y ( t + 2 ) , are shown in Equation (3), and so on.
y ( t | t ) = C ¯ x ( t ) y ( t + 1 | t ) = C ¯ x ( t + 1 ) = C ¯ A ¯ x ( t ) + C ¯ B u ( t ) + C ¯ G v ( t ) y ( t + 2 | t ) = C ¯ x ( t + 2 ) = C ¯ A ¯ x ( t + 1 ) + C ¯ B u ( t + 1 ) + C ¯ G v ( t + 1 ) = C ¯ A ¯ ( A ¯ x ( t ) + B u ( t ) + G v ( t ) ) + C ¯ B u ( t + 1 ) + C ¯ G v ( t + 1 ) = C ¯ A ¯ 2 x ( t ) + C ¯ A ¯ B u ( t ) + C ¯ A ¯ G v ( t ) + C ¯ B u ( t + 1 ) + C ¯ G v ( t + 1 )
Then the output Y from the time t to t + N 1 can be transformed into Equation (4).
Y = M x x ( k ) + M u U + M v V
where Y is the system output in the predicted time period, U is the predicted control in the predicted time period, Δ U is the predicted control increment in the predicted time period, V is the external disturbance in the predicted time period,
Y = [ y ( t | t ) y ( t + 1 | t ) y ( t + N 1 | t ) ] ,   U = [ u ( t | t ) u ( t + 1 | t ) u ( t + N 1 | t ) ] ,   V = [ v ( t | t ) v ( t + 1 | t ) v ( t + N 1 | t ) ] ,   M x = [ C A ¯ C ¯ A 2 ¯ C ¯ A N ¯ ] ,
M u = [ C B ¯ 0 0 0 C ¯ A B ¯ C B ¯ 0 C ¯ A N 1 B ¯ C ¯ A N 2 B ¯ 0 ] ,   M v = [ C G ¯ 0 0 0 C ¯ A G ¯ C G ¯ 0 C ¯ A N 1 G ¯ C ¯ A N 2 G ¯ 0 ]
The cost function (2) has three variables, such as y , u and Δ u . In order to find the best value of Δ u that minimizes J ( y , u , Δ u ) , y and u should be replaced by Δ u . The relationship between u and Δ u is shown in function (5).
U = T Δ u Δ U + u ( t 1 ) T u
Then, combining the function and the cost function (4) and (5), the cost function (2) can be transformed into Equation (6).
J ( Δ U ) = Δ U T K 1 Δ U + 2 K 2 Δ U
where K 1 = T Δ u T ( M u T W y M u + M u ) T Δ u + W Δ u .
K 2 = [ x T ( t ) M x T + u ( t 1 ) T u T M u T + V T M v T ] W y M u T Δ u + u ( t 1 ) T u T W u T Δ u ,
Δ U = [ Δ u ( t | t ) Δ u ( t + 1 | t ) Δ u ( t + N 1 | t ) ] ,   T Δ u = [ 1 0 0 1 1 0 0 1 1 1 ] N × N ,   T u = [ 1 1 1 ] N × 1
W y = d i a g [ w y w y w y ]
W u = d i a g [ w E d a w E d a w E d a ]
W Δ u = d i a g [ w Δ E d a w Δ E d a w Δ E d a ]
The predictive input and output constraints of the adaptive cruise system are established as Equation (7).
{ Δ d min Δ d Δ d max Δ v min Δ v Δ v max a f min a f Δ d f max a f min a f d e s a f max a ˙ f min a ˙ f a ˙ f max y min y ( k + 1 | t ) y max u min u ( k | t ) u max Δ u min Δ u ( k | t ) Δ u max
where Δ d max and Δ d min are the limits of the distance error; Δ v max and Δ v min are the limits of the relative vehicle speed; Δ a f max and Δ a f min are the limits of the acceleration; a ˙ f max and a ˙ f min are the limits of the impact; y min = [ Δ d min Δ v min Δ a f min ] is the lower bound of system output; y max = [ Δ d max Δ v max Δ a f max ] is the upper bound of system output; u min = a f min is the lower bound of control quantity; u max = a f max is the upper bound of control quantity; Δ u min = a f min T s is the lower bound of control increment; Δ u max = a f max T s is the upper bound of control increment.

4. Predictive Control Law Based on Variable Compass Operator PIO

4.1. Pigeon-Inspired Algorithm

Inspired by the behavior of pigeons in nature, Duan Haibin [31] proposed a pigeon-inspired optimization (PIO) algorithm. PIO has been used to solve multi-objective optimization problems. Two different operator models are proposed by imitating the mechanism by which pigeons use different navigation tools in different stages of finding a target.
  • Map and compass operator. Pigeons can sense the geomagnetic field and then form a map in their mind. They use the sun’s altitude as a compass to adjust their flight direction, and as they approach their destination, their dependence on the sun and magnetic field decreases.
  • Landmark operator. The landmark operator is used to simulate the effect of landmarks on pigeons in the navigation tool. As pigeons approach their destination, they will rely more on nearby landmarks. If the pigeons are familiar with the landmarks, they will fly directly to the destination. Otherwise, they will follow those pigeons that are familiar with the landmarks.
In the PIO model, virtual pigeons are used to simulate the navigation process. First, the position and speed of the pigeons are initialized, and the position and speed are updated in each iteration based on the map and the compass operator searching in the multidimensional space. Position and velocity are noted as X i = [ x i 1 , x i 2 , x i D ] , V i = [ v i 1 , v i 2 , v i D ] , where i = 1 , 2 , , N . Each pigeon updates its position and velocity according to Equation (8) where R is the compass factor, which takes the value range from 0 to 1. N c is the current number of iterations and X g b e s t is the optimal global position obtained after N c 1 iterations.
V i N c = V i N c e R × N c + r a n d ( X g b e s t X i N c 1 ) X i N c = X i N c 1 + V i N c
When the number of cycles reaches the preset value, the map and compass operator are stopped, the landmark operator is entered, and the search for the optimal solution is continued according to Equation (9).
{ X i = X i N C 1 + r a n d ( X c e n t e r N C 1 X i N C 1 ) X c e n t e r N c 1 = ( i = 1 N N c 1 X N c 1 ) / N c 1
where N N c = N N c 1 / 2 .
In this algorithm, in order to improve the global and local convergence speed of the compass operator, the variable compass operator pigeon-inspired algorithm with a variable compass operator factor (R) is used, which gradually decreases from 1 to 0.3 during the iteration process. It can ensure a robust global search capability in the beginning stage and increase the local convergence speed in the later stages of the search.

4.2. Adaptive Cruise Prediction Control Law Based on Variable Compass Operator PIO

In this paper, the variable compass operator PIO is used in the optimal control law, where Δ u is used as the control variable. The steps are as follows:
  • At the moment t , real-time sampling is used to obtain the adaptive cruise system’s input and state variables;
  • Determine the objective function and constraints by calculating K 1 , K 2 , T ;
  • Use the variable compass operator pigeon-inspired algorithm to calculate the new control sequence;
  • Repeat step 2 and step 3 to find the optimal control sequence Δ U that satisfies the requirements;
  • Choose the first component of Δ U as the control input increment and update the optimal control value u ( t ) = Δ u ( t | t ) + u ( t 1 ) ;
  • Let t = t + 1 and return to step 1.

5. Particle Swarm Optimization

The particle swarm optimization (PSO) algorithm originated from the behavior of birds. The basic idea of the particle swarm optimization algorithm is to find the optimal solution through cooperation and information sharing among individuals in the group. The steps for PSO are as follows:
  • Initialize all particles;
  • Update the velocity and position according to Formula (10), where w = 0.3 ;
  • Evaluate the fitness value;
  • Update the historical optimal position of each other particle;
  • Update the global optimal location of the group.
V i N c = w V i N c + r a n d ( ) ( X p b e s t X i N c ) + r a n d ( ) ( X g b e s t X i N c ) X i N c + 1 = X i N c + V i N c

6. Simulations

The adaptive cruise prediction control algorithm based on variable compass operator pigeon-inspired optimization proposed in this paper was verified by a simulation where the front car first decelerates and then accelerates. The initial speed of the front car is 20 m/s, which decelerates to 12 m/s at about 6 s, then accelerates to 20 m/s again at about 12 s and maintains this speed. The simulation parameters are shown in Table 1.
The simulation results for variable compass operator PIO compared with PSO are shown in Figure 2 and Figure 3.
From the simulation results, the adaptive cruise system can reach a steady state quickly under the control law of PIO or PSO. Further, the vehicle reaches a stable distance of 35 m in 10.2 s with variable compass operator PIO, while the PSO algorithm reaches 35 m in 11.2 s. Therefore, the adaptive cruise adjustment process with variable compass operator PIO is about 1 s faster than PSO. Compared with the PSO algorithm, the dynamic response time of adaptive cruise predictive control based on variable compass operator PIO is reduced by 8.9%.
Since the variable compass operator factor (R) decreases during the iteration process, the optimizing speed with variable compass operator PIO is better than PSO under limited iterations. In Figure 1, the control variable Δ u is similar for variable compass operator PIO and PSO when the car is in a state of continuous acceleration or deceleration. However, during the state change between acceleration and deceleration, the control variable Δ u is better with variable compass operator PIO because the speed v f changes faster to decrease the car’s distance more quickly than PSO.

7. Conclusions

A vehicle adaptive cruise predictive control algorithm based on variable compass operator PIO is suggested. Simulations of two methods were conducted and the results show that variable compass operator PIO and PSO were both effective. Compared with PSO, the dynamic response time of adaptive cruise predictive control based on variable compass operator PIO reached a stable state more rapidly. The method of calculating the optimal solution for MPC with PSO and variable compass operator PIO is not only suitable to vehicle adaptive cruise control, but is also effective for other problems with MPC.
Further, the parameters of algorithm and cost function have a larger impact on the system’s dynamic performance, which is worth pursuing further. Developing more effective optimization methods is also a potential direction for future research.

Author Contributions

Conceptualization, Z.L. and S.S.; methodology, Z.L.; validation, Z.L.; formal analysis, Z.L.; writing—original draft preparation, Z.L.; writing—review and editing, Z.L. and Y.D. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the Aeronautical Foundation of China (Grant No. 20185851022).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data sharing not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Li, X.; Zeng, C.; Luo, J. Research on adaptive cruise control algorithm based on linear quadratic optimal control. J. Wuhan Univ. Technol. Inf. Manag. Eng. 2019, 41, 81–86. [Google Scholar]
  2. Li, S.E.; Deng, K.; Li, K. Terminal sliding mode control of automated car-following system without reliance on longitudinal acceleration information. Mechatronics 2015, 30, 327–337. [Google Scholar] [CrossRef]
  3. Li, W.; Duan, J.M. Modeling and simulation of start-stop cruise system of hybrid electric vehicle. Control Eng. 2011, 18, 91–95. [Google Scholar]
  4. Ali, Z.; Popov, A.A.; Charles, G. Model predictive control with constraints for a nonlinear adaptive cruise control vehicle model in transition manoeuvres. Veh. Syst. Dyn. 2013, 51, 943–963. [Google Scholar] [CrossRef]
  5. Luo, L.H.; Gong, L.L.; Li, P. Design of dual-mode adaptive cruise control considering driver’s driving characteristics. J. Zhejiang Univ. Eng. 2011, 45, 2073–2078. [Google Scholar]
  6. Zhang, L.; Chen, F.; Ma, X.; Pan, X.D. Fuel economy in truck platooning: A literature overview and directions for future research. J. Adv. Transp. 2020, 2020, 2604012. [Google Scholar] [CrossRef]
  7. Chen, X.; Yang, J.; Zhai, C. Economic Adaptive Cruise Control for Electric Vehicles Based on ADHDP in a Car-Following Scenario. IEEE Access 2021, 9, 74949–74958. [Google Scholar] [CrossRef]
  8. Wu, C.; Xu, Z.; Liu, Y. Spacing Policies for Adaptive Cruise Control: A Survey. IEEE Access 2020, 8, 50149–50162. [Google Scholar] [CrossRef]
  9. Lazar, C.; Tiganasu, A. String Stable Vehicle Platooning Using Adaptive Cruise Controlled Vehicles—ScienceDirect. IFAC-PapersOnLine 2019, 52, 1–6. [Google Scholar] [CrossRef]
  10. Gunter, G.; Gloudemans, D.; Stern, R.E. Are Commercially Implemented Adaptive Cruise Control Systems String Stable? IEEE Trans. Intell. Transp. Syst. 2021, 22, 6992–7003. [Google Scholar] [CrossRef]
  11. Gunter, G.; Janssen, C.; Barbour, W. Model-Based String Stability of Adaptive Cruise Control Systems Using Field Data. IEEE Trans. Intell. Veh. 2020, 5, 90–99. [Google Scholar] [CrossRef] [Green Version]
  12. Knoop, V.L.; Wang, M.; Wilmink, I. Platoon of SAE Level-2 Automated Vehicles on Public Roads: Setup, Traffic Interactions, and Stability. Transp. Res. Rec. J. Transp. Res. Board 2019, 2673, 311–322. [Google Scholar] [CrossRef]
  13. Lee, D.; Leea, S.; Chen, Z. Design and field evaluation of cooperative adaptive cruise control with unconnected vehicle in the loop. Transp. Res. Part C Emerg. Technol. 2021, 132, 103364. [Google Scholar] [CrossRef]
  14. Yasir, H.M.; Bhatti, A.I.; Mahmood, A. Longitudinal Cruise Control of a Car using Sliding Mode Approach. In Proceedings of the 2019 International Conference on Electrical, Communication, and Computer Engineering (ICECCE), Swat, Pakistan, 24–25 July 2019; pp. 1–5. [Google Scholar]
  15. Wang, S.; Hui, Y.; Sun, X. Neural Network Sliding Mode Control of Intelligent Vehicle Longitudinal Dynamics. IEEE Access 2019, 7, 162333–162342. [Google Scholar] [CrossRef]
  16. Baldi, S.; Liu, D.; Jain, V. Establishing Platoons of Bidirectional Cooperative Vehicles With Engine Limits and Uncertain Dynamics. IEEE Trans. Intell. Transp. Syst. 2021, 22, 2679–2691. [Google Scholar] [CrossRef]
  17. Li, Y.; Tang, C.; Srinivas, P. Nonlinear Consensus-Based Connected Vehicle Platoon Control Incorporating Car-Following Interactions and Heterogeneous Time Delays. IEEE Trans. Intell. Transp. Syst. 2019, 20, 2209–2219. [Google Scholar] [CrossRef]
  18. Albeaik, S.; Wu, T.; Vurimi, G. Deep truck cruise control: Field experiments and validation of heavy duty truck cruise control using deep reinforcement learning. Control Eng. Pract. 2022, 121, 105026. [Google Scholar] [CrossRef]
  19. Wu, G.Q.; Zhang, L.X.; Liu, Z.Y. Research status and development trend of automobile adaptive cruise control system. J. Tongji Univ. Nat. Sci. 2017, 45, 90–99. [Google Scholar]
  20. Yu, G.K.; Wong, P.K.; Zhao, J. Design of an Acceleration Redistribution Cooperative Strategy for Collision Avoidance System Based on Dynamic Weighted Multi-Objective Model Predictive Controller. IEEE Trans. Intell. Transp. Syst. 2021, 99, 1–13. [Google Scholar] [CrossRef]
  21. Sun, X.Q.; Cai, Y.F.; Wang, S.H. Optimal control of intelligent vehicle longitudinal dynamics via hybrid model predictive control. Robot. Auton. Syst. 2019, 112, 190–200. [Google Scholar] [CrossRef]
  22. Pan, X.; Chen, B.; Evangelou, S.A. Optimal Vehicle Following Strategy for Joint Velocity and Energy Management Control of Series Hybrid Electric Vehicles. IFAC-PapersOnLine 2020, 53, 14161–14166. [Google Scholar] [CrossRef]
  23. Cheng, S.; Li, L.; Guo, H.Q. Longitudinal Collision Avoidance and Lateral Stability Adaptive Control System Based on MPC of Autonomous Vehicles. IEEE Trans. Intell. Transp. Syst. 2019, 21, 2376–2385. [Google Scholar] [CrossRef]
  24. Ren, Y.; Zheng, L.; Yang, W. Potential field-based hierarchical adaptive cruise control for semi-autonomous electric vehicle. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2019, 233, 2479–2491. [Google Scholar] [CrossRef]
  25. Luu, D.L.; Pham, H.T.; Lupu, C. Research on Cooperative Adaptive Cruise Control System for Autonomous Vehicles based on Distributed Model Predictive Control. In Proceedings of the 2021 International Conference on System Science and Engineering (ICSSE), Ho Chi Minh City, Vietnam, 26–28 August 2021; pp. 13–18. [Google Scholar]
  26. Ma, G.Q.; Wang, B.Q.; Ge, S.S. Robust optimal control of connected and automated vehicle platoons through improved particle swarm optimization. Transp. Res. Part C Emerg. Technol. 2022, 135, 103488. [Google Scholar] [CrossRef]
  27. Ma, H.; Chu, L.; Guo, J. Cooperative Adaptive Cruise Control Strategy Optimization for Electric Vehicles Based on SA-PSO With Model Predictive Control. IEEE Access 2020, 8, 225745–225756. [Google Scholar] [CrossRef]
  28. Li, L.; Xu, S.; Nie, H.; Mao, Y.; Yu, S. Collaborative Target Search Algorithm for UAV Based on Chaotic Disturbance Pigeon-Inspired Optimization. Appl. Sci. 2021, 11, 7358. [Google Scholar] [CrossRef]
  29. Zhang, L.X.; Wu, G.Q.; Guo, X.X. Vehicle multi-objective adaptive cruise control algorithm. J. Xi’an Jiaotong Univ. 2016, 50, 136–143. [Google Scholar]
  30. Zhou, J.M.; Zhang, L.X.; Yi, F.Y.; Peng, J.K. Automotive adaptive cruise prediction control based on particle swarm optimization. J. Beijing Inst. Technol. 2021, 41, 214–220. [Google Scholar]
  31. Duan, H.B.; Qiao, P.X. Pigeon-inspired optimization: A new swarm intelligence optimizer for air robot path planning. Int. J. Intell. Comput. Cybern. 2014, 7, 24–37. [Google Scholar] [CrossRef]
Figure 1. Longitudinal kinematics model of adaptive cruise.
Figure 1. Longitudinal kinematics model of adaptive cruise.
Electronics 11 01377 g001
Figure 2. Comparison of PSO and variable compass operator PIO in terms of (a) speed and (b) acceleration.
Figure 2. Comparison of PSO and variable compass operator PIO in terms of (a) speed and (b) acceleration.
Electronics 11 01377 g002
Figure 3. Distance curves for PSO and variable compass operator PIO.
Figure 3. Distance curves for PSO and variable compass operator PIO.
Electronics 11 01377 g003
Table 1. The simulation parameters.
Table 1. The simulation parameters.
ParameterValueParameterValue
Time-distance t h / s 1.5Upper limit Δ d min / m −5
System gain K L 1.05Weight coefficient w y diag(0.12,1,0)
Time constant T L / s 0.393Weight coefficient w E d a 0.1
Sampling period T s / s 0.1Weight coefficient w Δ E d a 0.001
Lower limit a f min / ( m s 2 ) −2Predict period N 40
Upper limit a f max / ( m s 2 ) 2Particle swarm size m 100
Lower limit a ˙ f min / ( m s 2 ) −1Learning factor c12
Upper limit a ˙ f max / ( m s 2 ) 1Learning factor c22
Lower limit Δ d max / m 5Inertia weight t h / s 0.5
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Li, Z.; Deng, Y.; Sun, S. Adaptive Cruise Predictive Control Based on Variable Compass Operator Pigeon-Inspired Optimization. Electronics 2022, 11, 1377. https://doi.org/10.3390/electronics11091377

AMA Style

Li Z, Deng Y, Sun S. Adaptive Cruise Predictive Control Based on Variable Compass Operator Pigeon-Inspired Optimization. Electronics. 2022; 11(9):1377. https://doi.org/10.3390/electronics11091377

Chicago/Turabian Style

Li, Zhaobo, Yimin Deng, and Shuanglei Sun. 2022. "Adaptive Cruise Predictive Control Based on Variable Compass Operator Pigeon-Inspired Optimization" Electronics 11, no. 9: 1377. https://doi.org/10.3390/electronics11091377

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