Next Article in Journal
Compression Failure Characteristics of Interface Section Coal Pillar Excavation and Backfill Composite Structure
Previous Article in Journal
Patient-Specific Computational Fluid Dynamics Analysis of Anticancer Agent Distribution in Superselective Intra-Arterial Chemotherapy for Oral Cancer
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Front–Rear Camera Switching Strategy for Indoor Localization in Automated Valet Parking Systems with Extended Kalman Filter and Fiducial Markers

1
Hyunbo Corporation, Yongin-si 17111, Republic of Korea
2
Department of Intelligent Mobility Engineering, Kongju National University, Cheonan-si 31080, Republic of Korea
*
Author to whom correspondence should be addressed.
Appl. Sci. 2025, 15(18), 9927; https://doi.org/10.3390/app15189927
Submission received: 28 July 2025 / Revised: 31 August 2025 / Accepted: 6 September 2025 / Published: 10 September 2025
(This article belongs to the Special Issue Intelligent Vehicle Collaboration and Positioning)

Abstract

Automated Valet Parking (AVP) systems require high-precision positioning, especially in indoor environments where Global Positioning System (GPS) is unavailable. Existing methods, which use markers installed on parking lot walls or ceilings, often encounter difficulties due to marker detection failures caused by complex parking behaviors, such as infrastructure constraints or perpendicular parking. This study proposes an optimized indoor positioning system for AVP using fiducial markers recognized by front and rear vehicle cameras. To enhance accuracy and robustness, an Extended Kalman Filter (EKF) fuses vehicle kinematic data with marker pose information. Critically, to address the issue of marker occlusion by the front camera during reverse parking, a novel camera switching algorithm employing a hysteresis pattern based on vehicle position, heading, and motion direction is introduced. This ensures continuous marker visibility and stable positioning during parking maneuvers. The system’s effectiveness was validated through simulations and extensive real-vehicle experiments in a real parking space. Results demonstrate that the EKF significantly reduces positioning errors compared to kinematic prediction alone, particularly during curved driving. Furthermore, the proposed camera switching algorithm successfully overcomes the limitations of a front-only camera system, significantly improving positioning accuracy (e.g., reducing RMS error by up to 25.0% in X and 17.6% in Y during parking) and eliminating instability observed with simpler switching logic. This research contributes a cost-effective and reliable positioning solution, advancing the feasibility of AVP systems in challenging indoor environments.

1. Introduction

The global trend of urbanization has led to a significant increase in the number of vehicles, which has resulted in a severe shortage of parking spaces worldwide. This issue is particularly acute in indoor parking facilities, where drivers face difficulties not only in finding available spaces but also in maneuvering their vehicles into tight spots. To address these challenges, autonomous driving technologies are rapidly evolving, focusing on safety and convenience features that enable vehicles to detect parking spaces and park autonomously [1,2,3].
Among these advancements, AVP systems have emerged as a prominent solution that not only enhances driver convenience but also maximizes parking space utilization [3,4,5]. The core challenge for AVP is achieving robust and precise vehicle localization in indoor environments where GPS signals are unavailable [2]. International standards like ISO 23374-1:2023 [4] have been established to address this, providing a practical framework for vehicle–infrastructure cooperation, often centered on fiducial markers.
To solve the indoor localization problem, research is actively progressing beyond simple sensors. One major trend is the tightly coupled fusion of multiple sensors, such as LiDAR, vision, and IMU, to achieve highly reliable localization [5,6,7,8,9]. Another significant area is the advancement of Simultaneous Localization and Mapping (SLAM) technology, which incorporates semantic information [10,11,12], physical constraints [13], or AI-based deep learning [14] to overcome the challenges of feature-poor environments. While these advanced approaches show great promise, they often require significant computational resources or complex sensor setups. In contrast, fiducial marker-based systems offer a practical and cost-effective solution for near-term commercialization, with recent work focusing on improving core components like the markers themselves [15].
Aligning with the practical and cost-effective approach of the ISO standard, this study focuses on enhancing a marker-based positioning system. However, this approach is not without its own limitations. General-purpose visual SLAM algorithms, for example, often struggle with long-term drift in the visually repetitive environments of parking lots. Even with markers, the system must contend with the cumulative error of the vehicle’s Inertial Navigation System (INS) between marker sightings [13]. Furthermore, other map-based positioning methods can lack economic viability due to expensive sensors like LiDAR [2,4,16,17,18].
To overcome these specific challenges, this paper makes two key contributions. First, we implement an EKF to effectively fuse vehicle odometry with observations from fiducial markers, mitigating the drift errors inherent in INS. Second, to address the critical issue of marker occlusion during reverse parking, we propose a novel hysteresis-based camera switching algorithm. This algorithm intelligently transitions between front and rear cameras, ensuring continuous marker visibility and preventing the “chattering” instability that can occur near switching boundaries. The effectiveness of the proposed system is validated through both high-fidelity simulations and extensive real-vehicle experiments.
The remainder of this paper is organized as follows: Section 2 provides an overview of the proposed system architecture and vehicle configuration. Section 3 details the core methodologies, including the fiducial marker design, the EKF formulation, and the proposed camera switching algorithm. Section 4 presents the experimental results from both simulation and real-vehicle tests to validate the system’s performance. Finally, Section 5 concludes the paper and discusses future work.

2. System Overview

This section explains the overall structure and operational principles of the proposed positioning system. The system primarily consists of three key components: fiducial markers, the positioning system architecture, and the proposed operational algorithm.
The positioning system for an AVP application must operate without GPS in indoor environments while adhering to international standards and being economically viable to implement. Furthermore, it should achieve a positioning accuracy of less than 30 cm to support safe and accurate parking maneuvers.

2.1. Vehicle System and Configuration

The localization system proposed in this study is designed and validated for application in a real-world vehicle environment. The core of the system architecture lies in generating precise position information by utilizing the vehicle’s onboard sensors and internal communication network. The overall system configuration is illustrated in the block diagram shown in Figure 1.
As depicted in Figure 2, the vehicle is equipped with both front and rear cameras to recognize fiducial markers attached to the parking lot. These cameras transmit image data to the ‘Marker Detection Node’ in a Robot Operating System (ROS) environment. This node detects markers from the input video stream and outputs their unique IDs along with their 3D relative coordinates calculated within the vehicle’s coordinate system. This setup enables the system to continuously perceive and utilize marker information regardless of the vehicle’s direction of movement during parking maneuvers. Figure 2a illustrates the overall test vehicle, while Figure 2b provides close-up views detailing the placement of the front-facing and rear-facing cameras for fiducial marker detection.
Simultaneously, to acquire the vehicle’s state information, the system interfaces with the In-Vehicle Network (IVN). Specifically, it periodically receives vehicle status data such as vehicle speed, steering angle, and yaw rate from the gateway Electronic Control Unit (ECU). This information is relayed to the ‘Controller Area Network (CAN) Node’, where it is processed into odometry data. This odometry data then serves as input for the prediction model of the EKF.
Finally, the marker’s position information from the ‘Marker Detection Node’ and the vehicle’s odometry data from the ‘CAN Node’ are fed into the ‘Fiducial SLAM Node’. This node, which incorporates the EKF, fuses these two heterogeneous sources of information to estimate the vehicle’s precise position and the marker map in real time. The final estimated position is then transmitted to a higher-level controller, the ‘Automated Parking Controller’. Based on this information, the automated parking system performs precise parking control.
A key design consideration for this architecture is real-time performance, as the system must operate within the 20 ms cycle of the 50 Hz CAN bus data rate. As shown in Figure 1, the computational load is managed efficiently. The most computationally intensive process, the Marker Detection Node, identifies markers from the single active camera stream in under 7 ms. The Fiducial SLAM Node then fuses this data with odometry and performs the EKF update in under 3 ms. This results in a total processing time of less than 10 ms per cycle, which is well within the real-time constraint and demonstrates the system’s feasibility for practical deployment.

2.2. Localization System Configuration

The proposed localization system is structured around an EKF that fuses vehicle kinematics with fiducial marker measurements [19,20,21,22]. The core of the EKF is its prediction model, which is based on the vehicle kinematic model shown in Figure 3. The system acquires kinematic data from onboard sensors, including wheel speed, steering angle (α), and yaw rate, which are essential for the motion prediction model. This model was chosen because the system is designed for low-speed automatic valet parking (under 10 km/h), a condition where tire slip effects can be safely neglected [23]. The kinematic model predicts the vehicle’s state—its position ( x , y ) and heading ( θ )—using motion data inputs such as velocity and steering angle (α). Subsequently, the EKF’s measurement model updates and corrects this prediction using high-precision position data obtained from the detected fiducial markers.

3. Methodology

This section describes the implementation of a positioning system for an AVP application in a real-world parking structure. The methodology addresses the following key elements:
  • An algorithm that utilizes fiducial markers and an EKF for precise positioning;
  • A front–rear camera-switching algorithm designed to compensate for positioning gaps during parking maneuvers. Furthermore, this section details the performance evaluation of the proposed algorithms through the following:
  • Simulations conducted in a digital twin environment using the CAR Learning to Act (CARLA) simulator;
  • Real-vehicle experiments.
These evaluations aim to validate the effectiveness and reliability of the proposed positioning system in real-world AVP scenarios.

3.1. Fiducial Marker

This system incorporates a dedicated algorithm for recognizing fiducial markers that comply with the ISO 23374 standard [4]. The process of calculating a marker’s precise six degrees of freedom (6-DOF) pose from an image is as follows.
First, as depicted in Figure 4c, the algorithm detects the pixel coordinates of the four corner points of a fiducial marker: M 1 , M 2 , M 3 , a n d   M 4 . From these four points, the marker’s local coordinate system and center point, denoted as O M a r k e r , can be calculated [24,25,26]. As shown in Figure 4a, the origin O M a r k e r is located at the physical center of the marker. Its local coordinate system is defined by the Z-axis (①), which is normal to the marker’s surface, and the X-axis (②) and Y-axis (③), which lie along its plane, together forming a right-handed coordinate system.
For instance, the unit vector for the marker’s X-axis can be determined using the midpoints of the lines connecting the corner points, as described in Equations (1)–(4). Figure 4b further illustrates the calculation of the marker’s yaw angle within the global coordinate frame ( X G , Y G ) .
Vertex coordinates of each marker:
M 1,2 , 3,4 = ( X 1,2 , 3,4 ) , ( Y 1,2 , 3,4 ) , ( Z 1,2 , 3,4 )
Equation to determine the X-axis unit vector of the marker:
O M a r k e r = X 2 X 1 , 0 , Z 2 Z 1
X = X 3 X 2 , 0 , Z 3 Z 1
X ^ = X X O M a r k e r
Equation to determine the yaw angle:
Y a w a n g l e = X ^ · 1,0 , 0
By using the calculated unit vectors for the X, Y, and Z axes and the marker’s center position ( O M a r k e r ), the final 6-DOF pose, which includes its 3D position and orientation relative to the camera, can be expressed as shown in Equation (6).
M a r k e r   P o s e = O M a r k e r x , O M a r k e r y , O M a r k e r z , θ r o l l , θ p i t c h , θ y a w
Equation (6) provides the transformation from the marker’s coordinate system to the camera’s coordinate system. Therefore, if the absolute pose of a marker in the global frame is known, the vehicle’s precise position and orientation in the global frame can be determined by leveraging this relative transformation.
To validate the accuracy of the fiducial marker detection system, a comparative analysis was conducted between its distance estimations and ground truth measurements. The experimental setup, as depicted in Figure 5a, consisted of a custom-fabricated fiducial marker and the system’s camera. For ground truth measurement, a high-precision laser rangefinder was used, which is visible in the background of Figure 5b. We compared the distance from the camera to the center of the reference marker, as calculated by our system, against the actual distance measured with this laser rangefinder. Figure 5b further shows examples of successful marker detection, with the calculated 3D coordinate axes overlaid on the markers. This evaluation demonstrated that the measurement data provided by the system is reliable within a maximum range of approximately 7 m.

3.2. Design of Extened Kalman Filter

The Extended Kalman Filter (EKF) is a well-established algorithm for state estimation in nonlinear systems and has been widely applied in autonomous vehicle localization to fuse data from various sensors. For instance, Rezaei and Sengupta [20] demonstrated the integration of DGPS and vehicle sensors using an EKF, and it has been a core component in vision-aided inertial navigation systems like the Multi-State Constraint Kalman Filter (MSCKF) [27].
Although more advanced filters, such as the Unscented Kalman Filter (UKF) [22], can provide higher accuracy for highly nonlinear systems, they impose a greater computational burden. The choice of the EKF for this study was a deliberate decision based on this trade-off. The vehicle kinematic model for low-speed AVP maneuvers is only mildly nonlinear, a condition where the performance difference between EKF and UKF is often marginal. Given these conditions, the EKF provides a robust and computationally efficient solution that meets the target for positioning accuracy of less than 30 cm required for AVP without demanding excessive processing power from the vehicle’s embedded controller. Our work, therefore, adapts this proven framework to our specific application, as detailed in the following sections.
The proposed localization system utilizes an EKF to robustly estimate the vehicle’s state by fusing data from in-vehicle sensors. As illustrated in Figure 6, the EKF process is recursive and consists of two main steps: prediction and correction. The process includes a prediction step utilizing vehicle motion data (vehicle speed, yaw rate) and a correction step based on measurements from recognized fiducial markers.
In the prediction step, the vehicle’s next position is estimated based on its own motion data. This is achieved using a vehicle kinematic model that takes odometry information, such as vehicle speed and yaw rate, as inputs. While a complete vehicle model could also consider the slip angle, it is assumed to be zero in this study, which is a valid simplification for the low-speed maneuvers in an automated parking environment.
In the correction step, the error accumulated during the prediction phase is corrected using an external, absolute measurement. The system uses the precise pose information of fiducial markers, recognized by the camera, to adjust the predicted position. By continuously iterating through this prediction–correction cycle, the EKF effectively combines the vehicle’s internal odometry with external landmark information, leading to accurate and reliable real-time localization. The detailed mathematical models for both the prediction and correction steps will be described in the following sections.

3.2.1. Prediction Model

As previously stated, the vehicle’s speed during parking maneuvers is low enough to assume that tire slip is negligible. Therefore, a vehicle kinematic model is employed as the process model for the EKF’s prediction step. This step estimates the vehicle’s current state based on its previous state and control inputs. Figure 7 describes the vehicle states used in the vehicle kinematic model.
The state vector of the vehicle at time step k is defined as x k It consists of the vehicle’s 2D position ( x k , y k ) and heading angle ( θ k ) in the global coordinate frame.
x k = x k ,   y k ,   θ k T
The state of the vehicle at time k is predicted using a nonlinear function f of the previous state x k 1 and the control input u k 1
x k = f ( x k 1 ,   u k 1 ) .
The control input vector u k 1 consists of the linear velocity v k 1 and angular velocity (yaw rate) ω k 1 , which are obtained from the vehicle’s onboard sensors (CAN data).
u k 1 = v k 1 , ω k 1 T
Based on the kinematic bicycle model (assuming slip angle β = 0), the detailed state transition equations are as follows, where dt is the time interval between steps:
x k y k θ k = x k 1 y k 1 θ k 1 + v k 1 c o s ( θ k 1 ) d t   v k 1 s i n ( θ k 1 ) d t ω k 1   d t
The EKF prediction process involves two steps: predicting the state and predicting the error covariance.
First, the a priori state estimate ( x ^ k | k 1 ) is calculated using the process model with the previous state estimate ( x ^ k 1 | k 1 ).
x ^ k | k 1 = f x ^ k 1 | k 1 , u k 1
Second, the error covariance matrix P k | k 1 is projected forward. This requires the Jacobian matrix ( F k ) of the process model f with respect to the state x.
P k | k 1 = F k P k 1 | k 1 F k T + Q k
Here, P k | k 1   is the error covariance of the previous state, and Q k is the process noise covariance matrix, which models the uncertainty in the process model itself. The Jacobian matrix F k is calculated as:
F k = f x | x ^ k 1 | k 1 , u k 1 = 1 0 v k 1 d t   s i n ( θ k 1 ) 0 1 v k 1 d t   c o s ( θ k 1 ) 0 0 1
The predicted state x ^ k | k 1 and its covariance P k | k 1 are then passed to the correction step, where they will be updated using the fiducial marker measurements.

3.2.2. Correction Model

The correction step updates the a priori state estimate ( x ^ k | k 1 ), which was predicted in the previous step, using the actual measurement obtained from the fiducial marker. This process corrects the accumulated errors and provides a more accurate a posteriori state estimate ( x ^ k | k ).
The measurement vector z k represents the vehicle’s pose as measured by the marker recognition system at time step k . When the camera recognizes a marker, whose absolute global pose is known from a pre-built map, the system can calculate the vehicle’s own global pose. Thus, the measurement vector is in the same space as the state vector.
z k = x m e a s , y m e a s , θ m e a s T
Consequently, the measurement function h that maps the predicted state to the measurement space is a linear identity function
z k = h ( x ^ k | k 1 ) + v k = H k x ^ k | k 1 + w k
Here, w k is the measurement noise, which is assumed to be a zero-mean Gaussian noise with covariance R k . The measurement Jacobian matrix ( H k ) is the partial derivative of h with respect to the state x , which becomes a simple identity matrix in this case.
H k = h x | x ^ k | k 1 = 1 0 0 0 1 0 0 0 1
The measurement noise covariance matrix ( R k ) represents the uncertainty of our measurement system.
The correction process consists of three main steps: calculating the Kalman gain, updating the state estimate, and updating the error covariance.
First, the innovation or residual ( y ~ k ), which is the difference between the actual measurement z k and the predicted measurement h ( x ^ k | k 1 ) is calculated.
y ~ k = z k h ( x ^ k | k 1 )
Next, the Kalman gain ( K k ) is computed. The Kalman gain is a crucial weighting factor that determines how much the prediction is corrected based on the new measurement. A high gain means higher trust in the measurement, while a low gain means higher trust in the prediction.
K k = P k | k 1 H k T ( H k P k | k 1 H k T + R k ) 1
Finally, the a posteriori state estimate ( x ^ k | k ) and its error covariance ( P k | k ) are updated using the Kalman gain and the innovation.
x ^ k | k = x ^ k | k 1 + K k y ~ k
P k | k = ( I K k H k ) P k | k 1
These updated values, x ^ k | k and P k | k , then serve as the input for the next prediction cycle at time step k + 1 . Through this recursive process of prediction and correction, the system continuously refines the vehicle’s position estimate, providing robust and accurate localization.

3.2.3. Coordinate Transformation for Measurement Model

To utilize the information from a detected fiducial marker in the EKF’s correction step, a mathematical relationship between the vehicle’s state and the marker measurement must be defined. Our system involves multiple coordinate frames as shown in Figure 8: the fixed global frame (G), the vehicle frame (V), the camera frame (C), and the marker frame (M). The spatial relationships between these frames are described using 4 × 4 homogeneous transformation matrices. Figure 8 specifically illustrates how the system estimates the vehicle’s pose by relating the marker frame (measured relative to the camera frame) to the vehicle (odometry) frame and the fixed global frame.
A homogeneous transformation matrix T A B represents the pose (position and orientation) of frame {B} relative to frame {A}. The key transformations in our system are:
  • T G V : The vehicle’s pose relative to the global frame. This is the state vector x k = x v , y v , θ v T   that we aim to estimate;
  • T V C : The camera’s pose relative to the vehicle frame. This is a static transformation, determined by the camera’s fixed mounting position and orientation. It is calibrated beforehand;
  • T C M : The marker’s pose relative to the camera frame. This is a dynamic measurement obtained from the marker recognition algorithm.
The EKF’s correction step requires a measurement model h ( x ) that predicts what the measurement should be, given a predicted state. In our system, the measurement z k is the marker’s pose as seen by the camera ( T C M ). The function h ( x ) must therefore predict this value based on the vehicle’s predicted global pose ( x ^ k | k 1 ) and the marker’s known global pose, which is stored in a pre-built map.
Let the known global pose of the i-th marker be T G M i . The predicted measurement for this marker, as seen from the camera, can be derived by chaining the transformations as follows:
P r e d i c t e d   T C M i = ( T G C ) 1 · T G M i   =   ( T G V · T V C ) 1 · T G M i = ( T V C ) 1 · ( T G V ) 1 · T G M i
As illustrated in Figure 9, let the vehicle’s predicted pose T G V   be defined by x v , y v , θ v T and the i-th marker’s known global pose T G M i be defined by x y i , y y i , θ y i T . The transformation ( T G V ) 1 corresponds to H v . i n v in Equation (22), and T G M i corresponds to H y i . By performing this matrix multiplication as shown in Equation (22), we can derive the predicted relative pose of the marker, H m .
H m = H v . i n v * H y i = c o s θ v s i n θ v 0 x v . i n v s i n θ v c o s θ v 0 y v . i n v 0 0 1 0 0 0 0 1 c o s θ y i s i n θ y i 0 x y i s i n θ y i c o s θ y i 0 y y i 0 0 1 0 0 0 0 1 = c o s ( θ y i θ v ) s i n ( θ y i θ v ) 0 x y i x v c o s θ v + ( y y i y v ) s i n θ v s i n ( θ y i θ v ) c o s ( θ y i θ v ) 0 x y i x v s i n θ v + ( y y i y v ) c o s θ v 0 0 1 h z 0 0 0 1
From the resulting transformation matrix, we can extract the predicted 2D position ( h x , h y ) and relative orientation ( h θ ) of the marker with respect to the vehicle’s camera. This vector constitutes the measurement model h ( x ) :
h ( x ) = h x h y h θ = x y i x v c o s θ v + ( y y i y v ) s i n θ v x y i x v s i n θ v + ( y y i y v ) c o s θ v θ y i θ v
This predicted measurement h ( x ^ k | k 1 ) is then used in the EKF correction step (as described in Section 3.2.2 to calculate the innovation y ~ k = z k h ( x ^ k | k 1 ) , where z k is the actual measurement from the camera.

3.3. Front and Rear Camera Switching Algorithm

During the evaluation of the positioning system, which utilized a front monocular camera and markers, it was found that the majority of automated valet parking maneuvers are performed in reverse perpendicular mode. As previously mentioned, the effective recognition distance of the camera is within 7 m. Consequently, as depicted in Figure 10, depending on the marker installation environment, the recognizable markers may disappear during the parking process, particularly when the vehicle’s distance to the forward wall exceeds the camera’s effective range during reverse parking. In such instances, positioning relies solely on vehicle information, leading to the accumulation of errors. This highlights a critical need for a rear-camera-based solution to maintain continuous marker visibility.
In parking environments, the most suitable locations for installing fiducial markers are columns, beams, and walls. For reverse perpendicular parking, placing markers on the wall behind the vehicle is advantageous. Consequently, to ensure efficient positioning in the parking space, switching between the front and rear cameras can be employed. This approach provides more effective positioning performance.
While using both front and rear cameras simultaneously could be optimal, this approach would require additional image processing engines compared to existing systems and poses challenges in synthesizing positioning data from two cameras. Considering economic feasibility, we propose a switching method. However, this method introduces additional considerations:
  • Frequent switching in threshold regions based solely on position could lead to system instability;
  • Forward perpendicular parking mode is necessary for charging services during parking.
To address these issues, this study proposes a switching algorithm based on a hysteresis pattern. This algorithm considers:
  • The vehicle’s motion direction (forward or reverse);
  • Stabilization conditions in threshold regions.
This approach aims to enhance the stability and versatility of the AVP system while maintaining cost-effectiveness. The proposed hysteresis-based camera switching algorithm is further detailed in Figure 11. Figure 11a defines the vehicle’s heading angle ( θ ) , which is crucial for determining the vehicle’s forward or reverse motion. Figure 11b conceptually illustrates the camera switch as the vehicle enters the final parking zone, indicating the strategic point at which the camera view is transitioned. The core of this algorithm is the hysteresis logic, depicted in Figure 11c, which applies different switching boundaries (±γ, ±β) based on the vehicle’s position to prevent instability or “chattering” near the threshold regions. The hysteresis values (±γ, ±β) were determined empirically based on the test vehicle’s characteristics and the parking environment. The positional buffer (β and γ) was set to 1.0 m. This value was selected to be approximately double the combined width of two standard vehicle tires (roughly 0.5 m), providing a robust margin to accommodate various tire widths and ensure that small lateral deviations or steering corrections near the boundary do not cause unintended camera switching. The heading angle condition was triggered when the vehicle’s heading deviated more than 45 degrees from the main driving path, providing a clear and reliable indicator of the driver’s intent to execute a perpendicular parking maneuver.
This mechanism ensures a single, stable camera switch. Figure 11d presents the detailed flowchart of the algorithm, explicitly incorporating checks for the switching zone, the hysteresis zone, and the vehicle’s heading angle to facilitate robust and reliable camera management. To further enhance reproducibility, the detailed logic of this process is formally presented in Algorithm 1.
Algorithm 1. Hysteresis-based Camera Switching Logic
Require: Y p o s :   Vehicle s   current   Y - axis .   θ :   Vehicle s   current   heading   angle .
C c u r r e n t :   Current   active   camera   ( Front   or   Rear ) .
Y b o u n d a r y :   Predefined   parking   zone   entry   boundary
β :   Hysteresis   buffer   for   vehicle s   x - position .
γ :   Hysteresis   buffer   for   vehicle s   y - position .
R h e a d i n g : Range of angles defining reverse motion.
Ensure:   C n e w :   T h e   u p d a t e   c a m e r a   s t a t e
1:if  C c u r r e n t = Front   and   Y p o s > ( Y b o u n d a r y + β )   and   θ R h e a d i n g  then
2:  return ‘Rear’
3:else if  C c u r r e n t = Rear   and   Y p o s < Y b o u n d a r y γ
4:  return ‘Front’
5:else
6:  return  C c u r r e n t
7:end if

4. Experiments and Results

This section evaluates the effectiveness of the proposed localization and camera-switching algorithms through a two-stage process: virtual simulation and real-vehicle experiments. Importantly, the identical core algorithm developed in Section 3 was deployed in both environments. The initial simulations were conducted to verify the algorithm’s fundamental logic and performance in a controlled and repeatable setting. Subsequently, the same algorithm was tested on a physical vehicle in a real-world parking facility to evaluate its practical effectiveness and robustness under actual operating conditions.

4.1. Experimental Environment Setup

To validate the performance of the proposed AVP system, a real-world testbed was established in an indoor parking facility near the Hyunbo Kiheung R&D Center. As shown in Figure 12, the environment was carefully designed to include key areas such as designated operation zones, driving paths, available parking slots, a charging station, a drop-off/pick-up point and the strategic placement of various types of fiducial markers on poles, H-beams, and walls.
In accordance with ISO standards for marker-based localization, fiducial markers were strategically installed on various surfaces such as columns, H-beams, and walls at different heights. Specifically, Figure 12 illustrates the precise layout of these elements and the strategic placement of various types of fiducial markers across the environment. Based on a detailed field survey of this physical environment, a high-fidelity digital twin map was created. This map serves as the foundation for the simulation experiments described in Section 4.2.
Furthermore, for the quantitative evaluation of positioning accuracy, a Velodyne Ultra Puck (VLP-32C) 32-channel LiDAR sensor (Velodyne Lidar, San Jose, CA, USA) was mounted on the experimental vehicle to acquire ground truth position data. The performance of our proposed system was then assessed by comparing its output against this high-precision ground truth data.

4.2. Simulation

This section details the experiments conducted in a simulated environment. Before deployment on the actual vehicle, the fundamental performance of the proposed algorithms was first verified in this controlled and repeatable setting. The following subsections describe the simulation setup and present the results of the evaluation.

4.2.1. Simulation Setup

To verify the performance and stability of the proposed localization algorithm in a controlled and repeatable manner prior to real-car experiments, a series of simulations were conducted using CARLA (Version 0.9.13), an open-source simulator specialized for autonomous driving scenarios.
As mentioned in Section 4.1, a high-fidelity digital twin of the physical test environment was created. This digital representation was then implemented in the CARLA simulator to ensure that the simulation conditions closely mirrored the real world. Figure 13 provides a visual comparison, highlighting the strong resemblance between the actual parking facility (Figure 13a) and the virtual environment (Figure 13b), including the layout of structures and the exact placement of fiducial markers. The CARLA simulator precisely replicates these key structures and marker placements, as shown in Figure 13b.
A virtual vehicle model was equipped with simulated sensors that mimic the real-car setup. Key simulation parameters were carefully configured to ensure high fidelity. This included setting realistic noise models for the virtual IMU and camera sensors to reflect real-world imperfections and placing fiducial markers at their precise world coordinates corresponding to the physical testbed. The virtual vehicle was also configured to generate odometry data, such as vehicle speed and yaw rate. The localization and camera-switching algorithms were then tested within this meticulously established virtual environment.

4.2.2. Simulation Result

The primary objective of the simulation was to quantitatively evaluate the accuracy of the proposed EKF-based fiducial marker localization system. The evaluation was performed by comparing the trajectory estimated by our system (‘marker SLAM’) with the ground-truth data provided by a simulated 32-channel LiDAR sensor within the CARLA environment.
Figure 14 shows the simulation test in progress, depicting the real-time visualization of the vehicle’s navigation and data processing within the virtual environment. This visual representation includes the virtual vehicle’s position, the real-time map and marker data visualization on the left, and a chase camera perspective from the top-right. Figure 15 presents the detailed results of this comparative analysis. As shown in the trajectory plots (Figure 15a,c), the X and Y positions estimated by the proposed system closely follow the ground truth path throughout the entire driving maneuver, demonstrating the system’s correct operation.
For a more detailed quantitative analysis, the position errors over time are plotted in Figure 15b,d. The calculated Root Mean Square (RMS) errors were 0.0975 m for the X-axis and 0.1544 m for the Y-axis. The maximum absolute errors were found to be 0.2208 m for the X-axis and 0.2969 m for the Y-axis. These results confirm that the proposed EKF-based localization algorithm, which fuses odometry and marker information, achieves high-accuracy positioning. Crucially, the maximum positioning error remained below the target performance threshold of 0.3 m, thus validating the effectiveness of the system design in a simulated environment.

4.3. Real-Car Experiment

This section presents the experimental results from the real-world testbed, validating the system’s performance beyond the simulation. The effectiveness and practicality of the proposed localization and camera-switching algorithms were evaluated on the physical vehicle under actual operating conditions. The subsequent sections describe the experimental setup (Section 4.3.1), followed by an analysis of the positioning accuracy (Section 4.3.2) and the camera switching performance (Section 4.3.3).

4.3.1. Real-Car Experiment Setup

The real-car experiments were conducted using the test platform and environment detailed in the preceding sections.
The experimental vehicle was a Genesis GV60, whose sensor configuration and system architecture were introduced in Section 2.1. All driving tests were performed in the indoor parking facility that was meticulously mapped and equipped with fiducial markers, as detailed in Section 4.1. To ensure a direct and fair comparison with the simulation results, the same 32-channel LiDAR was used to acquire the ground truth trajectory for performance evaluation.

4.3.2. EKF Experiment Results

Based on the promising simulation results, the performance of the proposed localization system was evaluated in the real-world environment detailed in Section 4.1. To analyze the algorithm’s effectiveness under different conditions, experiments were conducted for two distinct driving scenarios: (1) straight driving and (2) curved driving. The performance of the proposed EKF-based method was compared against a dead-reckoning method (using only kinematic prediction from vehicle sensors). The ground truth for this evaluation was provided by the 32-channel LiDAR system, as described in [28,29]. Figure 16 illustrates these two driving scenarios, with Figure 16a showing a diagram of the straight and curved driving paths within the test environment, and Figure 16b depicting the experimental vehicle performing a test run.
The first experiment was conducted while the vehicle was driven straight along the parking aisle (primarily in the Y-direction). The trajectory comparison and position errors for this scenario are presented in Figure 17 and Figure 18, respectively. As shown in Figure 17a, the X-axis position of the proposed EKF method closely matches the reference, and similarly, Figure 17b shows a close alignment for the Y-axis position, particularly benefiting from measurement compensation in the EKF with marker data.
Table 1 summarizes the quantitative results for the straight driving scenario. In this scenario, as shown in Figure 18b, the dead-reckoning method showed a maximum error of 0.488 m in the Y-direction. The proposed EKF method significantly reduced this error to 0.178 m, achieving a 63.5% improvement in lateral accuracy. For the longitudinal X-direction, where odometry error is inherently small during straight driving, both methods showed comparable performance. Furthermore, the standard deviation (SD) of the Y-axis error was reduced from 0.1863 to 0.0962, indicating that the EKF compensation not only reduces the peak error but also provides a more stable and consistent localization performance, as illustrated in Figure 18a.
The second experiment involved a more complex trajectory that included curved sections, simulating a typical parking maneuver. The results are shown in Figure 19 and Figure 20, and summarized in Table 2. As illustrated in Figure 19a,b, the trajectories estimated by the EKF method closely align with the reference (ground truth) data for both X-axis and Y-axis positions, even during curved driving. This demonstrates the EKF’s effectiveness in maintaining accurate positioning during complex maneuvers where dead-reckoning alone would typically accumulate significant errors.
In this scenario, as shown in Figure 20a,b, the dead-reckoning method exhibited significant error accumulation due to lateral motion, with maximum errors reaching 0.836 m (X-axis) and 1.449 m (Y-axis). In contrast, the proposed EKF method effectively compensated for these errors by using fiducial marker measurements. It maintained high accuracy, with maximum errors of only 0.279 m and 0.326 m for the X and Y axes, respectively. This corresponds to a remarkable error reduction of 66.6% in the X-axis and 77.5% in the Y-axis compared to the dead-reckoning method. Crucially, the standard deviation of the error was also drastically reduced—by 60% for the X-axis and 76% for the Y-axis—confirming that the EKF with marker compensation provides exceptionally stable and reliable positioning during complex turning maneuvers, where dead-reckoning alone becomes highly volatile.
These findings conclusively demonstrate that while dead-reckoning is prone to large, accumulating errors, especially during turning maneuvers, the proposed EKF-based localization system provides consistently accurate and reliable positioning performance, well within the target accuracy of 30 cm for the most challenging axes. Specifically, as detailed in Table 2, the EKF compensation method significantly reduces both maximum and RMS errors across both X and Y axes compared to the INS method during curved driving, confirming its robust performance.

4.3.3. Camera Switching Algorithm Experiment Results

The previous experiments confirmed that the EKF-based method, which uses fiducial markers for correction, satisfies the target positioning accuracy. However, this performance is predicated on the continuous detection of markers. In real-world parking environments, such as the one shown in Figure 12, obstacles or driving paths can cause the vehicle to lose sight of markers. During reverse parking, for instance, valid markers may disappear from the forward camera’s field of view, forcing the system to rely solely on dead-reckoning and leading to a degradation in localization performance.
To overcome this limitation, a method of switching between the front and rear cameras is necessary to ensure a constant line of sight to reference markers, particularly those placed on the wall behind the parking space.
An initial, straightforward approach to camera switching was based on a simple geographic boundary. As illustrated in Figure 21d, this concept involved activating the rear camera for one direction and the front camera for another, effectively switching based on the parking space boundary. However, experimental testing of this method revealed a critical flaw. As shown in Figure 21a,b, when the vehicle’s position hovered near this switching boundary, the system became highly unstable, rapidly oscillating between the front and rear cameras in a phenomenon known as “chattering.” This instability highlighted the need for a more intelligent switching logic. To resolve this, the hysteresis-based algorithm (defined in Section 3.3 and Figure 11) was applied. Figure 21c visually confirms that this proposed algorithm ensures a single, stable switch without chattering. Figure 21d shows the initial concept of front and rear camera switching based on a simple geographic boundary.
This scenario includes straight driving, curved driving, and a final reverse perpendicular parking maneuver (from point ⓑ to ⓓ in Figure 22b).
To validate its effectiveness, a comprehensive experiment was designed to simulate a realistic automated valet parking scenario, as illustrated in Figure 22. This scenario includes straight driving, curved driving, and a final reverse perpendicular parking maneuver (from point ⓐ to ⓓ). Figure 22a provides a trajectory representation for the vehicle positioning scenario, while Figure 22b shows this trajectory mapped onto the digital map of the parking facility. Furthermore, Figure 22c indicates the vehicle’s position at key points (start point, first curved point, second curved point, parked point) during the maneuver.
Specifically, Figure 23a presents the X-axis position comparison, while Figure 23b illustrates the Y-axis position comparison, clearly demonstrating the trajectory alignment and the impact of the switching algorithm.
Figure 24 presents a detailed analysis of the position errors over time, comparing the conventional (front camera only) method and the proposed algorithm. A visual inspection of Figure 24a,b shows that the proposed algorithm results in noticeably smaller error fluctuations for both X-axis and Y-axis errors, indicating enhanced stability compared to the conventional approach.
For a quantitative evaluation, the maximum error and RMS error were compared, as shown in Table 3. The proposed algorithm significantly reduced the maximum X-axis error by 34.2% (from 0.4239 m to 0.2791 m) and the maximum Y-axis error by 8.4% (from 0.3261 m to 0.2987 m). Furthermore, the overall precision, indicated by the RMS error, also improved significantly, with reductions of 25.0% for the X-axis and 17.6% for the Y-axis. The reduction in standard deviation for both axes further demonstrates that the proposed hysteresis-based switching algorithm not only prevents large errors when markers are out of view but also contributes to enhancing the overall stability and consistency of the localization system during the entire parking maneuver.
In summary, the real-world experiments were designed to provide a progressive validation of the proposed system. The initial tests in Table 1 and Table 2 first established the significant performance improvement of the core EKF-based method over the Dead-reckoning baseline, not only in terms of peak error but also in positioning stability, as indicated by the Standard Deviation (SD). Subsequently, the final experiment in Table 3, now also including detailed statistical metrics, demonstrated that the proposed hysteresis-based switching algorithm provides a further, crucial enhancement over the conventional front-camera-only approach. This step-by-step comparative analysis, with all results validated against high-precision ground truth data, collectively confirms the effectiveness and validity of the final proposed system for practical AVP applications.

5. Conclusions

This study addressed the critical challenge of achieving accurate and robust vehicle positioning for AVP systems in GPS-denied indoor environments. We proposed and validated an optimized positioning system that leverages fiducial markers, front and rear cameras, and an EKF for sensor fusion.
The research demonstrated that fusing vehicle kinematic data with fiducial marker observations through an EKF significantly enhances localization accuracy compared to relying solely on vehicle odometry, especially mitigating error accumulation during maneuvers such as curved driving (achieving error reductions up to 78%). However, a key limitation identified was the potential loss of marker visibility from the front camera during reverse perpendicular parking, a common AVP scenario.
To overcome this limitation, a novel camera switching algorithm incorporating a hysteresis mechanism based on vehicle position, heading, and motion direction was developed. Real-world experiments confirmed that this switching strategy effectively maintains positioning accuracy and system stability during critical parking phases, preventing the performance degradation observed with a front-camera-only approach (reducing RMS error by 25.0% for the X-axis and 17.6% for the Y-axis) and avoiding the instability issues associated with simple switching logic.
In conclusion, the developed system, which integrates EKF-based fusion and intelligent front–rear camera switching, provides a reliable, accurate, and cost-effective solution for indoor AVP positioning. By effectively utilizing readily available camera sensors and robust algorithms, this work makes a significant contribution to advancing the practical implementation of autonomous driving functions in complex indoor parking facilities.

Author Contributions

Conceptualization, Y.-W.L. and M.-S.K.; methodology, Y.-W.L. and D.-J.K.; software, D.-J.K. and Y.-J.J.; validation, Y.-W.L., D.-J.K., Y.-J.J. and M.-S.K.; investigation, Y.-W.L. and D.-J.K.; resources, Y.-W.L.; data curation, Y.-W.L. and D.-J.K.; writing—original draft preparation, Y.-W.L.; writing—review and editing, Y.-W.L. and M.-S.K.; visualization, Y.-W.L.; supervision, M.-S.K.; project administration, Y.-W.L.; funding acquisition, Y.-W.L. All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported by the Ministry of Trade, Industry and Energy (MOTIE) and Korea Planning & Evaluation Institute of Industrial Technology (KEIT) grant funded in 2025 (No. 20018448, Development of Demand-Responsive Automated Valet Parking and Service Technology).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

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

Conflicts of Interest

Authors Young-Woo Lee, Dong-Jun Kim, and Yu-Jung Jung were employed by the company Hyunbo Corporation. The remaining author declares that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
AVPAutomated Valet Parking
CANController Area Network
CARLACAR Learning to Act
DOFDegrees of Freedom
ECUElectronic Control Unit
SLAMSimultaneous Localization and Mapping
EKFExtended Kalman Filter
GPSGlobal Positioning System
IVNIn-Vehicle Network
INSInertial Navigation System
RMSRoot Mean Square
ROSRobot Operating System

References

  1. Khalid, M.; Wang, K.; Aslam, N.; Cao, Y.; Ahmad, N.; Khan, M.K. From smart parking towards autonomous valet parking: A survey, challenges and future Works. J. Netw. Comput. Appl. 2021, 175, 102935. [Google Scholar] [CrossRef]
  2. Timpner, J.; Friedrichs, S.; van Balen, J.; Wolf, L. K-Stacks: High-density valet parking for automated vehicles. In Proceedings of the 2015 IEEE Intelligent Vehicles Symposium (IV), Seoul, Republic of Korea, 28 June–1 July 2015. [Google Scholar]
  3. Sturm, A.W.; Kascha, M.; Mejri, M.A.; Henze, R.; Heister, L.; Mueck, A. Automated Park and Charge: Concept and Energy Demand Calculation; No. 2024-01-2988, SAE Technical Paper; SAE International: Warrendale, PA, USA, 2024. [Google Scholar]
  4. ISO 23374-1; Intelligent Transport Systems-Automated Valet Parking Systems, Part 1, Annex C. International Organization for Standardization: Geneva, Switzerland, 2023.
  5. Bian, X.; Chen, W.; Ran, D.; Liang, Z. FiMa-reader: A cost-effective fiducial marker reader system for autonomous mobile robot docking in manufacturing environments. Appl. Sci. 2023, 13, 13079. [Google Scholar] [CrossRef]
  6. Shao, X.; Zhang, L.; Zhang, T.; Shen, Y.; Zhou, Y. Mofis slam: A multi-object semantic slam system with front-view, inertial, and surround-view sensors for indoor parking. IEEE Trans. Circuits Syst. Video Technol. 2021, 32, 4788–4803. [Google Scholar] [CrossRef]
  7. Leutenegger, S.; Lynen, S.; Bosse, M.; Siegwart, R.; Furgale, P. Keyframe-based visual–inertial odometry using nonlinear optimization. Int. J. Robot. Res. 2015, 34, 314–334. [Google Scholar] [CrossRef]
  8. Zhang, J.; Singh, S. LOAM: Lidar odometry and mapping in real-time. Robot. Sci. Syst. 2014, 3–8. [Google Scholar]
  9. Yin, H.; Wang, Y.; Tang, L.; Ding, X.; Huang, S.; Xiong, R. 3D LIDAR map compression for efficient localization on resource constrained vehicles. IEEE Trans. Intell. Transp. Syst. 2020, 22, 837–852. [Google Scholar] [CrossRef]
  10. Zhu, Y.; An, H.; Wang, H.; Xu, R.; Wu, M.; Lu, K. RC-SLAM: Road constrained stereo visual SLAM system based on graph optimization. Sensors 2024, 24, 536. [Google Scholar] [CrossRef] [PubMed]
  11. Engel, J.; Schöps, T.; Cremers, D. LSD-SLAM: Large-scale direct monocular SLAM. In Proceedings of the European Conference on Computer Vision, Zurich, Switzerland, 6–12 September 2014. [Google Scholar]
  12. Mur-Artal, R.; Tardós, J.D. ORB-SLAM2: An open-source SLAM system for monocular, stereo, and RGB-D cameras. IEEE Trans. Robot. 2017, 33, 1255–1262. [Google Scholar] [CrossRef]
  13. Song, J.; Jo, H.; Jin, Y.; Lee, S.J. Uncertainty-aware depth network for visual inertial odometry of mobile robots. Sensors 2024, 24, 6665. [Google Scholar] [CrossRef] [PubMed]
  14. Zhang, H.; Du, L.; Bao, S.; Yuan, J.; Ma, S. LVIO-fusion: Tightly-coupled LiDAR-visual-inertial odometry and mapping in degenerate environments. IEEE Robot. Autom. Lett. 2024, 9, 3783–3790. [Google Scholar] [CrossRef]
  15. Jiang, S.; Zhao, C.; Zhu, Y.; Wang, C.; Du, Y. A practical and economical ultra-wideband base station placement approach for indoor autonomous driving systems. J. Adv. Transp. 2022, 2022, 3815306. [Google Scholar] [CrossRef]
  16. Qin, T.; Chen, T.; Chen, Y.; Su, Q. AVP-SLAM: Semantic visual mapping and localization for autonomous vehicles in the parking lot. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Las Vegas, NV, USA, 25–29 October 2020. [Google Scholar]
  17. Qin, T.; Li, P.; Shen, S. Vins-mono: A robust and versatile monocular visual-inertial state estimator. IEEE Trans. Robot. 2018, 34, 1004–1020. [Google Scholar] [CrossRef]
  18. Le Gentil, C.; Vidal-Calleja, T.; Huang, S. In2lama: Inertial lidar localisation and mapping. In Proceedings of the 2019 International Conference on Robotics and Automation (ICRA), Montreal, QC, Canada, 20–24 May 2019. [Google Scholar]
  19. Lim, H.; Lee, Y.S. Real-time single camera SLAM using fiducial markers. In Proceedings of the 2009 ICCAS-SICE, Fukuoka, Japan, 18–21 August 2009. [Google Scholar]
  20. Rezaei, S.; Sengupta, R. Kalman filter-based integration of DGPS and vehicle sensors for localization. IEEE Trans. Control. Syst. Technol. 2007, 15, 1080–1088. [Google Scholar] [CrossRef]
  21. Polack, P.; Altché, F.; d’Andréa-Novel, B.; de La Fortelle, A. The kinematic bicycle model: A consistent model for planning feasible trajectories for autonomous vehicles? In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017. [Google Scholar]
  22. Julier, S.J.; Uhlmann, J.K. New extension of the Kalman filter to nonlinear systems. In Proceedings Volume 3068, Signal Processing, Sensor Fusion, and Target Recognition VI; SPIE: Bellingham, WA, USA, 1997. [Google Scholar]
  23. Spong, M.W.; Hutchinson, S.; Vidyasagar, M. Robot Modeling and Control; Wiley: New York, NY, USA, 2006; pp. 76–85. [Google Scholar]
  24. Lim, H.; Yang, J.-H.; Lee, Y.-S.; Kim, J.-G. Indoor single camera SLAM using fiducial markers. J. Inst. Control. Robot. Syst. 2009, 15, 353–364. [Google Scholar] [CrossRef]
  25. Häne, C.; Sattler, T.; Pollefeys, M. Obstacle detection for self-driving cars using only monocular cameras and wheel odometry. In Proceedings of the 2015 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Hamburg, Germany, 28 September–2 October 2015. [Google Scholar]
  26. Grimmett, H.; Buerki, M.; Paz, L.; Pinies, P.; Furgale, P.; Posner, I.; Newman, P. Integrating metric and semantic maps for vision-only automated parking. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015. [Google Scholar]
  27. Mourikis, A.I.; Roumeliotis, S.I. A multi-state constraint Kalman filter for vision-aided inertial navigation. In Proceedings of the 2007 IEEE International Conference on Robotics and Automation, Roma, Italy, 10–14 April 2007. [Google Scholar]
  28. Schwesinger, U.; Rufli, M.; Furgale, P.; Siegwart, R. A sampling-based partial motion planning framework for system-compliant navigation along a reference path. In Proceedings of the 2013 IEEE Intelligent Vehicles Symposium (IV), City of Gold Coast, Australia, 23–26 June 2013. [Google Scholar]
  29. Brunker, A.; Wohlgemuth, T.; Frey, M.; Gauterin, F. Odometry 2.0: A slip-adaptive EIF-based four-wheel-odometry model for parking. IEEE Trans. Intell. Veh. 2018, 4, 114–126. [Google Scholar] [CrossRef]
Figure 1. Proposed localization system architecture for automated valet parking.
Figure 1. Proposed localization system architecture for automated valet parking.
Applsci 15 09927 g001
Figure 2. Experimental vehicle and sensor configuration: (a) test vehicle; (b) close-up views of the mounted front and rear cameras.
Figure 2. Experimental vehicle and sensor configuration: (a) test vehicle; (b) close-up views of the mounted front and rear cameras.
Applsci 15 09927 g002
Figure 3. Sensor configuration for vehicle odometry estimation, including wheel speed sensors, a steering angle sensor, and a yaw rate sensor. The dashed line represents the vehicle’s longitudinal axis.
Figure 3. Sensor configuration for vehicle odometry estimation, including wheel speed sensors, a steering angle sensor, and a yaw rate sensor. The dashed line represents the vehicle’s longitudinal axis.
Applsci 15 09927 g003
Figure 4. Definition and coordinate system of the fiducial marker: (a) local coordinate system; (b) yaw angle calculation in the global frame; (c) example of markers placed on a map.
Figure 4. Definition and coordinate system of the fiducial marker: (a) local coordinate system; (b) yaw angle calculation in the global frame; (c) example of markers placed on a map.
Applsci 15 09927 g004
Figure 5. Accuracy validation of the fiducial marker detection system: (a) The experimental setup for performance validation; (b) A direct comparison showing the system correctly identifying a marker with ID = 43 and estimating its distance as 0.950 m. This estimation demonstrates high consistency with the ground truth value of 0.947 m, measured by a high-precision laser rangefinder.
Figure 5. Accuracy validation of the fiducial marker detection system: (a) The experimental setup for performance validation; (b) A direct comparison showing the system correctly identifying a marker with ID = 43 and estimating its distance as 0.950 m. This estimation demonstrates high consistency with the ground truth value of 0.947 m, measured by a high-precision laser rangefinder.
Applsci 15 09927 g005
Figure 6. Recursive structure of the EKF for localization.
Figure 6. Recursive structure of the EKF for localization.
Applsci 15 09927 g006
Figure 7. Illustration of the vehicle states in the kinematic model.
Figure 7. Illustration of the vehicle states in the kinematic model.
Applsci 15 09927 g007
Figure 8. Relationship between the key coordinate frames. The numbers denote ① the transformation relationship from the global frame to the vehicle’s camera frame, and ② the measurement relationship between the camera and a detected marker.
Figure 8. Relationship between the key coordinate frames. The numbers denote ① the transformation relationship from the global frame to the vehicle’s camera frame, and ② the measurement relationship between the camera and a detected marker.
Applsci 15 09927 g008
Figure 9. Geometric derivation of the measurement model h ( x ) .
Figure 9. Geometric derivation of the measurement model h ( x ) .
Applsci 15 09927 g009
Figure 10. Challenging localization scenario: undetectable front-facing markers.
Figure 10. Challenging localization scenario: undetectable front-facing markers.
Applsci 15 09927 g010
Figure 11. Proposed hysteresis-based camera switching algorithm: (a) vehicle heading angle definition; (b) camera switch illustration for parking; (c) hysteresis logic; (d) algorithm flowchart.
Figure 11. Proposed hysteresis-based camera switching algorithm: (a) vehicle heading angle definition; (b) camera switch illustration for parking; (c) hysteresis logic; (d) algorithm flowchart.
Applsci 15 09927 g011
Figure 12. Layout of the experimental indoor parking environment.
Figure 12. Layout of the experimental indoor parking environment.
Applsci 15 09927 g012
Figure 13. Simulation environment implemented as a digital twin of the real-world testbed: (a) panoramic view of the actual indoor parking lot; (b) corresponding view within the CARLA simulator.
Figure 13. Simulation environment implemented as a digital twin of the real-world testbed: (a) panoramic view of the actual indoor parking lot; (b) corresponding view within the CARLA simulator.
Applsci 15 09927 g013
Figure 14. Simulation experiment in progress within the CARLA environment. The view includes the virtual vehicle, real-time map and marker data visualization (left), and chase camera perspective (top-right) and system logs (bottom-right). In the visualization panel, the green cubes represent the mapped positions of fiducial markers, while the purple point cloud constitutes the ground-truth map.
Figure 14. Simulation experiment in progress within the CARLA environment. The view includes the virtual vehicle, real-time map and marker data visualization (left), and chase camera perspective (top-right) and system logs (bottom-right). In the visualization panel, the green cubes represent the mapped positions of fiducial markers, while the purple point cloud constitutes the ground-truth map.
Applsci 15 09927 g014
Figure 15. Simulation results for the EKF-based localization algorithm: (a) estimated X-axis trajectory comparison with Lidar ground truth; (b) X-axis position error over time; (c) estimated Y-axis trajectory comparison with Lidar ground truth; (d) Y-axis position error over time.
Figure 15. Simulation results for the EKF-based localization algorithm: (a) estimated X-axis trajectory comparison with Lidar ground truth; (b) X-axis position error over time; (c) estimated Y-axis trajectory comparison with Lidar ground truth; (d) Y-axis position error over time.
Applsci 15 09927 g015aApplsci 15 09927 g015b
Figure 16. Real-world evaluation scenarios: (a) straight and curved driving paths; (b) experimental vehicle performing a test run.
Figure 16. Real-world evaluation scenarios: (a) straight and curved driving paths; (b) experimental vehicle performing a test run.
Applsci 15 09927 g016
Figure 17. Trajectory comparison during the straight driving test: (a) X-axis position; (b) Y-axis position.
Figure 17. Trajectory comparison during the straight driving test: (a) X-axis position; (b) Y-axis position.
Applsci 15 09927 g017
Figure 18. Position error during the straight driving test: (a) X-axis error over time; (b) Y-axis error over time.
Figure 18. Position error during the straight driving test: (a) X-axis error over time; (b) Y-axis error over time.
Applsci 15 09927 g018
Figure 19. Trajectory comparison during the curved driving test: (a) X-axis position; (b) Y-axis position.
Figure 19. Trajectory comparison during the curved driving test: (a) X-axis position; (b) Y-axis position.
Applsci 15 09927 g019
Figure 20. Position error during the curved driving test: (a) X-axis error over time; (b) Y-axis error over time.
Figure 20. Position error during the curved driving test: (a) X-axis error over time; (b) Y-axis error over time.
Applsci 15 09927 g020
Figure 21. Comparison of camera state before and after applying the hysteresis algorithm: (a) legacy switching with rapid oscillations; (b) magnified view of “chattering” phenomenon; (c) stable switch with the proposed hysteresis algorithm; (d) a top-down view of the vehicle’s position at the switching moment, where the white outline represents the vehicle, the green lines show the parking lot map, and the red line indicates the predefined switching boundary.
Figure 21. Comparison of camera state before and after applying the hysteresis algorithm: (a) legacy switching with rapid oscillations; (b) magnified view of “chattering” phenomenon; (c) stable switch with the proposed hysteresis algorithm; (d) a top-down view of the vehicle’s position at the switching moment, where the white outline represents the vehicle, the green lines show the parking lot map, and the red line indicates the predefined switching boundary.
Applsci 15 09927 g021
Figure 22. Scenario for validating algorithm effectiveness: (a) trajectory representation; (b) mapping onto digital map; (c) indication of vehicle position at key points.
Figure 22. Scenario for validating algorithm effectiveness: (a) trajectory representation; (b) mapping onto digital map; (c) indication of vehicle position at key points.
Applsci 15 09927 g022
Figure 23. Trajectory comparison: (a) X-axis position between conventional (front camera only) and proposed (switching) methods; (b) Y-axis position between conventional (front camera only) and proposed (switching) methods.
Figure 23. Trajectory comparison: (a) X-axis position between conventional (front camera only) and proposed (switching) methods; (b) Y-axis position between conventional (front camera only) and proposed (switching) methods.
Applsci 15 09927 g023
Figure 24. Position error comparison: (a) X-axis error over time; (b) Y-axis error over time.
Figure 24. Position error comparison: (a) X-axis error over time; (b) Y-axis error over time.
Applsci 15 09927 g024
Table 1. Quantitative comparison of localization errors for the straight driving scenario (unit: m).
Table 1. Quantitative comparison of localization errors for the straight driving scenario (unit: m).
Max
Error
(X)
RMS
(X)
SD
(X)
Rate of
Error
Reduction
(X)
Max
Error
(Y)
RMS
(Y)
SD
(Y)
Rate of
Error
Reduction *
(Y)
INS0.29800.18130.0995-0.48780.27550.1863-
EKF compensation0.30700.18130.10040%0.17770.09910.096264%
* Rate of error reduction = 1 − (RMS (EKF)/RMS (INS)).
Table 2. Quantitative comparison of localization errors for the curved driving scenario (unit: m).
Table 2. Quantitative comparison of localization errors for the curved driving scenario (unit: m).
Max
Error
(X)
RMS
(X)
SD
(X)
Rate of
Error
Reduction
(X)
Max
Error
(Y)
RMS
(Y)
SD
(Y)
Rate of
Error
Reduction *
(Y)
INS0.83600.36540.3581-1.44900.53100.4536-
EKF compensation0.27910.14550.141760%0.32610.12850.128576%
* Rate of error reduction = 1 − (RMS (EKF)/RMS (INS)).
Table 3. Quantitative comparison of localization errors with and without the proposed switching algorithm (unit: m).
Table 3. Quantitative comparison of localization errors with and without the proposed switching algorithm (unit: m).
Max
Error
(X)
RMS
(X)
SD
(X)
Rate of
Error
Reduction
(X)
Max
Error
(Y)
RMS
(Y)
SD
(Y)
Rate of
Error
Reduction *
(Y)
Conventional method0.42390.19390.1852-0.32610.13890.1374-
Proposed Algorithm0.27910.14550.141725%0.29870.11450.113917.6%
* Rate of error reduction = 1 − (RMS (Proposed Algorithm)/RMS (Conventional method)).
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.

Share and Cite

MDPI and ACS Style

Lee, Y.-W.; Kim, D.-J.; Jung, Y.-J.; Kim, M.-S. Front–Rear Camera Switching Strategy for Indoor Localization in Automated Valet Parking Systems with Extended Kalman Filter and Fiducial Markers. Appl. Sci. 2025, 15, 9927. https://doi.org/10.3390/app15189927

AMA Style

Lee Y-W, Kim D-J, Jung Y-J, Kim M-S. Front–Rear Camera Switching Strategy for Indoor Localization in Automated Valet Parking Systems with Extended Kalman Filter and Fiducial Markers. Applied Sciences. 2025; 15(18):9927. https://doi.org/10.3390/app15189927

Chicago/Turabian Style

Lee, Young-Woo, Dong-Jun Kim, Yu-Jung Jung, and Moon-Sik Kim. 2025. "Front–Rear Camera Switching Strategy for Indoor Localization in Automated Valet Parking Systems with Extended Kalman Filter and Fiducial Markers" Applied Sciences 15, no. 18: 9927. https://doi.org/10.3390/app15189927

APA Style

Lee, Y.-W., Kim, D.-J., Jung, Y.-J., & Kim, M.-S. (2025). Front–Rear Camera Switching Strategy for Indoor Localization in Automated Valet Parking Systems with Extended Kalman Filter and Fiducial Markers. Applied Sciences, 15(18), 9927. https://doi.org/10.3390/app15189927

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