You are currently viewing a new version of our website. To view the old version click .
Machines
  • Article
  • Open Access

17 August 2024

Abnormal Driving Area Detection Using Multiple Vehicle Dynamic Model-Based Filter: Design and Experimental Validation

,
and
1
Department of Electrical Engineering, Incheon National University, Incheon 22012, Republic of Korea
2
Agency for Defense Development, Daejeon 34060, Republic of Korea
3
School of Mechanical Engineering, Chungbuk National University, Cheongju 28644, Republic of Korea
*
Author to whom correspondence should be addressed.
This article belongs to the Special Issue Autonomous Navigation of Mobile Robots and UAV

Abstract

The main concern of remote control systems for autonomous ground vehicles (AGVs) is to perform the given mission according to the purpose of the operator. Although most remote systems are composed of a screen-based architecture, they are insufficient to transfer sufficient information to the remote operator. Therefore, in this paper, we present and experimentally validate an abnormal driving area detection system using an interacting multiple model (IMM) filter for the remote control system. In the proposed IMM filter, the unknown dynamic behavior of the vehicle, which changes according to changes in the driving environment, was lumped into a parameter change of the system model. As a result, we can obtain the probability of each model representing the reliability of each model, but an index can be used to infer the current status of the AGV and the driving environment. The index can help us detect both unusual behavior of the AGV such as skidding or sliding, and areas with low-friction road conditions that are not confirmed by images from the camera sensor. Thus, the remote operator can directly decide whether to continue operating or not. The proposed method is simple but useful and meaningful for the remote operator compared to the image-only method. The overall procedure of the proposed method was experimentally validated via a multi-purpose AGV on rough unpaved proving ground. Nine abnormal driving areas were discovered on the ground. In five of these areas, vehicles consistently exhibited abnormal driving behavior. The remaining four areas were confirmed to be affected by variables such as weather conditions and vehicle tire wear.

1. Introduction

Autonomous ground vehicles (AGVs) have been studied to replace missions carried out by humans. In particular, they are widely used not only in industrial fields such as logistics and security robots but also in the defense field because they can handle tasks that are difficult or dangerous for humans to do. In the military field, AGVs are often used for missions such as detecting and removing landmines to minimize casualties. In addition, AGVs are also used for surveillance and reconnaissance of enemy forces [1,2,3,4]. To fulfill these special purposes and have solid durability, military AGVs are usually constructed in the form of skids, unlike ordinary passenger cars, as shown in Figure 1. The skid-type AGV steers with the speed difference between the left and right wheels and at the same time achieves the desired target speed. AGV includes both remote driving and autonomous driving types. In remote driving, the remote operator controls the AGV via a remote controller using communication over a long distance. The operator understands the driving situation through the AGV’s camera view displayed on the remote controller. Then, the operator judges the holistic situation and gives control commands to the vehicle to reach the desired destination. To enhance the operator’s driving realism, the operator often controls the AGV through the screen of the control system decorated as if in a vehicle such as a virtual reality headset or 360-degree screen [5,6]. Nevertheless, when the driving environment is transmitted only through the screen, there is a problem that it is difficult for the operator to feel a sense of reality because vibration and sound felt in the actual driving environment are not transmitted. In particular, it is difficult to distinguish whether a skid-type vehicle is skidding due to steering or slipping due to the driving environment because a skid-type vehicle steers with a difference in speed between the left and right wheels.
Figure 1. Target test autonomous ground vehicle.
AGVs in the form of autonomous driving are widely used in enemy surveillance and reconnaissance missions. When the operator remotely selects the mission area, the AGV itself performs all perception, decision, and control. A global path for a given environment and map is automatically planned considering topographic information. Both perception and decision are continuously repeated during trips through sensors such as cameras and lidars. Consequently, a local path is calculated in a path-planning algorithm that can simultaneously achieve both objectives, avoiding dynamic obstacles and following the global path [7]. Then, the controller autonomously controls the AGV to follow the planned local path. The operator checks in real time whether autonomous driving is working well from a remote location and, if necessary, immediately converts to remote control mode for control. Many researchers have studied stable and reliable autonomous driving in various fields such as object classification using convolutional neural networks [8,9], planning an optimal path to avoid dynamic obstacles [10,11], understanding driving scenes using artificial intelligence, and model predictive control techniques considering vehicle constraints [12]. Combined envelope control techniques for AGVs, including both active front steering and direct yaw-moment control, are proposed in [13]. To guarantee robustness against unknown disturbance, a backstepping control approach for path control with an extended-state observer was also proposed [14]. In [15], the polytopic method was introduced to characterize the time-varying vehicle speed while using fewer vertices to simplify the control scheme. However, such autonomous driving research has mainly been performed in well-known environments such as highways and racing tracks. One of the problems that must be overcome for AGVs is exploring and driving autonomously on uncertain rough terrain that has not been visited. In particular, AGVs do not run on roads paved with asphalt but mainly drive on unpaved roads or rough terrain.

3. Vehicle Model

To design a model-based vehicle abnormal driving area detection system, a simple lateral dynamic motion model of a skid-type vehicle is presented in this section. And, a vehicle status indexing scheme is also covered by specifying certain tire cornering stiffness.

3.1. Lateral Vehicle Dynamics

The dynamic motion model of the 6 × 6 skid-type ground vehicle is briefly described in this section. The structure and coordinate frames are shown in Figure 2. The equation lateral motion for the given 6 × 6 skid-type vehicle is obtained as follows
m ( y ¨ + r v x ) = F y f + F y m + F y r .
m, y ¨ , r, and v x denote mass, lateral acceleration, yaw rate, and longitudinal velocity of the vehicle, respectively. The lateral tire force, F y , can be written with the cornering stiffness of the tire and tire slip angle as follows:
F y f = F y 1 + F y 2 = 2 C α f α f , F y m = F y 3 + F y 4 = 2 C α m α m , F y r = F y 5 + F y 6 = 2 C α r α r ,
where the slip angle of the tire, α , is defined as the negative value of the velocity vector’s orientation due to the orientation of the tire is always zero for the skid-type vehicle.
α = θ v ,
where θ v is the angle that the velocity vector makes with the longitudinal axis of the vehicle. Now, one can make use of the following relations to calculate θ v f ,   θ v m and θ v r considering the relative position between each wheel and the center of gravity, respectively.
tan ( θ v f ) = v y + l f r v x , tan ( θ v m ) = v y + l m r v x , tan ( θ v r ) = v y l r r v x .
l f , l m , and l r denote the distance from the center of gravity to each wheel, respectively. Substituting from (2)–(4) into (1) using small-angle approximation and y ˙ = v y , the lateral motion equation can be written as
y ¨ = 2 ( C α f + C α m + C α r ) m v x y ˙ v x r + 2 ( C α f l f + C α m l m C α r l r ) m v x r ,
where C f denotes the cornering stiffness of the tire. One can make use of the following equation for the yaw dynamics:
I z r ˙ = M z ,
where I z and M z denote the moment of inertia and lateral moment, respectively. Let us define the state x = [ y ˙ r ] T and the input u = M z . Then, the state space representation of the overall vehicle motion can be written as
x ˙ = A x + B u
where
A = a 11 a 12 0 0 , B = 0 b 21 ,
with
a 11 = 2 ( C α f + C α m + C α r ) m V x ,
a 12 = V x 2 ( C α f l f + C α m l m C α r l r ) m V x , b 21 = 1 I z .
Figure 2. Base structure and coordinate frames.

3.2. Cornering Stiffness

The tire cornering stiffness is the coefficient representing the relationship between the tire slip angle and the lateral tire force. However, it is quite difficult to determine the value of cornering stiffness because of its nonlinearity [24]. This cornering stiffness varies according to the external environment conditions such as vertical tire force, and road friction. In particular, the stiffness also changes as the tire slip angle changes, as shown in Figure 3. It can be seen that the higher the tire–road friction (asphalt) and the smaller the tire slip angle, the larger the coefficient value. Therefore, once the coefficient values are specified, one can indirectly infer the tire slip angle and know the situation in which the vehicle is slipping. So, we design a multiple model for various cornering stiffnesses depending on the driving environment and specify the stiffness to index the vehicle status.
Figure 3. Example of cornering stiffness characteristics.
In this paper, we obtained the nominal cornering stiffness of the tire via simulation from the TruckSim simulator released from the mechanical simulation. The vehicle and tire models were set as close to the real one as possible, and the cornering stiffness of the tire was calculated through simulation results. In the next section, we are about to develop multiple models to specify the unmeasurable and nonlinear varying cornering stiffness. Consequently, an interacting multiple model (IMM) filter-based abnormal driving area detection system is presented.

4. Interacting Multiple Model

An interacting multiple model (IMM) filter has been developed as the cost-effective suboptimal hybrid state estimation scheme [17,18]. In this paper, we use the IMM filter to specify the cornering stiffness and infer the status of the vehicle for remote control. The cornering stiffness according to the slip of the vehicle is defined in advance, and the status of the vehicle is determined by monitoring the state and probability from the IMM filter. The overall proposed structure is described in Figure 4. The IMM filter consists of four steps: interaction, filtering, updating, and combination.
Figure 4. Block diagram of the IMM filter for N-models.
The IMM begins with the selection of a set of candidate models, each representing a different hypothesis about the system dynamics. These models can vary in complexity and may capture different aspects of the system behavior. The IMM incorporates mode transition probabilities, which govern the likelihood of the system switching from one model to another over time. These probabilities are typically estimated based on the system’s history or predefined rules. Mode transition probabilities play a crucial role in adapting the IMM framework to changes in the system dynamics. The core of IMM involves the filtering or estimation process, where the outputs of multiple models are combined to generate an optimal estimate of the system state. Each model’s output is weighted according to its current mode probability, reflecting the confidence in that model’s prediction. After the filtering step, the mode probabilities and model weights are updated based on the observed data. This update process ensures that models that provide more accurate predictions are given higher weights in subsequent iterations, while less accurate models are down-weighted. Weight update strategies can vary depending on the specific IMM implementation and application requirements. Once the filtering process is complete, the estimated system state can be used for prediction or control purposes. In prediction tasks, IMM can provide more accurate forecasts by leveraging the diversity of multiple models.

4.1. Multiple Model Setting

Let us consider the state space model using model index n { 1 , , N } according to the cornering stiffness.
x k + 1 = Φ ( n ) x k + Γ ( n ) u k + w k ( n ) y k = C ( n ) x k + v k ( n )
where w k ( n ) N ( 0 , Q ( n ) ) and v k ( n ) N ( 0 , R ( n ) ) . Here, we assume that the model index at time k, n k , is modeled as a time-invariant Markov chain with transition probability matrix Π as follows:
Π = { π i j = P ( n k + 1 = i | n k = j ) } ,
where i , j { 1 , , N } and π i j denotes the Markov probability of a transition from model j to i.

4.2. Interaction of Multiple Model

Let us define the probability of model i at time k as μ k | k i . The model probability represents the likelihood that a particular mode best describes the system state at a given time. This probability is calculated based on the degree of match between the mode’s state estimate and the actual observations. Then, we can represent the mixing probability μ k 1 | k 1 i j using the model probability as follows:
μ k 1 | k 1 i j = π i j μ k 1 | k 1 j c ¯ i ,
where the normalization factor is
c ¯ i = j = 1 N π i j μ k 1 | k 1 i j .
Here, the mixing probability indicates the likelihood of transitioning between different modes, providing information on how modes might change over time. It is computed by combining the previous time’s mode probabilities with the current time’s mode transition probabilities.
Then, the mixed initial state x ˜ k 1 | k 1 i and the mixed initial covariance P ˜ k 1 | k 1 i of model i at sample time k 1 are given by
x ˜ k 1 | k 1 i = j = 1 N μ k 1 | k 1 i j x ^ k 1 | k 1 j P ˜ k 1 | k 1 i = j = 1 N μ k 1 | k 1 i j P ^ k 1 | k 1 j + ( x ^ k 1 | k 1 j x ˜ k 1 | k 1 i ) ( x ^ k 1 | k 1 j x ˜ k 1 | k 1 i ) T ,
where x ^ k 1 | k 1 j and P ^ k 1 | k 1 j denote the estimated state and covariance of model j at sample time k 1 , respectively. Then, each single Kalman filter using model indexed i starts filtering with this mixed initial state and covariance.

4.3. Filtering

Remark 1.
For the given 6 × 6 skid-type lateral motion model, only the system matrix Φ is changed by the cornering stiffness. Therefore, the input matrix Γ and the measurement matrix C for each model are exactly the same as each other. Thus, the following measurement matrix C is used in each model.
C = 1 0 0 1 .
Now, the prediction and correction of both state and covariance are performed by each single Kalman filter.

4.3.1. Prediction

The prediction of both state and covariance is calculated using the system model in (1) and mixed initial values.
x ¯ k | k 1 i = Φ k 1 i x ˜ k 1 | k 1 i + Γ u k 1 P ¯ k | k 1 i = Φ k 1 i P ˜ k 1 | k 1 i ( Φ k 1 i ) T + Q k 1 i ,
where x ¯ k | k 1 i and P ¯ k | k 1 i denote the predicted value at time k calculated from sample time k 1 for model i. Φ k 1 i denotes the system matrix for model i with the cornering stiffness C α f i , C α m i , C α r i at time k 1 . For simplification, we set C α f i = C α m i = C α r i .

4.3.2. Correction

The correction of state and covariance is calculated using both the measurement and the predicted values.
S k i = C P ¯ k | k 1 i C T + R k 1 i K k i = P ¯ k | k 1 i C T ( S k i ) 1 x ^ k | k i = x ¯ k | k 1 i + K k i ( y k i C x ¯ k | k 1 i ) P ^ k | k i = ( I K k i C ) P ¯ k | k 1 i
where y k i and S k i are innovation and its covariance filter using model i, respectively.
Remark 2.
For the given system, the measurement y k i is exactly the same as each other for all i.
The correction of both state and covariance is used when calculating the initial value of the mixing step in the next iteration.

4.4. Updating

The likelihood function of each model i at time k, Λ k i , is given by the Gaussian assumption
Λ k i = exp [ ( 1 2 ) ( y k i ) T ( S k i ) 1 ( y k i ) ] | 2 π S k i | 1 2 .
Then, the model probabilities of each model are calculated as follows:
μ k | k i = 1 c Λ k i j = 1 N π i j μ k 1 | k 1 j = 1 c Λ k i c ¯ i ,
where c is the normalization factor for i = 1 N μ k | k i = 1 .

4.5. Merging

The merged state x ^ k | k and its covariance P ^ k | k are calculated as follows using the standard Gaussian mixture mean and covariance formula
x ^ k | k = i = 1 N μ k | k i x ^ k | k i P ^ k | k = i = 1 N μ k | k i [ P ^ k | k i + ( x ^ k | k i x ^ k | k ) ( x ^ k | k i x ^ k | k ) T ] .
Note that the correction of both state and covariance of each filter is used recursively to compute the initial mixed value of each filter in the next step, but the fused state and covariance are not. The convergence of the IMM filter with theoretical proof is detailed in [25].

4.6. Indexing

We can make use of the model probabilities at every sample time in Equation (17). Therefore, this model probability, μ k | k i , is adopted for the abnormal driving area detection system. We set four models ( N = 4 ) considering AGV driving conditions using cornering stiffness. The highest probability from the IMM filter indicates the current status of AGV (1: Danger; 2: Semi-Danger; 3: Semi-Stable; 4: Stable). For example, the lowest cornering stiffness represents the Danger ( n = 1 ). The low stiffness indicates a situation where the ground is frozen or the tire slip angle is large. Then, we can infer that the vehicle is in a state of severe slippage. On the other hand, a high stiffness means that the tire–road friction coefficient is high or the tire slip angle is small ( n = 4 ). Consequently, it can be inferred that the vehicle is driving stably.

5. Experiment Results

5.1. Experiment Setup

The proposed monitoring system was validated through several field tests on the unpaved proving ground as shown in Figure 5. For the field tests, the 6 × 6 skid-type AGV shown in Figure 1 is used. The AGV weighing more than 5000 [kg] is powered by a hybrid engine consisting of a gasoline engine and battery connected in series. And its maximum speed is about 40–50 [kph]. Various sensors such as inertial measurement unit (IMU), global positioning system (GPS), 2/3D LiDAR, and cameras were implemented on the AGV to perceive the uncertain and unknown driving environment and to measure the state of the dynamic model. The algorithm of AGV is composed of perception, planning, and control components. A remote operating control system is also utilized to interact with the AGV. Control commands such as speed, stop/start, and reconnaissance points are transmitted to the AGV, and vehicle state information such as images from the camera and current global position is received from the remote control system. The global and local path planning proceeded sequentially in the path planning algorithm using the reconnaissance points [26]. During the path planning and control, the multi-sensor fusion algorithm using 3D range registration was utilized in the experiments to enhance the robustness and accuracy of AGV localization against vulnerable GPS data from external disturbances [27]. The robust path controller using a disturbance observer was implemented for the path control. The proposed method is not integrated into the controller. The overall IMM procedure was processed through post-processing after the completion of each driving.
Figure 5. Proving ground for driving experiment. Red indicates the road the vehicle traveled on.

5.2. Results Analysis

Figure 6 shows a snapshot of the abnormal driving area detection system using the proposed method. The lower-left subfigure shows the AGV’s current global position. The upper-left and middle subfigures show the local path planning result of the AGV to follow the global path. The upper-middle subfigure shows the probability map for the surrounding environment used for local path planning. The below-middle subfigure shows the front view obtained by the camera mounted on the AGV. The rest shows the AGV speed, the probability value of each model from IMM, and the index. The index is determined based on the output probability of the IMM and indicates the number of the model with the highest probability. Note that the AGV is slipping due to the severe bank angle of the unpaved road. To validate the proposed algorithm, we conducted the test for two cases.
Figure 6. Snapshot of driving data of abnormal driving area detection system for AGV in Case 2.
  • Case 1. Wet ground after rain, and worn tires.
  • Case 2. Dry ground, and new tires.
Experiments in these two cases allow us to identify the danger areas due to changes in tire–road friction. It is also possible to identify areas of danger that occur identically in both experiments as permanent areas of risk. Before we index the status of the AGV based on the probability values resulting from the interaction of multiple models, it can be confirmed that the proposed IMM filter can estimate the actual sensor value by showing reasonable performance as shown in Figure 7b and Figure 8b. Experiment results for both cases are represented in Figure 7 and Figure 8.
Figure 7. Case 1: wet ground after rain, and worn tires.
Figure 8. Case 2: dry ground, and new tires.
For comparison between the two cases, the areas showing the same pattern in the two tests are marked in a green circle, and the areas showing a different pattern are marked in a black circle as shown in Figure 7a and Figure 8a. The AGV was in a dangerous state in A, D, F, and H in Case 1, but it was not in Case 2. These sections have a greater curvature than other sections. In an autonomous path control algorithm, the target speed of the AGV is set to reach the maximum speed in consideration of the result of local path planning to complete the mission quickly. At this time, a normal driving condition is assumed, but if the frictional force between the tire and the road decreases, a slipping phenomenon occurs as shown in Case 1. As friction decreases, the speed must be reduced to maintain stability. But friction change is not taken into account in local path planning, sliding on curvy roads is inevitable. Area H is not very curvature, but since it is the point where the downhill road ends, it can be confirmed that slipping occurs in Case 1, where the frictional force between the road and the tire is low.
In both cases, AGV shows a dangerous status in B, C, E, G, and I. The test track consists of various types of unpaved roads, and the roads in sections B, C, and E are made up of small gravel. Therefore, the AGV did not take sufficient grip in both cases at these sections, so it caused a slip of AGV and a dangerous state appeared. Section G is a flat road that appears on the way downhill. In this section, the AGV shows a dangerous index in both cases because slip occurs due to inertia. In Section I, it can be observed that both cases are equally dangerous due to the severe curvature. The probabilities from interacting multiple models to identify the AGV status are shown in Figure 7c and Figure 8c. One can confirm that the probability of models 3 and 4 increases whenever the AGV slips for some reason such as longitudinal skidding or lateral sliding. One can also see that the index changes according to the highest probability value. Using the proposed algorithm, remote operators can monitor AGV danger status in real time. It is also possible to design control strategies based on driving conditions. Based on the driving status information of the reconnaissance AGV, additional strategies can be reorganized, such as selecting a different reconnaissance route and changing target speed.

6. Conclusions

In this research, we present the design scheme and experimental validation of an autonomous ground vehicle (AGV) abnormal driving area detection system using an interacting multiple model (IMM) filter. The dynamic behavior of the vehicle, which changes according to changes in the driving environment, was lumped into a parameter change of the system model. Using the probability of interacting multiple models, we can indirectly check the status of the vehicle in an unknown area. Also, it can help us detect abnormal behavior of the AGV such as skidding or sliding. Nine abnormal driving areas were discovered in the proving ground. In five of these areas, vehicles consistently exhibited abnormal driving behavior. The remaining four areas were confirmed to be affected by variables such as weather conditions and vehicle tire wear. As a result, using the proposed approach, the remote operator can directly decide whether to continue operating or not. Furthermore, additional strategies can be reorganized, such as selecting a different reconnaissance route and changing the target speed for the following AGV. The proposed method is simple but useful and meaningful for the remote operator compared to the image-only method. An operating strategy will be developed and a controller will be designed using this status index in future research.

Author Contributions

Conceptualization, C.K.; methodology, C.K.; software, C.K.; validation, C.K., T.L. and J.S.; formal analysis, C.K.; investigation, C.K. and T.L.; resources, C.K., T.L., and J.S.; data curation, C.K., T.L., and J.S.; writing original draft preparation, C.K.; visualization, C.K. and J.S.; supervision, J.S.; project administration, J.S. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by Incheon National University Research Grant in 2021.

Data Availability Statement

The original contributions presented in the study are included in the article; further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Shin, J.; Kwak, D.J.; Kim, J. Autonomous platooning of multiple ground vehicles in rough terrain. J. Field Robot. 2021, 38, 229–241. [Google Scholar] [CrossRef]
  2. Ni, J.; Hu, J.; Xiang, C. A review for design and dynamics control of unmanned ground vehicle. Proc. Inst. Mech. Eng. Part D J. Automob. Eng. 2021, 235, 1084–1100. [Google Scholar] [CrossRef]
  3. Grocholsky, B.; Keller, J.; Kumar, V.; Pappas, G. Cooperative air and ground surveillance. IEEE Robot. Autom. Mag. 2006, 13, 16–25. [Google Scholar] [CrossRef]
  4. Naranjo, J.E.; Jimenez, F.; Anguita, M.; Rivera, J.L. Automation kit for dual-mode military unmanned ground vehicle for surveillance missions. IEEE Intell. Transp. Syst. Mag. 2018, 12, 125–137. [Google Scholar] [CrossRef]
  5. Yang, Z.; Xiang, D.; Cheng, Y. VR panoramic technology in urban rail transit vehicle engineering simulation system. IEEE Access 2020, 8, 140673–140681. [Google Scholar] [CrossRef]
  6. Tikanmäki, A.; Bedrník, T.; Raveendran, R.; Röning, J. The remote operation and environment reconstruction of outdoor mobile robots using virtual reality. In Proceedings of the IEEE International Conference on Mechatronics and Automation (ICMA), Takamatsu, Japan, 6–9 August 2017; pp. 1526–1531. [Google Scholar]
  7. Jiang, C.; Hu, Z.; Mourelatos, Z.P.; Gorsich, D.; Jayakumar, P.; Fu, Y.; Majcher, M. R2-RRT*: Reliability-based robust mission planning of off-road autonomous ground vehicle under uncertain terrain environment. IEEE Trans. Autom. Sci. Eng. 2022, 19, 1030–1046. [Google Scholar] [CrossRef]
  8. Gao, H.; Cheng, B.; Wang, J.; Li, K.; Zhao, J.; Li, D. Object classification using CNN-Based fusion of vision and LIDAR in autonomous vehicle environment. IEEE Trans. Ind. Inform. 2018, 14, 4224–4231. [Google Scholar] [CrossRef]
  9. Dong, Z.; Wu, Y.; Pei, M.; Jia, Y. Vehicle type classification using a semisupervised convolutional neural network. IEEE Trans. Intell. Transp. Syst. 2015, 16, 2247–2256. [Google Scholar] [CrossRef]
  10. Sock, J.; Kim, J.; Min, J.; Kwak, K. Probabilistic traversability map generation using 3D-LIDAR and camera. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Stockholm, Sweden, 16–21 May 2016; pp. 5631–5637. [Google Scholar] [CrossRef]
  11. Wang, B.; Liu, Z.; Li, Q.; Prorok, A. Mobile robot path planning in dynamic environments through globally guided reinforcement learning. IEEE Robot. Autom. Lett. 2020, 5, 6932–6939. [Google Scholar] [CrossRef]
  12. Guo, H.; Shen, C.; Zhang, H.; Chen, H.; Jia, R. Simultaneous trajectory planning and tracking using an MPC method for cyber-physical systems: A case study of obstacle avoidance for an intelligent vehicle. IEEE Trans. Ind. Inform. 2018, 14, 4273–4283. [Google Scholar] [CrossRef]
  13. Ni, J.; Hu, J.; Xiang, C. Envelope control for four-wheel independently actuated autonomous ground vehicle through AFS/DYC integrated control. IEEE Trans. Veh. Technol. 2017, 66, 9712–9726. [Google Scholar] [CrossRef]
  14. Hwang, Y.; Kang, C.M.; Kim, W. Robust nonlinear control using barrier Lyapunov function under lateral offset error constraint for lateral control of autonomous vehicles. IEEE Trans. Intell. Transp. Syst. 2022, 23, 1565–1571. [Google Scholar] [CrossRef]
  15. Liang, J.; Tian, Q.; Feng, J.; Pi, D.; Yin, G. A polytopic model-based robust predictive control scheme for path tracking of autonomous vehicles. IEEE Trans. Intell. Veh. 2024, 9, 3928–3939. [Google Scholar] [CrossRef]
  16. Mazor, E.; Averbuch, A.; Bar-Shalom, Y.; Dayan, J. Interacting multiple model methods in target tracking: A survey. IEEE TRansactions Aerosp. Electron. Syst. 1998, 34, 103–123. [Google Scholar] [CrossRef]
  17. Blom, H.A.; Bar-Shalom, Y. The interacting multiple model algorithm for systems with markovian switching coefficients. IEEE Trans. Autom. Control 1988, 33, 780–783. [Google Scholar] [CrossRef]
  18. Li, X.R.; Jilkov, V.P. Survey of maneuvering target tracking. Part V. Multiple-model methods. IEEE Trans. Aerosp. Electron. Syst. 2005, 41, 1255–1321. [Google Scholar]
  19. Toledo-Moreo, R.; Zamora-Izquierdo, M.A.; Úbeda-Miñarro, B.; Gómez-Skarmeta, A.F. High-integrity IMM-EKF-based road vehicle navigation with low-cost GPS/SBAS/INS. IEEE Trans. Intell. Transp. Syst. 2007, 8, 491–511. [Google Scholar] [CrossRef]
  20. Kang, C.M.; Lee, S.-H.; Chung, C.C. Vehicle lateral motion estimation with its dynamic and kinematic models based interacting multiple model filter. In Proceedings of the IEEE Conference on Decision and Control, Las Vegas, NV, USA, 12–14 December 2016; pp. 2449–2454. [Google Scholar]
  21. Kong, J.; Pfeiffer, M.; Schildbach, G.; Borrelli, F. Kinematic and dynamic vehicle models for autonomous driving control design. In Proceedings of the IEEE Intelligent Vehicles Symposium, Seoul, Republic of Korea, 28 June–1 July 2015; pp. 1094–1099. [Google Scholar]
  22. Judalet, V.; Glaser, S.; Gruyer, D.; Mammar, S. IMM-based sensor fault detection and identification for a drive-by-wire vehicle. IFAC-PapersOnLine 2015, 48, 1158–1164. [Google Scholar] [CrossRef]
  23. Kim, B.; Yi, K.; Yoo, H.-J.; Chong, H.-J.; Ko, B. An IMM/EKF approach for enhanced multitarget state estimation for application to integrated risk management system. IEEE Trans. Veh. Technol. 2014, 64, 876–889. [Google Scholar] [CrossRef]
  24. Rajamani, R. Vehicle Dynamics and Control, 2nd ed.; Springer: Berlin/Heidelberg, Germany, 2012. [Google Scholar]
  25. Seah, C.E.; Hwang, I. Algorithm for performance analysis of the IMM algorithm. IEEE Trans. Onaerospace Electron. Syst. 2011, 47, 1114–1124. [Google Scholar] [CrossRef]
  26. Shin, J.; Kwak, D.; Kwak, K. Robust path control for an autonomous ground vehicle in rough terrain. Control Eng. Pract. 2020, 98, 104384. [Google Scholar] [CrossRef]
  27. Choi, J.-H.; Park, Y.-W.; Kim, J.; Choe, T.-S.; Song, J.-B. Federated filter based unmanned ground vehicle localization using 3D range registration with digital elevation model in outdoor environments. J. Field Robot. 2012, 29, 298–314. [Google Scholar] [CrossRef]
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Article Metrics

Citations

Article Access Statistics

Multiple requests from the same IP address are counted as one view.