Keywords

1 Introduction

The emergence of autonomous mining trucks (AMTs) shows great promise in addressing safety hazards and the aging workforce [1]. However, the deployment of AMTs in typical mining operations is still challenging [2]. Shovel-loading operation is one of the most complex scenarios in open-pit mines, which significantly influences the ore production efficiency [3]. To ensure the safety and efficiency of the loading process, the loading position and orientation of AMTs are strictly constrained [4]. Under this restriction, the global path planning of AMTs is crucial to generate an obstacle-free reference path with accurate final orientation for subsequent motion control [5].

The global path planning of AMTs in the shovel-loading area encounters two primary challenges. Firstly, the global reference path must satisfy non-holonomic constraints of AMTs and final pose constraints to ensure the safety of the loading process. Thus, some conventional methods are not suitable for AMTs due to their neglection of final orientation and vehicle kinematics, such as A* [6] and Rapidly-exploring Random Tree [7]. In addition, the irregular massif and scattered rocks form various obstacle distributions in large-scale shovel-loading areas. Under this circumstance, conventional methods that adopt a fixed step exhibit a dramatic decrease in search efficiency and path quality.

At present, global path planning for autonomous mining trucks mainly adopts Hybrid A* [8] and its variants, which utilize motion primitives and Reeds-Shepp curve to satisfy non-holonomic and final pose constraints respectively. In [9], Hybrid A* considering tire cost is designed based on a high-precision digital map for global path planning of AMTs. In [10], the dichotomy process is introduced to Hybrid A* to determine a near-optimal steering angle in the node expansion stage, thus improving the smoothness of the global reference path. In [11], a modified Hybrid A* using different curvature in forward and backward motion primitives is proposed to generate a global feasible path for subsequent trajectory optimization. However, the state space of Hybrid A* increases significantly when encountered with large-scale areas, leading to unacceptable computation time. To tackle this problem, prior research has proposed the concept of variable step length. In [12], a variable-step-length A* based on an improved cost function is proposed to reduce the overall computation time. In [13], a step selection strategy based on dangerous area construction is proposed for sparse A*. Nevertheless, these approaches determine step length from discrete value sets based on simple rules, thus lacking the adaptability required for the intricate environment in shovel-loading scenarios.

In summary, the strict restrictions on the final pose and complex environment result in performance degradation of conventional methods. To deal with these challenges, this paper focuses on improving computational efficiency and path quality of global path planning. The contribution of the paper lies in proposing a novel joint dichotomy optimization method to determine near-optimal step length and steering angle in the node expansion stage of Hybrid A*. The generated near-optimal nodes typically have lower costs, contributing to the improvement of computation time and path quality of global path planning.

2 Methodology

Our proposed method contains the map pre-processing stage and the path planning stage. The overall framework of the proposed DO-VSLHA* is shown in Fig. 1.

Fig. 1.
figure 1

The overall framework of the proposed DO-VSLHA*. The original grid map is pre-processed to eliminate U-shape obstacles which typically lead to unnecessary node exploration. The obstacle grids are clustered into groups and transformed into convex polygons, forming a new map for collision detection in the path planning stage. In each node expansion iteration of the path planning stage, joint sampling on step length and steering angle is applied to generate the initial successor nodes. Subsequently, the cost of each initial node is updated based on collision detection and heuristic function. Then, a dichotomy optimization is proposed to determine near-optimal step length and steering angle based on dichotomy optimization. The near-optimal nodes are subsequently generated and added to the open set of Hybrid A*.

In map pre-processing, DBSCAN [14] is applied to cluster obstacle grids into different groups. The eps-neighbourhood \(N_{\epsilon }(\cdot )\) and core object in DBSCAN is defined as follows:

$$\begin{aligned} N_{\epsilon }(p)=\{q\in \mathcal {G} | dist(p,q) < \epsilon \} \end{aligned}$$
(1)
$$\begin{aligned} p \; \text {is} {\left\{ \begin{array}{ll} \text {core object}& if \; \Vert N_{\epsilon }\Vert >= Minpts \\ \text {others}& if \; \Vert N_{\epsilon }\Vert < Minpts \end{array}\right. } \end{aligned}$$
(2)

where p and q represent the obstacle grid. \(dist(\cdot )\) represents the distance function and adopts Euclidean distance in our case. Minpts and \(\epsilon \) represent the number threshold of obstacle grids and distance threshold respectively. In our case, we let

$$\begin{aligned} {\left\{ \begin{array}{ll} \epsilon = w + 2d \\ Minpts = 2 \end{array}\right. } \end{aligned}$$
(3)

where w represents the width of ATMs and d represents the safety margin on each side. After clustering, the convex hull algorithm is applied to every cluster to generate a convex polygon. Ray-casting method is utilized to filter invalid convex polygons when the loading point and starting point are located inside them. With map pre-processing, U-shape obstacles are eliminated, thus avoiding unnecessary node searches.

In the path planning stage, the node expansion of Hybrid A* is described as follows

$$\begin{aligned} \begin{bmatrix} x_{s}\\ y_{s}\\ \theta _{s}\end{bmatrix}=\begin{bmatrix} x_{c}\\ y_{c}\\ \theta _{c}\end{bmatrix}+ d\cdot L\begin{bmatrix} \cos {\theta _{c}}\\ \sin {\theta _c}\\ \frac{\tan {\delta }}{ l_{w}}\end{bmatrix} \end{aligned}$$
(4)

where \(N_{c}(x_{c}, y_{c}, \theta _{c}, d_{c})\) and \(N_{s}(x_{s}, y_{s}, \theta _{s}, d_{s})\) represent the state of the current node and the successor node respectively. \(d\in \{-1, 1\}\) denotes the forward or backward motion and \(l_{w}\) denotes the wheelbase of AMTs. L and \(\delta \) denote the step length and steering angle. By determining near-optimal L and \(\delta \), successor nodes with less cost are generated to accelerate the overall node expansion process.

A joint optimization of step length and steering angle based on dichotomy is proposed to generate near-optimal nodes. The pseudo-code of the dichotomy optimization is shown in Algorithm 1. A joint sampling on step length and steering with a given discrete interval is performed to generate an initial successor set. Then, we generate near-optimal nodes with a given number of iterations. In each iteration, the node with the least cost and its corresponding step length \(s_{m}\) and steering angle \(\delta _{m}\) are selected. Then, the adjacent value of step length and steering angle can be found, denoted as \(s_{l}\), \(s_{r}\), \(\delta _{l}\), \(\delta _{r}\). Subsequently, we generate four new nodes based on the mean value of these parameters, as shown in line 11 and 12 in Algorithm 1. The node with the least cost among the generated nodes is chosen to generate a new node with \(n_{m}\). By repeating the dichotomy process, the step length and angle will converge to a near-optimal value, and these near-optimal nodes will be added to the initial node set.

Algorithm 1
figure a

. Dichotomy(Nodes)

3 Experiments

To validate our proposed method, we conduct field tests on an AMT at an open-pit mine, as shown in Fig. 2a. The original grid map is generated according to a 913 m\(\times \)1037 m shovel loading platform with the resolution of 1 m for path planning, as shown in Fig. 2b. We compared our method with Hybrid A* and D-HA* [10]. Path length L, smoothness \(\varPhi \) and computation time T are calculated to verify the effectiveness of path planning methods. Smoothness \(\varPhi \) is calculated with \(\varPhi = \sum _{i=1}^{N}\left| \phi _{i}-\phi _{i-1}\right| \), where N represents the number of path points and \(\phi \) represents yaw angle of each path point.

Fig. 2.
figure 2

The shovel-loading scenario, grid map, and experimental results of field tests.

Results are shown in Fig. 2c and Table 1. Our method outperforms conventional methods in path length, smoothness, and computation time. Unlike Hybrid A* using fixed parameters in node expansion, the proposed dichotomy optimization generates near-optimal nodes with optimized exploration parameters, thus reducing the number of iterations and the overall computation time. In addition, compared to D-HA* which only optimizes steering angle by dichotomy process and faces more computation burden, our method jointly optimizes step length and steering angle, thus improving the path quality and overall computational efficiency.

Table 1. The comparison results between our proposed method and others.

4 Conclusion

This paper presents a novel variable-step-length Hybrid A* based on dichotomy optimization which jointly optimizes step length and steering angle and generates near-optimal nodes in the node expansion stage. The experiment demonstrates that our proposed method outperforms other conventional methods in computation time and path quality, indicating better adaptability in complex environments at open-pit mines.