A Review of Robotic Aircraft Skin Inspection: From Data Acquisition to Defect Analysis
Abstract
1. Introduction
1.1. Background
1.2. Objectives
2. Related Works
3. Materials and Methods
4. Results and Analysis
4.1. Data Acquisition Phase
4.1.1. Motion Planning
- Offline Path PlanningOffline path planning, which achieves global path optimization based on a prior environmental model, is the dominant approach in static known environments and can be further categorized into two primary paradigms: task-point-based path planning and coverage path planning.
- Task-point-based Path PlanningIn task-point-based path planning, critical waypoints are predefined according to aviation inspection protocols. For instance, Ruiqian et al. [15] designed a UAV inspection route for a Y-7-100 3D model, covering key components including the fuselage surface, wings, engines, and vertical/horizontal stabilizers. Similarly, Jovančević [16] systematically defined 21 preset inspection points labeled as P1 through P21 in his doctoral dissertation. This layout transforms maintenance procedures into executable robotic paths through three key technological innovations: geometric constraint modeling, sensor characteristic integration, and fault-tolerance mechanisms. The implementation achieved a 250 percent efficiency improvement while reducing missed detection rates below 0.5 percent. Both studies employ applied path planning strategies tailored to specific mission requirements, relying on manual prior knowledge. The former leverages the capabilities of a UAV platform to achieve rapid coverage of upper surface skin areas across multiple aircraft types, while the latter utilizes a ground robot platform focused on high-precision image acquisition of critical components.However, the effectiveness and generalization capability of this applied strategy, defined by task points based on manual prior knowledge, highly depend on the designer’s in-depth understanding of specific aircraft types and inspection protocols. It lacks adaptive planning capabilities for unknown environments or novel aircraft. Notably, Bugaj et al. [17] adopted the same path planning paradigm in their pre-flight inspection study on the PA-34 series aircraft. Based on the inspection procedures stipulated in the official Aircraft Flight Manual (AFM), the study manually predefined a sequence of waypoints around the aircraft and used Euclidean geometry to calculate segment distances. Its core contribution lies in the introduction of a mathematical constraint model for restricted zones, which ensures the physical safety of the drone’s trajectory through geometric conditions, thereby avoiding collision risks with the aircraft surface. This design approach shares the same origin as Li et al.’s area coverage strategy [15] and Jovancevic’s key-point detailed inspection method [16], collectively reflecting a “task-knowledge-driven rather than environment-data-driven” planning logic.
- Coverage Path PlanningThe aim of Coverage Path Planning (CPP) is to determine an optimal path to enable the robot to use its end effector to cover the Region of Interest (ROI). Research on CPP has been extensively conducted across various fields, given its broad applications in robotic inspection, manufacturing, and other domains that target full-area coverage tasks. Several review papers have also systematically summarized the development history, core methodologies, and unresolved challenges of CPP, providing a comprehensive reference for researchers in this area. For a more in-depth understanding of the current status and evolution of CPP research, readers can refer to [18,19]. Advanced CPP typically involves two main steps: viewpoint generation and path planning. Initially, a set of viewpoints that can encompass the ROI is generated by solving the Set Cover Problem (SCP). Subsequently, an optimal sequence of these viewpoints is derived by solving the TSP. In research on aircraft skin CPP, the core objective is to holistically optimize path execution efficiency and inspection quality while ensuring high coverage rates and simultaneously satisfying robot dynamic constraints. Studies aiming to fulfill this objective exhibit a diversity of emphasis, with an overview of the associated technical approaches presented in Table 2.Some studies focus on high-quality path planning, aiming to achieve extremely high coverage rates and imaging precision, but this often comes at the cost of reduced efficiency. Silberberg and Leishman [20] aimed to verify the feasibility of multirotor UAVs for military aircraft skin visual inspection; they improved the open-source Adaptive Search Space Coverage Path Planner (ASSCPP) algorithm by optimizing viewpoint generation (via collision, distance, and coverage filters), modifying path planning to avoid revisited points and add orientation-selectable parameters, and studying two data collection paradigms (continuous flight for speed and noncontinuous flight with waypoint delays for accuracy). They conducted simulations in Gazebo with F-15/F-35 models and real-world tests on a 1/7-scale F-15 using an X8 octocopter (equipped with a camera and VICON localization), validating precise close-range path tracking (average 5.7 cm error for noncontinuous flights) and sufficient imagery quality for defect detection, while estimating full-scale F-35 inspection feasibility. Another example is Piao et al. [21], who proposed a hybrid sampling viewpoint generation method. They employed dual-layer sampling to satisfy the three major constraints (equidistance, orthogonality, and overlap), followed by primal sampling to adapt to equipment limitations, ensuring imaging quality under 98.1% coverage.In contrast to the former, the study in [21] focuses on addressing the challenge of generating viewpoints under stringent device constraints to achieve a high coverage rate and superior imaging quality. However, the work stops at producing high-quality discrete viewpoints, not only failing to connect them into a complete and executable coverage path, but also leaving unresolved the motion stability issues of the lifting devices already adopted in the prior research (where these issues arise from the elevated center of mass caused by the lifting devices). To address both gaps simultaneously, Piao et al. developed a column-wise scanning mode based on the viewpoint projection merging strategy: this mode targets the stability problem of the existing lifting devices, effectively mitigating risks from a high center of mass and enhancing the safety of the system’s motion. On this optimized, stable foundation, the study further plans out the trajectory of the UGV between waypoints using the A* and TEB (Timed-Elastic Band) algorithms, finally forming a fully executable coverage path. The entire UGV system, along with the planned trajectories, is illustrated in Figure 5.To this end, in their subsequent work [22], Piao et al. further proposed a Bézier curve-based path planning method specifically addressing the motion safety issue of the UGV caused by its elevated center of gravity due to the lifting mechanism. Building upon the previously generated viewpoints, this method employs Sequential Quadratic Programming (SQP) to optimize and generate a smooth path that satisfies curvature constraints and obstacle avoidance requirements, effectively preventing the risk of the UGV tipping over during motion. Thereby, it achieves a fully automated end-to-end coverage inspection process from viewpoint generation to path execution.Nevertheless, in the aforementioned “first-sample-then-connect” approach, path quality heavily depends on the distribution and density of the viewpoint set. In stark contrast, Tong et al. [23] pioneered a fundamentally different continuous coverage path planning method based on 3D mesh parameterization. This approach abandons the discrete viewpoint sampling paradigm altogether. Instead, it parameterizes and maps the 3D model of the aircraft skin onto a 2D plane, directly generating a continuous, collision-free Boustrophedon scanning path within this 2D domain, and then transforms it back into 3D space via barycentric coordinate mapping. Its primary advantage lies in its inherent ability to guarantee extreme consistency in observation distance and angle throughout the scanning process, thereby providing subsequent damage detection algorithms with highly uniform image data. Simulations demonstrate that this method achieves coverage rates as high as 94% on complex surfaces, with a significantly lower standard deviation in observation distance compared to sampling-based methods. However, the trade-off is its heavy reliance on predefined high-precision 3D models. Furthermore, the entire planning process is conducted offline, lacking the capability for real-time adjustments in response to dynamic environmental changes. The optimality of the path and computational efficiency are also constrained by the distortion inherent in the parameterization process.Consequently, current research in high-quality coverage path planning presents two parallel technical pathways: “discrete viewpoint optimization” and “continuous path parameterization”. The former offers greater flexibility but results in less coherent paths, while the latter ensures superior data consistency at the cost of weaker environmental adaptability. Integrating the strengths of both approaches represents a key focus for future research.In scenarios with extremely high efficiency requirements, such as pre-flight walk-around inspections, the rapidity of path planning is crucial. Although quality-oriented path planning can collect high-quality data and provide a solid foundation for subsequent high inspection accuracy, efficiency is equally important in such contexts. Therefore, some researchers have focused on improving efficiency, primarily through two approaches: optimizing path length and reducing algorithm runtime, with the goal of achieving more efficient inspections.Some research concentrates on optimizing path length to improve task execution efficiency. For example, Cao et al. [24] proposed a hierarchical multi-resolution coverage path planning framework for UAV platforms. Based on octree-based spatial partitioning and two-level Traveling Salesman Problem (TSP) optimization, this framework significantly shortens the coverage path length in complex 3D structured environments by decoupling the planning of subspace sequences at the global scale from viewpoint path planning at the local scale.Some research, on the other hand, focuses on reducing algorithm runtime to enhance efficiency. For example, Tappe et al. [25] integrated point cloud downsampling with an enhanced Genetic Algorithm (GA) based on the open-path Traveling Salesman Problem (TSP), successfully reducing path planning time to 90 s. Simulation results demonstrate that this approach achieves complete coverage of an Airbus A320 surface within 60 min. Meanwhile, Almadhoun et al. [26] proposed a GPU-accelerated coverage path planning method for UAV platforms. This method, combining a heuristic reward function with CUDA parallelization techniques, significantly improves the efficiency of key computational steps such as frustum culling and occlusion culling.In aircraft skin inspection tasks, both efficiency and quality are core optimization objectives. Unlike the aforementioned studies that solely focus on a single objective, some researchers are dedicated to the collaborative optimization of quality and efficiency, and on this basis, conduct path planning. Almadhoun et al. [27] developed Adaptive Sampling-based Coverage Path Planning (ASSCPP), which combines multi-resolution octree entropy optimization with graph search strategies. This approach significantly reduces path length while achieving 98% coverage. The following year, the team further enhanced performance by refining aspects like heuristic functions, proposing the SSCPP algorithm [28].Specifically, Liu et al. [29] proposed the Quality-Efficiency Coupled Iterative Coverage Path Planning (QECI-CPP) method. This method employs a subspace processing strategy with differential constraints for narrow/normal spaces and quality-guided non-random initialization to generate inspection paths that simultaneously optimize image resolution, orthogonality, and path efficiency. Additionally, by introducing a weight-adjustable objective function, this method allows users to dynamically adjust the trade-off between inspection quality and execution efficiency according to specific task requirements, thereby significantly enhancing the applicability and flexibility of the algorithm across various application scenarios. Simulations demonstrate that while maintaining moderate computation time, QECI-CPP significantly enhances inspection quality and outperforms comparative methods in path efficiency.Existing research primarily focuses on single-robot CPP methods. However, both UAVs and UGVs exhibit inherent limitations: UAVs can only effectively cover the top external surfaces of aircraft, while UGVs are primarily suitable for inspecting sidewall regions. Furthermore, there exist marked differences in their detection accuracy and coverage capabilities: UAVs enable rapid large-area coverage but offer limited precision, whereas UGVs can provide localized high-precision inspection yet suffer from restricted coverage range. Multi-robot collaboration enables functional complementarity, significantly enhancing the comprehensive performance of path planning.Piao et al. [30] developed a Collaborative Coverage Path Planning (CCPP) method for aircraft skin inspection, utilizing a heterogeneous UAV-UGV robotic collaboration framework. By integrating a dual-chromosome genetic algorithm with DDA-RRT* path planning, their method generates smooth coverage paths under curvature constraints, photogrammetric coverage requirements, and endurance limitations, ultimately reducing the total inspection time by 4.7%.However, such methods still focus on algorithm-level collaborative optimization and fail to fully account for uncertainties in real open environments, such as wind and dynamic obstacles, that affect motion stability and continuous data acquisition. For instance, under strong wind disturbances, the pose jitter or even path deviation of UAVs can significantly degrade image capture quality, a challenge that purely planning-based algorithms struggle to effectively mitigate. In recent years, some studies have begun to explore enhancing system robustness through physical coupling, such as the tethered UAV–ground Robot Composite (RC) system designed for open environments: it uses a tether mechanism to synchronize platform motion, suppressing strong wind interference while ensuring continuous data collection [31]. This suggests that future research in collaborative path planning should further integrate disturbance rejection mechanisms to develop comprehensive solutions that combine algorithmic excellence with physical reliability.So far, all the offline path planning methods mentioned share a common limitation: they heavily rely on predefined CAD models. The precision and accuracy of these models significantly impact the algorithm’s performance. However, in practical inspection scenarios, such models are often difficult to obtain and costly to construct. Sun and Ma [32] proposed an innovative two-stage UAV scanning framework that effectively addresses this shortcoming. This framework first controls the UAV to perform a long-distance coarse scan along a preset safe path, generating a coarse octree model. Then, based on this model, it generates candidate viewpoints and applies either the Monte Carlo Tree Search (MCTS) or the Max–Min Ant System (MMAS) algorithm to solve the CPP problem, computing the optimal fine-grained scanning path. Experimental validation demonstrates that this method can automatically scan and cover over 70% of the aircraft surface within approximately one hour, significantly improving inspection efficiency and reducing reliance on manual labor.
- Online Path PlanningCurrently, the majority of path planning research focuses on offline methods. However, in practical application scenarios, dynamic factors, such as tug vehicles and personnel, frequently introduce uncertainties, making it difficult for existing systems to achieve efficient real-time detection. As a result, a growing number of researchers are shifting their emphasis to online path planning techniques. Such methods prioritize the system’s real-time performance and dynamic adaptability, enabling the autonomous adjustment of the inspection path based on environmental changes, thereby enhancing the overall robustness and flexibility of the application.To address the limitations of traditional coverage planning (low efficiency in non-uniform information fields, neglect of spatial correlations, and an inability to respond online to observations, Zhu et al. [33] keenly identified the fundamental limitations of traditional coverage planning in complex information fields and pioneered an online adaptive framework based on the manifold Gaussian Process (mGP). Their approach not only leverages the mGP to characterize spatial correlations for guiding exploration but, more importantly, incorporates rolling horizon optimization to dynamically integrate real-time observation data. This facilitates a paradigm shift from “predefined coverage” to “active sensing”. Their work has laid an important foundation for subsequent research on learning-based active perception in three-dimensional environments.In the field of multi-robot online coverage planning, the work by Almadhoun et al. [34] offers an inspiring new direction. The outstanding contribution of their proposed Hybrid Coverage Path Planning (HCPP) framework lies in its integration of a dynamically switching traditional Next Best View (NBV) strategy with a Long Short-Term Memory (LSTM)-based view prediction strategy, representing a hybrid paradigm for addressing real-time bottlenecks. Through a simple dual-trigger mechanism, it successfully achieves a dynamic balance between “computational accuracy” and “response speed”. The significance of this research lies in its demonstration of the fact that regularities embedded in historical path sequences can be effectively extracted and utilized to improve the efficiency of future planning. This approach points toward future research directions, specifically how to more finely design strategy-switching criteria and how to embed other learning models into this hybrid framework to cope with more complex scenarios.
- Current Status Analysis on Motion Planning Technology
- A significant gap exists in research on dynamic environments. Most operational scenarios for aircraft skin inspection are typical dynamic environments, such as airport aprons, where the movement of ground support vehicles (e.g., refueling trucks) and jet bridges, along with the temporary intervention of maintenance personnel, all trigger real-time changes in environmental states. However, current motion planning research mostly relies on a static environment assumption, which predefines known aircraft models and environmental models, without accounting for these dynamic interference factors. This assumption deviates from practical operational requirements and gives rise to multiple challenges: during on-site skin inspection, aircraft skin inspection robots may encounter unforeseen obstacles. If obstacles block the line of sight between inspection viewpoints and the fuselage surface, local missed inspection of the skin will occur directly; if obstacles occupy the positions of unfinished inspection viewpoints, collision risks may arise; if obstacles appear on the path between preset waypoints, path costs (e.g., increased detour distance, higher energy consumption) will change, ultimately rendering the originally planned optimal coverage path invalid. These dynamic interferences demand real-time path replanning, yet the real-time response performance of current algorithms generally fails to meet this requirement.Current research on real-time Coverage Path Planning (CPP) primarily focuses on simple planar or curved surfaces [35,36,37,38,39]. In [35], an effective approach based on the “predator–prey” model is put forward: the robot (acting as the “prey”) is guided to cover regions distant from a virtual location (the “predator”) via a reward function. This enables rapid path replanning when unknown obstacles arise. This concept is further extended in [36,37] to multi-agent real-time CPP in unbounded environments. However, these studies are primarily applicable to cleaning or painting robots, scenarios where photography-related computations (a key requirement for aircraft skin defect detection, e.g., high-resolution image acquisition and defect localization) are unnecessary.
- The coupling relationship between viewpoint generation and path planning has not been effectively addressed. Viewpoint generation and path planning are core links of motion planning, and they have a strong coupling relationship; reasonable viewpoint distribution needs to adapt to path accessibility, and optimized path planning relies on the spatial correlation of viewpoints. However, most current mainstream algorithms adopt a decoupling strategy: first, generating a set of viewpoints covering the entire surface through random sampling or grid division, and then performing path search based on this viewpoint set. Although this method reduces the complexity of a single link, it has obvious defects: the generated viewpoints can meet the skin coverage requirement, but due to the lack of collaborative design with path planning, the robot’s motion trajectory is prone to frequent turns and sudden speed changes, violating dynamic constraints, such as maximum acceleration and steering angular velocity; at the same time, the path connection between viewpoints lacks global optimization, which easily leads to repeated detours and increases the total path length and energy consumption. Although a few studies [28,40,41] attempt to explore the joint optimization of the two, such as building a multi-objective optimization model based on genetic algorithms or reinforcement learning methods, joint optimization needs to simultaneously consider multiple objective functions, including coverage integrity, path length, and trajectory smoothness, which greatly increases model complexity, reduces algorithm efficiency and makes it difficult to meet the real-time requirements of on-site inspection.
- Path planning research has a gap concerning practical application, with insufficient focus on trajectory planning. Most current studies only focus on path planning, i.e., generating the geometric path of robots from the start point to the end point, specifically, generating a sequence of waypoint coordinates, while paying insufficient attention to the key link of trajectory planning, trajectory planning needs to combine the dynamic characteristics of robots such as speed, acceleration, and motion time to convert geometric paths into executable motion commands such as motor speed and steering angle. This research bias makes it difficult for planning results to be directly applied: geometric paths may meet the coverage requirement, but due to the lack of consideration of dynamic constraints such as the speed limit of unmanned ground vehicles on uneven ground and the attitude stability of unmanned aerial vehicles under gusts, trajectory deviation and motion oscillation are prone to occur during actual execution. More critically, existing studies mostly rely on simulation environment verification, often simplifying complex practical factors such as raised joints on the airport ground and the impact of electromagnetic interference on positioning accuracy; experimental verification in real scenarios is extremely scarce, with only a few studies conducting small-scale tests for a single aircraft model or simple static scenarios [20,24,27,28], lacking systematic verification of adaptability to multiple aircraft models and robustness to dynamic interference. This renders the effectiveness of current planning algorithms [21,22,25,26,29,30,31,32,33,34] only valid in simulations, and their reliability in real airport environments still needs further verification.
4.1.2. Perception Module
No. | Coverage | Viewpoint Generation Technology | Path Planning Technology | TSP Solving Technology | Comments | Robot Platform | Research | |
---|---|---|---|---|---|---|---|---|
Advantages | Disadvantages | |||||||
[20] | Offline | 1. Uniform sampling for initial viewpoint generation 2. Adaptive sampling, focusing on areas with low coverage or poor accuracy 3. Euclidean clustering to identify uncovered areas | Enhanced A* Algorithm: Graph-based path planning with a visited-list and multi-orientation configuration. | — | 1. Faster, more detailed path computation. 2. More intuitive inspection paths. 3. Allow multiple orientations at the same point. | 1. Could be improved by optimizing the path by solving the traveling salesman problem 2. A textured mesh model could be implemented into the simulation environment. | UAV | simulation experiment |
[21] | A mixed sampling method: dual sampling and primal sampling | — | — | 1. Achieve a high coverage rate and quality 2. Meet the photogrammetric requirements, as well as multiple constraints 3. Meet the real-time requirement | 1. The uncovered area is concentrated on the tail 2. Do not include trajectory planning | UGV | Simulation | |
[22] | 1. A dual sampling approach (initial viewpoint set) 2. Viewpoint selection by minimizing the number of waypoints | 1. Quartic Bézier curve path parameterization 2. Nonlinear optimization via SQP | — | 1. Effectively addresses multiple practical constraints 2. Plans a coverage path satisfying constraints, including curvature and obstacle avoidance 3. Ensures efficient and effective aircraft skin inspection | 1. Heavily relies on prior environmental models 2. It does not consider the potential impact of external disturbances, such as dynamic obstacles, uneven terrain, and wind, on the motion of the UGV in real-world environments | UGV | Simulation | |
[24] | 1. Solves for optimal viewing pose parameters 2. Occlusion and collision checking | — | A multi-resolution hierarchical framework: 1. Global Layer: Plans optimal sequence between subspaces (Octree). 2. Local Layer: Plans shortest TSP tour within each subspace. | 1. Runs significantly faster 2. Shorter generated paths | 1. Irrespective of the semantic meanings of the objects 2. In highly occluded or geometrically complex regions, incomplete coverage may persist | UAV | Simulation experiment | |
[25] | 1. A point cloud: A laser scan or 3D model 2. Inspection poses: Determined based on surface normal vectors | — | Genetic algorithm | 1. Can be planned before the actual inspection starts and is very beneficial 2. Beneficial for repeatedly inspecting multiple objects of the same type | 1. The next step will be to validate this process chain for a real maintenance process | UAV | Simulation | |
[26] | 1. Grid discretization with multi-angle sampling 2. GPU-accelerated multi-criteria filtering | Incremental graph search for stepwise viewpoint selection | — | 1. Performing parallel implementation for the frustum and occlusion culling processes 2. Use a heuristic reward function that evaluates the distance, turning angle, and sensor accuracy at each viewpoint | 1. Does not incorporate the surface mesh area and a measure of information gain into its planning heuristics | UAV | Simulation | |
[27] | Offline | Adaptive sampling: 1. Uniform initialization: Sample viewpoints at predefined position and orientation resolutions 2. Iterative refinement: Perform iterative, denser sampling in low-coverage or geometrically complex regions 3. Cluster-based completion: Identify uncovered areas via Euclidean clustering and resample them | Graph-based heuristic search: Employs an exponential decay heuristic, R = E · exp( d), to simultaneously optimize for the shortest path length and maximum information gain | — | 1. Integrated sensor models 2. Improves the path length, number of viewpoints, average extra coverage, and accuracy per viewpoint | 1. The current heuristic reward function does not incorporate surface mesh area 2. It lacks support for multi-agent collaborative coverage 3. A TSP solver has not yet been introduced | UAV | Simulation Experiment |
[28] | 1. Spatial discretization: Grid space at a set resolution 2. Multi-angle sampling: Sample multiple yaw angles per grid point to generate candidate viewpoints 3. Multi-sensor adaptation: Transform coordinates based on sensor configuration to generate multi-perspective views 4. Three-stage filtering: Filter viewpoints through collision/distance/coverage checks | Progressive hybrid search strategy: 1. Method: Graph search combining greedy and global exploration 2. Heuristic: Prioritizes nodes using a weighted function R(n) to balance path length and information gain 3. Process: Iteratively expands nodes by managing open/closed lists until coverage threshold is met | — | 1. Supports multiple sensors to cover large occluded areas to reduce consumed time 2. Targets areas with no coverage to generate a reduced set of viewpoints | 1. Limited to single-robot operation and lacks the capability for multi-robot collaborative coverage path planning 2. Does not employ advanced techniques like deep learning for identifying occluded regions | UAV | Simulation experiment | |
[29] | 1. High-quality, partitionable mesh preprocessing 2. Quality-guided viewpoint init: computes optimal pose for each qualified mesh face | RRT * plans collision-free shortest paths for all viewpoint pairs | LKH algorithm | 1. Simultaneously considers inspection quality and efficiency 2. Improves computational efficiency through effective initialization and the separation of viewpoint direction calculations | 1. The proposed QECI-CPP algorithm has not been validated on real UAV systems 2. Does not account for critical real-world disturbances, such as wind effects, localization errors, or non-ideal control of camera actuators. | UAV | Simulation | |
[30] | A mixed sampling method: dual sampling and primal sampling | 1. DDA algorithm: For fast collision-checking of line-of-sight paths between viewpoints 2. RRT algorithm: * For planning 3D collision-free alternative paths when direct paths are blocked | Dual-chromosome genetic algorithm: Chromosome 1: Encodes the TSP-style tour order of viewpoints Chromosome 2: Encodes the assignment of each viewpoint to a UAV or UGV | 1. The method takes into account the maneuverability, endurance, and collision constraints between the robots and aircraft. | 1. Does not include collision avoidance between robots, path smoothing, optimization, and handling other uncertainties | UAV+UGV | Simulation | |
[31] | Offline | Define Regions of Interest (ROI) on the 3D model surface, and then sample viewpoints with specified resolution and overlap rate | The path is pre-defined based on the aircraft type 1. UAV path R: Pre-planned for inspecting upper aircraft surfaces 2. UGV path S: Projected from R for UGV to follow the UAV 3. UGV path T: Independently planned for inspecting lower aircraft surfaces | — | 1. The prevention of collisions of an unmanned aerial vehicle with an aircraft 2. Soft landing of this device on the landing place of an unmanned ground vehicle | 1. Tether swing interference 2. High system complexity with increased failure points | A tether-based hybrid UGV-UAV cooperative robotic system | Simulation |
[32] | 1. Basis: Octree voxel model 2. Generation: estimate the surface normals and offset along the normal by the working distance to generate candidate viewpoints 3. Key techniques: Surface-normal estimation and frustum culling | — | 1. Max–Min Ant System (MMAS) 2. Monte Carlo Tree Search (MCTS) | 1. Reduce human workload, eliminate human error, and improve work efficiency 2. Find an approximate optimal path in terms of the flying distance | 1. The current MCTS-based approach exhibits poor performance in large search spaces 2. The method fails to provide a solution for inspecting confined areas. | UAV | Simulation | |
[33] | Online | — | 1. Discrete viewpoint search: Employs a sequential greedy strategy to select the next viewpoint from a predefined library that offers maximum information gain, with preliminary collision checking 2. Continuous trajectory optimization: Smoothens and optimizes the path obtained from the discrete search | — | 1. Captures spatial correlations of information over complex surface geometries 2. Faster map uncertainty and error reduction 3. Improves the information-gathering efficiency | 1. Online informative path planning may be trapped at some local minima 2. Does not account for dynamically changing information fields 3. Does not incorporate multi-robot information-gathering strategies | UAV | Simulation |
[34] | 1. NBV method: Generates optimal viewpoints using Information Gain (IG) and entropy evaluation 2. LSTM prediction: Uses a neural network to predict viewpoint sequences, improving planning efficiency | — | 1. Generating fast coverage paths and generalizes to different structures of similar shapes 2. Fostered the intelligence and versatility of combining the conventional approach with the ML approach utilizing the advantages of both | 1. The LSTM network could be enhanced by integrating CNN to add more features to the learning process, improving predictions 2. Handling online multi-robot planning for unknown structures is challenging | UAV | Simulation |
- SLAM-based PerceptionSimultaneous Localization and Mapping (SLAM) systems are designed to enable robots to achieve autonomous localization and mapping in unknown or partially unknown environments. The core approach involves fusing multi-sensor data to estimate the robot’s motion trajectory in real-time while incrementally constructing an environmental map, thereby achieving continuous autonomous localization and navigation without relying on external pre-established infrastructure. Representative algorithms such as vision-based ORB-SLAM3 [42] and LiDAR-inertial sensing-based LIO-SAM [43] exemplify SLAM implementation frameworks based on optimization and filtering, respectively. These methods are widely applied in fields such as robotics, autonomous driving, and augmented reality. Depending on whether external sensors are relied upon, SLAM systems can be further categorized into those entirely self-reliant for perception and those dependent on external sensors for perception.
- Self-reliant for PerceptionThe operation of SLAM requires an initial pose as a prerequisite. Oh et al. [44] proposed a monocular PTZ camera-based method combined with CNN-driven pose estimation, achieving relative pose initialization for aircraft on an infrastructure-less airport apron by providing this fundamental pose. Trained on synthetic data and employing a geometrically constrained loss function (ICSC loss), their approach requires only a single image input to achieve median pose estimation errors of 0.22 m and 0.73 degrees.Researchers have advanced the application of SLAM-based localization and mapping technology in aerial inspection tasks from various perspectives. These efforts demonstrate progress in sensor fusion and the use of structural priors, while also highlighting the persistent issues of strong environmental dependency and limited generalization capabilities in current methods.Yan et al. [45] integrated an RGB-D camera with ORB-SLAM3 to achieve real-time point cloud mapping and localization for a mobile platform inspecting aircraft surfaces. The approach offers the advantage of providing real-time visual SLAM pose output without relying on external infrastructure. However, the method is highly dependent on environmental visual texture and is prone to tracking failures in hangar environments with weak textures or significant lighting variations. Additionally, the depth camera shows measurement noise and scale drift in large-scale scenes.Saha et al. [46] proposed a multi-UAV collaborative inspection system that employs calibration-free cross-coordinate system registration technology. By leveraging FPFH template matching for alignment across different coordinate systems and integrating LIO-SAM with a multi-layer safe navigation strategy, the system achieves high-precision localization and obstacle avoidance in GPS-denied environments. While the design demonstrates innovation in collaborative logic and safety, its FPFH matching mechanism is prone to mismatches in highly dynamic or structurally repetitive environments. Moreover, the complex system architecture demands substantial computational and communication resources, posing challenges for practical engineering deployment.R-LOAM [47] mitigates long-term drift and improves localization and map consistency in GPS-denied environments by incorporating mesh features of known reference objects and constructing point-to-plane constraints to optimize LiDAR point clouds. The contribution of this method lies in its explicit use of environmental structural priors. However, its performance heavily depends on the accuracy and visibility of predefined reference objects. System performance may degrade significantly when objects are missing, occluded, or altered, making it a condition-dependent enhanced SLAM approach rather than a fully adaptive environmental perception solution.
- Dependent on External Sensors for PerceptionTo enhance system robustness and localization accuracy in complex environments, SLAM-based positioning solutions are often frequently fused with external sensors. By leveraging the complementary nature of multi-source heterogeneous data, a tightly coupled collaborative perception framework is constructed, enabling stable and reliable pose estimation even under sensor degradation or dynamic environmental changes.Liu et al. [48] proposed a method that integrates visual-inertial odometry (VIO) with pre-calibrated ArUco markers to mitigate positioning drift of VIO in texture-sparse areas on aircraft surfaces. Based on the VINS-Mono framework, the study incorporates ArUco observations as external constraints into a joint optimization model and designs an adaptive weighting mechanism to balance the reliability of different constraints. Additionally, it eliminates the requirement for the UAV to start operations from a fixed take-off point.Another integrated localization system [49] fuses stereo Visual–Inertial Odometry (VIO) with an ultrasonic Real-Time Locating System (RTLS) to achieve centimeter-level positioning for UAVs in GPS-denied hangar environments (root-mean square error of 0.288 m, a 52% improvement over a pure VIO approach). This performance is realized through graph-optimization-based multi-sensor fusion and outlier rejection techniques, while sustaining continuous positioning capability even during temporary interruptions of ultrasonic signals.The aforementioned studies achieve higher accuracy and more robust localization in challenging environments by tightly coupling SLAM with external sensors. However, both approaches exhibit a non-negligible reliance on predeployed infrastructure, which fundamentally limits their applicability in fully unknown or dynamically reconfigured environments. Although such hybrid systems effectively compensate for the shortcomings of pure SLAM in perceptually degraded settings, they also introduce additional complexities in terms of calibration, maintenance, and system scalability. Consequently, despite demonstrating performance improvements in structured industrial scenarios, these methods remain conditional solutions rather than universally applicable technical frameworks for autonomous navigation.
- Non-SLAM-based LocalizationIn non-SLAM localization approaches, systems typically rely on pre-deployed external sensor infrastructure, prior maps, or global markers to achieve pose estimation. The core idea lies in acquiring the position through direct measurement or matching with known beacons or databases, eliminating the need for online environment modeling. This enables high computational efficiency and reliability under specific conditions. However, such methods exhibit significant limitations in adapting to unknown or dynamic environments due to their heavy dependence on external infrastructure or high-precision prior information.
- Known Beacons:Ruiqian et al. [15] innovatively proposed the use of ArUco visual markers to address the localization challenges for UAVs performing aircraft surface inspections in hangar environments. By detecting ArUco markers deployed on the hangar floor or at designated locations, the system calculates the UAV’s positional offset and yaw deviation relative to the markers in real time, enabling online calibration that effectively corrects flight path drifts caused by accumulated errors in the Inertial Navigation System (INS). Although this study introduces an innovative online correction of UAV localization errors via ArUco markers, the overall localization performance heavily depends on the density and visibility of pre-deployed markers. Robustness significantly decreases in scenarios where markers are obscured or damaged, making this approach fundamentally a localized solution suited for controlled environments rather than broadly applicable autonomous perception scenarios.
- Databases:Cazzato et al. [50] proposed a vision-based aircraft pose estimation method utilizing natural features (i.e., naturally textured regions on the aircraft surface). Through ORB feature matching, multi-probe LSH matching, and Perspective-n-Point (PnP) solving, the approach achieves real-time high-accuracy pose localization for UAVs performing close-range inspection of large aircraft, even under constraining conditions such as the absence of artificial markers and partial visibility of the aircraft. Unlike traditional SLAM, which estimates camera ego-motion, this method directly outputs the relative pose of the target object, effectively addressing failure modes of SLAM in scenes with repetitive or missing textures.
- External InfrastructureBlokhinov et al. [51] proposed and validated a real-time UAV localization system based on a fixed multi-camera network. By deploying multiple cameras in a hangar as external sensing sources, the system employs the YOLOv3 algorithm to detect UAVs in video streams in real time. The precise three-dimensional position of the UAV within the hangar is then computed by integrating multi-view observations with bundle adjustment techniques.
Additionally, Pugliese et al. [52] proposed a LiDAR-RANSAC model based on the cylindrical geometric prior of aircraft. This method integrates LiDAR-based local fitting, iGPS absolute positioning, and IMU motion prediction to establish a fused localization framework that “relies on LiDAR-IMU in the short term and iGPS correction in the long term”. Although the approach achieves millimeter-level accuracy in iGPS-covered areas and LiDAR provides relative measurement capability independent of external infrastructure, its overall performance remains highly dependent on the availability and quality of the iGPS signals, potentially degrading in scenarios with signal obstruction or interruption.Similarly, Dose et al. [53] developed a hardware-in-the-loop simulation platform for UAV-based aircraft inspection, which achieves centimeter-level pose estimation in GPS-denied indoor environments by fusing high-precision external motion capture systems with onboard IMUs. The advantage of this approach lies in its ability to overcome the inaccuracy of traditional magnetometers and barometers in indoor settings. However, its localization capability fundamentally depends on high-cost, pre-configured external tracking systems such as motion capture, which severely limits its scalability and practical applicability in real-world, open environments.In aircraft inspection scenarios, visual recognition results of external components can be directly used to correct robot localization. The Air-Cobot project [54,55,56] detects the poses of parts in images through SURF features or 3D model projection, matches these poses with a predefined aircraft model to generate spatial constraints, and thereby enables dynamic adjustment of robot pose estimation. The method simultaneously integrates laser point cloud matching and multi-source confidence weighting techniques, significantly improving navigation accuracy under complex lighting and dynamic environmental conditions. This establishes a closed-loop optimization framework characterized by “perception validating localization, and localization guiding perception”. - Current Status Analysis on Perception Technology
- Dilemmas in Feature Matching Caused by Weak Texture on the Aircraft Skin Surface:The aircraft skin surface generally exhibits sparse or repetitive texture, posing significant challenges to visual localization. Traditional SLAM technologies often fail in localization due to insufficient feature points or mismatching in such scenarios. Although Cazzato et al. [50] proposed using natural texture regions on the aircraft surface for pose estimation, they still face the problem of feature absence in smooth skin areas or paint-peeled regions. Studies by Liu et al. [48] show that sparse texture on the aircraft surface leads to obvious drift in Visual–Inertial Odometry (VIO), which requires compensation through external constraints such as ArUco markers; this increases system complexity and dependence on the environment.
- Insufficient Adaptability to All-Weather and All-Time Environments:The lighting conditions in airport environments are complex and variable, ranging from direct intense light and backlight to low illumination at night, and from severe weather such as rain, snow, and fog to artificial lighting in hangars. These conditions place extremely high demands on the environmental adaptability of perception systems. Visual SLAM [42] experiences significant performance degradation under strong light, backlight, or low illumination. Although LiDAR [52] sensors are less affected by lighting, they still face the problem of degraded point cloud quality in rainy and snowy weather. While multi-sensor fusion strategies (e.g., vision + LiDAR [54]) alleviate this issue to a certain extent, the differences in performance attenuation characteristics of different sensors under extreme environments remain difficult to reconcile perfectly. Achieving truly stable all-weather and all-time operation remains an unsolved problem.
- Interference from Dynamic Obstacles and Complex Scenarios:Open environments such as airport aprons contain a large number of dynamic obstacles, including refueling trucks, luggage carts, and pedestrian traffic. These dynamic elements severely interfere with the map-building and localization processes of SLAM systems. Although Saha et al. [46] designed multi-layered safe navigation zones and integrated LiDAR-IMU state estimation methods to ensure obstacle avoidance safety, real-time detection and elimination of dynamic obstacles remain technical difficulties. In addition, the complex metal structures around aircraft cause electromagnetic interference, which affects the accuracy of radio localization technologies such as UWB. For example, although IR-UWB technology has a certain robustness to radio frequency interference, it may still exhibit localization deviations near high-voltage equipment.
- Localization Drift in GPS Signal-Deficient Environments:In scenarios such as inside hangars or under aircraft, GPS signals are often blocked or greatly attenuated, rendering traditional GPS-dependent localization systems ineffective. Studies have shown that prolonged GPS absence leads to a gradual increase in cumulative errors between the robot pose output by the localization module and the actual pose. Although technologies such as LIO-SAM [46] and R-LOAM [47] significantly reduce long-term pose drift by fusing 3D LiDAR point cloud features with known reference object mesh features, the error suppression effect of these methods remains unsatisfactory in large-area smooth skin regions with no structural features. How to maintain long-term high-precision localization in environments with complete GPS absence and sparse features remains a core unsolved problem.
- Deployment Limitations and Dependence on External Auxiliary Equipment:Localization solutions relying on external markers or infrastructure can provide high precision, but they face a trade-off between deployment cost and flexibility. The ArUco marker-based localization method proposed by Ruiqian et al. [15] requires the predeployment of a marker network and mandates that UAVs start tasks from fixed take-off points, which severely limits operational flexibility. Although the multi-camera network localization system proposed by Blokhinov et al. [51] enables real-time high-precision localization of UAVs inside hangars, it requires large-scale deployment of external cameras and complex calibration, increasing system costs and maintenance difficulties. In large airport scenarios, this strong dependence on external equipment poses significant challenges to the practical implementation of the technology.
- Insufficient Scene Adaptability and Generalization Capability:Current perception technologies are mostly optimized for specific scenarios and lack cross-scenario generalization capabilities. The open, dynamic environment of airport aprons and the closed, static environment of hangars have vastly different requirements for perception systems, making it difficult to develop a unified perception framework. For example, marker-assisted localization suitable for hangars has limited practicality in open apron scenarios; localization methods relying on fixed aircraft models require re-modeling when facing diverse aircraft types, resulting in poor adaptability. Although the Air-Cobot project [54,55,56] attempted to improve adaptability through closed-loop optimization characterized by “perception verifying localization and localization guiding perception”, it still experiences response lags in scenarios involving rapid aircraft type switching.
4.2. Data Processing Phase
4.2.1. Traditional Algorithms
No. | Perception Sensor Types | Implement the Algorithm | Comments | Robot Platform | Research | |
---|---|---|---|---|---|---|
Advantages | Disadvantages | |||||
[45] | RGB-D camera | ORB-SLAM3 | 1. The mobile platform with a SLAM function can be used to inspect the appearance of the aircraft 2. Lays a foundation for the subsequent establishment of dense map that can be navigated independently | Focused on the feasibility and preliminary experimental validation of the ORB-SLAM3-based method, without an in-depth discussion of its limitations | — | Experiment |
[44] | Monocular RGB camera | The pose regression model based on a deep convolutional neural network (DCNN): an improved PoseNet+ architecture with an Xception backbone, combined with the proposed ICSC loss function | Have demonstrated that camera pose estimation with respect to an aircraft can be achieved without any infrastructure or prior access to a real aircraft | The current method relies solely on a single type of sensor data and does not support sensor fusion, limiting its robustness and accuracy in complex environments | — | Simulation experiment |
[46] | RGB-D camera, 64-line 3D LiDAR, IMU | LIO-SAM | 1. The registration process helps in task distribution among the participating UAVs 2. The UAVs navigate using a proposed multilayered zones for safe navigation around the aircraft by avoiding obstacles | 1. When UAV1 is not operational, other UAVs are stuck 2. Does not include any upward or downward-looking cameras on the UAVs | UAVs | Simulation |
[47] | 3D LiDAR | An improved algorithm based on the LOAM framework: R-LOAM | 1. Extracted mesh features from a 3D triangular mesh 2. Point-to-mesh correspondences are then added to the novel joint optimization problem | 1. Reliance on a perfect 3D model and its precise pose 2. Performance is limited when the reference is not visible | UAV | Simulation |
[51] | Visible-range cameras, inertial measurement unit | 1. UAV detection: YOLOv3 2. 3D coordinate calculation: Bundle adjustment, stereo-vision triangulation | Solves the problem of drone indoor navigation, where the signal from satellite positioning systems is weak or there is no signal | 1. Complex deployment and high initial cost 2. Dependence on external infrastructure, poor flexibility | UAV | Experiment |
[15] | Camera | Visual sensor (camera): ArUco marker-based recognition and pose estimation algorithm | The speed and accuracy of recognizing ArUco markers are good, and the position and pose of the drone can be estimated based on the correspondences between the drone and the markers | 1. Dependence on pre-placed markers 2. Implied environmental limitations | UAV | Experiment |
[48] | Monocular camera, IMU | Based on the VINS-Mono framework, ECLM is introduced | 1. The localization drifts are significantly reduced through utilizing the proposed ECLM 2. The localization accuracy is further improved because of the ArUco marker | 1. The dependence of visual localization on features in the scene 2. Has an insufficient defect detection capability when the defect is extremely slight | UAV | Simulation experiment |
[50] | Monocular RGB camera | ORB feature detection + KNN matching + RANSAC homography estimation + PnP pose solving + multi-landmark fusion optimization | A proper choice of the landmarks can allow self-positioning of the UAV, addresses traditional SLAM methods often fail in areas with repetitive patterns or lack of texture | 1. Relies on initial pose information for tracking 2. Lacks effective optimization schemes to handle cases where multiple landmarks are detected within the same image frame | UAV | Simulation Experiment |
[52] | LiDAR, IMU, iGPS | RANSAC/MSAC cylindrical fitting, EKF, ICP, intensity filtering | 1. Achieves submeter-level localization accuracy without external hardware 2. LiDAR data can be utilized to safely re-establish the Line of Sight (LoS) between the iGPS transmitter and receiver | Divergence of the existing sensor fusion of IMU and iGPS measurements in absence of the latter over long time spans due to the non-complete observability of the system | UAV | Experiment |
[54] | LiDAR, visual camera, IMU, odometry | Multi-sensor fusion (3D point cloud matching, visual feature tracking and SLAM, confidence-index-based arbitration algorithm) | 1. Reduces the mission time 2. Adds sticker information to increase visual cues | 1. The navigation cameras have not been fully integrated or optimized for autonomous inspection 2. The robustness of the algorithm has not been thoroughly validated under extreme weather conditions | UGV | Experiment |
[55] | LiDAR, camera, GPS, IMU | Laser point cloud matching, visual feature extraction and tracking, multi-sensor fusion arbitration mechanism (under development) | Various interaction requests between the robot and its operator reduce the whole mission time and improve the productivity of the duo | The effectiveness of laser and visual positioning methods heavily relies on the detection of a sufficient number of distinctive features | UGV | Experiment |
[56] | LiDAR, camera, GPS, IMU | Laser point cloud matching, visual feature extraction and tracking, multi-sensor fusion arbitration | Human–robot collaboration will increase the efficiency and the reliability of inspection, reduces the risk and uncertainties, self-adapt to different types of aircrafts, service types, investigation contexts, and operational circumstances | The application of collaborative robots may add complexity to airport management | UGV | Experiment |
[53] | Cameras, IMU | EKF state estimation fusing motion capture data and onboard IMU | A hardware in the loop simulation was designed to enable the controlled testing of flight control and obstacle avoidance algorithms in various situations | In the next part of our research we will work on integrating an AI-based path planning algorithm to map out a flight path around the inspected airplane | UAV | Experiment |
[49] | Stereo camera, IMU, ultrasonic beacons | VINS-Fusion (VIO) + graph optimization + custom outlier filter | 1. Effectively compensates for accumulated drift error in VIO in case of stable RTLS conditions 2. In the case of unstable RTLS conditions, abnormal RTLS data are rejected and localization can continue using VIO without RTLS | Plan to develop a system that can change into RTLS fused with IMU mode in situations of VIO divergence or tracking loss | UAV | Experiment |
- Two-Dimensional Image Processing-Based Defect Detection MethodsTwo-dimensional images represent objects on a plane through pixel grayscale or color information, intuitively reflecting surface features and shape characteristics. In early technological development, 2D image processing research primarily focused on establishing fundamental aircraft surface defect detection capabilities. Jovančević et al. [57] developed a specialized PTZ camera-based inspection system that combined Laws texture filtering with Hough line detection algorithms to attain 0% missed detection rates for door status and engine blade absence inspections. Such a method highlights the advantages of combining texture features and geometric features in specific scenarios but requires customized detection solutions for different components. Concurrently, Jovančević [16] implemented EDCircles ellipse detection technology on a mobile robot platform, achieving perfect 100% accuracy in vent status recognition, proving the extreme reliability of traditional geometric algorithms in detecting regular, high-contrast defects.Technological advancements have driven research to diversify into three directions: general frameworks [58], specialized solutions [59], and algorithm fusion [60]. Rice et al. [58] pioneered the development of a universal inspection framework based on commercial cameras, establishing a scalable system architecture through innovative integration of 3D model projection registration and multiple feature extraction algorithms. The advantage of such a general framework lies in its adaptability to various detection tasks, but it suffers from high system complexity and reduced real-time performance. Concurrently, Siegel and Gunatilake [59] addressed the specialized requirements for high-risk area inspection by developing a dedicated solution that combines robotic Automated Nondestructive Inspector or Crown Inspection Mobile Platform (ANDI/CIMP) systems with wavelet-based multiscale edge analysis. Although specialized solutions are optimized for specific scenarios, they often involve high computational costs and rely on specific hardware platforms, resulting in poor generalizability. Meanwhile, Mumtaz et al. [60] achieved breakthroughs at the algorithmic level through their Non-Subsampled Contourlet Transform-Discrete Cosine Transform (NSCT-DCT) fusion framework. By integrating multiple advanced algorithms, including NSCT, DCT, and dot product classification, they achieved 96.6% crack recognition accuracy across 300 test images. Multi-domain feature fusion methods enhance noise resistance and improve the recognition accuracy of subtle defects by leveraging the advantages of different transform domains, but they also significantly increase computational complexity.In recent years, research has progressed toward higher precision and engineering practicality. Mumtaz et al. [61] made significant theoretical breakthroughs with their directional texture energy-based detection method, innovatively combining Contourlet transform with DCT joint feature extraction to achieve an exceptional 98.3% scratch recognition accuracy across 600 test images. This study achieved a high recognition rate but placed greater demands on computational resources and algorithm parameter tuning. Meanwhile, Gunatilake et al. [62] advanced technological innovation from an engineering application perspective, successfully integrating multi-scale edge analysis and wavelet algorithms into the Crown Inspection Mobile Platform (CIMP) robotic system through their remote visual inspection framework. This solution not only achieved 71.5% crack recognition accuracy but, more importantly, resolved critical safety and operational challenges in high-altitude aircraft inspections. The value of this work lies in its successful integration of algorithms into a robotic system for engineering applications, even though the absolute accuracy is not the highest, as it addresses key issues in practical applications.
- Three-Dimensional Point Cloud-Based Surface Defect QuantificationThree-dimensional point clouds refer to a collection of discrete points acquired through laser scanning or stereo-vision techniques, where each point contains spatial coordinates and may also contain intensity or color information, enabling precise representation of objects’ 3D geometry and surface details. Yang et al. [63] successfully integrated the Canny edge detection algorithm with the Douglas–Peucker polygonal approximation method to achieve accurate recognition of aircraft hatch covers, attaining a recognition accuracy of 96% in experimental settings. The study not only extracted 2D edge features of the covers but also recovered their 6-DoF (Degrees-of-Freedom) poses in 3D space using pose estimation algorithms such as EPnP, thereby enabling stable registration and tracking of virtual and real objects in an augmented reality environment. This method demonstrates strong robustness in recognizing industrial parts with sparse texture and similar geometries. However, its performance remains highly dependent on image quality, edge integrity, and the accuracy of depth sensors, and it may encounter challenges under complex lighting conditions or partial occlusions. Reyno et al. [64] pioneered a laser-scanning-based non-destructive evaluation framework that successfully achieved millimeter-level depth measurement accuracy on 54 planar dents and 74 curved-surface dents by precisely registering and comparing actual scan data with CAD reference models, establishing a methodological foundation for subsequent research. The core value of this work lies in establishing a standard procedure for defect quantification through CAD model comparison, but its reliance on high-precision scanning equipment and high-quality CAD models results in high practical application costs. Building upon this, Jovančević et al. [65] made significant advancements by innovatively incorporating Moving Least Squares (MLS) surface reconstruction: first smoothing raw point clouds and estimating local curvature features, then implementing a normal-constrained region-growing segmentation strategy. This approach successfully enabled automatic identification and 3D quantification of various defects on actual Airbus A320 fuselages, achieving average depth errors below 8%, ultimately developing a comprehensive inspection framework integrable with the Air-Cobot mobile robotic platform. This study demonstrates the transition of 3D point cloud analysis from the laboratory to engineering applications, showcasing a technical route different from traditional algorithms for regular defect detection. However, it involves substantial computational load and is highly sensitive to point cloud quality.As research progressed, point cloud analysis algorithms achieved remarkable breakthroughs in both precision and efficiency. Lafiosca et al. [66] significantly improved traditional Fourier Transform Profilometry (FTP) by incorporating adaptive bandpass filters and virtual reference plane technology, reducing the mean absolute error of dent detection by 34%. This improvement demonstrates the potential of traditional optical measurement methods for continuous precision optimization. Algorithmic innovations effectively suppressed noise and contour distortion, but the measurement accuracy remains susceptible to limitations from environmental vibrations and lighting interference. Based on these developments, Bu et al. [67] further proposed a local curvature-aware algorithm: initially extracting defect transition zone point clouds through curvature thresholding, then combining shortest geodesic distance calculations with cross-sectional projection analysis to achieve submillimeter-level precision measurements (0.0505 mm) for complex curved-surface defects on aircraft skin. This algorithm achieves high measurement accuracy through multi-feature fusion, making it particularly suitable for detecting complex curved surface defects. However, the algorithm complexity and computation time also increase significantly accordingly.
- Multimodal Data Fusion MethodsMultimodal technologies address the “information blind spots” inherent in single detection methods by integrating data from diverse sources such as infrared sensors and lasers, effectively overcoming the limitations of individual data modalities. Numerous researchers have pursued studies from the perspective of multimodal data fusion. Fan et al. [68] and Deng et al. [69] pioneered the development of an automated detection system based on magneto-optical imaging, employing Morphological Bandpass Filtering (MBF) and skewness classification algorithms to achieve real-time detection performance with a Probability of Detection (POD) of 0.9 and a false alarm rate less than or equal to 1% across 720 rivet site samples. Such work demonstrates the unique advantages of magneto-optical imaging technology in detecting sub-surface defects, achieving high-speed, high-sensitivity real-time detection. However, its effectiveness relies on specialized magneto-optical sensors and specific data processing workflows. Gray et al. [70] combined infrared thermography with Phased Array Ultrasonic (PA) testing technology to develop a composite material defect evaluation system capable of 0.4mm layer thickness resolution. This fusion strategy cleverly combines the rapid scanning capability of infrared for surface/near-surface defects with the precise detection ability of ultrasound for internal defects, enabling a holistic assessment of composite structures. However, the system is very expensive and complex to operate, requiring highly specialized personnel. Zheng et al. [71] developed an advanced automated inspection system that implemented a multistage image processing algorithm chain, integrating Fluorescent Penetrant Inspection (FPI) with image processing techniques to enhance FPI efficiency by over 300-fold compared to manual inspection. This solution significantly improves efficiency by automating traditional inspection processes and is suitable for high-volume surface crack detection. However, it requires relatively stringent pre-treatment and environmental control, posing certain limitations in practical applications.These technological innovations were supported by Cook’s [72] theoretical research. Cook’s study demonstrated that single detection modalities exhibit a POD below 0.7 for impact dents more than or equal to 5 joules (J). Building on this theory, this study developed a three-level multimodal fusion system: force sensors record impact energy, which is combined with optical topography and eddy current testing data, followed by Bayesian algorithm-based data fusion. This hierarchical fusion architecture embodies a complete fusion approach from data-level to feature-level and then to decision-level, fully leveraging the advantages of each modality. Experimental results showed this system increased POD to 0.93 while reducing false alarm rates by 42%.
- Current Status Analysis on Traditional Algorithm Techniques for Aircraft Skin InspectionAs summarized in Table 4 (Complete Summary of Traditional Algorithm Techniques for Aircraft Skin Inspection), traditional algorithms have laid a solid foundation for aircraft surface defect detection, demonstrating strong interpretability, computational efficiency, and scenario adaptability, especially in the early stages. Two-dimensional image processing methods excel in detecting regular shapes and high-contrast defects but are generally sensitive to lighting conditions and face challenges in detecting geometric defects. Three-dimensional point cloud analysis enables precise quantification of defects, showing particular advantages in inspecting complex curved structures; however, its performance heavily relies on point cloud quality and computational resources, and it involves high equipment costs. Multimodal data fusion methods significantly enhance detection comprehensiveness and robustness by integrating the strengths of different sensors, excelling in identifying hidden defects and complex structures. However, these systems are complex, costly, and require highly skilled operators. Overall, traditional algorithms still face significant limitations in addressing complex environments, variable lighting, subtle defects, and real-time requirements. These challenges have motivated the introduction and development of new approaches, such as deep learning.
4.2.2. Deep Learning Methods
- Deep Learning-Based Defect Detection MethodsTraditional algorithms face challenges in feature extraction and generalization when processing large-scale complex data, prompting the emergence of deep learning. This approach employs multi-layer nonlinear transformations in artificial neural networks to automatically learn hierarchical feature representations from data, significantly enhancing performance in tasks like image recognition and natural language processing. In aircraft surface defect detection, YOLO series [51,73,74,75,76] algorithms have become mainstream solutions due to their real-time advantages. In early research, Blokhinov et al. [51] developed a comprehensive automated aircraft surface defect detection system through deep integration of UAV visual data with multi-source sensor data. This system employs the YOLOv3 algorithm to analyze high-definition camera images of aircraft surfaces in real-time for defect identification, while incorporating sensor data from inertial navigation systems and multi-camera positioning systems. By implementing Kalman filtering, it achieves centimeter-level precision in UAV positioning, ultimately mapping defect locations accurately to a three-dimensional aircraft coordinate system. Zhang et al. [76]’s research on YOLOv7 laid the foundation for subsequent advancements. The Fine-Coordinated YOLO (FC-YOLO) algorithm addressed multi-scale feature fusion challenges through the efficient layer aggregation networks with coordinate and channel attention modules and an adaptive path aggregation network, achieving mean Average Precision (mAP) improvements of 3.1% and 2.7% on two test datasets, respectively, and demonstrating the effectiveness of attention mechanisms in improving multi-scale feature fusion and providing an important reference for subsequent research.In the wave of YOLOv8 improvements, Suvittawat and Ribeiro [73] first validated the framework’s applicability in aviation inspection, with their optimized network structure successfully identifying three typical defect types: cracks, dents, and corrosion. This study demonstrates precise defect localization through bounding box prediction and grid division methods. Its significance lies in establishing a benchmark for YOLOv8 in the field of aviation defect detection, providing a paradigm for algorithm adaptation in specific domains. Building on this, Connolly et al. [74] enhanced training strategies through data augmentation and loss function optimization, achieving 85% mAP. This indicates that in scenarios with limited data, targeted optimization of training strategies can effectively enhance model performance. Wang’s research group [75] made more systematic contributions by innovatively combining shuffle attention modules with Scylla Intersection over Union (SIOU) loss functions and focal loss optimization, maintaining 139 FPS while achieving 97.9% accuracy. This study demonstrates the immense potential of combining lightweight model design with advanced attention mechanisms and loss functions, but it also increases model complexity and deployment difficulty.The latest YOLOv9 applications continue this technological evolution. Liao et al. [77] improved the Feature Pyramid Networks (FPNs) and integrated Real-Time Messaging Protocol (RTMP) servers, achieving 0.842 mean average precision at a 50% intersection over union (mAP@0.5) while establishing a complete real-time monitoring system. Notably, this research combined Wang’s [75] high-speed processing solution with Zhang’s [76] multi-scale feature processing approach.However, despite significant progress by YOLO series models in aircraft surface defect detection, data scarcity remains a critical bottleneck limiting deep learning model performance. To address this challenge, researchers have proposed various innovative solutions, driving rapid development in data augmentation techniques. Gaul and Leishman [78] proposed 3D rendering pipeline technology, generating automatically annotated synthetic images to solve training data shortages. This foundational work established a new research direction combining computer graphics with deep learning. Li et al. [79] made major progress with their Fourier Generative Adversarial Network (Fourier GAN), introducing innovative components including High-Frequency Spectrum Discriminators (HFSD) and High-Frequency Calibration (HFC) modules. These novel components significantly improved the generated image quality and diversity, with experiments confirming that training detection models with Fourier GAN-generated data noticeably improved accuracy, providing an effective solution for few-shot learning challenges. This work enhanced the quality and diversity of generated images through domain constraints, providing new ideas for GAN-based data augmentation. However, the training process is complex and prone to mode collapse. Beyond generative adversarial networks, researchers have explored alternative technical approaches to address data challenges. Kähler et al. [80] adopted convolutional autoencoders for anomaly detection, effectively mitigating data bias issues, particularly suitable for scenarios where obtaining large defect samples is difficult. These studies on data scarcity resolution collectively form a technological spectrum from traditional data augmentation to intelligent generative adversarial methods, providing diversified solutions for data bottlenecks while indicating multiple potential future research directions.
- Current Status Analysis on Deep Learning Techniques for Aircraft Skin InspectionAs summarized in Table 5, deep learning technology has significantly advanced the field of aircraft surface defect detection, demonstrating strong potential especially in handling complex backgrounds, multi-scale targets, and real-time detection requirements. Detection algorithms represented by the YOLO series have continuously improved detection accuracy and speed through the introduction of attention mechanisms, optimized loss functions, and multi-scale feature fusion. Meanwhile, in response to the challenge of data scarcity, data augmentation techniques such as Generative Adversarial Networks (GANs) and 3D rendering have effectively expanded the diversity and scale of training samples, providing crucial support for model training. Multimodal fusion methods further integrate visual and non-visual data, enhancing the system’s robustness and localization accuracy in complex environments. However, deep learning still faces challenges such as high model complexity, deployment difficulties, strong dependence on data quality, and domain gaps between synthetic and real data. Future research needs to further explore lightweight network design, cross-domain generalization capabilities, and end-to-end multimodal fusion systems to promote the practical application and widespread deployment of deep learning in aviation inspection.
4.2.3. Hybrid Algorithm Integration
- Hybrid Algorithm-Based Defect Detection MethodsHybrid algorithm integration combines the operational effectiveness of traditional algorithms, the powerful feature extraction capabilities of deep learning, and the flexible modeling advantages of machine learning, enabling a more comprehensive approach to solving complex problems. For instance, in industrial inspection, traditional algorithms can rapidly preprocess images, deep learning can accurately identify defect features, and machine learning can optimize classification decisions, thereby achieving a balance between efficiency, accuracy, and generalization. This collaborative model provides efficient and reliable solutions for complex tasks.In aircraft skin inspection, algorithm fusion is a key strategy for enhancing detection performance, with the most common approach being the integration of deep learning and traditional algorithms. Alberts et al. [81] employed the Mask R-CNN model to detect dents on aircraft surfaces and combined it with traditional image enhancement techniques such as geometric transformations and brightness adjustments, significantly improving model performance: the F1 score increased from 54% to 69%, and recall improved from 46% to 57%. This work demonstrates that even simple traditional image enhancement techniques can effectively improve the performance of deep learning models, representing a low-cost, high-benefit improvement strategy. Similarly, Plastropoulos et al. [82] used the EfficientDet D1 model to detect aircraft skin defects and incorporated traditional methods such as edge detection and morphological processing for image preprocessing, achieving an average precision of 71% under complex lighting conditions. This research shows how traditional preprocessing methods can provide cleaner input for deep learning models, thereby improving detection performance in complex environments. Additionally, Bouarfa et al. [83] proposed a semi-automatic inspection method based on human–machine collaboration, combining the autonomous flight capability of the Aerostack framework with the Fast Hierarchical Clustering and Extraction (FHCE) algorithm. The FHCE algorithm rapidly screens suspicious defect regions through edge detection and morphological operations, while the vision module of Aerostack employs a CNN to perform fine-grained classification of these candidate regions, addressing false detections in complex textures. This hierarchical processing strategy cleverly balances detection efficiency and accuracy, making it particularly suitable for resource-constrained mobile platform applications. On the other hand, Teixeira Vivaldini et al. [84] adopted a deep convolutional autoencoder (CAE) at the front end and integrated traditional rules such as area threshold filtering and shape heuristic classification for post-processing of the CAE outputs. This hybrid approach achieved an accuracy of 95.5%, significantly outperforming purely traditional methods in similar tasks. This method combines the feature learning capability of unsupervised deep learning with the interpretability of traditional rules, offering a new approach for defect detection.Similarly, researchers have explored the synergistic effects of different deep learning models. Miranda et al. [85] combined convolutional neural networks (CNNs) with generative adversarial networks (GANs), using CNNs to identify screw positions and GANs to generate screw patterns for matching actual detection results, thereby accurately identifying missing or loose screws. This dual deep learning framework leverages the feature extraction capabilities of CNNs and the data generation capabilities of GANs, providing new insights for detecting complex defects.In resource-constrained or small-data scenarios, the fusion of machine learning and traditional image processing techniques demonstrates unique advantages. Wang et al. [86] employed Genetic Algorithms (GAs) to optimize Support Vector Machine (SVM) parameters and combined them with Gray-Level Co-occurrence Matrix (GLCM) and ultrasonic signal features to detect skin cracks, achieving an average recognition accuracy of 93.3%, significantly outperforming single-sensor methods. This indicates that even in the era of deep learning, well-designed feature engineering combined with optimization algorithms still maintains a competitive advantage in small-data scenarios. Tzitzilonis et al. [87] integrated a random forest classifier with Structural Similarity (SSIM) and histogram comparison algorithms, achieving defect detection accuracy exceeding 96% for wing panels. This approach demonstrates the value of effectively combining traditional image features with machine learning models, achieving excellent detection performance while maintaining high efficiency. These methods enhance detection accuracy while maintaining efficiency through the combination of optimized algorithms and feature engineering. The development of hybrid algorithms shows that no single algorithm can perform optimally in all scenarios; selecting the appropriate combination of algorithms based on specific task requirements is the best practice.
- Current Status Analysis of Hybrid Algorithm Techniques for Aircraft Skin InspectionAs summarized in Table 6, hybrid algorithms integrate the efficiency of traditional image processing, the feature abstraction capabilities of deep learning, and the decision-making optimization strengths of machine learning, constructing a multi-level and complementary technical framework for aircraft surface defect detection. Traditional methods rapidly accomplish noise suppression and candidate region extraction during the preprocessing stage, deep learning models achieve precise identification of complex defects, and machine learning methods enhance system robustness through feature optimization and classification decisions. This integrated strategy achieves an effective balance among detection accuracy, real-time performance, and interpretability, making it particularly suitable for engineering scenarios with limited data and constrained resources. However, this approach faces core challenges such as system integration complexity due to module heterogeneity, difficulties in cross-paradigm parameter coordination, and increased computational overhead. Future efforts need to break through key technologies, including modular plug-and-play architectures, cross-modal feature alignment mechanisms, and dynamic computational path selection, to promote the large-scale application of hybrid algorithms in the field of aviation inspection.
5. Discussion
5.1. Limitations of Existing Research
- Fragmentation of Core Technical Modules: Unresolved Domain-Specific BottlenecksEach key technical link in the robotic inspection pipeline (motion planning, perception, and defect analysis) remains constrained by scenario-specific challenges, with no single module yet achieving the robustness required for complex real-world airport environments. These bottlenecks are not isolated but mutually reinforce, creating a “chain of limitations” that undermines the overall system performance: in motion planning, most methods rely on static environmental assumptions or preconfigured models, failing to adapt to dynamic interferences like moving ground support vehicles or uneven aprons, while the coupling between viewpoint generation and path planning leads to trajectory inefficiencies or stability risks (e.g., UGV tipping due to elevated centers of gravity) and the trade-off between coverage, efficiency, and imaging precision remains unresolved; in perception, weak or repetitive aircraft skin textures cause SLAM feature-matching failures and positioning drift, sensor performance degrades under extreme weather (strong light, rain, and snow) or electromagnetic interference, and dynamic obstacle detection struggles to distinguish transient disturbances from critical hazards, leading to false alarms or collision risks; in defect analysis, traditional algorithms lack generalization across defect types and environmental variations, deep learning methods face data scarcity for rare subtle defects (e.g., hairline cracks) and domain gaps between synthetic and real data, and the consistency between data acquisition (e.g., viewpoint errors during scanning) and defect analysis is often overlooked, directly degrading detection accuracy.
- Lack of Mature Integrated Systems: Gaps in Practical Validation and Safety AssuranceCurrent research focuses heavily on optimizing individual technical modules, with a notable absence of mature integrated systems that unify data acquisition (robot platform + sensors) and defect analysis (algorithms + decision-making) into a cohesive workflow. This fragmentation results in three critical gaps for practical application:First, system-level integration is incomplete. Most single-robot inspection solutions remain at the algorithmic simulation stage and lack hardware-software co-design: for instance, failing to integrate real-time data transmission (e.g., 5G for UAV visual data feedback) or targeted energy management (e.g., tethered power supply for UAVs to extend endurance and battery life optimization for UGVs under heavy sensor loads) into the inspection pipeline. Even mature single-robot platforms are rarely validated for long-term continuous operation; existing tests are typically short-duration, small-scale, or limited to static hangar environments.Second, safety and reliability mechanisms are insufficient. While OEMs like Airbus and Boeing have approved some UAV inspection solutions, these systems lack standardized safety protocols for emergency scenarios, such as UAV pose jitter under strong winds, UGV navigation failures on uneven pavements, or wall-climbing robot detachment risks on curved skin surfaces. Critical safeguards (e.g., real-time fault diagnosis, automatic return-to-home, and collision avoidance with aircraft) are either missing or unvalidated under realistic stress conditions. Additionally, there is no consensus on safety metrics (e.g., maximum allowable positioning error and acceptable false alarm rates for defects) to ensure compliance with aviation maintenance regulations.Third, operational adaptability to complex scenarios is lacking. Existing systems are optimized for specific aircraft models or fixed inspection tasks and fail to generalize across diverse aircraft types (e.g., narrow-body vs. wide-body) or extended scenarios. The absence of dynamic task scheduling (e.g., matching “flights–robots–time windows” based on flight delays) further limits their integration into actual airport operations, where inspection robots must coordinate with other ground support vehicles.
5.2. Future Research Directions
- Improvement and Adaptation of Regulatory Systems:Integrating robots into airport surface operations requires a systematic regulatory framework—this includes setting operational rules for robots based on their autonomous functions such as navigation path planning, speed limits and emergency response, and refining detailed guidelines from aspects like airport clear zone management and aircraft safety protection; currently, UAV flight in airport clear zones is strictly restricted due to safety risks, and wall-climbing robots’ contact-based measurement is banned as it may damage aircraft fuselage coatings. Nevertheless, many global and domestic firms have developed airport inspection robot products; in UAV inspection, startups Mainblades [88] and Donecle [89] stand out, having made progress in gaining Original Equipment Manufacturer (OEM) approval, with Airbus, a major aviation player, having long approved their UAVs for aircraft inspection [90] and Boeing recently having added their UAV inspection solutions to its 737 series maintenance manuals; this affirms the technology’s compliance, practicality and potential for large-scale use. Looking ahead, to promote compliant use of ground, aerial and wall-climbing inspection robots, three core steps are key: setting up differentiated access approval mechanisms tailored to different robot types and their application scenarios, building real-time full-process operation monitoring systems that track robots’ operational status to ensure stable performance in complex airport environments, and clarifying safety responsibility boundaries that define the roles of airport management entities, robot operators and R&D (Research and Development) enterprises; additionally, a cross-departmental collaborative mechanism involving airport authorities, air traffic control departments and robot R&D enterprises should be established, and emergency response plans for potential risks such as robot loss of control and equipment failure should be prepared upfront to avoid disrupting airport operations, ultimately realizing the safe and efficient integration of robot technology into airport operations.
- Collaborative Design of Multi-Type Robot Heterogeneous Systems:UGVs have strong load capacity and endurance, can carry multiple inspection devices simultaneously, and feature high motion stability, ensuring high-precision positioning and operational safety. However, limited by height, they cannot cover high-altitude areas such as the fuselage back and upper wing surfaces, and are prone to navigation deviations on complex pavements. UAVs can flexibly reach high-altitude complex parts, but suffer from weak load capacity, short endurance and poor motion stability, which easily lead to insufficient positioning accuracy or collision risks. Wall-climbing robots can operate on vertical fuselage surfaces, adapting to the inspection of special areas such as the fuselage side and engine nacelle, but their contact-based operation may damage the skin. and they have high requirements for surface flatness. Therefore, there is an urgent need to construct a heterogeneous robotic system for full-area coverage inspection of aircraft skins, focusing on researching core collaborative technologies: first, dynamic task allocation, which divides the operation scope of different robots according to the characteristics of inspection areas and adjusts dynamically (as marked in Figure 6); second, spatiotemporal registration and fusion of multi-device data, which unifies the coordinate systems of various devices to solve data blind spots; third, hardware and algorithm optimization, which improves the environmental adaptability and safety performance of robots, and reduces operational risks through obstacle avoidance algorithms.
- Intelligent and Dynamic Multi-Robot Task Scheduling:Similar to other ground support vehicles in airports, aircraft skin inspection robots need to address the problem of efficient task scheduling, with the core being the accurate matching of “flights-robots-time windows”. The scheduling system needs to combine the entire flight support process, including flight parking gaps, maintenance windows, and dynamic adjustment of flight delays, while taking into account robot operation efficiency and real-time equipment status to build a dynamic scheduling model; in addition, edge computing technology should be introduced to realize real-time issuance of scheduling instructions, and 5G communication should be used to ensure the collaborative response speed of multiple robots, avoiding operational conflicts with other support vehicles such as refueling trucks and jet bridges, and improving the overall operation efficiency of the airport surface. At the same time, the maintenance cycle of robots should be incorporated into the scheduling plan to avoid inspection interruptions due to equipment failures; for the demand for inspecting multiple flights during peak hours, a priority mechanism should be introduced to give priority to key flights, ensuring the flexibility and practicality of the scheduling system.
- Intelligent Airworthiness Assessment Based on Large Models and Expert Knowledge Bases:After robots complete defect detection, it is necessary to conduct rapid airworthiness assessments based on the inspection results, such as judging whether the aircraft has immediate take-off conditions and clarifying the priority and time limit for defect repair. This process can rely on large-model technology to build an intelligent assessment system: on the one hand, the expert knowledge base needs to cover skin defect standards for different aircraft models, the impact of environmental factors on defect propagation, and the latest airworthiness regulations; on the other hand, large models should have incremental learning capabilities to continuously incorporate new defect cases and regulatory updates, and combine defect characteristics and aircraft operating conditions to achieve automated, accurate and timely airworthiness assessments. In addition, a human–machine collaborative verification mechanism should be designed, and when there is a dispute over the assessment results of large models, it will be automatically pushed to human experts for review to ensure assessment reliability.
- Expansion and Adaptation of Skin Inspection Scenarios:Aircraft skin defect detection can be appropriately extended to residual ice/snow detection scenarios. Such detection also requires full-fuselage coverage, but faces the challenge of strong signal reflection by smooth ice surfaces, which may affect recognition accuracy. In the future, inspection algorithms can be optimized to adapt to special scenario requirements, without excessive investment in non-core technology research and development. The focus should still be on the iterative upgrading of skin defect detection technology itself, ensuring the adaptability between the extended scenarios and the core theme, and avoiding resource dispersion.
Funding
Conflicts of Interest
References
- Airports Council International (ACI). ACI World Airport Traffic Forecasts 2024–2053. 2025. Available online: https://aci.aero/2025/02/26/aci-world-projects-22-3-billion-passengers-by-2053/ (accessed on 18 September 2025).
- International Air Transport Association (IATA). IATA Safety Report 2018. 2018. Available online: https://libraryonline.erau.edu/online-full-text/iata-safety-reports/IATA-Safety-Report-2018.pdf (accessed on 18 September 2025).
- Airports Council International (ACI). Autonomous Vehicles and Systems at Airports. 2019. Available online: https://crp.trb.org/acrpwebresource13/aci-autonomous-vehicles-and-systems-at-airports-report__trashed/ (accessed on 18 September 2025).
- International Civil Aviation Organization (ICAO). ICAO Safety Report 2025 Edition: Global Aviation Safety Plan (GASP) 2023–2025. 2025. Available online: https://www.icao.int/sites/default/files/sp-files/safety/Documents/ICAO_SR_2025.pdf (accessed on 18 September 2025).
- Wang, Y.; Gogu, C.; Binaud, N.; Bes, C.; Haftka, R.T.; Kim, N.H. Predictive airframe maintenance strategies using model-based prognostics. Proc. Inst. Mech. Eng. Part O J. Risk Reliab. 2018, 232, 690–709. [Google Scholar] [CrossRef]
- Saltoğlu, R.; Humaira, N.; İnalhan, G. Aircraft scheduled airframe maintenance and downtime integrated cost model. Adv. Oper. Res. 2016, 2016, 2576825. [Google Scholar] [CrossRef]
- Plastropoulos, A.; Zolotas, A.; Avdelidis, N. A comprehensive review of robotics-aided aircraft non-destructive inspection towards the smart hangar. Aeronaut. J. 2025, 1–32. [Google Scholar] [CrossRef]
- Bardis, K.; Avdelidis, N.P.; Ibarra-Castanedo, C.; Maldague, X.P.; Fernandes, H. Advanced diagnostics of aircraft structures using automated non-invasive imaging techniques: A comprehensive review. Appl. Sci. 2025, 15, 3584. [Google Scholar] [CrossRef]
- Jess, H. Hangar of the Future. 2016. Available online: https://www.airbus.com/en/newsroom/news/2016-12-hangar-of-the-future (accessed on 1 September 2025).
- Dhoot, M.K.; Fan, I.S.; Skaf, Z. Review of Robotic Systems for Aircraft Inspection. In Proceedings of the 9th International Conference on Through-Life Engineering Service, Cranfield, UK, 3–4 November 2020; pp. 1–10. [Google Scholar]
- Groo, L.; Juhl, A.T.; Baldwin, L.A. Toward soft robotic inspection for aircraft: An overview and perspective. MRS Commun. 2024, 14, 741–751. [Google Scholar] [CrossRef]
- Yasuda, Y.D.; Cappabianco, F.A.; Martins, L.E.G.; Gripp, J.A. Aircraft visual inspection: A systematic literature review. Comput. Ind. 2022, 141, 103695. [Google Scholar] [CrossRef]
- Rodríguez, D.A.; Tafur, C.L.; Daza, P.F.M.; Vidales, J.A.V.; Rincón, J.C.D. Inspection of aircrafts and airports using UAS: A review. Results Eng. 2024, 22, 102330. [Google Scholar] [CrossRef]
- Page, M.J.; McKenzie, J.E.; Bossuyt, P.M.; Boutron, I.; Hoffmann, T.C.; Mulrow, C.D.; Shamseer, L.; Tetzlaff, J.M.; Akl, E.A.; Brennan, S.E.; et al. The PRISMA 2020 statement: An updated guideline for reporting systematic reviews. bmj 2021, 372. [Google Scholar]
- Ruiqian, L.; Juan, X.; Hongfu, Z. Automated surface defects acquisition system of civil aircraft based on unmanned aerial vehicles. In Proceedings of the 2020 IEEE 2nd International Conference on Civil Aviation Safety and Information Technology, Weihai, China, 14–16 October 2020; pp. 729–733. [Google Scholar]
- Jovančević, I. Exterior Inspection of an Aircraft Using a Pan-Tilt-Zoom Camera and a 3D Scanner Moved by a Mobile Robot: 2D Image Processing and 3D Point Cloud Analysis. Ph.D. Thesis, Ecole des Mines d’Albi-Carmaux, Albi, France, 2016. [Google Scholar]
- Bugaj, M.; Novák, A.; Stelmach, A.; Lusiak, T. Unmanned aerial vehicles and their use for aircraft inspection. In Proceedings of the 2020 New Trends in Civil Aviation (NTCA), Prague, Czech Republic, 23–24 November 2020; pp. 45–50. [Google Scholar]
- Jayalakshmi, K.; Nair, V.G.; Sathish, D. A Comprehensive Survey on Coverage Path Planning for Mobile Robots in Dynamic Environments. IEEE Access 2025, 13, 60158–60185. [Google Scholar] [CrossRef]
- Cabreira, T.M.; Brisolara, L.B.; Paulo R, F.J. Survey on coverage path planning with unmanned aerial vehicles. Drones 2019, 3, 4. [Google Scholar] [CrossRef]
- Silberberg, P.; Leishman, R.C. Aircraft inspection by multirotor UAV using coverage path planning. In Proceedings of the 2021 International Conference on Unmanned Aircraft Systems (ICUAS), Athens, Greece, 15–18 June 2021; pp. 575–581. [Google Scholar]
- Piao, M.; Li, H.; Zhang, F.; Du, X.; Yue, T.; Huang, Y. Viewpoint generation for coverage inspection of airplane fuselage surface based on unmanned ground vehicles. In Proceedings of the 2023 42nd Chinese Control Conference (CCC), Tianjin, China, 24–26 July 2023; pp. 4413–4418. [Google Scholar]
- Piao, M.; Sun, M.; Li, H.; Xie, Y. Coverage Path Planning for Aircraft Skin Inspection UGV under Curvature Constraints. In Proceedings of the CCF National Conference of Computer Applications; Springer: Singapore, 2024; pp. 201–213. [Google Scholar]
- Tong, H.W.; Li, B.; Huang, H.; Wen, C.Y. Coverage Path Planning for Autonomous Aircraft Inspection Using UAVs. In Proceedings of the AIAA SCITECH 2025 Forum, Orlando, FL, USA, 6–10 January 2025; p. 0216. [Google Scholar]
- Cao, C.; Zhang, J.; Travers, M.; Choset, H. Hierarchical coverage path planning in complex 3d environments. In Proceedings of the 2020 IEEE International Conference on Robotics and Automation (ICRA), Paris, France, 31 May–31 August 2020; pp. 3206–3212. [Google Scholar]
- Tappe, M.; Dose, D.; Alpen, M.; Horn, J. Autonomous surface inspection of airplanes with unmanned aerial systems. In Proceedings of the 2021 7th International Conference on Automation, Robotics and Applications (ICARA), Prague, Czech Republic, 4–6 February 2021; pp. 135–139. [Google Scholar]
- Almadhoun, R.; Taha, T.; Seneviratne, L.; Dias, J.; Cai, G. GPU accelerated coverage path planning optimized for accuracy in robotic inspection applications. In Proceedings of the 2016 IEEE 59th International Midwest Symposium on Circuits and Systems (MWSCAS), Abu Dhabi, United Arab Emirates, 16–19 October 2016; pp. 1–4. [Google Scholar]
- Almadhoun, R.; Taha, T.; Gan, D.; Dias, J.; Zweiri, Y.; Seneviratne, L. Coverage path planning with adaptive viewpoint sampling to construct 3D models of complex structures for the purpose of inspection. In Proceedings of the 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 1–5 October 2018; pp. 7047–7054. [Google Scholar]
- Almadhoun, R.; Taha, T.; Dias, J.; Seneviratne, L.; Zweiri, Y. Coverage path planning for complex structures inspection using unmanned aerial vehicle (UAV). In Proceedings of the International Conference on Intelligent Robotics and Applications; Springer: Cham, Switzerland, 2019; pp. 243–266. [Google Scholar]
- Liu, X.; Piao, M.; Li, H.; Li, Y.; Lu, B. Quality and Efficiency of Coupled Iterative Coverage Path Planning for the Inspection of Large Complex 3D Structures. Drones 2024, 8, 394. [Google Scholar] [CrossRef]
- Piao, M.; Luo, J.; Li, H.; Zhou, Y.; Fan, L. Cooperative Coverage Path Planning for Air-Ground Heterogeneous Robots in Aircraft Skin Inspection Tasks. In Proceedings of the CCF National Conference of Computer Applications; Springer: Singapore, 2024; pp. 123–132. [Google Scholar]
- Aleshin, B.S.; Chernomorsky, A.I.; Kuris, E.D.; Lelkov, K.S.; Ivakin, M.V. Robotic complex for inspection of the outer surface of the aircraft in its parking lot. Incas Bull. 2020, 12, 21–31. [Google Scholar] [CrossRef]
- Sun, Y.; Ma, O. Automating aircraft scanning for inspection or 3D model creation with a UAV and optimal path planning. Drones 2022, 6, 87. [Google Scholar] [CrossRef]
- Zhu, H.; Chung, J.J.; Lawrance, N.R.; Siegwart, R.; Alonso-Mora, J. Online informative path planning for active information gathering of a 3D surface. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021; pp. 1488–1494. [Google Scholar]
- Almadhoun, R.; Taha, T.; Seneviratne, L.; Zweiri, Y. Multi-robot hybrid coverage path planning for 3D reconstruction of large structures. IEEE Access 2021, 10, 2037–2050. [Google Scholar] [CrossRef]
- Hassan, M.; Liu, D. PPCPP: A predator–prey-based approach to adaptive coverage path planning. IEEE Trans. Robot. 2019, 36, 284–301. [Google Scholar] [CrossRef]
- Hassan, M.; Mustafic, D.; Liu, D. Dec-PPCPP: A decentralized predator–prey-based approach to adaptive coverage path planning amid moving obstacles. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Las Vegas, NV, USA, 24 October–24 January 2021; pp. 11732–11739. [Google Scholar]
- Zhang, J.; Zu, P.; Liu, K.; Zhou, M. A herd-foraging-based approach to adaptive coverage path planning in dual environments. IEEE Trans. Cybern. 2023, 54, 1882–1893. [Google Scholar] [CrossRef] [PubMed]
- Zhou, Y.; Sun, R.; Yu, S.; Sun, Y.; Sun, L. A complete coverage path planning algorithm for cleaning robots based on the distance transform algorithm and the rolling window approach in dynamic environments. In Proceedings of the 2017 IEEE 7th Annual International Conference on CYBER Technology in Automation, Control, and Intelligent Systems (CYBER), Honolulu, HI, USA, 31 July–4 August 2017; pp. 1335–1340. [Google Scholar]
- Liu, H.; Ma, J.; Huang, W. Sensor-based complete coverage path planning in dynamic environment for cleaning robot. CAAI Trans. Intell. Technol. 2018, 3, 65–72. [Google Scholar] [CrossRef]
- Snyder, L.V.; Daskin, M.S. A random-key genetic algorithm for the generalized traveling salesman problem. Eur. J. Oper. Res. 2006, 174, 38–53. [Google Scholar] [CrossRef]
- Li, K.; Zhang, T.; Wang, R.; Wang, Y.; Han, Y.; Wang, L. Deep reinforcement learning for combinatorial optimization: Covering salesman problems. IEEE Trans. Cybern. 2021, 52, 13142–13155. [Google Scholar] [CrossRef]
- Campos, C.; Elvira, R.; Rodríguez, J.J.G.; Montiel, J.M.; Tardós, J.D. Orb-slam3: An accurate open-source library for visual, visual–inertial, and multimap slam. IEEE Trans. Robot. 2021, 37, 1874–1890. [Google Scholar] [CrossRef]
- Shan, T.; Englot, B.; Meyers, D.; Wang, W.; Ratti, C.; Rus, D. Lio-sam: Tightly-coupled lidar inertial odometry via smoothing and mapping. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Las Vegas, NV, USA, 24 October 2020–24 January 2021; pp. 5135–5142. [Google Scholar]
- Oh, X.; Loh, L.; Foong, S.; Koh, Z.B.A.; Ng, K.L.; Tan, P.K.; Toh, P.L.P.; Tan, U.X. Initialisation of autonomous aircraft visual inspection systems via CNN-based camera pose estimation. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021; pp. 11047–11053. [Google Scholar]
- Yan, H.; Yuhang, Z.; Haobing, H.; Pengju, C. Research on Application of SLAM in Appearance Inspection of Civil Aviation Aircraft. In Proceedings of the 2022 2nd International Conference on Big Data Engineering and Education (BDEE), Chengdu, China, 5–7 August 2022; pp. 168–172. [Google Scholar]
- Saha, A.; Kumar, L.; Sortee, S.; Dhara, B.C. An autonomous aircraft inspection system using collaborative unmanned aerial vehicles. In Proceedings of the 2023 IEEE Aerospace Conference, Big Sky, MT, USA, 4–11 March 2023; pp. 1–10. [Google Scholar]
- Oelsch, M.; Karimi, M.; Steinbach, E. R-LOAM: Improving LiDAR odometry and mapping with point-to-mesh features of a known 3D reference object. IEEE Robot. Autom. Lett. 2021, 6, 2068–2075. [Google Scholar] [CrossRef]
- Liu, Y.; Dong, J.; Li, Y.; Gong, X.; Wang, J. A UAV-based aircraft surface defect inspection system via external constraints and deep learning. IEEE Trans. Instrum. Meas. 2022, 71, 5019315. [Google Scholar] [CrossRef]
- Park, I.; Cho, S. Fusion localization for indoor airplane inspection using visual inertial odometry and ultrasonic RTLS. Sci. Rep. 2023, 13, 18117. [Google Scholar] [CrossRef]
- Cazzato, D.; Olivares-Mendez, M.A.; Sanchez-Lopez, J.L.; Voos, H. Vision-based aircraft pose estimation for uavs autonomous inspection without fiducial markers. In Proceedings of the IECON 2019-45th Annual Conference of the IEEE Industrial Electronics Society, Lisbon, Portugal, 14–17 October 2019; Volume 1, pp. 5642–5648. [Google Scholar]
- Blokhinov, Y.B.; Gorbachev, V.; Nikitin, A.; Skryabin, S. Technology for the visual inspection of aircraft surfaces using programmable unmanned aerial vehicles. J. Comput. Syst. Sci. Int. 2019, 58, 960–968. [Google Scholar] [CrossRef]
- Pugliese, R.; Konrad, T.; Abel, D. LiDAR-aided relative and absolute localization for automated UAV-based inspection of aircraft fuselages. In Proceedings of the 2021 IEEE International Conference on Multisensor Fusion and Integration for Intelligent Systems (MFI), Karlsruhe, Germany, 23–25 September 2021; pp. 1–6. [Google Scholar]
- Dose, D.; Tappe, M.; Alpen, M.; Horn, J. Hardware in the loop simulation of aircraft inspection by an unmanned aerial system. In Proceedings of the 2021 7th International Conference on Automation, Robotics and Applications (ICARA), Prague, Czech Republic, 4–6 February 2021; pp. 147–151. [Google Scholar]
- Leiva, J.R.; Villemot, T.; Dangoumeau, G.; Bauda, M.A.; Larnier, S. Automatic visual detection and verification of exterior aircraft elements. In Proceedings of the 2017 IEEE International Workshop of Electronics, Control, Measurement, Signals and Their Application to Mechatronics (ECMSM), Donostia, Spain, 24–26 May 2017; pp. 1–5. [Google Scholar]
- Futterlieb, M.; Frejaville, J.; Donadio, F.; Devy, M.; Larnier, S. Air-Cobot: Aircraft Enhanced Inspection by Smart and Collaborative Robot 2017. Available online: https://laris.univ-angers.fr/_resource/IFAC2017/IFAC_Paper_3176.pdf (accessed on 18 September 2025).
- Donadio, F.; Frejaville, J.; Larnier, S.; Vetault, S. Artificial intelligence and collaborative robot to improve airport operations. In Proceedings of the Online Engineering & Internet of Things: Proceedings of the 14th International Conference on Remote Engineering and Virtual Instrumentation REV 2017, Columbia University, New York, NY, USA, 15–17 March 2017; Springer: Cham, Switzerland, 2017; pp. 973–986. [Google Scholar]
- Jovančević, I.; Larnier, S.; Orteu, J.J.; Sentenac, T. Automated exterior inspection of an aircraft with a pan-tilt-zoom camera mounted on a mobile robot. J. Electron. Imaging 2015, 24, 061110. [Google Scholar] [CrossRef]
- Rice, M.; Li, L.; Ying, G.; Wan, M.; Lim, E.T.; Feng, G.; Ng, J.; Jin-Li, M.T.; Babu, V.S. Automating the visual inspection of aircraft. In Proceedings of the Singapore Aerospace Technology and Engineering Conference (SATEC), Singapore, 7 February 2018; Volume 7, pp. 1–5. [Google Scholar]
- Siegel, M.; Gunatilake, P. Remote inspection technologies for aircraft skin inspection. In Proceedings of the Proceedings of the 1997 IEEE Workshop on Emergent Technologies and Virtual Systems for Instrumentation and Measurement, Niagara Falls, ON, Canada, 15–17 May 1997; pp. 69–78. [Google Scholar]
- Mumtaz, R.; Mumtaz, M.; Mansoor, A.B.; Masood, H. Computer aided visual inspection of aircraft surfaces. Int. J. Image Process 2012, 6, 38–53. [Google Scholar]
- Mumtaz, M.; Mansoor, A.B.; Masood, H. A new approach to aircraft surface inspection based on directional energies of texture. In Proceedings of the 2010 20th International Conference on Pattern Recognition, Istanbul, Turkey, 23–26 August 2010; pp. 4404–4407. [Google Scholar]
- Gunatilake, P.; Siegel, M.; Jordan, A.G.; Podnar, G.W. Image understanding algorithms for remote visual inspection of aircraft surfaces. In Proceedings of the Machine Vision Applications in Industrial Inspection V. SPIE, San Jose, CA, USA, 8–14 February 1997; Volume 3029, pp. 2–13. [Google Scholar]
- Yang, X.; Fan, X.; Wang, J.; Yin, X.; Qiu, S. Edge-based cover recognition and tracking method for an AR-aided aircraft inspection system. Int. J. Adv. Manuf. Technol. 2020, 111, 3505–3518. [Google Scholar] [CrossRef]
- Reyno, T.; Marsden, C.; Wowk, D. Surface damage evaluation of honeycomb sandwich aircraft panels using 3D scanning technology. NDT E Int. 2018, 97, 11–19. [Google Scholar] [CrossRef]
- Jovančević, I.; Pham, H.H.; Orteu, J.J.; Gilblas, R.; Harvent, J.; Maurice, X.; Brèthes, L. 3D point cloud analysis for detection and characterization of defects on airplane exterior surface. J. Nondestruct. Eval. 2017, 36, 74. [Google Scholar] [CrossRef]
- Lafiosca, P.; Fan, I.S.; Avdelidis, N.P. Automated aircraft dent inspection via a modified Fourier transform profilometry algorithm. Sensors 2022, 22, 433. [Google Scholar] [CrossRef] [PubMed]
- Bu, H.; Huang, N.; Huang, J.; Liu, G.; Wang, Y.; Zhu, L. Geometric feature extraction and its profile accuracy evaluation for pockets on curved aircraft skin from scanned point clouds. Meas. Sci. Technol. 2024, 36, 015021. [Google Scholar] [CrossRef]
- Fan, Y.; Deng, Y.; Zeng, Z.; Udpa, L.; Shih, W.; Fitzpatrick, G. Aging aircraft rivet site inspection using magneto-optic imaging: Automation and real-time image processing. In Proceedings of the 9th Joint FAA/DoD/NASA Aging Aircraft Conference, Atlanta, GA, USA, 6–9 March 2006; p. 9. [Google Scholar]
- Deng, Y.; Liu, X.; Fan, Y.; Zeng, Z.; Udpa, L.; Shih, W. Characterization of magneto-optic imaging data for aircraft inspection. IEEE Trans. Magn. 2006, 42, 3228–3230. [Google Scholar] [CrossRef]
- Gray, I.; Padiyar, M.; Petrunin, I.; Raposo, J.; Zanotti Fragonara, L.; Kostopoulos, V.; Loutas, T.; Psarras, S.; Sotiriadis, G.; Tzitzilonis, V.; et al. A novel approach for the autonomous inspection and repair of aircraft composite structures. In Proceedings of the Proceedings of the 18th European Conference on Composite Materials, Athens, Greece, 24–28th June 2018; pp. 24–28. [Google Scholar]
- Zheng, J.; Xie, W.; Viens, M.; Birglen, L.; Mantegh, I. Design of an advanced automatic inspection system for aircraft parts based on fluorescent penetrant inspection analysis. Insight-Non-Destr. Test. Cond. Monit. 2015, 57, 18–34. [Google Scholar] [CrossRef]
- Buckhorst, A.F.; Kluge-Wilkes, A.; Schmitt, R.H. Flying Metrology and Defect Identification for Aircraft Surface Inspection: Automated optical investigation of aircraft surfaces after lightning strike events. PhotonicsViews 2019, 16, 68–71. [Google Scholar] [CrossRef]
- Suvittawat, N.; Ribeiro, N.A. Aircraft surface defect inspection system using AI with UAVs. In Proceedings of the Doctoral Symposium-ICRAT, Singapore, 1–4 July 2024. [Google Scholar]
- Connolly, L.; Garland, J.; O’Gorman, D.; Tobin, E.F. Deep-Learning-Based Defect Detection for Light Aircraft With Unmanned Aircraft Systems. IEEE Access 2024, 12, 83876–83886. [Google Scholar] [CrossRef]
- Wang, H.; Fu, L.; Wang, L. Detection algorithm of aircraft skin defects based on improved YOLOv8n. Signal Image Video Process. 2024, 18, 3877–3891. [Google Scholar] [CrossRef]
- Zhang, W.; Liu, J.; Yan, Z.; Zhao, M.; Fu, X.; Zhu, H. FC-YOLO: An aircraft skin defect detection algorithm based on multi-scale collaborative feature fusion. Meas. Sci. Technol. 2024, 35, 115405. [Google Scholar] [CrossRef]
- Liao, K.C.; Lau, J.; Hidayat, M. An innovative aircraft skin damage assessment using you only look once-version9: A real-time material evaluation system for remote inspection. Aerospace 2025, 12, 31. [Google Scholar] [CrossRef]
- Gaul, N.J.; Leishman, R.C. Artificial dataset generation for automated aircraft visual inspection. In Proceedings of the NAECON 2021-IEEE National Aerospace and Electronics Conference, Dayton, OH, USA, 16–19 August 2021; pp. 302–306. [Google Scholar]
- Li, H.; Wang, C.; Liu, Y. Aircraft skin defect detection based on Fourier GAN data augmentation under limited samples. Measurement 2025, 245, 116657. [Google Scholar] [CrossRef]
- Kähler, F.; Schmedemann, O.; Schüppstuhl, T. Anomaly detection for industrial surface inspection: Application in maintenance of aircraft components. Procedia CIRP 2022, 107, 246–251. [Google Scholar] [CrossRef]
- Alberts, C.; Carroll, C.; Kaufman, W.; Perlee, C.; Siegel, M. Automated inspection of aircraft. Technical Report; CARNEGIE-MELLON INST OF RESEARCH PITTSBURGH PA: Pittsburgh, PA, USA, 1998. [Google Scholar]
- Plastropoulos, A.; Bardis, K.; Yazigi, G.; Avdelidis, N.P.; Droznika, M. Aircraft skin machine learning-based defect detection and size estimation in visual inspections. Technologies 2024, 12, 158. [Google Scholar] [CrossRef]
- Bouarfa, S.; Doğru, A.; Arizar, R.; Aydoğan, R.; Serafico, J. Towards Automated Aircraft Maintenance Inspection. A use case of detecting aircraft dents using Mask R-CNN. In Proceedings of the AIAA Scitech 2020 Forum, Orlando, FL, USA, 6–10 January 2020; p. 0389. [Google Scholar]
- Teixeira Vivaldini, K.C.; Franco Barbosa, G.; Santos, I.A.D.; Kim, P.H.; McMichael, G.; Guerra-Zubiaga, D.A. An intelligent hexapod robot for inspection of airframe components oriented by deep learning technique. J. Braz. Soc. Mech. Sci. Eng. 2021, 43, 494. [Google Scholar] [CrossRef]
- Miranda, J.; Larnier, S.; Herbulot, A.; Devy, M. UAV-based inspection of airplane exterior screws with computer vision. In Proceedings of the VISIGRAPP (4: VISAPP), Prague, Czech Republic, 25–27 February 2019; pp. 421–427. [Google Scholar]
- Wang, C.; Wang, X.; Zhou, X.; Li, Z. The aircraft skin crack inspection based on different-source sensors and support vector machines. J. Nondestruct. Eval. 2016, 35, 46. [Google Scholar] [CrossRef]
- Tzitzilonis, V.; Malandrakis, K.; Zanotti Fragonara, L.; Gonzalez Domingo, J.A.; Avdelidis, N.P.; Tsourdos, A.; Forster, K. Inspection of aircraft wing panels using unmanned aerial vehicles. Sensors 2019, 19, 1824. [Google Scholar] [CrossRef] [PubMed]
- Mainblades. Mainblades Official Website: UAV-Based Aircraft Inspection Solutions. Available online: https://mainblades.com/ (accessed on 18 September 2025).
- Donecle. Donecle Solution: Aircraft Inspection Analysis Report. Available online: https://www.donecle.com/solution/#analyseReport (accessed on 18 September 2025).
- Airbus. Innovation Takes Aircraft Visual Inspections to New Heights. 2018. Available online: https://www.airbus.com/en/newsroom/news/2018-04-innovation-takes-aircraft-visual-inspections-to-new-heights (accessed on 18 September 2025).
Inclusion Criteria | Exclusion Criteria |
---|---|
|
|
Ref. | Sensor Type | Defect Types | Approach | Advantages | Disadvantages |
---|---|---|---|---|---|
2D Image Processing | |||||
[16] | PTZ Camera | Dents, Scratches, Corrosion | Region growing (normals/curvature) | Fast; low cost; rapid inspection. | Lighting sensitive; no 3D measurement. |
[57] | PTZ Camera | Cracks, Dents | HT, EDCircles, Color Segmentation | Modular; low cost; occlusion resistant. | Lighting sensitive; high computation; weak micro-defects. |
[58] | Depth/PTZ Camera | Cracks, Scratches, Fastener abnorm. | 3D Mapping, Multi-scale Features | Multi-sensor; accurate 3D; user-friendly. | Needs 3D model; surface defects only; lighting sensitive. |
[59] | Eddy Current/Stereo Camera | Cracks, Corrosion, Scratches | Multi-scale Edge Detection, NN | Remote safe; sensor fusion; enhanced detection. | Lighting sensitive; high false positives; precise positioning needed. |
[60] | Visible Light Camera | Cracks, Scratches | Threshold, Gabor, NN Classification | High accuracy; non-contact; fast; automatable. | Lighting sensitive; clear images needed; large training data. |
[61] | Visible Light Camera | Cracks, Scratches | Contourlet/DCT Fusion | High accuracy; non-contact; good texture analysis. | Lighting sensitive; clear images needed; feature overlap errors. |
[62] | Stereo/Navigation Camera, Dynamic Lighting | Cracks, Corrosion | Wavelet Edge Detection, NN | High precision; remote inspection; robust multi-scale. | Lighting/image quality sensitive; high false alarms; complex. |
3D Point Cloud Analysis | |||||
[63] | Intel RealSense D435 | Cover recognition | Edge extraction, VO, EPnP | Real-time; textureless objects; similar covers distinguished. | Depth quality dependent; motion/lighting sensitive; no micro-defects. |
[64] | FARO® Edge 3D Scanner | Dents | Laser Scan + CAD Fitting + Deviation Analysis | Non-contact; fast; accurate; auto damage recording. | Dense sampling needed; pro software; particle sensitive; high cost. |
[65] | Artec Eva 3D Scanner | Dents, Protrusions, Scratches | Point Cloud Processing + Region Growing | Non-contact; multi-defect; automated; lighting insensitive. | Point cloud quality dependent; high computation; manual thresholds. |
[66] | USB Camera + Laser Projector | Dents | Modified FTP (Phase Unwrapping + Triangulation) | Vibration resistant; auto filtering; accurate; low cost. | Lighting sensitive; laser speckle; boundary artifacts; slow processing. |
[67] | 3D Laser Scanner | Geometric accuracy | Curvature-aware extraction + Geodesic Analysis | High accuracy; no special tooling; cost-effective. | Point cloud quality dependent; noise sensitive; no surface defects. |
[70] | PA Ultrasound, IRT | Delamination | PA + IRT + Laser Repair | High precision internal; non-contact; fast automation. | Complex; costly; skilled operators needed; thermal risks. |
[68] | MOI Sensor | Rivet fatigue cracks | MOI + Motion Filtering + Skewness Classification | Fast large-area; lift-off insensitive; low false alarms. | Limited depth; background noise; edge integrity sensitive. |
Multi-modal Data Fusion | |||||
[69] | MOI Sensor | Cracks, Corrosion | MOI + Quantitative Characterization | Fast large-area; lift-off insensitive; surface/near-surface. | Sensor noise; limited non-crack defects; limited depth. |
[71] | UV Light + CCD Camera | Surface discontinuities | FPI + Image Processing | High sensitivity; complex geometry; low cost large areas. | Surface defects only; clean surface needed; noise sensitive; limited classification. |
[72] | Industrial Camera, iGPS, IMU | Lightning strike defects | UAV Imaging + AI Classification | Fast detection; accurate positioning; high automation. | High false positives; light/image dependent; manual review needed. |
Ref. | Sensor Type | Defect Types | Approach | Advantages | Disadvantages |
---|---|---|---|---|---|
Deep Learning-based Detection | |||||
[51] | HD camera (visible light), indoor positioning camera, IMU | Surface damage | UAV autonomous flight + YOLOv3 detection + DL defect recognition | High automation; GPS-denied applicable; fast detection; records defect location. | Relies on large training data; lighting/background sensitive; manual review needed; surface defects only. |
[73] | CMOS camera | Cracks, Dents, Scratches, Paint-off, Missing Rivet | YOLOv9 + UAV + RTMP real-time transmission | Real-time detection; high accuracy; remote access; hard-to-reach areas applicable. | Lighting sensitive; weak small-defect detection; RTMP delay; poor paint-off/scratch performance. |
[74] | 14MP Full HD 1080p camera | Rust, Scratches, Missing Rivet | YOLOv8 + UAV + Roboflow annotation/augmentation | Low cost; accessible hardware; real-time detection; high accuracy; blind spot inspection. | Limited defect types; lighting/shooting angle sensitive; low small-defect accuracy. |
[75] | iPhone XR, ZED 2i stereo vision camera | Corrosion, Fastener abnorm., Panel missing | YOLOv8 (PyTorch) + Albumentations + LabelImg | UAS improves safety/efficiency; semi-auto annotation optimizes training. | Lighting/color sensitive; poor scarce-sample generalization; manual annotation dependent. |
[76] | Nikon D3400, Huawei Mate40 Pro, iPhone13 | Cracks, Corrosion, Pits, Paint peeling | Improved YOLOv8n (Shuffle Attention++, BiFPN, SIOU+Focal Loss) | High accuracy; fast; small-object/complex-background robust; lightweight. | Missing some defect types (e.g., fastener abnorm.); extreme lighting/occlusion untested. |
[77] | Mobile platform-mounted cameras | Cracks, Deform, Rivet damage, Paint peel | FC-YOLO (YOLOv7-based) + CCA attention + A-PAN (ASFF) | High accuracy; strong multi-scale fusion; suppresses feature conflict; lightweight. | Slight speed reduction; missing some defect types (e.g., delamination); extreme condition untested. |
[78] | 3D rendering | Dents, Paint damage | Blender 3D synthetic data + auto annotation | Large accurately annotated data; flexible damage/lighting control; low cost; no physical collection. | Domain gap between synthetic/real data; affects real-scenario generalization. |
[79] | DJI Mavic 2 Pro, wall-climbing robot | Loose, Lose, Corrosion, Skin damage | Fourier GAN (HFSD + HFC) + Transformer | Improves detection accuracy with limited real samples; high-quality defect images. | Sensitive to light/angle changes. |
[80] | Industrial camera | Corrosion | Convolutional Autoencoder (anomaly detection) | No defect samples needed; detects unknown anomalies; scarce-defect applicable. | Blurry reconstructed images; high false positives; noise sensitive; not engineering-ready. |
Ref. | Sensor Type | Defect Types | Approach | Advantages | Disadvantages |
---|---|---|---|---|---|
Hybrid Algorithm-Based Detection | |||||
[81] | Reflection eddy current sensor, navigation camera, close-view camera | Cracks, Corrosion, Fastener Abnormalities, Scratches, Dents | Traditional: image preprocessing, matched filtering; deep: CNN for feature extraction | Combines traditional robustness with deep learning advantages; improves rivet recognition accuracy. | Complex system; large computation; dependent on high-quality training data. |
[82] | UAV-mounted camera, handheld camera, phone camera | Dents, Missing Paint, Scratches, Repair, Screw | Deep: CNN-based detection (EfficientDet, YOLO); traditional: Canny edge detection, contour analysis | Automatically detects multiple defects; good for challenging dents; complex background adaptable. | Low dent recall; sensitive to dataset imbalance; size estimation error-prone. |
[83] | Vision sensor | Dents | Mask R-CNN (segmentation) + traditional image enhancement | Pixel-level precise segmentation; good for irregular dents; transfer learning alleviates small samples. | High annotation cost; sensitive to lighting/reflection; prone to false positives. |
[84] | Raspberry Cam v2 (8MP RGB) | Fastener abnormalities - missing and improper installation | Hexapod robot + CAE + traditional rules (area filtering, shape classification) | Real-time automated detection; reduces annotated data dependence. | Single defect type only; sensitive to lighting/image quality; robot stability affects results. |
[85] | LiDAR, PTZ camera | Fastener abnormalities - missing/loose screws | CNN detection + GAN + bipartite matching (Hungarian algorithm) | High accuracy; complex lighting adaptable; non-contact. | Relies on 3D model; high computation; limited real-time performance. |
[86] | CCD image sensor, ultrasonic sensor | Cracks, Corrosion | Multi-source fusion + SVM + GA optimization | Multi-sensor improves accuracy; overcomes single sensor limitations. | Time-consuming; poor real-time; performance depends on parameter optimization. |
[87] | UV light source + wide-angle camera | Corrosion, Cracks | Traditional: SSIM, histogram comparison; ML: Random Forest classifier | High accuracy; fast training; reduces manual intervention. | Large computation; prone to false positives with few samples; image quality dependent. |
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. |
© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/).
Share and Cite
Piao, M.; Wang, X.; Wang, W.; Xie, Y.; Lu, B. A Review of Robotic Aircraft Skin Inspection: From Data Acquisition to Defect Analysis. Mathematics 2025, 13, 3161. https://doi.org/10.3390/math13193161
Piao M, Wang X, Wang W, Xie Y, Lu B. A Review of Robotic Aircraft Skin Inspection: From Data Acquisition to Defect Analysis. Mathematics. 2025; 13(19):3161. https://doi.org/10.3390/math13193161
Chicago/Turabian StylePiao, Minnan, Xuan Wang, Weiling Wang, Yonghui Xie, and Biao Lu. 2025. "A Review of Robotic Aircraft Skin Inspection: From Data Acquisition to Defect Analysis" Mathematics 13, no. 19: 3161. https://doi.org/10.3390/math13193161
APA StylePiao, M., Wang, X., Wang, W., Xie, Y., & Lu, B. (2025). A Review of Robotic Aircraft Skin Inspection: From Data Acquisition to Defect Analysis. Mathematics, 13(19), 3161. https://doi.org/10.3390/math13193161