Next Article in Journal
Performance Analysis of Maximum Likelihood Detection in Cooperative DF MIMO Systems with One-Bit ADCs
Previous Article in Journal
A Mathematical Method for Predicting Tunnel Pressure Waves Based on Train Wave Signature and Graph Theory
Previous Article in Special Issue
Development Status and Trend of Mine Intelligent Mining Technology
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Collision Detection Algorithms for Autonomous Loading Operations of LHD-Truck Systems in Unstructured Underground Mining Environments

School of Resources and Safety Engineering, Central South University, Changsha 410083, China
*
Author to whom correspondence should be addressed.
Mathematics 2025, 13(15), 2359; https://doi.org/10.3390/math13152359
Submission received: 19 June 2025 / Revised: 15 July 2025 / Accepted: 22 July 2025 / Published: 23 July 2025
(This article belongs to the Special Issue Mathematical Modeling and Analysis in Mining Engineering)

Abstract

This study addresses collision detection in the unmanned loading of ore from load-haul-dump (LHD) machines into mining trucks in underground metal mines. Such environments present challenges like heavy dust, confined spaces, sensor occlusions, and poor lighting. This work identifies two primary collision risks and proposes corresponding detection strategies. First, for collisions between the bucket and tunnel walls, LiDAR is used to collect 3D point cloud data. The point cloud is processed through filtering, downsampling, clustering, and segmentation to isolate the bucket and tunnel wall. A KD-tree algorithm is then used to compute distances to assess collision risk. Second, for collisions between the bucket and the mining truck, a kinematic model of the LHD’s working device is established using the Denavit–Hartenberg (DH) method. Combined with inclination sensor data and geometric parameters, a formula is derived to calculate the pose of the bucket’s tip. Key points from the bucket and truck are then extracted to perform collision detection using the oriented bounding box (OBB) and the separating axis theorem (SAT). Simulation results confirm that the derived pose estimation formula yields a maximum error of 0.0252 m, and both collision detection algorithms demonstrate robust performance.

1. Introduction

The intelligentization of underground metal mining has been developing rapidly. Automation in fixed workstations has reached a relatively mature stage, and research on the intelligentization of mobile equipment is gaining increasing attention [1,2]. As a crucial piece of mining equipment, the load-haul-dump (LHD) machine plays a fundamental role in the intelligentization of mines, attracting considerable attention [3,4]. Some mining sites have already begun trial operations of remotely controlled LHDs [5,6]. However, research on the intelligentization of LHD operations in specific scenarios remains limited. For instance, achieving fully unmanned ore loading into mining trucks remains a significant challenge.
The ore loading process presents several safety hazards, including improper coordination between the LHD machine and the mining truck; falling ore during loading that may strike the truck body or the driver; collisions between the LHD machine, the mining truck, or the surrounding tunnel walls; and failure of operators to follow safety regulations. Additionally, the ore loading environment is typically complex, characterized by high noise levels and dust pollution, both of which can adversely affect workers’ health and safety [7]. Therefore, achieving unmanned ore loading is of great significance in reducing workplace accidents and enhancing operational safety.
When the LHD machine and the mining truck operate in narrow and complex underground tunnels, collision risks exist in addition to the dangers posed by manual operation. Therefore, to successfully achieve unmanned ore loading, it is essential to fully account for potential collisions. Developing a collision detection algorithm tailored to the underground mining environment and the ore loading process is thus crucial. This algorithm must be capable of issuing timely warnings before potential collisions occur and guiding the control system to make necessary adjustments to ensure operational safety.
Collision detection refers to the process of determining whether two or more objects come into contact at one or more points. Current research in collision detection addresses the trade-off between accuracy and efficiency through several principal methodologies. An initial distinction often arises from sensor modality. Although vision-based detection systems demonstrate advantages in open environments [8,9,10,11,12], the challenges posed by light attenuation and dust interference in underground mining conditions have led researchers to explore LiDAR point cloud data as an alternative solution.
One prominent trajectory, model-based detection, circumvents external sensors by monitoring a system’s intrinsic dynamics. Foundational methods infer collisions from discrepancies between predicted and measured motor torque [13], while more advanced techniques use sophisticated observers to estimate external forces with greater sensitivity [14]. This approach has been further enhanced by integrating neural networks to compensate for complex nonlinearities like friction [15] or to serve as powerful classifiers within a momentum-observer framework [16]. Innovations in signal processing using “envelope-like lines” [17] and time-series analysis (TSA) [18] have also pushed the boundaries of creating a truly sensorless detection paradigm.
In parallel, the classical geometry-centric paradigm provides high-fidelity detection founded upon geometric representations. This approach is dominated by bounding volume hierarchies (BVHs), which use a variety of primitives—from simple spheres [19] to complex, application-tailored hybrid models combining shapes like ellipsoidal bounding boxes (EBBs), oriented bounding boxes (OBBs), and capsules [20,21,22]. The fidelity of these hierarchies is continually refined through improved axis-aligned bounding box (AABB) structures [23] and advanced node calculation methods [24]. To handle unstructured data from sensors like LiDAR, these methods are often augmented with spatial partitioning techniques such as KD-trees [25] and octrees [26] or voxel-based representations [27,28]. This can involve representing objects as “stretched primitives” [29] or employing multi-stage pipelines that sequentially filter and segment point clouds before generating bounding boxes [30,31]. Further innovations enhance performance through techniques like dual-resolution depth maps [32], depth-buffer comparison [33], and novel data structures [34]. Other works reformulate the problem entirely, using signed distance functions (SDFs) [35] or pseudodistance metrics [36] to improve efficiency.
More recently, a paradigm shift toward data-driven and AI approaches seeks to overcome the limitations of explicit modeling. End-to-end frameworks like CollisionNet learn to recognize collisions directly from sensor signals [37], while hybrid models such as DLGJK synergize the speed of deep learning for coarse checks with the precision of classical algorithms like the Gilbert–Johnson–Keerthi (GJK) for fine-level verification [38].
Complementing these core methodologies is a significant body of research focused on system-level and algorithmic optimization. This includes enhancing broad-phase algorithms like sweep-and-prune with temporal inference [39] or kinetic, event-driven mechanisms [40]. Hardware acceleration is another critical vector, leveraging GPU pipelines [41] and parallelization techniques like SIMD-KD trees [42]. In parallel, memory optimization is addressed through novel BVH representations with binary encodings [43] and specialized architectures like QuickNN that tackle memory bandwidth bottlenecks [44]. The research scope has also broadened beyond simple binary checks to include probabilistic methods for both general and specific applications [45,46], acceleration techniques that identify high-probability “feature points” [47], and algorithms designed to improve iterative efficiency [48]. This trend toward specialization is further underscored by custom data structures for high-resolution models [49] and tailored strategies for specific industrial machinery [50] or internal components like flexible joints [51].
In summary, significant progress has been made in the research of collision detection algorithms, with most efforts focused on improving algorithm efficiency and theoretical foundations. However, there has been little attention given to collision detection specifically for the operational scenarios of underground mining shovels. The mining operations studied in this paper are conducted in underground metal mining environments, which are characterized by heavy dust, confined spaces, and complex lighting conditions, making visual sensors such as cameras unsuitable. During the ore loading operation, the boom of the LHD needs to be lifted, which can obstruct the sensors and lead to missing scan data. Therefore, it is essential to develop an efficient and safe collision detection system specifically designed for unmanned ore loading in view of the complex underground environment and the possible collision situation during ore loading operation.
This study was conducted on the basis that both the LHD machine and the mining truck have already achieved autonomous operation. The potential collisions during the ore loading process were classified into two scenarios. The first scenario involves a collision between the bucket and the tunnel wall during the boom’s lifting process, while the second scenario concerns a collision between the bucket and the mining truck when dumping ore. For the first scenario, the point cloud data collected by the LiDAR were first processed using distance filtering and voxel downsampling. Then, the density-based spatial clustering of applications with noise (DBSCAN) algorithm was applied for clustering, and finally, collision detection was performed using nearest neighbor search based on the KD-tree. For the second scenario, the Denavit–Hartenberg (DH) parameter method was used to establish the kinematic model of the LHD’s working device, and the mathematical formula for calculating the bucket tooth tip pose was derived. Based on the geometric shapes of the bucket and the mining truck, an appropriate OBB was constructed. Collision detection was then conducted using the separating axis theorem (SAT). Finally, experiments were conducted in a simulated environment. The results demonstrate that the proposed pose calculation formula and collision detection algorithm are effective and feasible, well-suited for underground mining environments and ore loading operations. The complete workflow integrating these two approaches and their experimental validation is visually summarized in Figure 1.

2. Materials and Methods

2.1. Construction of a Simulation Environment for Ore Loading Operations in Underground Metal Mines

A realistic simulation environment representing an underground metal mine was constructed on the Isaac Sim platform. Isaac Sim, a physics-based robotics simulation platform developed by NVIDIA, was engineered to accelerate the development and testing of robots and automation systems. This platform features a high-fidelity physics engine and supports the entire robotics development lifecycle, from conceptual design to deployment. The simulation was executed on a workstation equipped with an Intel(R) Core(TM) i7-10700K CPU @ 3.80GHz (Intel Corporation, Santa Clara, CA, USA) and an NVIDIA GeForce RTX 2060 SUPER GPU (NVIDIA Corporation, Santa Clara, CA, USA) and running the Ubuntu 20.04 operating system.
As depicted in Figure 2, the simulation environment comprises three primary components: a tunnel, an LHD machine, and a mining truck. The LHD’s operational movements, which include linear translation (forward/backward), turning, boom actuation (lifting/lowering), and bucket tilting, were controlled via Python scripting. These scripted actions enable the simulation of the complete ore loading process from the LHD to the mining truck. The version of Python used in our research is Python 3.10.15.

2.2. LiDAR-Based Collision Detection Between the Bucket and the Tunnel

The ore loading process, which involves transferring material from an LHD machine to a mining truck, necessitates the preliminary lifting of the LHD’s boom. As the boom ascends within the confined space of an underground tunnel, the risk of collision between the bucket and the tunnel walls increases significantly. Such collisions can lead to spillage of ore and pose considerable safety hazards. To mitigate this risk, this study proposes a method that utilizes LiDAR to acquire 3D point cloud data of the operating environment, encompassing both the tunnel walls and the LHD bucket. The acquired point cloud data are then processed through a sequential pipeline of filtering, downsampling, clustering, and segmentation. Finally, collision risk is assessed by performing a nearest-neighbor search, accelerated by a KD-tree data structure.

2.2.1. LiDAR Installation Position and Data Acquisition

Since both the tunnel and the bucket need to be detected simultaneously during boom lifting, it is essential to select a LiDAR with a large vertical field of view and carefully consider its installation position. In this study, a multi-line mechanical LiDAR is used, featuring a horizontal field of view of 120° and a vertical field of view of 60°. It is installed at a height of 2.8 m from the chassis of the LHD. The LiDAR position and scanning range are shown in Figure 3.

2.2.2. Point Cloud Preprocessing

The raw point cloud data collected from the LiDAR are typically large and dense; therefore, a preprocessing stage is essential to facilitate efficient subsequent processing. This stage consists of two primary steps. The first step involves a distance-based filtering to remove points located far from the LiDAR sensor, which are irrelevant to collision detection and unnecessarily increase the computational load for subsequent stages. The second step is voxel grid downsampling, a technique that reduces point cloud density while preserving the overall geometric structure without significant alteration. This reduction in data volume decreases the computational time for subsequent algorithms, a crucial factor for achieving real-time performance.
A key parameter in the distance filtering process is the maximum range threshold. This threshold was set to 7 m, a value determined based on the LHD’s dimensions and its effective operational envelope. During the loading cycle, points beyond this range are considered irrelevant for imminent collision detection, so this filtering step effectively isolates the region of interest and significantly reduces the computational load for subsequent stages. The result of this filtering step is visualized in Figure 4.
In voxel downsampling, the 3D space is partitioned into a grid of cubic cells known as voxels. The principle of this method is to replace all points contained within each non-empty voxel with a single representative point. Typically, this representative point is the centroid (average) of the contained points. Voxel downsampling is computationally efficient and promotes a more uniform spatial distribution of points. The voxel size parameter directly controls the sparsity of the output point cloud. In this study, a voxel size of 0.1 m was used. This value represents a carefully considered trade-off between preserving sufficient geometric detail and ensuring real-time performance. Our empirical tests within the simulation environment confirmed that 0.1 m provides the optimal balance for this application, as a smaller size would increase computational cost unnecessarily, while a larger size could risk over-simplifying critical geometric features. The result of the voxel downsampling is illustrated in Figure 5.
By applying these two preprocessing steps, extraneous points are eliminated, enabling the collision detection algorithm to focus on the relevant target area. The significant reduction in the point count decreases the computational load and accelerates the algorithm’s execution. Furthermore, key geometric features are preserved, and the point distribution becomes more uniform, ensuring that subsequent clustering algorithms can operate effectively and yield accurate results.

2.2.3. Point Cloud Clustering and Segmentation

Point cloud clustering is the process of partitioning a point cloud dataset into distinct subsets, i.e., clusters, based on specific similarity criteria. Typically, points within a given cluster exhibit high similarity (e.g., spatial proximity), whereas points in different clusters are dissimilar.
The point cloud data collected by the LiDAR present several challenges that necessitate a sophisticated clustering approach. The data contain not only the intended targets (the bucket and tunnel) but also other components of the LHD, which manifest as noise or distinct objects. Furthermore, dynamic movements, such as the boom being raised, cause partial occlusions that alter the scanned area and data density. Consequently, the number and shape of object clusters are unknown and cannot be predetermined.
To address these conditions—namely the presence of noise, arbitrarily shaped clusters, and an unknown number of clusters—we employ the classical DBSCAN algorithm, as originally proposed by Ester et al. [52]. This method is particularly well-suited for our task because it identifies clusters based on local point density. Its core idea is to define clusters as high-density regions separated by areas of low density. This density-driven approach allows DBSCAN to effectively distinguish meaningful object clusters from sparse noise and discover clusters of arbitrary shapes, all without requiring the number of clusters as a predefined input.
The principles of DBSCAN can be described through the following core concepts:
1.
Core point: A point is considered a core point if its neighborhood (i.e., within a radius ε ) contains at least m i n P t s points. In other words, the density around the point is greater than or equal to m i n P t s ;
2.
Border point: A point is located within the neighborhood of another core point, but it is not itself a core point. Specifically, its neighborhood contains fewer than m i n P t s points, but it belongs to the neighborhood of a core point;
3.
Noise point: A point that is neither a core point nor a border point. It does not belong to any cluster and is typically considered an outlier or noise;
4.
Neighborhood: Given a point p , its neighborhood refers to all points within a radius ε of p .
The performance of DBSCAN is highly dependent on the choice of two key parameters: the neighborhood radius ( ε ) and the minimum number of points ( m i n P t s ). In this study, these parameters were determined through extensive empirical testing within our simulation environment to find the optimal values for our specific application.
We ultimately set ε to 0.11 m and m i n P t s to 4. The rationale for these specific values is as follows: The 0.11 m radius is slightly larger than our voxel grid size (0.1 m), which ensures that points on the same object surface, even if located in adjacent voxels, can be robustly connected into a single cluster. This value is also small enough to maintain a clear distinction between the bucket and tunnel wall during close-approach scenarios, thus preventing erroneous cluster merging. The m i n P t s value of 4 was found to be sufficient to identify the surfaces of our key objects after downsampling while still effectively filtering out isolated noise points. This combination provided the best balance between clustering sensitivity and noise immunity in our tests.
DBSCAN forms clusters by connecting neighboring points based on density. If a point is a core point, and there are other points within its neighborhood, these points will be connected to form a cluster. This process continues iteratively until the entire cluster is expanded. Points that cannot be connected to any cluster are considered noise. The clustered point cloud is shown in Figure 6.
The next step involves segmenting the output of the clustering algorithm to isolate the point clouds corresponding to the bucket and the tunnel wall for subsequent collision detection. Based on the a priori knowledge that the tunnel wall and bucket are the largest objects in the scene, the clusters are sorted by point count, and the two largest clusters are extracted. The final segmented point cloud, containing only the two target clusters, is shown in Figure 7.

2.2.4. Collision Detection Based on KD-Tree

A KD-ree is a space-partitioning data structure, organized as a binary tree, for storing points in a K-dimensional space. It enables efficient nearest-neighbor searches by recursively partitioning the space into nested regions. Each node in the tree corresponds to a data point and defines a hyperplane that splits the space into two half-spaces, represented by its child nodes. The splitting dimension typically cycles through the coordinates as the tree depth increases, distributing points into left and right subtrees. In collision detection, the process involves querying the nearest-neighbor distance between points in one point cloud and those in another to determine whether a collision has occurred.
In this section, we aim to detect whether the bucket has collided with the tunnel. The algorithm for implementing this collision detection is outlined as follows:
1.
Constructing the KD-tree: Build a KD-tree for the tunnel point cloud. This process partitions the space and organizes the tunnel point cloud into a tree structure;
2.
Setting the collision threshold: Define a d i s t a n c e _ t h r e s h o l d to determine whether two points are considered to be in collision;
3.
Iterating through the bucket point cloud: For each point in the bucket point cloud, use the KD-tree to query the nearest point in the tunnel point cloud;
4.
Computing the Euclidean distance: Calculate the Euclidean distance between the query point P 2 and its nearest neighbor P 1 in the tunnel point cloud using the formula
d P 1 , P 2 = x 2   x 1 2 + y 2   y 1 2 + z 2   z 1 2
where P 1   = x 1   , y 1 , z 1 and P 2 = x 2 , y 2 , z 2 are the coordinates of the two points;
5.
Querying the nearest neighbor: Utilize the KD-tree to search for the nearest neighbor in the tunnel point cloud. The query process can be represented using the following formula:
n e a r e s t n e i g h b o r P 2 = a r g min   d P 1 , P 2
P 2 is the query point from the bucket point cloud, while P 1   is the nearest point to P 2 found in the KD-tree, originating from the tunnel point cloud. The Euclidean distance between them is denoted as d P 1 , P 2 ;
6.
Collision determination: If the computed distance is smaller than the predefined threshold ( d i s t a n c e _ t h r e s h o l d ), a collision is considered to have occurred:
d P 1 , P 2 < d i s t a n c e _ t h r e s h o l d
where d P 1 , P 2 represents the Euclidean distance between P 1 and P 2 , and d i s t a n c e _ t h r e s h o l d is the predefined distance threshold.
If the distance between any pair of points is smaller than the threshold, a collision alert is triggered. If all points are checked and no collision is detected, the algorithm concludes that no collision has occurred.
The complete algorithmic workflow, presented as pseudocode, is divided into two main parts. Algorithm 1 details the point cloud preprocessing stage, which includes distance-based filtering and voxel grid downsampling. Algorithm 2 describes the subsequent pipeline for clustering, segmentation, and collision detection. This algorithm first clusters the point cloud using DBSCAN (with parameters ε and m i n P t s ), then segments the two largest clusters (the tunnel and bucket). Finally, it computes the minimum distance between these two clusters to determine if it falls below the predefined collision threshold.
Algorithm 1: PointCloudPreprocessor
Input:
  P_raw, The raw point cloud from the LiDAR sensor;
  d_max, The maximum distance threshold for filtering. (e.g., 7 m);
  v_size, The voxel size for downsampling. (e.g., 0.1).
Output:
  P_processed, The preprocessed (filtered and downsampled) point cloud.
1function PreprocessPointCloud(P_raw, d_max, v_size):
2  // Step 1: Filter by Distance
3  P_filtered ← an empty point cloud
4  for each point p in P_raw:
5      dist ← Calculate Euclidean distance of p from the origin
6      if dist < d_max then
7           P_filteredP_filtered ∪ {p}
8    end if
9  end for
10  // Step 2: Voxel Grid Downsampling
11  P_processed ← VoxelGridDownsample(P_filtered, v_size)
12  return P_processed
13
14function VoxelGridDownsample(P_in, voxel_size):
15   Create a voxel grid with resolution voxel_size over P_in
16   P_out ← an empty point cloud
17   for each non-empty voxel v in the grid:
18      p_centroid ← Compute the centroid of all points within v
19      P_outP_out ∪ {p_centroid}
20   end for
21   return P_out
Algorithm 2: DBSCAN Clustering and Collision Detection
Input:
  P_in, a preprocessed point cloud;
  eps, DBSCAN radius;
  min_pts, DBSCAN minimum points;
  N, number of clusters to select;
  τ, collision threshold.
Output:
  CollisionAlert, a boolean value.
1function ClusterAndCheckCollision(P_in, eps, min_pts, N, τ):
2// Step 1: Point Cloud Clustering
3labels ← DBSCAN(P_in, eps, min_pts)
5// Step 2: Select Largest Clusters
6all_clusters ← Group points from P_in by labels (excluding noise)
7 Sort all_clusters by size in descending order
8largest_clusters ← Select top N clusters from all_clusters
9C_tunnellargest_clusters[0]
10C_bucketlargest_clusters[1]
12// Step 3: Collision Detection
13kd_tree ← BuildKDTree(C_tunnel)
14for each point p in C_bucket:
15  dist ← FindNearestNeighborDistance(p, kd_tree)
16  if dist < τ then
17    return True // Collision detected
18  end if
19end for
20
21return False // No collision detected

2.3. Collision Detection Algorithm Based on the Pose of Key Points on the Bucket

During ore loading operations, there is a significant risk of collision between the LHD bucket and the mining truck. Such incidents can disrupt the operational workflow, cause equipment damage, and pose considerable safety risks. Therefore, it is crucial to detect potential collisions between the bucket and the mining truck. However, during the loading process, due to the lifting and lowering of the boom as well as the retraction and tilting of the bucket and the limited installation positions of sensors, the scanning range of the sensors may be obstructed, preventing them from fully capturing the bucket and the mining truck. In this case, the sensors are ineffective. This section establishes a DH kinematic model for the LHD’s working device and uses forward kinematics to calculate the precise pose of the bucket’s tip. Based on the geometric parameters of the bucket, the poses of key points on the bucket are then derived, and an OBB is constructed. For the mining truck, the poses of key points are derived based on the pose of the truck’s sensors and its geometric parameters. An OBB is constructed for each face of the truck. The OBB of the bucket is then checked for collisions with the OBB of each face of the truck using the SAT.

2.3.1. Kinematic Model of the LHD’s Working Device

The main components of the LHD’s working device consist of the boom, bucket, and other mechanisms such as the hydraulic cylinder, rocker, and linkage, as shown in Figure 8.
Robot kinematics is a field of study concerned with the motion of robotic manipulators, encompassing both forward and inverse kinematics. Forward kinematics solves for the pose (position and orientation) of the end-effector given a set of known joint variables. Conversely, inverse kinematics determines the required joint variables to achieve a desired end-effector pose. In forward kinematics, the spatial relationship between adjacent links is described by a homogeneous transformation matrix, representing six degrees of freedom (three translational and three rotational). By sequentially multiplying these transformation matrices from the base to the end-effector, the forward kinematic chain is computed, yielding the end-effector’s pose relative to the base coordinate system.
The DH parameter model is a widely used standardized method for representing and describing the relationships between the joints and links of a robotic arm. It uses a set of four parameters to represent the relative position and orientation of each joint and link in the robotic arm [53].
The core principle of the DH model is to define the spatial relationship between two consecutive links, using a minimal set of four parameters:
1.
θ i : Joint angle (rotation angle), which represents the rotation of the previous link relative to the current link around the Z i 1   axis. This parameter is typically associated with the rotation of the joint, with clockwise rotation defined as negative and counterclockwise rotation as positive;
2.
d i : Link offset (translation), which represents the displacement of the current link along the Z i 1 axis. This parameter is typically associated with the displacement of the joint;
3.
a i : Link length, which represents the distance between the previous and current links along the X i axis. This parameter describes the fixed length between the links;
4.
α i : Link twist angle, which represents the rotation of the previous link relative to the current link around the X i axis.
Using these four parameters, a 4 × 4 transformation matrix can be constructed to describe the relative transformation from the coordinate frame of l i n k i 1 to the coordinate frame of l i n k i . The transformation matrix ( T i 1 i ) for each joint can be represented as
T i 1 i = cos θ i sin θ i cos α i sin θ i sin α i a i cos θ i sin θ i cos θ i cos α i cos θ i sin α i a i sin θ i 0 sin α i cos α i d i 0 0 0 1
By sequentially multiplying these individual transformation matrices, the total transformation matrix from the base frame to the end-effector frame, T 0 n , can be computed as
T 0 n = T 0 1 T 1 2 T n 1 n
Using this matrix, the position and orientation of the end effector can be determined, enabling kinematic analysis and control. The coordinate systems of each link in the LHD’s working mechanism, established using the DH modeling method, are shown in Figure 9.
1.
O 1 , O 2 , and O 3 represent the origins of the three coordinate systems. O 1 is the articulation point between the boom and the base, O 2 is the articulation point between the bucket and the boom, and O 3 is located at the tip of the bucket;
2.
The z 1 , z 2 , and z 3 axes are parallel and perpendicular to the O 1 X 1 Y 1 plane;
3.
The X 1 axis is along the reference horizontal plane, the X 2 axis points in the direction of O 1 O 2 , and the X 3 axis points in the direction of O 2 O 3 .
The resulting DH parameters for the LHD’s working device are summarized in Table 1.

2.3.2. Forward Kinematics Analysis

Based on the previously established DH parameter model, the homogeneous transformation matrices between adjacent joints of the LHD’s working device are computed.
T 1 2 = cos θ 1 sin θ 1 0 l 1 cos θ 1 sin θ 1 cos θ 1 0 l 1 sin θ 1 0 0 1 0 0 0 0 1
T 2 3 = cos θ 2 sin θ 2 0 l 2 cos θ 2 sin θ 2 cos θ 2 0 l 2 sin θ 2 0 0 1 0 0 0 0 1
By multiplying these matrices, the total transformation from the base frame O 1 to the bucket tip frame O 3 is obtained as shown in Equation (8):
T 1 3 = T 1 2 T 2 3       = cos θ 1 + θ 2 sin θ 1 + θ 2 0 l 2 cos θ 1 + θ 2 + l 1 cos θ 1 sin θ 1 + θ 2 cos θ 1 + θ 2 0 l 2 sin θ 1 + θ 2 + l 1 sin θ 1 0 0 1 0 0 0 0 1
From this transformation matrix, the coordinates of the bucket tip in the base coordinate system are extracted as presented in the equations below:
x 3 = l 2 c o s θ 1 + θ 2 + l 1 c o s θ 1 y 3 = l 2 s i n θ 1 + θ 2 + l 1 s i n θ 1 z 3 = 0
From the above equation, it can be seen that by knowing θ 1 , θ 2 , l 1 , and l 2 , the pose corresponding to the bucket tip of the LHD can be determined. l 1 and l 2 are fixed parameters of the LHD and remain constant. Therefore, only the rotation angles θ 1 and θ 2 of the boom and bucket joints need to be calculated.
To facilitate this calculation, a simplified kinematic model of the LHD’s working device is introduced, as illustrated in Figure 10.
The measurement value of the inclination sensor represents the angle between its body and the horizontal direction, with positive values indicating an upward inclination and negative values indicating a downward inclination. Inclination Sensor1 is installed along the line connecting the boom pivot point O 1 and the rocker pivot point O 4 , with the measurement denoted as α 1 . Inclination Sensor2 is installed along the direction of O 4 O 5 , with the measurement denoted as α 2 . Inclination Sensor3 is installed along the direction of O 2 O 6 , with the measurement denoted as α 3 .
The first step is to calculate the boom’s rotation angle ( θ 1 ). θ 1 represents the angle between O 1 O 2 and the O 1 X 1 axis.
θ 1 = α 1 O 2 O 1 O 4
In triangle O 2 O 1 O 4 , the side lengths of this triangle are fixed structural parameters of the LHD. Using the law of cosines, the angle O 2 O 1 O 4 can be determined.
O 2 O 1 O 4 = arccos ( l O 1 O 2 2 + l O 1 O 4 2 l O 2 O 4 2 2 l O 1 O 2 l O 1 O 4 )
Next, the rotation angle θ 2 of the bucket is calculated.
θ 2 = π O 1 O 2 O 4 O 4 O 2 O 3
In triangle O 2 O 1 O 4 , the value of O 1 O 2 O 4 can be determined using the law of cosines.
O 1 O 2 O 4 = arccos ( l O 1 O 2 2 + l O 2 O 4 2 l O 1 O 4 2 2 l O 1 O 2 l O 2 O 4 )
In triangle O 2 O 4 O 5 , O 2 O 4 , O 4 O 5 , and O 5 O 2 are all fixed parameters of the LHD, and the value of O 2 O 4 O 5 can also be determined using the law of cosines.
O 2 O 4 O 5 = arccos ( l O 2 O 4 2 + l O 4 O 5 2 l O 2 O 5 2 2 l O 2 O 4 l O 4 O 5 )
In triangle O 2 O 7 O 3 :
O 2 O 7 O 3 = α 2 O 2 O 4 O 5
In triangle O 7 O 2 O 8 :
O 7 O 2 O 8 = O 2 O 7 O 3 + α 3 = α 2 O 2 O 4 O 5 + α 3
In triangle O 3 O 2 O 8 :
O 8 O 2 O 3 = O 2 O 6 O 3 + O 2 O 3 O 6
Thus, the results can be obtained as follows.
O 4 O 2 O 3 = O 8 O 2 O 3 O 7 O 2 O 8 = O 2 O 6 O 3 + O 2 O 3 O 6 + α 2 + O 2 O 4 O 5 α 3
Finally, by substituting all computed values back into Equation (11), a comprehensive formula for θ 2 is obtained (Equation (18)).
θ 2 = π O 1 O 2 O 4 O 4 O 2 O 3 = π l O 1 O 2 2 + l O 2 O 4 2 l O 1 O 4 2 2 l O 1 O 2 l O 2 O 4 O 2 O 6 O 3 O 2 O 3 O 6 α 2 O 2 O 4 O 5 + α 3
O 2 O 6 O 3 , O 2 O 3 O 6 , and O 2 O 4 O 5 are fixed parameters of the LHD.
Based on the above formula, the values of θ 1 and θ 2 can be determined. By substituting these values into Equations (6) and (8), the coordinates of the bucket–boom hinge point ( O 2 ) and the bucket tooth tip ( O 3 ) can be obtained. These calculated coordinates are referenced to the O 1 coordinate system and must be further transformed into the world coordinate system.
For more precise collision detection, it is also necessary to determine the coordinates of the key points of the bucket based on its geometric relationships. There are six key points in total, as shown in Figure 11a.
To determine the coordinates of all key points, it is necessary to first calculate the coordinates of points A and B , as shown in Figure 11b. The triangle A B O 3 lies in the same plane and is perpendicular to the horizontal plane. In triangle A O 2 O 3 , the coordinate O 2 corresponds to the previously obtained bucket–arm hinge point, and O 3 represents the bucket tooth tip. The side lengths A O 2 , O 2 O 3 , and A O 3 are fixed parameters of the bucket.
A O 2 O 3 = arccos ( l A O 2 2 + l O 2 O 3 2 l A O 3 2 2 l A O 2 l O 2 O 3 )
The slope of O 2 O 3 is k O 2 O 3 , so the angle between O 2 O 3 , and the horizontal line is given by arctan k O 2 O 3 . The angle between O 2 A and the horizontal line is given by a n g l e O 2 A = arctan k O 2 O 3 + A O 2 O 3 . Thus, the coordinates of point A are
x A = x O 2                                                                                               y A = l A O 2 cos a n g l e O 2 A + y O 2 z A = l A O 2 sin a n g l e O 2 A + z O 2
In triangle B O 2 O 3 , the coordinate O 2 corresponds to the bucket–arm hinge point, and O 3 represents the bucket tooth tip. The side lengths B O 2 , O 2 O 3 , and B O 3 are fixed parameters of the bucket.
B O 2 O 3 = arccos ( l B O 2 2 + l O 2 O 3 2 l B O 3 2 2 l B O 2 l O 2 O 3 )
The angle between O 2 B and the horizontal line is given by
a n g l e O 2 B = arctan k O 2 O 3 B O 2 O 3
The coordinates of point B are
x B = x O 2                                                                                               y B = l B O 2 cos a n g l e O 2 B + y O 2 z B = l B O 2 sin a n g l e O 2 B + z O 2
After obtaining the coordinates of points A and B , the six key points of the bucket can be determined by incorporating the bucket’s width.

2.3.3. Constructing the OBB

The OBB is the minimum-volume rectangular prism that tightly encloses an object or a point cloud. Unlike an AABB, an OBB’s orientation is aligned with the principal axes of the enclosed object rather than being constrained to the world coordinate axes. This tighter fit reduces the enclosed volume, thereby enhancing the precision and efficiency of subsequent collision detection algorithms [54].
The construction of the OBB follows these steps:
1.
Compute the principal direction of the point cloud: The first step in constructing an OBB is determining the primary direction of the point cloud. This is typically achieved using principal component analysis (PCA), which identifies the principal directions by analyzing the covariance matrix of the point cloud. The principal direction corresponds to the direction with the highest variance in the data;
2.
Steps of PCA: Compute the mean of the point cloud:
μ = 1 N i = 1 N x i .
where x i represents the i -th point in the point cloud, and μ is the mean of all points.
Compute the covariance matrix of the point cloud:
= 1 N i = 1 N ( x i μ ) ( x i μ ) T
Performing eigenvalue decomposition yields the eigenvectors and eigenvalues of the covariance matrix. The eigenvectors represent the principal directions, while the eigenvalues indicate the variance along each direction;
3.
Rotating the point cloud: Using the principal direction obtained from PCA, a rotation matrix is constructed so that after the point cloud is projected into the new coordinate system, the principal direction aligns with the coordinate axes;
4.
Calculating the dimensions of the point cloud: After rotation, the point cloud typically forms a rectangular box along three axes. The dimensions (length, width, and height) of the bounding box can be determined by calculating the maximum and minimum values of the rotated point cloud along each axis.
Assumptions of the projections of the rotated point cloud on the X, Y, and Z are as follows:
m i n x = min x r o t ,         m a x x = max x r o t m i n y = min y r o t   ,         m a x y = max y r o t m i n z = min z r o t ,         m a x z = max z r o t
The l e n g t h , w i d t h , and h e i g h t of the bounding box are as follows:
l e n g t h = m a x x m i n x w i d t h = m a x y m i n y h e i g h t = m a x z m i n z
5.
Determine the center point and rotation information of the bounding box: The center ( c ) of the OBB is the mean of the rotated point cloud:
c = μ
The rotation information is provided by the rotation matrix calculated through PCA, which represents the rotation of the bounding box relative to the world coordinate system.
The PCA-based method described above is standard for constructing an OBB from a general, dense point cloud. However, in our specific application, the structures of the bucket and truck are well-defined and geometrically simple. Therefore, instead of using a full point cloud, we simplify the process by extracting a small set of key points (e.g., the six vertices of the bucket). The OBB is then constructed directly from these key points using geometric principles analogous to those in PCA.
The OBB for the bucket is constructed from the set of its six previously computed key points. Similarly, an OBB for the mining truck could be constructed from the vertices of its cargo bed. However, as the truck’s cargo bed is an open, concave container (effectively a rectangular prism missing its top face), a single OBB would poorly represent its geometry. A single OBB is not applicable, as it would enclose a large empty volume above the cargo bed, leading to inaccurate collision detection (i.e., false positives). To address this issue, our approach models the truck’s cargo bed as a composite of its five constituent planar surfaces. A distinct OBB is then constructed for each of these five faces. A visualization of the resulting OBBs for both the bucket and the truck is provided in Figure 12.

2.3.4. SAT Method for Collision Detection

The SAT is a geometric algorithm for determining whether two convex polyhedra are intersecting. The core principle of SAT states that two convex objects do not intersect if and only if there exists a “separating axis” onto which the projections of the two objects do not overlap. Conversely, if the objects’ projections overlap on all potential separating axes, the objects are deemed to be intersecting [54].
The basic process of the SAT algorithm can be divided into the following steps:
1.
Generation of candidate separating axes:
For two 3D objects, the normal directions of each surface are first extracted as the primary separating axes. Next, the perpendicular direction of the direction vectors of each pair of edges between the two objects is calculated (using the cross product), and these directions are added to the set of candidate axes. Finally, all axes are merged and duplicates are removed to form a complete list of separating axes to be tested;
2.
Projection onto separating axes:
For each separating axis, the projection of both objects onto the axis is computed. If the projections of the two objects overlap, they are not separated along that axis; if the projections do not overlap on any axis, the objects are not colliding. For each object, the minimum and maximum values of its projection on the separating axis are calculated, resulting in a projection interval. These intervals are then compared to check if they overlap;
3.
Collision determination:
If the projection intervals of the two objects do not overlap on any separating axis, the objects are considered not to collide. If the projection intervals of the two objects overlap on all separating axes, it indicates that a collision has occurred.
In conclusion, during the ore loading process from the LHD to the mining truck, the bucket may collide with the mining truck. Based on the pose of key points, OBBs for both the bucket and the mining truck are constructed, and the SAT method is used to detect whether the bucket’s OBB collides with the OBB of the mining truck.

3. Results

In this study, a simulated underground metal mining environment was constructed using the Isaac Sim simulation platform. The environment includes tunnels, an LHD machine, and a mining truck. A series of experiments were conducted within this simulation environment to verify the feasibility of the proposed collision detection algorithm.

3.1. Experimental Setup

The experiments were performed on the Isaac Sim platform, running on a workstation with an Intel Core i7-10700K CPU (Intel Corporation, Santa Clara, CA, USA), an NVIDIA GeForce RTX 2060 SUPER GPU (NVIDIA Corporation, Santa Clara, CA, USA), and Ubuntu 20.04. The simulated environment features a tunnel, an LHD machine, and a mining truck.
  • Algorithm 1 (LiDAR-based) Parameters:
    • LiDAR Sensor: 120° horizontal FoV, 60° vertical FoV.
    • Voxel Downsampling: Voxel size = 0.1 m.
    • DBSCAN: Neighborhood radius ( ε ) = 0.11 m, minimum points ( m i n P t s ) = 4. These parameters were empirically tuned to balance sensitivity and noise rejection.
    • Collision Threshold: 0.15 m. An alarm is triggered if the minimum distance between the bucket and tunnel point clouds is less than this value.
2.
Algorithm 2 (Kinematics-based) Parameters:
  • Sensor Model: The inclination sensors were simulated to provide ideal, noise-free measurements. This approach was chosen to validate the intrinsic accuracy of the kinematic model itself.
  • Evaluation Metric: The SAT output. A negative overlap value indicates a collision (penetration), with its magnitude representing the penetration depth. A positive value indicates separation, with its magnitude representing the minimum clearance distance between the OBBs.

3.2. Verification of the Bucket Tooth Tip Pose

To verify the accuracy of the bucket tooth tip pose formula, experiments were conducted within the simulation environment. First, the LHD machine’s boom was raised to its maximum height within the tunnel. Then, the bucket was controlled to rotate downward to its maximum angle. During this process, both the ground truth and measured values of the bucket tooth tip pose were recorded for subsequent calculation and analysis. A total of 493 ground truth and 493 measured pose values were obtained. These values were rounded to four decimal places, and their distribution in 3D space is shown in Figure 13.
This paper evaluates the proximity between the ground truth and measured values of the bucket tooth tip pose by calculating the Euclidean distance between them. The calculation results are shown in Table 2.
From the calculation results, it is observed that the maximum distance between the ground truth and measured values is 0.0252 m. Considering the large size of the LHD, this distance falls within a reasonable range. The minimum distance is 0 m, as the sensor measurements in the simulation environment are highly accurate, allowing for the possibility of a zero distance. The average distance is 0.0141 m, indicating that throughout the entire ore loading process, the pose error remains relatively stable. This low error margin is crucial, as it confirms that the kinematic model is a highly reliable foundation for the subsequent OBB construction and collision detection. The high accuracy validates that our method of using inclination sensors and geometric calculations can effectively and precisely track the bucket’s pose, even when external sensors like LiDAR are occluded. This lays a solid foundation for the reliability of the kinematics-based collision detection algorithm.

3.3. Validation of Collision Detection Algorithm in Different Scenarios

3.3.1. Validation of Bucket and Tunnel Wall Collision Detection Algorithm

During the upward lifting process of the LHD’s boom, there is a potential for the bucket to collide with the tunnel wall. Since the tunnel wall is arch-shaped, this study performed 100 lifting actions of the LHD’s boom on the left (Figure 14), middle (Figure 15), and right (Figure 16) sides of the tunnel to verify the effectiveness of the collision detection algorithm.
To test the effectiveness and reliability of the LiDAR-based algorithm (Section 2.2) in preventing collisions between the bucket and the tunnel wall, three challenging scenarios were designed to simulate common operational risks. In each scenario, the LHD attempts to lift its boom 100 times.
  • Scenario 1: LHD positioned close to the left tunnel wall (Figure 14);
  • Scenario 2: LHD positioned in the center of the tunnel (Figure 15);
  • Scenario 3: LHD positioned close to the right tunnel wall (Figure 16).
When the system detects a collision between the bucket and the tunnel wall, the distance between the two is recorded, as shown in the figures below.
The performance of the algorithm was rigorously validated through 300 trials, achieving a perfect 100% detection rate with no instances of false alarms or missed detections, establishing its exceptional reliability. A deeper analysis of the results, presented in Figure 17, Figure 18 and Figure 19 reveals a critical insight: alarms were consistently triggered when the minimum distance was just shy of the 0.15 m threshold. This outcome has two profound implications for the system’s effectiveness. Firstly, it validates that the 0.15 m threshold is not merely a random value but a well-calibrated parameter that provides a timely and practical safety margin. Secondly, and more critically, it underscores the power of the DBSCAN clustering algorithm. The ability to maintain the integrity of two distinct point cloud clusters when they are nearly in contact is a non-trivial challenge. The algorithm’s success here proves that DBSCAN effectively prevents cluster merging, a common failure mode that would lead to a catastrophic missed detection. Therefore, the synergistic effect of a precise threshold and a robust clustering method confirms the validity and superiority of our proposed approach.

3.3.2. Verification of the Collision Detection Algorithm for the Bucket and Mining Truck

To verify the feasibility of the collision detection algorithm between the bucket and the mining truck, three distinct operational scenarios were tested, with each scenario repeated 100 times. During the experiments, the collision detection results and the distances between the separating axes were recorded. Specifically, after traversing all separating axes, the overlap on each axis was calculated. If there was any axis with no overlap, the smallest positive overlap among all axes was recorded. If all axes had overlap, the largest negative overlap was recorded. The experimental location is shown in Figure 20.
First, without lifting the boom, the LHD approaches the mining truck at varying speeds. This experiment was repeated 100 times, and the results, as shown in Figure 21, demonstrate that collisions were successfully detected in each instance, as expected. The range of the maximum negative overlap during each collision was (−3.4209 m, −2.8743 m).
Next, a series of operations in the simulated ore loading process were conducted, including the LHD dumping ore into the mining truck. This experiment was repeated 100 times, and the results, as shown in Figure 22, demonstrate that no collision was detected when the bucket entered the mining truck’s compartment, as expected, since the truck’s compartment is not a completely enclosed space. The range of the minimum positive overlap during non-collision events was (0.0120 m, 0.0455 m).
The LHD’s position was moved directly above the edge of the mining truck. If ore loading operations were performed at this position, a collision would inevitably occur when the LHD dumped the ore. This experiment was repeated 100 times, and the results, as shown in Figure 23, demonstrate that a collision was detected every time, as expected. The range of the maximum negative overlap during each collision was (−1.5760 m, −1.2952 m).
The results show a perfect 100% success rate in correctly identifying the outcome for all 300 trials. The SAT output provides unambiguous results. In collision scenarios (1 and 3), the system consistently reported a negative overlap (Figure 21 and Figure 23), confirming penetration. The magnitude of this value can even serve as an indicator of the potential severity of the collision. The success of Scenario 2 is particularly significant. The algorithm correctly registered no collision, reporting a small but safe positive separation distance (Figure 22). This directly validates our design choice to model the open truck bed as five individual planar OBBs. A naive single-OBB approach would have enclosed the empty space above the cargo bed, leading to constant false alarms during this critical, normal operational phase. Our method completely avoids this pitfall. The algorithm’s ability to differentiate between the safe clearance in Scenario 2 and the definite collision in Scenario 3, which can be geometrically very similar, showcases the high precision of the SAT method when applied to accurately constructed OBBs.
In conclusion, the comprehensive experimental results provide compelling quantitative validation for the two proposed collision detection algorithms. We have demonstrated that
  • The kinematic pose formula achieves centimeter-level accuracy (1.41 cm average error), establishing a reliable foundation for the subsequent collision detection;
  • The algorithm for bucket-and-tunnel collision detection, which is based on LiDAR, provides 100% reliable, real-time protection. Its robustness is underscored by the DBSCAN method’s success in preventing cluster-merging failures, even when the objects are in extreme proximity;
  • The kinematics-based algorithm for bucket-and-truck collision detection also achieved a perfect 100% success rate, critically overcoming the challenges of sensor occlusion and solving the intractable false-alarm problem inherent in naive models of the open-top truck.
By synergistically combining these two complementary algorithms, this study delivers a holistic safety solution that provides comprehensive coverage for the entire ore loading process in challenging underground environments.

4. Discussion

The findings of this study confirm that the proposed dual-algorithm system provides a robust and reliable solution for collision detection in LHD loading operations. The successful validation of the kinematic model with centimeter-level accuracy is not merely a confirmation of the DH parameters but rather establishes the viability of a model-based approach as a powerful fallback for when direct-sensing methods, like LiDAR, are compromised by occlusion—a frequent occurrence in confined underground environments.
In the context of previous studies, much of the existing work on kinematic modeling has focused on equipment like excavators in open-pit mines or construction sites. Our research extends this paradigm to the unique challenges of underground mining, specifically addressing the critical failure point of sensor occlusion during the bucket–truck interaction. Furthermore, our solution for the truck collision problem represents a significant advancement. While OBBs and SAT are established techniques, our key innovation lies in the multi-faceted OBB representation of the truck bed. This novel approach effectively resolves the persistent issue of false-positive alarms that plagues naive, single-volume models, demonstrating a practical path toward system reliability that previous approaches have not addressed.
The broader implications of this work are twofold. From a practical safety perspective, this system offers a tangible pathway to reducing equipment damage, operational downtime, and, most importantly, human-involved accidents in one of the most hazardous phases of underground mining. It represents a critical enabling technology for higher levels of automation. From a technological standpoint, our work underscores the power of a synergistic, complementary system design. By combining a perception-based algorithm (LiDAR) for general awareness with a model-based algorithm (kinematics) for precision tasks under occlusion, we showcase a robust architectural pattern applicable to a wide range of autonomous robotic systems operating in complex, unstructured environments.
However, we must acknowledge the limitations of this study, which in turn highlight promising directions for future research. A primary limitation is the reliance on an ideal, noise-free sensor model in the simulation. Future work should incorporate stochastic sensor models to rigorously evaluate the system’s robustness and explore the integration of state estimation filters (e.g., Kalman filters) to handle real-world data imperfections. Secondly, this validation was conducted entirely within a simulation. The ultimate test will be the deployment and verification of this system on a physical LHD platform in a real-world mining environment. Finally, our current work focuses on static obstacles (tunnel and parked truck); extending the system to detect and react to dynamic obstacles, such as other vehicles or personnel, remains a critical next step towards a fully comprehensive safety solution.

5. Conclusions

In response to the complex environment of underground metal mines and the unmanned ore loading process, we developed a collision detection algorithm tailored to this context. The algorithm employs laser radar to address the challenges of the underground environment, and it incorporates a series of preprocessing steps such as point cloud filtering, downsampling, clustering, and segmentation. Collision detection is then performed based on a KD-tree structure with appropriately set thresholds. To address the issue of sensor occlusion, we derived a calculation formula for the bucket tooth pose. Using the geometric features of the bucket, we calculated the pose of key points on the bucket and established bounding boxes, which were subsequently used for collision detection via the SAT. Experimental results show that our pose calculation formula is applicable to the entire ore loading process, providing accurate results. The collision detection algorithms for both the bucket–tunnel wall and the bucket–mining truck are equally effective and function well in the underground metal mining environment.

Author Contributions

Conceptualization, M.L. and P.P.; methodology, M.L.; validation, M.L. and R.L.; investigation, M.L. and Y.L. (Ya Liu); resources, M.L.; data curation, M.L.; writing—original draft preparation, M.L.; writing—review and editing, P.P., L.W. and Y.L. (Yongchun Liu); visualization, M.L., C.Z. and Y.Z.; supervision, Y.Z., Y.L. (Ya Liu) and C.Z.; project administration, P.P.; funding acquisition, P.P. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the National Key Research and Development Program of China under grant 2022YFC2904105 and 2023YFC2907403, the National Natural Science Foundation of China under grant 52374168, the Science and Technology Innovation Program of Hunan Province under grant 2023RC3069.

Data Availability Statement

Data are contained within the article.

Conflicts of Interest

The authors declare no conflicts of interest.

Abbreviations

The following abbreviations are used in this manuscript:
LHDLoad-haul-dump
DHDenavit–Hartenberg
OBBOriented bounding box
SATSeparating axis theorem
AABBAxis-aligned bounding box
DBSCANDensity-based spatial clustering of applications with noise
PCAPrincipal component analysis
TSATime-series analysis
BVHsBounding volume hierarchies
EBBsEllipsoidal bounding boxes
SDFsSigned distance functions
GJKGilbert–Johnson–Keerthi

References

  1. Li, J.; Zhan, K. Intelligent Mining Technology for an Underground Metal Mine Based on Unmanned Equipment. Engineering 2018, 4, 381–391. [Google Scholar] [CrossRef]
  2. Cucuzza, J. The Status and Future of Mining Automation: An Overview. IEEE Ind. Electron. Mag. 2021, 15, 6–12. [Google Scholar] [CrossRef]
  3. Wang, J.; Wang, L.; Peng, P.; Jiang, Y.; Wu, J.; Liu, Y. Efficient and Accurate Mapping Method of Underground Metal Mines Using Mobile Mining Equipment and Solid-State Lidar. Measurement 2023, 221, 113581. [Google Scholar] [CrossRef]
  4. Wang, J.; Wang, L.; Jiang, Y.; Peng, P.; Wu, J.; Liu, Y. A Novel Global Re-Localization Method for Underground Mining Vehicles in Haulage Roadways: A Case Study of Solid-State LiDAR-Equipped Load-Haul-Dump Vehicles. Tunn. Undergr. Space Technol. 2025, 156, 106270. [Google Scholar] [CrossRef]
  5. Xiao, W.; Liu, M.; Chen, X. Research Status and Development Trend of Underground Intelligent Load-Haul-Dump Vehicle—A Comprehensive Review. Appl. Sci. 2022, 12, 9290. [Google Scholar] [CrossRef]
  6. Huh, S.; Lee, U.; Shim, H.; Park, J.-B.; Noh, J.-H. Development of an Unmanned Coal Mining Robot and a Tele-Operation System. In Proceedings of the 2011 11th International Conference on Control, Automation and Systems, Gyeonggi-do, Republic of Korea, 26–29 October 2011; IEEE: Piscataway, NJ, USA, 2011; pp. 31–35. [Google Scholar]
  7. Ranjan, A.; Zhao, Y.; Sahu, H.B.; Misra, P. Opportunities and Challenges in Health Sensing for Extreme Industrial Environment: Perspectives from Underground Mines. IEEE Access 2019, 7, 139181–139195. [Google Scholar] [CrossRef]
  8. Maric, B.; Jurican, F.; Orsag, M.; Kovacic, Z. Vision Based Collision Detection for a Safe Collaborative Industrial Manipulator. In Proceedings of the 2021 IEEE International Conference on Intelligence and Safety for Robotics (ISR), Tokoname, Japan, 4–6 March 2021; IEEE: Piscataway, NJ, USA, 2021; pp. 334–337. [Google Scholar]
  9. Bauer, P.; Hiba, A. Vision Only Collision Detection with Omnidirectional Multi-Camera System. IFAC-Pap. 2017, 50, 15215–15220. [Google Scholar] [CrossRef]
  10. Zhang, F.; Liu, H.; Chen, Z.; Wang, L.; Zhang, Q.; Guo, L. Collision Risk Warning Model for Construction Vehicles Based on YOLO and DeepSORT Algorithms. J. Constr. Eng. Manag. 2024, 150, 04024053. [Google Scholar] [CrossRef]
  11. Lu, S.; Xu, Z.; Wang, B. Human-Robot Collision Detection Based on the Improved Camshift Algorithm and Bounding Box. Int. J. Control Autom. Syst. 2022, 20, 3347–3360. [Google Scholar] [CrossRef]
  12. Imam, M.; Baina, K.; Tabii, Y.; Ressami, E.M.; Adlaoui, Y.; Benzakour, I.; Abdelwahed, E.H. The Future of Mine Safety: A Comprehensive Review of Anti-Collision Systems Based on Computer Vision in Underground Mines. Sensors 2023, 23, 4294. [Google Scholar] [CrossRef] [PubMed]
  13. Xiang, Q.; Chen, C.; Jiang, Y. Servo Collision Detection Control System Based on Robot Dynamics. Sensors 2025, 25, 1131. [Google Scholar] [CrossRef] [PubMed]
  14. Sun, S.; Song, C.; Wang, B.; Huang, H. Research on Dynamic Parameter Identification and Collision Detection Method for Cooperative Robots. Ind. Robot. 2023, 50, 1024–1035. [Google Scholar] [CrossRef]
  15. Xu, T.; Fan, J.; Fang, Q.; Zhu, Y.; Zhao, J. A New Robot Collision Detection Method: A Modified Nonlinear Disturbance Observer Based-on Neural Networks. J. Intell. Fuzzy Syst. 2020, 38, 175–186. [Google Scholar] [CrossRef]
  16. Ye, J.; Fan, Y.; Kang, Q.; Liu, X.; Wu, H.; Zheng, G. MomentumNet-CD: Real-Time Collision Detection for Industrial Robots Based on Momentum Observer with Optimized BP Neural Network. Machines 2025, 13, 334. [Google Scholar] [CrossRef]
  17. Zhang, T.; Hong, J. Collision Detection Method for Industrial Robot Based on Envelope-like Lines. Ind. Robot. 2019, 46, 510–517. [Google Scholar] [CrossRef]
  18. Zhang, T.; Ge, P.; Zou, Y.; He, Y. Robot Collision Detection Without External Sensors Based on Time-Series Analysis. J. Dyn. Syst. Meas. Control 2021, 143, 041005. [Google Scholar] [CrossRef]
  19. Zhang, D.; Zhao, J.; Zhang, H. Six-Degree-of-Freedom Manipulator Fast Collision Detection Algorithm Based on Sphere Bounding Box. In Proceedings of the 2024 2nd International Conference on Artificial Intelligence and Automation Control (AIAC), Guangzhou, China, 20–22 December 2024; IEEE: Piscataway, NJ, USA, 2024; pp. 184–187. [Google Scholar]
  20. Dong, L.; Xiao, Y.; Li, Y.; Shi, R. A Collision Detection Algorithm Based on Sphere and EBB Mixed Hierarchical Bounding Boxes. IEEE Access 2024, 12, 62719–62729. [Google Scholar] [CrossRef]
  21. Nie, S.; Chen, B.; Li, Y.; Wang, D.; Xu, Y. The Autonomous Route Planning Algorithm for Rock Drilling Manipulator Based on Collision Detection. J. Field Robot. 2025, in press. [CrossRef]
  22. Yang, W.; Ji, Y.; Zhang, X.; Zhao, D.; Ren, Z.; Wang, Z.; Tian, S.; Du, Y.; Zhu, L.; Jiang, J. A Multi-Camera System-Based Relative Pose Estimation and Virtual-Physical Collision Detection Methods for the Underground Anchor Digging Equipment. Mathematics 2025, 13, 559. [Google Scholar] [CrossRef]
  23. Hou, D.; Wang, X.; Liu, J.; Yang, B.; Hou, G. Research on Collision Avoidance Technology of Manipulator Based on AABB Hierarchical Bounding Box Algorithm. In Proceedings of the 2021 5th Asian Conference on Artificial Intelligence Technology (ACAIT), Haikou, China, 29–31 October 2021; IEEE: Piscataway, NJ, USA, 2021; pp. 406–409. [Google Scholar]
  24. Gan, B.; Dong, Q. An Improved Optimal Algorithm for Collision Detection of Hybrid Hierarchical Bounding Box. Evol. Intel. 2022, 15, 2515–2527. [Google Scholar] [CrossRef]
  25. Schauer, J.; Nüchter, A. Collision Detection between Point Clouds Using an Efficient K-d Tree Implementation. Adv. Eng. Inform. 2015, 29, 440–458. [Google Scholar] [CrossRef]
  26. Huang, Z.; Yang, X.; Min, J.; Wang, H.; Wei, P. Collision Detection Algorithm on Abrasive Belt Grinding Blisk Based on Improved Octree Segmentation. Int. J. Adv. Manuf. Technol. 2022, 118, 4105–4121. [Google Scholar] [CrossRef]
  27. Lu, B.; Wang, Q.; Li, A. Massive Point Cloud Space Management Method Based on Octree-Like Encoding. Arab. J. Sci. Eng. 2019, 44, 9397–9411. [Google Scholar] [CrossRef]
  28. Xiaolong, C.; Zhangyan, C.; Jun, X.; Long, Z.; Ying, W. Voxel-Based Meshing Collision Detection Accelerating Algorithm for DDA2D. J. Univ. Chin. Acad. Sci. 2023, 40, 540. [Google Scholar]
  29. Yang, P.; Shen, F.; Xu, D.; Liu, R. A Fast Collision Detection Method Based on Point Clouds and Stretched Primitives for Manipulator Obstacle-Avoidance Motion Planning. Int. J. Adv. Robot. Syst. 2024, 21, 17298806241283382. [Google Scholar] [CrossRef]
  30. Wang, Z.; Yu, B.; Chen, J.; Liu, C.; Zhan, K.; Sui, X.; Xue, Y.; Li, J. Research on Lidar Point Cloud Segmentation and Collision Detection Algorithm. In Proceedings of the 2019 6th International Conference on Information Science and Control Engineering (ICISCE), Shanghai, China, 20–22 December 2019; IEEE: Piscataway, NJ, USA, 2019; pp. 475–479. [Google Scholar]
  31. Yang, A.; Liu, Q.; Naeem, W.; Fei, M. Robot Dynamic Collision Detection Method Based on Obstacle Point Cloud Envelope Model. In Intelligent Equipment, Robots, and Vehicles; Han, Q., McLoone, S., Peng, C., Zhang, B., Eds.; Springer: Singapore, 2021; Volume 1469, pp. 370–378. [Google Scholar]
  32. Niwa, T.; Masuda, H. Interactive Collision Detection for Engineering Plants Based on Large-Scale Point-Clouds. Comput.-Aided Des. Appl. 2016, 13, 511–518. [Google Scholar] [CrossRef]
  33. Ueki, S.; Mouri, T.; Kawasaki, H. Collision Avoidance Method for Hand-Arm Robot Using Both Structural Model and 3D Point Cloud. In Proceedings of the 2015 IEEE/SICE International Symposium on System Integration (SII), Nagoya, Japan, 12–13 December 2015; IEEE: Piscataway, NJ, USA, 2015; pp. 193–198. [Google Scholar]
  34. Ramsey, C.W.; Kingston, Z.; Thomason, W.; Kavraki, L.E. Collision-Affording Point Trees: SIMD-Amenable Nearest Neighbors for Fast Collision Checking. arXiv 2024, arXiv:2406.02807. [Google Scholar]
  35. López-Adeva Fernández-Layos, P.; Merchante, L.F.S. Convex Body Collision Detection Using the Signed Distance Function. Comput. Aided Des. 2024, 170, 103685. [Google Scholar] [CrossRef]
  36. Xia, R.; Wang, D.; Mou, C. Collision Detection Between Convex Objects Using Pseudodistance and Unconstrained Optimization. IEEE Trans. Robot. 2025, 41, 253–268. [Google Scholar] [CrossRef]
  37. Heo, Y.J.; Kim, D.; Lee, W.; Kim, H.; Park, J.; Chung, W.K. Collision Detection for Industrial Collaborative Robots: A Deep Learning Approach. IEEE Robot. Autom. Lett. 2019, 4, 740–746. [Google Scholar] [CrossRef]
  38. Wu, D.; Yu, Z.; Adili, A.; Zhao, F. A Self-Collision Detection Algorithm of a Dual-Manipulator System Based on GJK and Deep Learning. Sensors 2023, 23, 523. [Google Scholar] [CrossRef] [PubMed]
  39. Cao, J.; Wang, M. A Fast and Generalized Broad-Phase Collision Detection Method Based on KD-Tree Spatial Subdivision and Sweep-and-Prune. IEEE Access 2023, 11, 44696–44710. [Google Scholar] [CrossRef]
  40. Qi, B.; Pang, M. An Enhanced Sweep and Prune Algorithm for Multi-Body Continuous Collision Detection. Vis. Comput. 2019, 35, 1503–1515. [Google Scholar] [CrossRef]
  41. Li, J.-R.; Xin, R.-H.; Wang, Q.-H.; Li, Y.-F.; Xie, H.-L. Graphic-Enhanced Collision Detection for Robotic Manufacturing Applications in Complex Environments. Int. J. Adv. Manuf. Technol. 2024, 130, 3291–3305. [Google Scholar] [CrossRef]
  42. Serpa, Y.R.; Rodrigues, M.A.F. Flexible Use of Temporal and Spatial Reasoning for Fast and Scalable CPU Broad-Phase Collision Detection Using KD-Trees. Comput. Graph. Forum 2019, 38, 260–273. [Google Scholar] [CrossRef]
  43. Chitalu, F.M.; Dubach, C.; Komura, T. Binary Ostensibly-Implicit Trees for Fast Collision Detection. Comput. Graph. Forum 2020, 39, 509–521. [Google Scholar] [CrossRef]
  44. Pinkham, R.; Zeng, S.; Zhang, Z. QuickNN: Memory and Performance Optimization of k-d Tree Based Nearest Neighbor Search for 3D Point Clouds. In Proceedings of the 2020 IEEE International Symposium on High Performance Computer Architecture (HPCA), San Diego, CA, USA, 22–26 February 2020; IEEE: Piscataway, NJ, USA, 2020; pp. 180–192. [Google Scholar]
  45. Park, J.S.; Park, C.; Manocha, D. Efficient Probabilistic Collision Detection for Non-Convex Shapes. In Proceedings of the 2017 IEEE International Conference on Robotics and Automation (ICRA), Singapore, 29 May–3 June 2017; IEEE: Piscataway, NJ, USA, 2017; pp. 1944–1951. [Google Scholar]
  46. Zou, Y.; Zhang, H.; Feng, D.; Liu, H.; Zhong, G. Fast Collision Detection for Small Unmanned Aircraft Systems in Urban Airspace. IEEE Access 2021, 9, 16630–16641. [Google Scholar] [CrossRef]
  47. Fan, Q.; Tao, B.; Gong, Z.; Zhao, X.; Ding, H. Fast Global Collision Detection Method Based on Feature-Point-Set for Robotic Machining of Large Complex Components. IEEE Trans. Autom. Sci. Eng. 2023, 20, 470–481. [Google Scholar] [CrossRef]
  48. Montaut, L.; Le Lidec, Q.; Petrik, V.; Sivic, J.; Carpentier, J. GJK++: Leveraging Acceleration Methods for Faster Collision Detection. IEEE Trans. Robot. 2024, 40, 2564–2581. [Google Scholar] [CrossRef]
  49. Melero, F.J.; Aguilera, Á.; Feito, F.R. Fast Collision Detection between High Resolution Polygonal Models. Comput. Graph. 2019, 83, 97–106. [Google Scholar] [CrossRef]
  50. Liu, Z.; Yan, S.; Zou, K.; Xie, M. Collision Detection Method for Anchor Digging Machine Water Drilling Rig. Sci. Rep. 2025, 15, 726. [Google Scholar] [CrossRef] [PubMed]
  51. Ren, T.; Dong, Y.; Wu, D.; Chen, K. Collision Detection and Identification for Robot Manipulators Based on Extended State Observer. Control Eng. Pract. 2018, 79, 144–153. [Google Scholar] [CrossRef]
  52. Ester, M.; Kriegel, H.-P.; Sander, J.; Xu, X. A Density-Based Algorithm for Discovering Clusters in Large Spatial Databases with Noise. In Proceedings of the Second International Conference on Knowledge Discovery and Data Mining, Portland, OR, USA, 2–4 August 1996; AAAI Press: Washington, DC, USA, 1996; pp. 226–231. [Google Scholar]
  53. Zhang, J.; Zhang, Z.; Luo, N. Kinematics Analysis and Trajectory Planning of the Working Device for Hydraulic Excavators. J. Phys. Conf. Ser. 2020, 1601, 062024. [Google Scholar] [CrossRef]
  54. Gottschalk, S.; Lin, M.C.; Manocha, D. OBBTree: A Hierarchical Structure for Rapid Interference Detection. In Proceedings of the 23rd Annual Conference on Computer Graphics and Interactive Techniques, New York, NY, USA, 1 August 1996; Association for Computing Machinery: New York, NY, USA, 1996; pp. 171–180. [Google Scholar]
Figure 1. The complete research workflow, illustrating the dual-algorithm collision detection system and its experimental validation.
Figure 1. The complete research workflow, illustrating the dual-algorithm collision detection system and its experimental validation.
Mathematics 13 02359 g001
Figure 2. From left to right: simulated models of the tunnel, load-haul-dump (LHD) machine, and mining truck.
Figure 2. From left to right: simulated models of the tunnel, load-haul-dump (LHD) machine, and mining truck.
Mathematics 13 02359 g002
Figure 3. LiDAR installation position and scanning range. The coordinate system shown represents the LiDAR frame.
Figure 3. LiDAR installation position and scanning range. The coordinate system shown represents the LiDAR frame.
Mathematics 13 02359 g003
Figure 4. Point cloud filtering results. The left shows the original point cloud, and the right shows the filtered point cloud.
Figure 4. Point cloud filtering results. The left shows the original point cloud, and the right shows the filtered point cloud.
Mathematics 13 02359 g004
Figure 5. Voxel downsampling results. The left shows the point cloud before downsampling, and the right shows the point cloud after downsampling.
Figure 5. Voxel downsampling results. The left shows the point cloud before downsampling, and the right shows the point cloud after downsampling.
Mathematics 13 02359 g005
Figure 6. Point cloud clustering results. The clustered point cloud includes the tunnel, bucket, and some unnecessary points.
Figure 6. Point cloud clustering results. The clustered point cloud includes the tunnel, bucket, and some unnecessary points.
Mathematics 13 02359 g006
Figure 7. Point cloud segmentation results. Only the tunnel and bucket remain after segmentation.
Figure 7. Point cloud segmentation results. Only the tunnel and bucket remain after segmentation.
Mathematics 13 02359 g007
Figure 8. Diagram of the LHD’s working device, including the boom, bucket, cylinder, rocker, and linkage.
Figure 8. Diagram of the LHD’s working device, including the boom, bucket, cylinder, rocker, and linkage.
Mathematics 13 02359 g008
Figure 9. Denavit–Hartenberg (DH) model of the LHD’s working device.
Figure 9. Denavit–Hartenberg (DH) model of the LHD’s working device.
Mathematics 13 02359 g009
Figure 10. Simplified model of the LHD’s working device. The boom and bucket are simplified for mathematical analysis. The figure also shows the installation positions of three inclination sensors.
Figure 10. Simplified model of the LHD’s working device. The boom and bucket are simplified for mathematical analysis. The figure also shows the installation positions of three inclination sensors.
Mathematics 13 02359 g010
Figure 11. In Figure (a), numbers 1 to 6 represent the six key points of the bucket. Point O 3 denotes the coordinate of the bucket tooth tip, while points A and B are located at the midsection of the bucket and lie on the same plane as point O 3 . Figure (b) shows the side view of the bucket, where point O 2 represents the coordinate of the joint between the bucket and the boom.
Figure 11. In Figure (a), numbers 1 to 6 represent the six key points of the bucket. Point O 3 denotes the coordinate of the bucket tooth tip, while points A and B are located at the midsection of the bucket and lie on the same plane as point O 3 . Figure (b) shows the side view of the bucket, where point O 2 represents the coordinate of the joint between the bucket and the boom.
Mathematics 13 02359 g011
Figure 12. Oriented bounding boxes (OBBs) of the bucket and the mining truck. The triangular prism is formed by the poses of the key points on the bucket, and the mining truck is represented by a cuboid bounding box.
Figure 12. Oriented bounding boxes (OBBs) of the bucket and the mining truck. The triangular prism is formed by the poses of the key points on the bucket, and the mining truck is represented by a cuboid bounding box.
Mathematics 13 02359 g012
Figure 13. Distribution of ground truth and measured values of bucket tooth tip pose. Red represents the ground truth, and blue represents the measured values. The X, Y, and Z axes denote the pose coordinates of the bucket tooth tip.
Figure 13. Distribution of ground truth and measured values of bucket tooth tip pose. Red represents the ground truth, and blue represents the measured values. The X, Y, and Z axes denote the pose coordinates of the bucket tooth tip.
Mathematics 13 02359 g013
Figure 14. The LHD is positioned on the left side of the tunnel interior. The left shows the simulated environment, and the right shows the real-time visualized point cloud.
Figure 14. The LHD is positioned on the left side of the tunnel interior. The left shows the simulated environment, and the right shows the real-time visualized point cloud.
Mathematics 13 02359 g014
Figure 15. The LHD is positioned in the middle of the tunnel interior. The left shows the simulated environment, and the right shows the real-time visualized point cloud.
Figure 15. The LHD is positioned in the middle of the tunnel interior. The left shows the simulated environment, and the right shows the real-time visualized point cloud.
Mathematics 13 02359 g015
Figure 16. The LHD is positioned on the right side of the tunnel interior. The left shows the simulated environment, and the right shows the real-time visualized point cloud.
Figure 16. The LHD is positioned on the right side of the tunnel interior. The left shows the simulated environment, and the right shows the real-time visualized point cloud.
Mathematics 13 02359 g016
Figure 17. Distance between the bucket and the tunnel wall recorded upon collision detection during LHD operation on the left side of the tunnel interior. The horizontal axis represents the experiment number, and the vertical axis represents the distance.
Figure 17. Distance between the bucket and the tunnel wall recorded upon collision detection during LHD operation on the left side of the tunnel interior. The horizontal axis represents the experiment number, and the vertical axis represents the distance.
Mathematics 13 02359 g017
Figure 18. Distance between the bucket and the tunnel wall recorded upon collision detection during LHD operation in the middle of the tunnel interior. The horizontal axis represents the experiment number, and the vertical axis represents the distance.
Figure 18. Distance between the bucket and the tunnel wall recorded upon collision detection during LHD operation in the middle of the tunnel interior. The horizontal axis represents the experiment number, and the vertical axis represents the distance.
Mathematics 13 02359 g018
Figure 19. Distance between the bucket and the tunnel wall recorded upon collision detection during LHD operation on the right side of the tunnel interior. The horizontal axis represents the experiment number, and the vertical axis represents the distance.
Figure 19. Distance between the bucket and the tunnel wall recorded upon collision detection during LHD operation on the right side of the tunnel interior. The horizontal axis represents the experiment number, and the vertical axis represents the distance.
Mathematics 13 02359 g019
Figure 20. Collision detection experimental location between the bucket and the mining truck. The circled area in the figure indicates the experimental location.
Figure 20. Collision detection experimental location between the bucket and the mining truck. The circled area in the figure indicates the experimental location.
Mathematics 13 02359 g020
Figure 21. Collision detection results without lifting the boom. The left shows the simulation scenario, and the right shows the maximum negative overlap recorded during collision. The X-axis represents the experiment number, and the Y-axis represents the maximum negative overlap.
Figure 21. Collision detection results without lifting the boom. The left shows the simulation scenario, and the right shows the maximum negative overlap recorded during collision. The X-axis represents the experiment number, and the Y-axis represents the maximum negative overlap.
Mathematics 13 02359 g021
Figure 22. Collision detection results during loading operation. The left shows the simulation scenario, and the right shows the minimum positive overlap recorded during collision. The X-axis represents the experiment number, and the Y-axis represents the minimum positive overlap.
Figure 22. Collision detection results during loading operation. The left shows the simulation scenario, and the right shows the minimum positive overlap recorded during collision. The X-axis represents the experiment number, and the Y-axis represents the minimum positive overlap.
Mathematics 13 02359 g022
Figure 23. Collision detection results in failed loading scenarios. The left shows the simulation scenario, and the right shows the maximum negative overlap recorded during collision. The X-axis represents the experiment number, and the Y-axis represents the maximum negative overlap.
Figure 23. Collision detection results in failed loading scenarios. The left shows the simulation scenario, and the right shows the maximum negative overlap recorded during collision. The X-axis represents the experiment number, and the Y-axis represents the maximum negative overlap.
Mathematics 13 02359 g023
Table 1. Represents the length between O 1 and O 2 , l 2 denotes the length between O 2 and O 3 , θ 1 is the angle between O 1 O 2 and O 1 X 1 , and θ 2 is the angle between O 2 X 2 and O 2 O 3 .
Table 1. Represents the length between O 1 and O 2 , l 2 denotes the length between O 2 and O 3 , θ 1 is the angle between O 1 O 2 and O 1 X 1 , and θ 2 is the angle between O 2 X 2 and O 2 O 3 .
Link  i θ i d i a i α i
2 θ 1 0 l 1 0
3 θ 2 0 l 2 0
Table 2. Pose error of the bucket tooth tip, including the maximum, minimum, and average distances.
Table 2. Pose error of the bucket tooth tip, including the maximum, minimum, and average distances.
Maximum Distance (m)Minimum Distance (m)Average Distance (m)
0.025200.0141
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Lei, M.; Peng, P.; Wang, L.; Liu, Y.; Lei, R.; Zhang, C.; Zhang, Y.; Liu, Y. Collision Detection Algorithms for Autonomous Loading Operations of LHD-Truck Systems in Unstructured Underground Mining Environments. Mathematics 2025, 13, 2359. https://doi.org/10.3390/math13152359

AMA Style

Lei M, Peng P, Wang L, Liu Y, Lei R, Zhang C, Zhang Y, Liu Y. Collision Detection Algorithms for Autonomous Loading Operations of LHD-Truck Systems in Unstructured Underground Mining Environments. Mathematics. 2025; 13(15):2359. https://doi.org/10.3390/math13152359

Chicago/Turabian Style

Lei, Mingyu, Pingan Peng, Liguan Wang, Yongchun Liu, Ru Lei, Chaowei Zhang, Yongqing Zhang, and Ya Liu. 2025. "Collision Detection Algorithms for Autonomous Loading Operations of LHD-Truck Systems in Unstructured Underground Mining Environments" Mathematics 13, no. 15: 2359. https://doi.org/10.3390/math13152359

APA Style

Lei, M., Peng, P., Wang, L., Liu, Y., Lei, R., Zhang, C., Zhang, Y., & Liu, Y. (2025). Collision Detection Algorithms for Autonomous Loading Operations of LHD-Truck Systems in Unstructured Underground Mining Environments. Mathematics, 13(15), 2359. https://doi.org/10.3390/math13152359

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop