Youngmin Yoon, Kyongsu Yi
©SHUTTERSTOCK.COM/TEMP-64GTX
This article presents a method for the trajectory prediction of surrounding vehicles and proactive longitudinal control of autonomous vehicles (AVs) in an urban road environment. A long short-term memory (LSTM)-based deep learning model is designed for the surrounding vehicles’ trajectory prediction. In our model, the historical evolution of the relation between a target vehicle and lanes is considered to learn the driver’s behavior in a lane-aware manner. Interaction among adjacent vehicles is captured based on a graph convolutional network (GCN), which uses a self-attention mechanism. Compared to other approaches, our prediction model utilizes environment information that is acquirable in AVs with local sensors. A model predictive control (MPC) is designed to derive the control inputs of acceleration for AVs. The proposed control method utilizes the prediction results of the target vehicle to give action requests to AV in a proactive manner considering both safety and ride quality. The results of comparative studies indicate that the proposed prediction model achieves improved accuracy compared to baselines. The control results provided by automated driving tests show that the proposed control algorithm applied by the LSTM-based prediction model enables AVs to achieve safety with respect to surrounding vehicles and provide ride comfort to passengers.
Autonomous driving technology for road vehicles has gained a lot of attention due to expectations for reducing driver fatigue and improving road safety. To provide convenience to drivers along with safety, AVs must be able to perform predictive maneuvers reacting to the dynamic motion of the surrounding traffic participants. For instance, AVs need to proactively plan decelerating maneuvers in response to dangerous cut-in vehicles. The predictive motion planning of AVs requires prediction results of the future trajectories of surrounding vehicles that cover the time horizon of motion planning. Many studies have reported that accurate motion prediction helps AVs behave with improved driving performance in terms of ride comfort and control effort [1], [2]. Therefore, it is necessary to develop a reliable trajectory prediction model and predictive control algorithm for AVs to deal with dynamic driving scenarios.
Various studies have been conducted to predict the future trajectories of surrounding vehicles. Physics-based motion models, such as constant velocity (CV) and constant yaw rate and acceleration, have been applied to trajectory prediction [3]. However, these approaches provide reliable results only in short-term prediction problems. To overcome the short-time-horizon issue, behavioral assumptions have been given to the prediction model. A cut-in motion prediction method has been suggested using a Gaussian mixture model [4]. However, for general application, the algorithm design needs to be easy to apply for various maneuvers as well as the cut-in maneuver. To capture motion dynamics and behavioral context delicately, the deep learning approach has been widely used for trajectory prediction problems and has shown good performance compared to traditional machine learning approaches.
The application of an LSTM-based recurrent neural network (NN) has improved prediction accuracy due to its capability of encoding time-series information [5]. However, interdependencies among surrounding vehicles need to be considered to capture the social behavioral nature of traffic agents. To consider social interaction, convolutional social pooling has been suggested to derive social context features by encoding a social tensor [6]. A graph NN has been used to encode the interaction feature by modeling the traffic scene as a graph that assumes traffic agents and their interconnection as nodes and edges, respectively [7]. However, this approach has a limitation in that the interaction among spatially distant agents is not considered. To quantify the interaction among distant agents, an attention mechanism has been applied to NNs to derive interaction features [8].
However, since this work has assumed a straight road environment, consideration of lane geometry is insufficient. Lane-aware NNs have been suggested to reduce the prediction error by constraining the vehicle motion within lane-based boundaries [9]. However, this model lacks the consideration of social interaction among surrounding agents. In several works, environmental information such as target vehicle state and lane geometry is considered based on the space-fixed coordinates attached to the target agent. However, for implementation in AVs that are equipped with local perception sensors, only relative information based on the body-fixed coordinates attached to the ego vehicle is acquirable.
In the field of predictive control, many researchers have applied the MPC technique, which utilizes finite-horizon optimization. In its application in AVs, MPC has been used in adaptive cruise control based on a cost function that penalizes reference tracking error and control effort and on constraints related to system dynamics, collision safety, and driving comfort [10], [11], [12], [14]. Due to its capability of reflecting the prediction results of environmental information, MPC has been utilized to deal with car-following scenarios with the existence of cut-in vehicles [12]. However, the performance has been evaluated only via simulation studies and lacked a validation process in real vehicle tests. Moreover, most of the studies that validate MPC via real vehicle tests have applied rule-based kinematic models for the prediction of target vehicles [10], [11], [14]. However, the application of the deep learning-based prediction model to MPC has been evaluated only via simulations [12].
This article provides a methodology for the trajectory prediction of surrounding vehicles and longitudinal control of AVs in an urban road environment. The proposed trajectory prediction algorithm estimates the future motion of target vehicles through a deep learning model based on the LSTM. The behavioral characteristics of vehicles considering lane geometry are modeled by learning the relation between the vehicles and lanes. The nature of social interaction among adjacent vehicles, which is the tendency of drivers to follow socially acceptable driving patterns to maintain a reasonable risk level, is modeled by constructing a graph representation with a learned adjacency matrix. The GCN layer encodes the graph-based traffic scene.
The proposed prediction model improves prediction accuracy by learning the social interaction and relationship between lanes and vehicles. Considering the applicability to AVs, our deep learning model takes environmental information acquirable from local perception sensors equipped in AVs. MPC is designed for the longitudinal control of AVs in car-following scenarios. The future states estimated by the LSTM-based model are applied to the MPC to proactively react to the dynamic changes of the target vehicle’s motion. The proposed algorithm has been implemented in our AV and validated by real driving tests.
The main contributions of this work can be summarized as follows:
This study focuses on the trajectory prediction of surrounding vehicles and longitudinal control of AVs in road environments with surrounding vehicles. The main objective of this work is to improve the trajectory prediction accuracy and establish a proper control strategy for AVs that guarantees safety and provides ride comfort in dynamic traffic situations. The overall structure of the proposed algorithm is described in Figure 1. First, the surrounding vehicle prediction algorithm provides the time-series data of the future position and speed of a target vehicle, utilizing the historical data of the states of the ego vehicle, surrounding vehicles, and lane information.
Figure 1 The overall structure of the proposed algorithm.
To encode the historical information and derive the prediction results, an LSTM-based NN is used in the prediction algorithm. Intervehicle interaction is considered by utilizing the GCN layer. The GCN layer encodes a graph structure with nodes represented as the dynamic features of surrounding vehicles encoded by the LSTM and edges represented as the relation weights derived by the self-attention mechanism applied by the node features. To consider the target vehicle’s intention about lanes, the probability distribution of future driving lanes is estimated using the encoded information of vehicle–lane relation and utilized in the future trajectory decoder. Second, a longitudinal control algorithm derives the control command for AVs. In our system, the longitudinal acceleration command is treated as the control command. An MPC problem is formulated to achieve the control objective, which is to minimize the cost function penalizing the desired state tracking error and control usage in a finite time horizon. To consider physical restrictions related to collision and actuator limit, inequality constraints are assigned in the MPC problem.
The surrounding vehicle prediction algorithm provides the future states of a target vehicle. The prediction of the future motion is treated as a regression problem solved by a deep learning approach. The structure of our deep learning model is described in Figure 2. The model consists of LSTM and GCN layers that model the temporal dependency of vehicle data and the social interaction among adjacent vehicles, respectively.
Figure 2 The structure of the proposed deep learning network for trajectory prediction of the target vehicle. w.r.t.: with regard to.
Our deep learning model takes the historical states of the surrounding vehicles, the ego vehicle, and lane information as input data. Considering the applicability of AVs, the inputs consist of information acquirable from the ego vehicle. The states of the surrounding vehicles consist of the relative position, heading angle, and speed, which can be derived by vehicle perception algorithms based on the body-fixed coordinates attached to the ego vehicle. The states of the ego vehicle consist of speed and yaw rate, which compensate for the coordinate change of the ego vehicle over time. The lane information is considered as the quadratic model-based coefficients of the left and right lane, which can be obtained by commercial sensors. To balance the influence of each input dimension, the deep learning model takes the standardized inputs. The outputs consist of the future position and speed of the target vehicle defined in the space-fixed coordinates centered at the ego vehicle at the current time.
The proposed network model can be divided into four submodules according to their functions: the vehicle dynamics encoder, lane encoder, interaction encoder, and future trajectory decoder. In the vehicle dynamics encoder, the snippets of the ego vehicle and surrounding vehicles are encoded through multilayer perceptron (MLP) layers and LSTM layers. The MLP layers embed the physical information into high-dimensional features at each historical step. The LSTM layers use the embedded features to update the hidden states and cell states sequentially and derive encoded LSTM state vectors fveh, i , where i implies the ith vehicle. The dynamic features of each vehicle are transformed into individual LSTM state vectors through the encoders, which share the same weights. To consider the coordinate change of the ego vehicle, the physical inputs of the ego vehicle and the surround vehicle are concatenated and fed to each vehicle’s encoder jointly.
The interaction encoder constructs a graph G = {V, E}, which represents the traffic scene to model the interaction among the traffic agents. The node set V consists of the N LSTM state vectors of each agent’s dynamics encoded by the vehicle dynamics encoder module, where N denotes the number of vehicles in the traffic scene. The edge set E represents the connection between the vehicles. The connection information is expressed as an adjacency matrix A, which is an N × N matrix consisting of connection weight Aij between the ith node and jth node. A self-attention mechanism is used to estimate the degree of interaction between the nodes as attention scores. The scaled dot product is applied to the node features of each vehicle interaction pair to derive the attention scores.
The connection weights in A are obtained by normalizing the attention scores row-wise through a softmax operation. A GCN layer updates the node attributes by assembling the information of the neighboring nodes according to the adjacency matrix A and a trainable 1D convolution weight [7]. In the interaction encoder, two GCN layers are successively applied to the graph representation to obtain an updated node feature of the target vehicle. The updated node feature is used as an interaction feature fint in the deep learning model.
The lane encoder encodes the historical lane information through MLP layers and LSTM layers to derive a lane feature. The lane feature flane is obtained by concatenating an LSTM state vector hlane and an embedded vector fprob of the probability distribution of the future driving lane selection. Lane coefficients are encoded through MLP and LSTM to derive hlane. To learn the relation between the target vehicle and lanes, the historical lateral offset of the target vehicle with respect to the centerline of the left, right, and ego driving lanes is fed into separate MLP and LSTM layers. The LSTM state vectors are normalized by a softmax operation to derive a probability distribution vector p, which is a 3 × 1 vector consisting of the probability of selecting the left, right, and ego driving lanes. fprob is derived by embedding p by an MLP and concatenated with hlane to obtain flane.
The future trajectory decoder generates the predicted states of the target vehicle through the LSTM. To consider the intervehicle interaction and lane as well as vehicle dynamics, the future trajectory decoder takes a context vector fcontext, which is calculated by concatenating fveh,target, fint, and flane as an input to the LSTM, where fveh,target is the vehicle dynamics feature of the target vehicle. Therefore, the LSTM provides the sequence data of the future states.
The parameters of the proposed network are trained to enhance the performance of the network. The main objective of the network training is to reduce the prediction error of the future states and to improve the classification accuracy of the future driving lane. The training process is based on supervised learning and aims to minimize the loss function described as follows: \[{\text{Loss}} = \mathop{\sum}\limits_{{i} = {1}}\limits^{N}{\left({L}_{{\text{traj}},i} + {\alpha}\,{\cdot}\,{L}_{{\text{lane}},i}\right)} \tag{1} \] where N is the number of training samples; Ltraj is the mean squared error (MSE) loss, which measures the error of the future trajectory prediction result; Llane is the cross-entropy loss for classification results of the future driving lane provided by the lane encoder; and a is the weight that balances the importance of two losses. In this work, an a of 4.0 is selected considering the prediction performance. For efficient training, the training samples are divided into several batches with a batch size of 32. The ADAM optimizer is used to minimize the loss function. The network is trained for 200 epochs, and a learning rate is applied with an initial value of 0.001 and a decay rate of 0.95 per five epochs to improve the accuracy while preventing overfitting. The hidden state dimensions of each encoder are set as 32 considering the prediction performance and computational efficiency. A PyTorch framework is utilized to train the network and implement it in the test environment [13].
In this article, the prediction algorithm provides prediction results with a predictive time horizon of 3 s using the past information for 2 s. The observation horizon and predictive horizon are chosen considering the prediction accuracy and application to predictive control, respectively. The sampling time of the sequence is 0.2 s. The driving data for network training and testing have been collected using a test vehicle equipped with environmental sensors such as a lidar system, front camera system, and GPS/inertial navigation system (GPS/INS). The lidar system and front camera system are used to collect the states of the surrounding vehicles and quadratic polynomial coefficients of the local lane, respectively. The GPS/INS provides the accurate position of the test vehicle so that the future trajectories of a target vehicle are processed in a fixed coordinate. We collected 22,351 samples and divided them into 15,645 samples for network training and 6,706 samples for network testing.
The longitudinal control algorithm is designed for AVs to provide a proper acceleration or deceleration command that aids AVs in maintaining safety with the preceding vehicles. The main objective of the algorithm is to maintain the desired clearance and adjust the velocity with a target vehicle without excessive control usage. To define the control problem, the desired travel distance and velocity of the ego vehicle are determined in the predictive horizon. The desired states are designed in the sense that the ego vehicle tends to be located at a desired clearance cdes behind the target vehicle and achieve the same speed as the target vehicle. To proactively deal with car-following scenarios where cut-in vehicles exist, the states of the cut-in vehicles as well as the preceding vehicles are considered. To carry out a moderate response of AVs in a cut-in situation, the target vehicle is assumed to be a virtual vehicle with speed and location information mixed with the preceding vehicle and cut-in vehicle. The states of the target vehicle are defined as \begin{align*}{p}_{{\text{TV}},k} & = {w}_{k}\,{\cdot}\,{p}_{{\text{CV}},k} + {\left({1}{-}{w}_{k}\right)}\,{\cdot}\,{p}_{{\text{PV}},k} \\ {v}_{TV,k} & = {w}_{k}\,{\cdot}\,{v}_{{\text{CV}},k} + {\left({1}{-}{w}_{k}\right)}\,{\cdot}\,{v}_{{\text{PV}},k} \\ {w} & = \frac{{N}_{\text{inv}}}{{N}_{p}} \tag{2} \end{align*} where k is the predictive time step; pPV and pCV are the longitudinal position of the preceding vehicle and cut-in vehicle, respectively; vPV and vCV are the speed of the preceding vehicle and cut-in vehicle, respectively; Np is the prediction horizon; and Ninv is the number of times the cut-in vehicle is predicted to invade the ego driving lane within the prediction horizon of Np. pPV, pCV, vPV, vCV, and w are derived from the results of the surrounding vehicle prediction algorithm. If there exists no cut-in vehicle, the value of w is 0, and the preceding vehicle is assumed to be the target vehicle. If a cut-in vehicle exists and changes its lane to the ego driving lane, the value of w increases from 0 to 1, and the cut-in vehicle becomes the target vehicle.
An optimization-based linear MPC problem is defined to derive a control command for AVs that conforms to the control objective. The cost function for the optimization is designed as a quadratic function that penalizes the tracking error of the desired states and control effort. To guarantee the physical feasibility of the control problem in the real world, constraints are assigned to the optimization problem. The optimization problem is defined as \[\mathop{\min}\limits_{u}\,{J} = \mathop{\sum}\limits_{{k} = {1}}\limits^{{N}_{p}}{\left\Vert{x}_{k}{-}{x}_{{\text{des}},k}\right\Vert}_{Q}^{2} + \mathop{\sum}\limits_{{k} = {0}}\limits^{{N}_{p}{-}{1}}{R}\,{\cdot}\,{u}_{k}^{2} \tag{3a} \] subject to \begin{align*}{x}_{{k} + {1}} & = {\left[\begin{array}{ccc}{1}&{\Delta}{t}&{0}\\{0}&{1}&{\Delta}{t}\\{0}&{0}&{1}{-}{\Delta}{t} / {\tau}\end{array}\right]}\,{x}_{k} + {\left[\begin{array}{c}{0}\\{0}\\{\Delta}{t} / {\tau}\end{array}\right]}{u}_{k} \tag{3b} \\ {u}_{\min} & {≤}\,{u}_{k}\,{≤}\,{u}_{\max} \tag{3c} \\ {p}_{{\min},k} & {≤}\,{p}_{k}\,{≤}\,{p}_{{\max},k} \tag{3d} \end{align*} where x is the state of the ego vehicle that consists of travel distance p, speed v, and acceleration a; xdes is the desired state of the ego vehicle, which is defined referring to [14]; u is the acceleration command, which serves as the control input; Q and R are the weight matrices that penalize the state tracking error and control effort, respectively; Dt is the sampling time; x is the first-order time constant of the response system of the acceleration actuator; umin and umax are the minimum and maximum allowable values of the control input; and pmin and pmax are the minimum and maximum allowable values of the travel distance of the ego vehicle derived by the surrounding vehicles. The desired position and speed in the xref are determined by selecting the smaller of the desired states according to the virtual target vehicle in (2) and the preceding vehicle.
In this article, a Q of diag(50, 3, 0); R of 80; umin of −5 m/s2; umax of 1.5 m/s2; Dt of 0.1 s; and x of 1 s are used. The optimization objective (3a) is related to the minimization of the state tracking error and control effort. The constraint (3b) describes the compliance with the control system model, which is designed as a point mass model. The constraint (3c) describes the physical limit of the actuator performance. The constraint (3d) describes the condition of collision prevention with respect to the surrounding vehicles. Therefore, the MPC problem enables AVs to determine the proper control inputs that guarantee safety and ride comfort through cost minimization with constraints.
The proposed algorithm has been evaluated to review its applicability to AVs. First, the performance of the surrounding vehicle prediction algorithm has been evaluated in terms of the accuracy of the prediction results. The testing dataset acquired by the test vehicle has been used in the evaluation. Second, the control performance has been validated in terms of safety and ride quality. The proposed algorithm has been implemented in our AV, and real vehicle tests have been conducted based on autonomous driving in the real world.
The performance of our deep learning-based prediction model has been evaluated based on the statistical analysis of the state prediction error on the testing dataset consisting of the 6,706 samples out of the 22,351 collected samples. The proposed model has been compared with five base algorithms described as follows:
The three LSTM baselines directly encode the lane coefficients via LSTM while omitting the relation between the target vehicle and lane. They have been trained with the same hyperparameters as the proposed model.
Table 1 shows the comparison results in terms of mean absolute error (MAE), root mean squared error (MSE), and miss rate (MR). The computational time required to perform the prediction task is evaluated for the LSTM-based models and described in Table 1. The MR is evaluated at the prediction horizon of 3 s based on the boundary of 4 m for the x position and 1 m for the y position. The average computational time to predict the behavior of 15 vehicles is evaluated using a NVIDIA GeForce GTX 1050, assuming the existence of 15 or fewer interesting vehicles in practical operating conditions. Compared to the CV and PF, the results show that using LSTM cells improves the prediction accuracy by encoding the temporal dependency of the historical inputs.
Table 1 A comparison of the statistical results of the trajectory prediction performed by the proposed model and the five baselines. The results are provided in terms of MAE and RMSE at the prediction horizons of 1, 2, and 3 s and MR at the prediction horizon of 3 s. The improvements of the prediction performance are shown as percentages compared to the CV. The average computation times required to predict 15 vehicles are described for the LSTM-based models.
The comparison results from the Vanilla-LSTM and Attention-LSTM models show that considering interaction leads to the improvement of the prediction accuracy. The proposed model outperforms other LSTM-based models on most of the error metrics. Both the graphical modeling of the multiagent traffic scene and the GCN-based encoding are shown to be effective in modeling intervehicle interaction and to have a significant impact on trajectory prediction. Furthermore, learning the relationship between lanes and vehicles contributes to a lower prediction error. The proposed model is shown to require the most computational time among the LSTM-based models. However, the average computational time is within 6 ms, which indicates that the proposed model hardly violates the cycle frequency of motion planning, which is typically 20 Hz or lower [14].
Figure 3 shows the visualized prediction results of the CV, Vanilla-LSTM, and the proposed model in a multivehicle scene where a target vehicle represented as black lines changes lanes. The past trajectories are represented as black-dotted lines, and the actual future trajectories are represented as a solid black line. The predicted trajectories provided by the prediction models are represented as dotted lines and markers at 0.5-s intervals. The proposed model predicts that the black vehicle accelerates and rapidly progresses lane-changing behavior to adjust the speed to the traffic flow of the middle lane. The results indicate that the proposed model predicts the motion, considering interaction with two adjacent vehicles in the middle lane. Comparing the lateral motion prediction accuracy with the Vanilla-LSTM, the results show that the proposed model successfully captures the lane-aware nature. Therefore, the consideration of interaction and lane relationships is advantageous for trajectory reasoning.
Figure 3 Examples of the prediction results of a lane-changing vehicle.
The performance of our vehicle control algorithm has been validated based on automated driving tests with our test vehicle. The test vehicle is equipped with a lidar, GPS/INS, front camera, actuators, and processors, as shown in Figure 4. The whole architecture in Figure 1 has been implemented on the test vehicle. The vehicle tests have been conducted with real traffic agents on urban driving roads with a speed limit of 50 km/h in Siheung, South Korea.
Figure 4 The equipment configuration of the test vehicle for algorithm implementation. (a) The equipment mounted on the test vehicle. (b) The field of view (FOV) covered by the environment perception sensors. ARM: Advanced RISC Machine; MDPS: motor-driven power steering; SCC: smart cruise control.
Figures 5 and 6 show the vehicle test results in a scenario where a white sedan cuts into the ego driving lane. Snapshots of the traffic scene with trajectories of the target vehicle and ego vehicle are depicted in Figure 5. The green and red lines indicate the trajectories of the target vehicle and ego vehicle, respectively. The trajectory prediction results of the target vehicle at t = 1.7 s are represented as brown lines. The gray lines indicate the lane information. Figure 6(a)–(c) summarizes the motion of the ego vehicle in terms of longitudinal acceleration, velocity, and clearance with respect to preceding vehicles.
Figure 5 The description of a scenario where a target vehicle cuts into the ego driving lane. (a) The trajectories of the ego vehicle and target vehicle. (b) The front view.
Figure 6 Vehicle test results in a cut-in scenario. (a) The longitudinal acceleration of the ego vehicle. (b) The speed of the preceding vehicle and the ego vehicle. (c) The clearance with respect to the preceding vehicle.
As shown in Figures 5 and 6(c), the target vehicle invades the ego driving lane at t = 3.7 s. At t = 1.7 s, the target vehicle is predicted to cross the lane, and the test vehicle starts to decelerate before the actual cut-in occurs, as shown in Figures 5 and 6(a). After the lane crossing, the clearance is smoothly recovered to the desired clearance due to the proactive deceleration of the ego vehicle, as shown in Figure 6(c). Figure 6(b) shows that the ego vehicle smoothly adapts its velocity to the target vehicle. The ego vehicle executes mild acceleration using the longitudinal acceleration within the range of −1.0–0.2 m/s2, as shown in Figure 6(a). The clearance with the cut-in vehicle is maintained safely with a minimum value of 14.5 m. In this scenario, the average solving time of the MPC is 0.18 ms, which hardly affects driving performance and is comparable with the study on applying MPC in vehicle tests [14]. Therefore, the vehicle control algorithm based on our prediction model allows the ego vehicle to guarantee collision safety and provide ride quality in a real driving environment.
A method of trajectory prediction of surrounding vehicles and the longitudinal control of AVs has been developed and evaluated via vehicle tests in an urban road environment. The future trajectories are estimated through an LSTM-based deep learning model trained with real driving data. The relation between target vehicles and lanes is encoded to learn lane-aware behaviors. Intervehicle interaction is considered by modeling the surrounding traffic scene as a graph and applying GCN layers. An adjacency matrix is learned by the self-attention mechanism and applied in the graph construction. An MPC problem is formulated to calculate the optimal acceleration command of AVs, which deals with car-following scenarios proactively.
The proposed algorithm has been evaluated in terms of the trajectory prediction accuracy and the control algorithm’s automated driving performance. The comparative evaluation of the prediction performance shows that the proposed model improves the prediction accuracy by capturing the relation between the target vehicle and surrounding environments. The vehicle test results show that the proposed control algorithm based on our prediction model allows the AV to proactively react to the dynamic motion changes of the target vehicle securing ride quality and collision safety. The future work will include the application of the prediction algorithm to the complex motion planning of AVs such as lane change maneuvers.
This work was supported in part by the Korea Institute of Marine Science & Technology Promotion (KIMST), funded by the Ministry of Oceans and Fisheries, South Korea (20220583); the Future Mobility Technical Center, Seoul National University (SNU-FMTC), South Korea; and the Institute of Engineering Research, Seoul National University, South Korea; and in part by the Institute of Advanced Machinery and Design, Seoul National University (SNU-IAMD), South Korea.
Youngmin Yoon (dudlass1@snu.ac.kr) is pursuing a Ph.D. in mechanical engineering at Seoul National University, Seoul 08826, South Korea. His research interests are the motion prediction of surrounding vehicles, predictive motion planning, and automated driving vehicle control. He received his B.S. degree in mechanical engineering from Seoul National University, South Korea, in 2018.
Kyongsu Yi (kyi@snu.ac.kr) a professor at the School of Mechanical Engineering at Seoul National University, Seoul 08826, South Korea. His research interests are control systems, driver assistant systems, active safety systems, and automated driving of ground vehicles. He received his B.S. and M.S. degrees in mechanical engineering from Seoul National University, South Korea and received his Ph.D. degree in mechanical engineering from the University of California, Berkeley. He is a Member of IEEE.
[1] D. Lee, Y. P. Kwon, S. McMains, and J. K. Hedrick, “Convolution neural network-based lane change intention prediction of surrounding vehicles for ACC,” in Proc. 2017 IEEE 20th Int. Conf. Intell. Transp. Syst. (ITSC), pp. 1–6, doi: 10.1109/ITSC.2017.8317874.
[2] S. Yoon, H. Jeon, and D. Kum, “Predictive cruise control using radial basis function network-based vehicle motion prediction and chance constrained model predictive control,” IEEE Trans. Intell. Transp. Syst., vol. 20, no. 10, pp. 3832–3843, Oct. 2019, doi: 10.1109/TITS.2019.2928217.
[3] C. G. Prevost, A. Desbiens, and E. Gagnon, “Extended Kalman filter for state estimation and trajectory prediction of a moving object detected by an unmanned aerial vehicle,” in Proc. 2007 Amer. Control Conf., pp. 1805–1810, doi: 10.1109/ACC.2007.4282823.
[4] J. Zhang, “An interaction-aware approach for online cut-in behavior prediction and risk assessment for autonomous driving,” M.S. thesis, Univ. of Waterloo, Waterloo, Canada, 2021.
[5] F. Altchè, and A. De La Fortelle, “An LSTM network for highway trajectory prediction,” in Proc. 2017 IEEE 20th Int. Conf. Intell. Transp. Syst. (ITSC), pp. 353–359, doi: 10.1109/ITSC.2017.8317913.
[6] N. Deo, and M. M. Trivedi, “Convolutional social pooling for vehicle trajectory prediction,” in Proc. IEEE Conf. Comput. Vis. Pattern Recognit. Workshops, 2018, pp. 1468–1476, doi: 10.1109/CVPRW.2018.00196.
[7] X. Li, X. Ying, and M. C. Chuah, “GRIP: Graph-based interaction aware trajectory prediction,” in Proc. 2019 IEEE Intell. Transp. Syst. Conf. (ITSC), pp. 3960–3966, doi: 10.1109/ITSC.2019.8917228.
[8] L. Lin, S. Gong, S. Peeta, and X. Wu, “Long short-term memory-based human-driven vehicle longitudinal trajectory prediction in a connected and autonomous vehicle environment,” Transp. Res. Rec., vol. 2675, no. 6, p. 0361198121993471, 2021, doi: 10.1177/0361198121993471.
[9] J. Pan et al., “Lane-attention: Predicting vehicles’ moving trajectories by learning their attention over lanes,” in Proc. 2020 IEEE/RSJ Int. Conf. Intell. Robots Syst. (IROS), pp. 7949–7956, doi: 10.1109/IROS45743.2020.9341233.
[10] V. Bageshwar, W. Garrard, and R. Rajamani, “Model predictive control of transitional maneuvers for adaptive cruise control vehicles,” IEEE Trans. Veh. Technol., vol. 53, no. 5, pp. 365–374, Sep. 2004, doi: 10.1109/TVT.2004.833625.
[11] S. Li, K. Li, R. Rajamani, and J. Wang, “Model predictive multi-objective vehicular adaptive cruise control,” IEEE Trans. Control Syst. Technol., vol. 19, no. 3, pp. 556–566, May 2011, doi: 10.1109/TCST.2010.2049203.
[12] R. Schmied, D. Moser, H. Waschl, and L. del Re, “Scenario model predictive control for robust adaptive cruise control in multi-vehicle traffic situations,” in Proc. 2016 IEEE Intell. Veh. Symp. (IV), pp. 802–807, doi: 10.1109/IVS.2016.7535479.
[13] A. Paszke et al., “PyTorch: An imperative style, high-performance deep learning library,” in Proc. Adv. Neural Inf. Process. Syst., 2019, pp. 8026–8037.
[14] H. Chae, Y. Jeong, H. Lee, J. Park, and K. Yi, “Design and implementation of human driving data-based active lane change control for autonomous vehicles,” Proc. Inst. Mech. Eng., D, J. Automobile Eng., vol. 235, no. 1, pp. 55–77, 2021, doi: 10.1177/0954407020947678.
[15] J. Suh, H. Chae, and K. Yi, “Stochastic model-predictive control for lane change decision of automated driving vehicles,” IEEE Trans. Veh. Technol., vol. 67, no. 6, pp. 4771–4782, Jun. 2018, doi: 10.1109/TVT.2018.2804891.
Digital Object Identifier 10.1109/MVT.2022.3207305