Next Article in Journal
Extraction of Irregularly Shaped Coal Mining Area Induced Ground Subsidence Prediction Based on Probability Integral Method
Next Article in Special Issue
Stochastic Predictions of Ore Production in an Underground Limestone Mine Using Different Probability Density Functions: A Comparative Study Using Big Data from ICT System
Previous Article in Journal
Microseismic Signal Denoising and Separation Based on Fully Convolutional Encoder–Decoder Network
Previous Article in Special Issue
Applications of the Open-Source Hardware Arduino Platform in the Mining Industry: A Review
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A New Challenge: Path Planning for Autonomous Truck of Open-Pit Mines in The Last Transport Section

School of Resources And Safety Engineering, Central South University, Changsha 410083, China
*
Author to whom correspondence should be addressed.
Submission received: 5 August 2020 / Revised: 13 September 2020 / Accepted: 14 September 2020 / Published: 22 September 2020
(This article belongs to the Special Issue Recent Advances in Smart Mining Technology)

Abstract

:
During the operation of open-pit mining, the loading position of a haulage truck often changes, bringing a new challenge concerning how to plan an optimal truck transportation path considering the terrain factors. This paper proposes a path planning method based on a high-precision digital map. It contains two parts: (1) constructing a high-precision digital map of the cutting zone and (2) planning the optimal path based on the modified Hybrid A* algorithm. Firstly, we process the high-precision map based on different terrain feature factors to generate the obstacle cost map and surface roughness cost map of the cutting zone. Then, we fuse the two cost maps to generate the final cost map for path planning. Finally, we incorporate the contact cost between tire and ground to improve the node extension and path smoothing part of the Hybrid A* algorithm and further enhance the algorithm’s capability of avoiding the roughness. We use real elevation data with different terrain resolutions to perform random tests and the results show that, compared with the path without considering the terrain factors, the total transportation cost of the optimal path is reduced by 10%–20%. Moreover, the methods demonstrate robustness.

1. Introduction

Cost control has always been the top priority in the mining industry, and how to control the cost is one of the critical points for mining companies to make profits. In the open-pit mines, the transportation cost accounts for about 50% of the total mining cost [1,2,3]. In the absence of mining technology innovation, how to improve transportation efficiency and reduce extra transportation costs are crucial to improve the profits of mining enterprises. The rise of driverless technology makes the problem have a new solution. At present, unmanned ground vehicles (UGVs) have been widely used in port or warehouse automation logistics, disaster relief, military, and other industrial and military fields [4,5,6,7,8].
In the mining field, autonomous navigation of the load-haul-dump (LHD) machine in underground mines has been successfully applied [9,10]. However, it is still a challenge to apply autonomous technology in open-pit mining. The open-pit mining area is an ideal environment for unmanned vehicles due to its closed environment and few external interference factors. Komatsu and other mining equipment manufacturing giants have carried out unmanned transportation experiments in a Chilean copper mine since 2008 [11]. Their results show that the transportation capacity is increased by 40% and the cost has reduced by 15% in the autonomous haulage system (AHS). Another unmanned transportation experiment in Australian mining also shows that unmanned transportation has more considerable economic significance compared with traditional transportation [12]. Nonetheless, Ayres [13] and Juliana Parreira [14] both pointed out that the AHS may have problems such as unable to respond to ground pits or rocks promptly, resulting in extra fuel consumption and tire wear. Also, some studies [3,15] have concluded that, when haulage trucks run on poor road conditions, the vehicle cost will be increased. Kansake [16], through the simulation experiment, concluded that under the general mining road conditions, the dynamic load of the tire would be 60% higher than the static load, which will aggravate the tire wear. For the existing AHS, only the large obstacles on the ground are considered in path planning. In contrast, the tiny obstacles are ignored, like rocks or terrain undulation on the surface, resulting in additional tire wear. Thus, the truck route should be planned on smoother ground.
The path planning of UGV is divided into route planning, trajectory planning, and motion planning [17]. Route planning is point-to-point planning, which regards the vehicle as a particle and does not consider other constraints, so it requires less map accuracy. Trajectory planning is based on route planning, with more constraints of vehicles, such Cering the most constraints, such as vehicle control strategy. Choi et al. [18] used the map from Google Earth to optimize the route of dump trucks in open-pit mines. Google Earth only provides a low-resolution surface elevation model, but the realization of trajectory planning requires more accurate surface topographic maps.
The digital surface model (DSM) is a model that contains the surface elevation information, and it is generally used for the reconstruction of the terrain model as its high precision. There are several methods to build a DSM: traditional digital mapping [19], unmanned aerial vehicle (UAV) lidar mapping [20,21], oblique photogrammetry [22], etc. Among these methods, the oblique photogrammetry has been widely used in urban surveying and mapping [23], disaster monitoring [24], and the open-pit mining industry [25,26,27] because of its high precision and convenient operation. Based on DSM, trajectory planning can be carried out. Jurgen Zoto et al. [28] planned a coverage path for UGV of vineyard based on DSM. Kai Zhang et al. [29] used lidar to measure the surface elevation point cloud and constructed the ground map to carry out the path planning of cross-country vehicles. These DSM-based path planning studies only separated obstacle information but did not consider surface roughness information in the planning map.
The transportation environment of open-pit mines is unstructured, and the Hybrid A* algorithm (HA* algorithm) is a heuristic algorithm widely used in real-time vehicle path planning for unstructured environments [30,31,32,33,34]. This algorithm adds the non-holonomic constraints into the heuristic functions and plans the path in the Voronoi field map. Nevertheless, in the planning process, the regular Hybrid A* algorithm only considers the large obstacles. However, it ignores the little pit or roughness of the surface, which may cause an additional cost for large vehicles.
There are a lot of open spaces in the cutting zone of open-pit mines without any obstacles. In this scenario, the path planner considers the road surface as a passable area without obstacles, thus planning a path directly to the loading position which may result in extra tire cost because of the ground roughness. In order to reduce the extra cost, this paper proposes a high-precision planning map construction method based on DSM and an improved Hybrid A* algorithm. This planning map contains both surface obstacles and roughness information. Firstly, the DSM is divided into an obstacle point set and surface roughness point set with different terrain features. Secondly, the obstacle point set is calculated as obstacle cost map (OCM) according to generalized Voronoi diagram (GVD). Then the sliding window standard deviation method is used to process the surface roughness point set and generate the roughness cost map (RCM) without obstacle. Finally, the two maps are integrated into the cost map (C-MAP) for path planning, which contains the information of obstacles and roughness on the road. With this C-MAP, we modified the Hybrid A* algorithm by adding the contact cost between the tire and ground into the heuristic function, so that the path can be planned on the smooth road surface. The main contributions of this paper are as follows:
  • We propose a truck path planning method based on high-precision digital map for the final transportation section of open-pit mines, which can effectively reduce the driving cost of trucks.
  • We design a planning map that contains obstacle information and roughness information on the road surface and its construction method.
  • We improve the Hybrid A* algorithm to incorporate the roughness information into the cost estimation function of node extension.
The structure of this paper is as follows: Section 2 describes the modified Hybrid A* algorithm in detail, including planning map building method and algorithm improvement. In Section 3, we evaluate the algorithm performance in different real open-pit cutting zone scenes and analyze the algorithm robustness through a thousand random tests with different terrain resolution maps. Conclusions and future work are presented in Section 4 and Section 5.

2. Materials and Methods

To avoid the rough area on the transportation road, it is necessary to make a planning map containing the roughness information and add it to the estimation function of the Hybrid A* algorithm. The method of constructing a planning map with roughness information is as follows:
  • DSM data acquisition and generation. The raw elevation data of cutting zone is obtained by some topographic mapping methods (oblique photogrammetry, lidar scanning, etc.), and the corresponding DSM is generated.
  • Constructing the obstacle cost map of the cutting zone. Firstly, the obstacle point set in DSM is filtered by setting different terrain factors thresholds. Then the obstacle binary map is constructed by the elevation scanning method, and finally, the obstacle cost map is made from GVD.
  • Constructing the roughness cost map of the cutting zone. Firstly, removing the obstacle point set in DSM, filtering the remaining point set with another terrain threshold. Then, using the standard deviation of moving window to traverse calculation, its value is taken as the roughness value of all coordinate points within the window range. Finally, normalizing the roughness matrix to generate the roughness cost Map of the cutting zone.
  • Generating the C-MAP. Overlaying and normalizing the value matrix of obstacle cost map and roughness cost map, get the C-MAP, which is used in path planning.
The modified parts of the Hybrid A* algorithm are as follows:
  • Modify the g-value estimation function. The contact cost between the tire and the ground surface is added into the g-value estimation function. Consequently, the step length a dynamic value instead of a static value in the part of the node extension.
  • Modify the conjugate gradient object function. The original Voronoi term is replaced by a new roughness term to correct the path points passing through rough area.
The primary process of map construction and modified Hybrid A* algorithm is shown in Figure 1.

2.1. Raw Data Collection and DSM Generation

There are many topographic surveys to collect DSM original image data. In this paper, UAV oblique photogrammetry is used for data collection. After that, using terrain processing software to extract the elevation points from the original image and generating the DSM, as shown in Figure 2. Save the elevation points information of DSM in the following matrix:
E = [ e 11 e 1 n e m 1 e m n ] ,
where e i j is the corresponding coordinate of elevation points.

2.2. Obstacle Cost Map Construction

2.2.1. Elevation Feature Points Extraction

In DSM, the pits or fallen rocks on the ground are expressed in the form of elevation difference. Wang et al. [35] proposed a method to extract the elevation feature points to represent the terrain changes. The feature points were extracted by the four directions (vertical, horizontal, 45° left, 45° right) scanning method based on the section scanning. The key is the selection of terrain thresholds to distinguish different terrains, such as obstacles or little pit. Moreover, for high-precision DSM, Wang pointed out that the equal-interval sampling method can improve the efficiency of subsequent calculations, and the model error is acceptable. Therefore, the original DSM with 0.032 m accuracy is reprocessed to 0.096 m accuracy by the equal-intervals sampling method in this paper. Referring [16], we set T = 0.3   m as the terrain threshold of impassable elevation difference, and θ = 15 ° as the slope threshold of the maximum passable slope. The steps of extracting elevation feature points are as follows (take the vertical scanning as an example):
  • Reforming the elevation matrix E according to the different scanning directions. The elements of each column in E is put into E i , as shown in Equation (2).
    E i = [ e 1 i e m i ] , E = ( E 1 , E 2 E n ) , i = 1 , 2 n
  • Scanning each data point sequentially in E i : set a searching group with e j 1 , e j , e j + 1 , ( j = 2 , 3 m 1 ) , the step length is one. If the point is the first or last point of E i , or local extremum of the group, add the point p to the candidate feature points set F p , where p contains the elevation value and coordinate information. The extracted feature points are shown in Figure 3a.
  • Filtering the points of F p by terrain threshold T which is defined by the characteristics of the cutting zone. Then determine whether p k and p k + 1 are adjacent in F p . If they are adjacent, judge the absolute value of two-point difference, whether it’s over the threshold T . If the value greater than T , p k + 1 will be reserved in F p . Otherwise, p k + 1 will be removed from F p . The original section scanning line and the final feature point set F p are shown in Figure 3b.

2.2.2. Binary Map Construction

Binary map construction is the preprocessing work for Obstacle Cost Map construction. Firstly, Compare whether the slope angle β of adjacent points p k ( x p k , y p k ) and p k + 1 ( x p k + 1 , y p k + 1 ) in F p greater than θ sequentially. If so, all the corresponding coordinate points between p k and p k + 1 are assigned as 1, otherwise, it is 0, i.e., the value of one is represented obstacle. As shown in Equations (3) and (4). Figure 4 is the schematic diagram of the four-direction scanning binary map.
β = t a n 1 ( y p k + 1 y p k x p k x p k ) ,
p j = { 1 , β θ 0 , β < θ , j = 1 , 2 m ,
where p j E i .
Secondly, fuse four scanning binary maps to form the final binary map in a simple mixture method: Traverse all points of the four maps. If the accumulated value of the same coordinates in four maps is greater than or equal to 2, then the value of the coordinate point is set to 1. Otherwise, it is 0. The final obstacle binary map is shown in Figure 5.

2.2.3. Obstacle Cost Map Generation

For the heuristic algorithm, the map cost value directly affects the accuracy of the estimation function, thus affecting the quality of the final path. Voronoi diagram is a geometry-based route planning method for robot path planning [36,37], which divides the space into several regional units according to the nearest neighbor attributes of the elements in the site collection. Dolgov [30], the inventor of the Hybrid A* algorithm, used the generalized Voronoi diagram to generate the planning map, which made the planning path can pass through the narrow area and without collision. The generation steps for the obstacle cost map are as follows:
  • Building the two-dimensional Voronoi diagram from the binary map. The 1-value coordinate points in the binary map of obstacles are regarded as the scatter points. Then, calculate the 2-D Voronoi diagram of all scatter points. The red dot is the Voronoi station, and the blue line is the Voronoi edge, as shown in Figure 6a.
  • Cutting off the Voronoi edges which passing through the obstacle polygon, and the remaining edges are the edges of GVD. The black square is the obstacle polygon, and the red line is the GVD edges, as shown in Figure 6b.
  • Converting the GVD into grid form by sampling method, as shown in Figure 6c. Then, calculating each grid cost by Equation (5) to construct the obstacle cost map. The grid cost reaches its maximum within obstacles, and the color is close to black. It reaches its minimum on the GVD edges. The color is close to white, as shown in Figure 6d.
g r i d C o s t ( x , y ) = { ( α α + d o ( x , y ) ) ( d v ( x , y ) d o ( x , y ) + d v ( x , y ) ) ( ( d o d o m a x ) 2 ( d o m a x ) 2 ) ,   d o < d o m a x 0 ,   o t h e r s
where g r i d C o s t ( x , y ) is the cost of each grid. It is continuously distributed in the range of 0 to 1, only takes 1 in the obstacles, and takes 0 on the Voronoi edge. α is the parameter to control the descent rate of cost, α > 0 . d o m a x is the maximum range of potential value distribution, d o m a x > 0 . For the grid points that exceed the d o m a x , the grid cost is 0. d o is the distance from the grid point to the nearest obstacle edge. d v is the distance from the grid point to the nearest Voronoi edge.
Using this method to process the obstacle binary map of the cutting zone, we get the corresponding obstacle cost map, as shown in Figure 7. However, due to the high grid precision and the maximum range of potential value distribution, only the area at the edge of the obstacle (black area) has an available cost (gray area). For the rest of the open space area (far away from the obstacle), the grid cost is 0 (white area). Therefore, to make the algorithm consider the cost in the open area, we construct the roughness cost map to complement this area.

2.3. Roughness Cost Map Construction

A large number of blank areas exist in the obstacle cost map of the cutting zone, in which there are many possible adverse road conditions. If it is not included in the heuristic function of the planning algorithm, it will result in a deviation of the planning path. Generally, the standard deviation of the sliding window can be used to estimate the ground surface roughness [38]. The smaller the standard deviation value, the smoother the road surface. We use this method to construct the roughness cost map:
  • Removing the coordinate of obstacles in the original elevation point set E , and obtained a new point set E r , which only keeps the elevation value of the open space area.
  • Using the section scanning method (threshold T = 0 ,   θ = 5 ° ) to process the open space area, deleting the elevation value of a point below the threshold from E r .
  • In E r , taking a window and using the sliding standard deviation method to traverse E r , and calculating the standard deviation of the window, then assigning its value back to each point in this window.
  • Normalizing all the values of points in E r with a range of 0 to 1, which is the same as the obstacle cost range.
  • Through the above steps, we can get the rough ground cost map of the cutting zone, as shown in Figure 8a.

2.4. C-MAP Generating

After constructing OCM and RCM with the same value range at c o s t = [ 0 , 1 ] , the C-MAP can be constructed as follows:
  • Removing the obstacle points (cost = 1) from OCM, and adding the remaining OCM to RCM.
  • Normalizing the obtained matrix.
  • Backfilling obstacle points of OCM.
The constructed C-MAP still maintain the value range at c o s t = [ 0 , 1 ] , and it contains both the obstacle information (black part of Figure 8b) and surface roughness information in the open space area (other color parts of Figure 8b), in which the planning algorithm can take roughness cost into account in the estimation function.

2.5. Hybrid A* Algorithm Improvement

This section introduces the planning process of the modified Hybrid A* algorithm, and how to optimize it to fit the scene described in this article. The Hybrid A* algorithm is an improved A* path planning heuristic algorithm proposed by Dolkov [30], which adds the vehicle non-holonomic constraints to the estimation function. Based on the two-dimensional grid ( x , y , θ ) extension of A* algorithm, it adds a three-dimensional search, considers the three-dimensional state ( x , y , θ , λ ) of the vehicle. Where x and y are coordinate information, θ is direction information, and λ is vehicle forward and backward status information. Nevertheless, the path produced by the Hybrid A* algorithm has local bending, so Dolkov uses the conjugate gradient (CG) method to smooth the path.
We add the cost of tire contact with the road surface into the estimation function of the Hybrid A* algorithm instead of only taking the cost of the center point as the estimation. Also, we replace the Voronoi term with the Roughness term to enhance the path’s avoiding ability for roughness surface.

2.5.1. Node Extension Improvement

The node extension of Hybrid A* is guided by two heuristic methods. One is the 2D heuristic method in the traditional A* algorithm, which considers the information of obstacles in the map, but ignores the physical attributes of the vehicle itself. Its node extension only contains coordinate information and direction information, as shown in Figure 9a. Another is the non-holonomic-without-obstacles heuristic method. This method considers the vehicle non-holonomic constraints and assumes that there are no obstacles in the map, assumes the goal state of ( x g , y g , θ g ) = ( 0 , 0 , 0 ) , computes the shortest path to the goal from every point ( x , y , θ ) . The schematic extension diagram is shown in Figure 9b. The second method uses the maximum of the two methods cost as the heuristic cost. Also, in order to save computing time, the algorithm uses Reed-Shepp (RS) curve to judge the current node and the goal node periodically. If there is no obstacle between the two points, an obstacle-free RS path will be generated directly between the two points. We set a few parameters, such as number of motion primitives (NMP), motion length (ML), and extension interval (EI), to control the node extension. NMP determines how many next nodes will be calculated based on the current node, by way of example, in Figure 9b, the NMP is 5, so there are five forward and five backward points. ML is the length of each extension determined by the minimum turning radius. EI determines how many loops to perform RS curve detector.
When the Hybrid A* algorithm estimates the moving cost, it usually takes the grid value of the center point as the estimation cost. We improve the g-value estimation function of the Hybrid A* algorithm, add a new term to estimate the cost of tire contact with the ground when the vehicle is moving. The improved node extension diagram is shown in Figure 10, the yellow area is the coverage area of the tire when extending, and the occupancy grid value within the range is taken as the extension cost.

2.5.2. Estimation Function Improvement

The Hybrid A* algorithm uses the Equation (6) to estimate the cost of each node extension.
f ( x ) = g ( x ) + h ( x ) ,
where the first term g ( x ) is the sum of the estimated cost from the start to the current node, the second term h ( x ) is the heuristic value from the current node to the goal, and the sum of the two terms is the evaluation function of the whole algorithm. This paper only improves the g ( x ) , and use the two heuristic functions of the original algorithm to calculate the h ( x ) . The calculation of g ( x ) is realized by Equation (7).
g ( x ) = D i r e c t i o n C o s t × ( g ( x p a r e n t ) + l e n g t h ( x p a r e n t , x ) + T i r e C o s t ( x p a r e n t , x ) ) + λ S witch C o s t
where D i r e c t i o n C o s t contains ForwardCost (FC) and ReverseCost (RC), penalizing the motion cost according to a different direction. g ( x p a r e n t ) represents the sum cost from the start point to the parent node of the current node. l e n g t h ( x p a r e n t , x ) is the length of the curved path between the parent node and the current node.   S witch C o s t is the direction switch cost to penalize the motion state, when the direction of the vehicle is changed λ = 1 , otherwise λ = 0 . We add a new cost term, T i r e C o s t ( x p a r e n t , x ) , based on the original g-value estimation function, to estimate the cost of tire contact with the surface. This term represents the sum cost of the occupied grid values by the tire line from the current node to its parent node:
T i r e C o s t ( x p a r e n t , x ) = i = x p a r e n t x ( C o s t M a p i ) + j = x p a r e n t x ( C o s t M a p j ) ,
where the first term is the accumulative cost of the left tire, and the second is the right.

2.5.3. Conjugate Gradient Method Improvement

There are still some unnecessary turns in the path planned by the Hybrid A* algorithm. Dolkov used the conjugate gradient (CG) smooth method to optimize the path. The objective function is:
P = ω ρ i = 1 N ρ v ( x i , y i ) + ω o i = 1 N σ o ( | x i o i | d m a x ) + ω κ i = 1 N 1 σ κ ( Δ Φ i | Δ x i | κ m a x ) + ω s i = 1 N 1 ( Δ x i + 1 Δ x i ) 2 ,
where the first term is Voronoi term to guide the path away from an obstacle in both narrow and wide passages, the second term is Obstacle term to penalize the collisions, the third term is curvature term to ensure the path curvature satisfies vehicle non-holonomic constraints, and the fourth term is the smoothness term to make the path smoother.
In the cutting zone scene, there is a large open space area instead of narrow passages. Thus, we replace the Voronoi term with roughness term in CG, and the function is:
P r = ω r i = 1 N 1 σ r ( n = 1 4 ω n ( | x i n r i n | ) )
The derivative is:
P r x i = 2 ω r ( n = 1 4 ω n ( | x i n r i n | ) ) ( n = 1 4 ω n x i n r i n | x i n r i n | ) ,
ω n = 1 ( r n m a x / n = 1 4 r n m a x ) ,
where ω r is the weight of gradient; σ r is a simple quadratic penalties function; x i n are the locations of four tire contact with the surface which corresponding to each path point; r i n are the locations of the maximum value roughness points nearest to the x i n ; r n m a x is the distance between r i n and x i n ; ω n is the weight of the gradient.
This term penalizes the contact between the tire and the nearby rough ground, which increases the ability to deviate from rough terrain during path point optimization.

2.5.4. The Modified Hybrid A* Algorithm in Detail

The modified Hybrid A* algorithm considering terrain roughness is improved on the regular Hybrid A* algorithm, which has the same essential parts. Before planning starts, it is necessary to set vehicle parameters, including length, width, tire information, and minimum turning radius, etc. Generally, tire information includes information on wheelbase and tire size. After that, the C-MAP is input, which includes both obstacle and roughness information to the path planner, and then the essential planning parameters are set, e.g., FC, RC, EI, etc. The pseudo code for Modified Hybrid A* algorithm (Algorithm 1) is as follows.
Algorithm 1 Modified Hybrid A*
1:Set Vehicle properties:
V P ( L e n g t h , W i d t h , T i r e   i n f o r m a t i o n , M i n i m u m   t u r n i n g   r a d i u s )
2:Set planner: p l a n n e r ( C o s t M a p , P l a n n i n g   p a r a m e t e r s ( M L , N M P , F C , R C , S C , E I ) )
3:Input: s t a r t N o d e ( x s , y s , ϕ s ) , g o a l N o d e ( x g , y g , ϕ g )
4:Procedure Hybrid A* planner   ( s t a r t N o d e , g o a l N o d e , V P , p l a n n e r )
5:  Node extension
6:  Validate the node
7:  RS curve check
8:  return Path Points
9:  Processing Path Points by ConjugateGradientSmoother   ( C o s t M a p , P a t h P o i n t s )
10:  return the Path Points after CG optimization
11:end procedure
12:Procedure gScore   ( n c u r r e n t , n n e x t , p l a n n e r , V P )
13:   g S c o r e p a r e n t g S c o r e of n c u r r e n t
14:   L e n g t h c u r r e n t n e x t M L
15:  Generate the tire path besides the extension line according to V P
16:  Calculate the occupied grid coordinates of the tire path
17:  Delete duplicate grid coordinates
18:   T i r e C o s t is the total cost of the occupied gird
19:  if the direction of n n e x t the direction of n c u r r e n t then
20:   g S c o r e = g S c o r e p a r e n t + L e n g t h c u r r e n t n e x t + T i r e C o s t + S C
21:  else
22:   g S c o r e = g S c o r e p a r e n t + L e n g t h c u r r e n t n e x t + T i r e C o s t
23:  end if
24:end procedure
The procedure gScore is an improved g-value estimation function. In each node extension step, it accumulates the total cost of the occupied grid of the corresponding tire path which is calculated from vehicle parameters. This allows Hybrid A* algorithm can incorporate surface roughness into motion cost estimation. Steps 19 to 23 mean that only when the motion status changes, in other words, when the motion direction changes from forward to backward, the SwitchCost will penalize the motion cost.

3. Performance Analysis of Modified Algorithm

To verify the effectiveness and robustness of the modified algorithm, we experiment with and analyze its performance in two different scenes of the Chengmenshan copper mine in Jiangxi. The original image data of the cutting zone are obtained by quad-rotor UAV oblique photogrammetry (Figure 11), and the corresponding C-MAPs of two scenes are constructed by the method proposed in this paper (Figure 12). In these two scenes, we set three different start positions and a fixed position of truck for path planning and verification. Path length, accumulative path cost, and path total score are used for the path evaluation.
Table 1 is the cartographic information, and Table 2 is the parameters of the simulated haulage truck. Table 3 shows the main parameters of the Hybrid A* algorithm. The parameters of conjugate gradient smoother are set to ω r = ω o = 0.002 ,   ω κ = ω s = 0.2 .

3.1. Analysis of Algorithm Capability in Different Scenes

According to the actual mining haulage route, we demarcate three initial starting positions in the green square frame, and a loading position in the red square frame, as shown in Figure 13. Then we verified the algorithm by the following two parts:
  • Testing the recognition and avoidance ability of modified Hybrid A* algorithm for rough terrain. Firstly, plan a path in the obstacle cost map without roughness information. Then, after a virtual rough area is artificially added to the map and plan the path again. The result is shown in Figure 14.
  • Evaluating the path planned by the modified Hybrid A* algorithm in obstacle cost map and C-MAP, the results are shown in Figure 15.
In the first part of the test, it is evident that after adding the virtual rough area in the obstacle cost map, the path avoids the rough area. It is proved that the modified Hybrid A* algorithm can detect and avoid the large roughness.
In the second part of the test, it is intuitive to see in the comparison diagram that the red line deviates from the rough area better than the black line. In order to quantitatively evaluate the different paths in two scenes, we measure the path length and the accumulative path cost of the tires on both sides.
Since it is challenging to integrate the path length and accumulative cost into actual vehicle operating cost, we use the entropy method [39] to calculate the weight and get the total score of each path to approximate the operating cost with the Equations (13) and (14).
E j = l n ( n ) 1 i n p i j l n ( p i j ) ,
ω i = 1 E j k E j ( i = 1 , 2 , , k ) ,
where p i j = Y i j / i = 1 n Y i j , Y i j = X i j m i n ( X i ) m a x ( X i ) m i n ( X i ) , X i = { l e n g t h , c o s t } . X i is a matrix of path length and accumulative cost information for each path.
In Table 4, the optimization rate refers to the optimization degree of the total score of C-MAP compared with the total score of OCM. The results of path evaluation Table 4 show that the planning path with consideration of roughness is better than that without consideration. In these three scenes, the optimization rate is more significant than zero, which shows that the modified algorithm can reduce the potential cost of the planning path.

3.2. Analysis of Algorithm Robustness

To test the optimization of the modified Hybrid A* algorithm under random conditions, we have conducted thousand planning experiments in two scenes with randomly given start position and goal position. We are moreover repeat the experiment at three different terrain resolutions scenes (0.1 m, 0.5 m, 1.0 m). Figure 16 is the schematic diagram of two scenes with lower resolution.
With the decrease of terrain resolution, C-MAP loses a lot of surface roughness information. As a result, in the planning of low-resolution maps, the optimization rate is more concentrated in the 0% to 10% range, as shown in Figure 17c–f. Significantly, when the resolution is from 0.1 m to 0.5 m, the average optimization rate of two scenes decreases rapidly, while the latter decreases slowly from 0.5 m to 1.0 m, as shown in Figure 18. The result shows that the planning algorithm cannot optimize the trajectory well when the terrain resolution (grid accuracy) is reduced from high to low.
Based on the results of the random test, we consider several factors that affect the optimization rate:
  • The influence of planning map construction, including the DSM accuracy and filter threshold. The accuracy of DSM directly affects the recognition ability of the construction algorithm for surface roughness. However, the improvement of accuracy will result in more computational work and the program needs to process more data units. Therefore, 0.1 m is an appropriate accuracy value.
  • For the filter threshold, it affects the ability of the construction algorithm to distinguish obstacles from the surface. Moreover, it is difficult to construct a surface roughness model if the terrain is flat.
  • The influence is caused by the parameter setting of Hybrid A* algorithm. The setting of parameters will directly affect the quality of the final path. To illustrate, if the ReverseCost setting is greater than ForwardCost, the algorithm will consider the backward situation more. If the Extension Interval setting is too large, it will cause extra computation. Switch Cost penalizes the direction change of a vehicle. However, in this paper, since Tire Cost is a dynamic value, the static value of Switch Cost will weaken its effect so that it can be considered as an adaptive value.
  • Caused by statistics of path cost. The entropy method may not be able to integrate the path length and the accumulative cost on the surface very well, which makes the calculation error.

4. Conclusions

The trajectory planning of cutting zone for unmanned trucks is essential in the autonomous transportation of open-pit mines. When planning the path, if we only consider the obstacle information, the roughness of ground may lead to extra tire wear. This paper proposes a path planning method considering terrain factors. (1) generate the DSM of the cutting zone using the UAV oblique photogrammetry method. (2) based on the DSM, construct a high-precision cost map (C-MAP) which contains both obstacle and roughness terrain information. (3) On the basis of C-MAP, plan a path by the modified Hybrid A* algorithm that incorporates the surface roughness information into the g-value estimation function. The random tests of actual scenes demonstrate a 10% to 20% reduction of the path cost. Therefore, our proposed method can reduce the transportation cost of the haulage truck and solve the problem of high cost in the last section of open-pit transportation.

5. Future Work

Due to the variability of the cutting zone environment, the method is only applicable to the global static map before transportation. During the mining operation, local elevation will change. Therefore, future work can be divided into two parts:
  • We will collect the environmental information of the cutting zone and construct a real-time local DSM map by using detection sensors, such as Lidar, camera, GNSS receiver, etc. This enables continuous path planning by continually updating the global map and maintaining its timeliness and accuracy. Due to the errors in acquisition equipment and mapping procedure, the matching and fusion updating of the real-time local map and the global map is the focus and difficulty of future works.
  • We will study the relationship between road roughness and vehicle transportation cost. Establishing a model to predict vehicle transportation costs based on different surface roughness conditions will be the critical feature of future work.

Author Contributions

Z.Z. and L.B. conceived, designed, and performed the experiments. Z.Z. analyzed the data and wrote the paper. All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported by the Fundamental Research Funds for the Central Universities of Central South University, project number 2020zzts709.

Acknowledgments

The authors gratefully acknowledge the funders and all advisors and colleagues who support our work.

Conflicts of Interest

The authors declare no conflict of interest. The funders had no role in the design of the study; in the collection, analyses, or interpretation of data; in the writing of the manuscript, or in the decision to publish the results.

References

  1. Mukhopadhjay, A. Selection, maintenance, and relations of various parameters for off-highway hauling tires. Off-Highw. Haul. Surf. Mines Ed. Golosinski Sraje Balkema 1989, 153–159. [Google Scholar]
  2. Widdifield, L.; Riggle, R. The Big Picture: An Overview Approach to Surface Mining. Min. Eng. 2016, 24, 3–5. Available online: http://me.smenet.org/docs/Publications/ME/Issue/Feb_Web_Exclusive1.pdf (accessed on 1 August 2020).
  3. Corporation, V. A new approach to building haul roads. Eng. Min. J. 2015, 216, 46–49. [Google Scholar]
  4. Arai, T.; Pagello, E.; Parker, L.E. Advances in multi-robot systems. IEEE Trans. Robot. Autom. 2002, 18, 655–661. [Google Scholar] [CrossRef] [Green Version]
  5. Farinelli, A.; Iocchi, L.; Nardi, D. Multi-robot systems: A classification focused on coordination. IEEE Trans. Syst. Man Cybern. Part B (Cybern.) 2004, 34, 2015–2028. [Google Scholar] [CrossRef] [Green Version]
  6. Yuan, K.; Yuan, L.; Fang, L.X. Recent Researches and Development on Multi- Robot System. J. Autom. 2007, 33, 785–794. [Google Scholar]
  7. Ni, J.; Hu, J. Dynamics control of autonomous vehicle at driving limits and experiment on an autonomous formula racing car. Mech. Syst. Signal Process. 2017, 90, 154–174. [Google Scholar] [CrossRef]
  8. Zhang, H.; Wang, J. Active steering actuator fault detection for an automatically-steered electric ground vehicle. IEEE Trans. Veh. Technol. 2016, 66, 3685–3702. [Google Scholar] [CrossRef]
  9. Roberts, J.M.; Duff, E.S.; Corke, P.I. Autonomous control of under-ground mining vehicles using reactive navigation. In Proceedings of the 2000 ICRA. Millennium Conference. IEEE International Conference on Robotics and Automation. Symposia Proceedings (Cat. No.00CH370665), San Francisco, CA, USA, 24–28 April 2000; Volume 4, pp. 3790–3795. [Google Scholar]
  10. Nebot, E.M.; Gonzalez, J.J. Main research issues for the deployment of full autonomous surface mining operations. In Proceedings of the 22nd International Conference on Computers and Their Applications, CATA-2007, Honolulu, HI, USA, 28–30 March 2007; pp. 213–218. [Google Scholar]
  11. Komatsu Ltd. Komatsu Celebrates 10th Anniversary of Commercial Deployment of Autonomous Haulage System [EB/OL]. 2018. Available online: https://home.komatsu/en/press/2018/others/1198705_1831.html (accessed on 1 August 2020).
  12. Bellamy, D.; Pravica, L. Assessing the impact of driverless haul trucks in Australian surface mining. Resour. Policy 2011, 36, 149–158. [Google Scholar] [CrossRef]
  13. Ayres, A. Considerations when implementing Autonomous Haulage in Open Cut Mining. 2016. Available online: https://amcconsultants.com/experience/dd-considerations-autonomous-haulage-open-cut-mining/ (accessed on 1 August 2020).
  14. Parreira, J. An Interactive Simulation Model to Compare an Autonomous Haulage Truck System with a Manually-Operated System. Ph.D. Dissertation, University of British Columbia, Vancouver, BC, Canada, 2013. [Google Scholar]
  15. Kondo, S. Relation Between Haul Road and Damage of Off-Highway Dump Trucks. In Proceedings of the 35th Annual Earthmoving Industry Conference, Peoria, IL, USA, 9–11 April 1984. [Google Scholar] [CrossRef]
  16. Kansake, B.A.; Frimpong, S. Analytical modelling of dump truck tire dynamic response to haul road surface excitations. Int. J. Min. Reclam. Environ. 2020, 34, 1–18. [Google Scholar] [CrossRef]
  17. Zhou, C.; Gu, S.; Wen, Y.; Du, Z.; Xiao, C.; Huang, L.; Zhu, M. The Review Unmanned Surface Vehicle Path Planning: Based on Multi-Modality Constraint. Ocean Eng. 2020, 200, 107043. [Google Scholar] [CrossRef]
  18. Choi, Y.; Nieto, A. Optimal haulage routing of off-road dump trucks in construction and mining sites using Google Earth and a modified least-cost path algorithm. Autom. Constr. 2011, 20, 982–997. [Google Scholar] [CrossRef]
  19. McPherron, S.J. Artifact orientations and site formation processes from total station proveniences. J. Archaeol. Sci. 2005, 32, 1003–1014. [Google Scholar] [CrossRef]
  20. Wehr, A.; Lohr, U. Airborne laser scanning—An introduction and overview. ISPRS J. Photogramm. Remote Sens. 1999, 54, 68–82. [Google Scholar] [CrossRef]
  21. Lin, Y.; Hyyppä, J.; Jaakkola, A. Mini-UAV-Borne LIDAR for Fine-Scale Mapping. IEEE Geosci. Remote Sens. Lett. 2011, 8, 426–430. [Google Scholar] [CrossRef]
  22. Frueh, C.; Sammon, R.; Zakhor, A. Automated texture mapping of 3D city models with oblique aerial imagery. In Proceedings of the 2nd International Symposium on 3D Data Processing, Visualization and Transmission, Thessaloniki, Greece, 6–9 September 2004; Volume 31, pp. 396–403. [Google Scholar]
  23. Toschi, I.; Ramos, M.M.; Nocerino, E.; Menna, F.; Remondino, F.; Moe, K.; Poli, D.; Legat, K.; Fassi, F. Oblique Photogrammetry Supporting 3D Urban Reconstruction of Complex Scenarios. ISPRS–International Archives of the Photogrammetry. Remote Sens. Spat. Inf. Sci. 2017, 519–526. [Google Scholar] [CrossRef] [Green Version]
  24. Qin, X.; Qin, Q.; Yang, X.; Wang, J.; Chen, C.; Zhang, N. Feasibility study of building seismic damage assessment using oblique photogrammetric technology. In Proceedings of the 2013 IEEE International Geoscience and Remote Sensing Symposium, Melbourne, Australia, 21–26 July 2013; pp. 208–211. [Google Scholar] [CrossRef]
  25. Kršák, B.; Blišťan, P.; Pauliková, A.; Puškárová, P.; Kovanič, Ľ.; Palková, J.; Zelizňaková, V. Use of low-cost UAV photogrammetry to analyze the accuracy of a digital elevation model in a case study. Measurement 2016, 91, 276–287. [Google Scholar]
  26. Rauhala, A.; Tuomela, A.; Davids, C. UAV remote sensing surveillance of a mine tailings impoundment in sub-arctic conditions. Remote Sens. 2017, 9, 1318. [Google Scholar] [CrossRef] [Green Version]
  27. Suh, J.; Choi, Y. Mapping hazardous mining-induced sinkhole subsidence using unmanned aerial vehicle (drone) photogrammetry. Environ. Earth Sci. 2017, 76, 144. [Google Scholar] [CrossRef]
  28. Zoto, J.; Musci, M.A.; Khaliq, A.; Chiaberge, M.; Aicardi, I. Automatic Path Planning for Unmanned Ground Vehicle Using UAV Imagery. In Proceedings of the International Conference on Robotics in Alpe-Adria Danube Region, Kaiserslautern, Germany, 19–21 June 2019; pp. 223–230. [Google Scholar] [CrossRef]
  29. Zhang, K.; Yang, Y.; Fu, M.; Wang, M. Traversability assessment and trajectory planning of unmanned ground vehicles with suspension systems on rough terrain. Sensors 2019, 19, 4372. [Google Scholar] [CrossRef] [Green Version]
  30. Dolgov, D.; Thrun, S.; Montemerlo, M.; Diebel, J. Practical search techniques in path planning for autonomous driving. Ann. Arbor. 2008, 1001, 18–80. [Google Scholar]
  31. Mizuno, N.; Ohno, K.; Hamada, R.; Kojima, H.; Fujita, J.; Amano, H.; Tadokoro, S. Enhanced path smoothing based on conjugate gradient descent for firefighting robots in petrochemical complexes. Adv. Robot. 2019, 33, 687–698. [Google Scholar] [CrossRef]
  32. Verlag, V. Application of Hybrid A to an Autonomous Mobile Robot for Path Planning in Unstructured Outdoor Environments; VDE Verlag: Berlin, Germany, 2012. [Google Scholar]
  33. Chu, K.; Kim, J.; Jo, K.; Sunwoo, M. Real-time path planning of autonomous vehicles for unstructured road navigation. Int. J. Automot. Technol. 2015, 16, 653–668. [Google Scholar] [CrossRef]
  34. Kurzer, K. Path Planning in Unstructured Environments: A Real-time Hybrid A* Implementation for Fast and Deterministic Path Generation for the KTH Research Concept Vehicle. Master’s Thesis, KTH Royal Institute of Technology, Stockholm, Sweden, December 2016. [Google Scholar] [CrossRef]
  35. Wang, J.; Wang, L.; Jia, M.; He, Z.; Bi, L. Construction and optimization method of the open-pit mine DEM based on the oblique photogrammetry generated DSM. Measurement 2020, 152, 107322. [Google Scholar] [CrossRef]
  36. Patle, B.K.; Pandey, A.; Parhi, D.R.K.; Jagadeesh, A. A review: On path planning strategies for navigation of mobile robot. Def. Technol. 2019, 15, 582–606. [Google Scholar] [CrossRef]
  37. Niu, H.; Savvaris, A.; Tsourdos, A.; Ji, Z. Voronoi-visibility roadmap-based path planning algorithm for unmanned surface vehicles. J. Navig. 2019, 72, 850–874. [Google Scholar] [CrossRef]
  38. Hengl, T.; Reuter, H.I. Geomorphometry-Concepts, Software, Applications. In Developments in Soil Science; Elsevier: Amsterdam, The Netherlands, 2009. [Google Scholar]
  39. Shannon, C.E. A mathematical theory of communication. Bell Syst. Tech. J. 1948, 27, 379–423. [Google Scholar] [CrossRef] [Green Version]
Figure 1. The primary process of map construction and Hybrid A* algorithm planning.
Figure 1. The primary process of map construction and Hybrid A* algorithm planning.
Applsci 10 06622 g001
Figure 2. Positive photograph and corresponding DSM of the cutting zone. (a) is the positive photograph; (b) is the digital surface model.
Figure 2. Positive photograph and corresponding DSM of the cutting zone. (a) is the positive photograph; (b) is the digital surface model.
Applsci 10 06622 g002
Figure 3. Schematic diagram of feature point extraction. In (a), the red dots are the extreme points on the section scanning line. In (b), the red marks are the feature points filtered according to the threshold T , and only the points with large elevation change are retained. The x-axis, which depends on the size of the point set represents the length of the scanline; the y-axis represents the elevation value of the point on the scanline.
Figure 3. Schematic diagram of feature point extraction. In (a), the red dots are the extreme points on the section scanning line. In (b), the red marks are the feature points filtered according to the threshold T , and only the points with large elevation change are retained. The x-axis, which depends on the size of the point set represents the length of the scanline; the y-axis represents the elevation value of the point on the scanline.
Applsci 10 06622 g003
Figure 4. Schematic diagram of four direction scanning binary map. (a) is the vertical scanning map; (b) is the horizontal scanning map; (c) is the 45° left scanning map; (d) is the 45° right scanning map.
Figure 4. Schematic diagram of four direction scanning binary map. (a) is the vertical scanning map; (b) is the horizontal scanning map; (c) is the 45° left scanning map; (d) is the 45° right scanning map.
Applsci 10 06622 g004
Figure 5. Obstacle binary map of cutting zone. The black area is the obstacle area, which retains the typical details of the four-direction scanning binary maps.
Figure 5. Obstacle binary map of cutting zone. The black area is the obstacle area, which retains the typical details of the four-direction scanning binary maps.
Applsci 10 06622 g005
Figure 6. Schematic diagram of Obstacle Cost Map generation. (a) is the original Voronoi diagram; (b) is the GVD; (c) is the grid form of GVD; (d) is the Obstacle Cost Map, the black color represents the obstacle grid and the white represents the Voronoi edge.
Figure 6. Schematic diagram of Obstacle Cost Map generation. (a) is the original Voronoi diagram; (b) is the GVD; (c) is the grid form of GVD; (d) is the Obstacle Cost Map, the black color represents the obstacle grid and the white represents the Voronoi edge.
Applsci 10 06622 g006
Figure 7. Schematic diagram of the open space. (a) is the obstacle cost map of cutting zone; (b) is the open space area in the red square in (a).
Figure 7. Schematic diagram of the open space. (a) is the obstacle cost map of cutting zone; (b) is the open space area in the red square in (a).
Applsci 10 06622 g007
Figure 8. Schematic diagram of Roughness Cost Map and C-MAP. (a) is the Roughness Cost Map without obstacle; (b) is the C-MAP. The color distribution represents the traversable of the road surface. Black represents obstacle area.
Figure 8. Schematic diagram of Roughness Cost Map and C-MAP. (a) is the Roughness Cost Map without obstacle; (b) is the C-MAP. The color distribution represents the traversable of the road surface. Black represents obstacle area.
Applsci 10 06622 g008
Figure 9. Schematic diagram of node extension. (a) is the traditional A* algorithm node extension; (b) is the nonholonomic constraint node extension of Hybrid A* algorithm. The central red dot is the current node and the green or blue node is the calculated next node.
Figure 9. Schematic diagram of node extension. (a) is the traditional A* algorithm node extension; (b) is the nonholonomic constraint node extension of Hybrid A* algorithm. The central red dot is the current node and the green or blue node is the calculated next node.
Applsci 10 06622 g009
Figure 10. Schematic diagram of the tire-contact cost estimation. The black solid line is the extension line from the current node to the next node. The dashed is the tire path calculated from vehicle properties. The yellow area is the occupied grid of the tire path.
Figure 10. Schematic diagram of the tire-contact cost estimation. The black solid line is the extension line from the current node to the next node. The dashed is the tire path calculated from vehicle properties. The yellow area is the occupied grid of the tire path.
Applsci 10 06622 g010
Figure 11. Quad-rotor UAV.
Figure 11. Quad-rotor UAV.
Applsci 10 06622 g011
Figure 12. Schematic diagram of two cutting zone scenes. (a,d) are the orthophotographs; (b,e) are the DSM; (c,f) are the C-MAP.
Figure 12. Schematic diagram of two cutting zone scenes. (a,d) are the orthophotographs; (b,e) are the DSM; (c,f) are the C-MAP.
Applsci 10 06622 g012
Figure 13. Schematic diagram of start and goal position of truck in two scenes. (a) is the map of scene 1; (b) is the map of scene 2. The green square frame represents the starting position and the red square is the goal position.
Figure 13. Schematic diagram of start and goal position of truck in two scenes. (a) is the map of scene 1; (b) is the map of scene 2. The green square frame represents the starting position and the red square is the goal position.
Applsci 10 06622 g013
Figure 14. Schematic diagram of the roughness avoidance ability of the algorithm. (a) is the planning path in the OCM; (b) is the planning path in the OCM with the virtual rough area (pink block).
Figure 14. Schematic diagram of the roughness avoidance ability of the algorithm. (a) is the planning path in the OCM; (b) is the planning path in the OCM with the virtual rough area (pink block).
Applsci 10 06622 g014
Figure 15. Verification of path planning in two scenes. (ac) are the path planning experiments in scene 1; (df) are the path planning experiments in scene 2.The black line represents the path planned in OCM, and the red line represents the path planned in C-MAP. The dotted line is the path without CG optimization, and the solid line represents the path after CG optimization.
Figure 15. Verification of path planning in two scenes. (ac) are the path planning experiments in scene 1; (df) are the path planning experiments in scene 2.The black line represents the path planned in OCM, and the red line represents the path planned in C-MAP. The dotted line is the path without CG optimization, and the solid line represents the path after CG optimization.
Applsci 10 06622 g015
Figure 16. Two scenes with different terrain resolution. (a,c) are the 0.5 m terrain resolution scenes; (b,d) are the 1.0 m terrain resolution scenes.
Figure 16. Two scenes with different terrain resolution. (a,c) are the 0.5 m terrain resolution scenes; (b,d) are the 1.0 m terrain resolution scenes.
Applsci 10 06622 g016
Figure 17. Optimization rate of the random path in two scenes with different terrain resolutions. (a,c,e) are the random tests in scene 1; (b,d,f) are the tests in scene 2. (a,b) are tested in the 0.1 m terrain resolution scenes; (c,d) are tested in the 0.5 m terrain resolution scenes; (e,f) are tested in the 1.0 m terrain resolution scenes.
Figure 17. Optimization rate of the random path in two scenes with different terrain resolutions. (a,c,e) are the random tests in scene 1; (b,d,f) are the tests in scene 2. (a,b) are tested in the 0.1 m terrain resolution scenes; (c,d) are tested in the 0.5 m terrain resolution scenes; (e,f) are tested in the 1.0 m terrain resolution scenes.
Applsci 10 06622 g017
Figure 18. Average optimization rate with different terrain resolution. The label under each point is the average optimization rate at that resolution.
Figure 18. Average optimization rate with different terrain resolution. The label under each point is the average optimization rate at that resolution.
Applsci 10 06622 g018
Table 1. Cartographic information.
Table 1. Cartographic information.
Camera Pixels of UAVDSM Original AccuracyDSM Accuracy after SamplingC-MAP Unit Size
20 megapixel × 50.032 m0.096 m0.1 m × 0.1 m
Table 2. Simulated haulage truck parameters.
Table 2. Simulated haulage truck parameters.
LengthWidthWheelbaseMinimum Turning RadiusTire Size
8.7 m4.525 m3.75 m7.2 m18.00-33-32 PR
Table 3. Hybrid A* algorithm parameters.
Table 3. Hybrid A* algorithm parameters.
Number of Motion PrimitivesMotion LengthForward CostReverse CostSwitching CostExtension Interval
5721510030
Table 4. Planning Path Evaluation Table in Two Scene.
Table 4. Planning Path Evaluation Table in Two Scene.
Path Length (m)Accumulative CostTotal ScoreOptimization Rate (%)
Scene 1OCM401124.41113.85.93
Start IC-MAP431057.71047.8
Scene 1OCM39926.9918.25.26
Start IIC-MAP37878.1869.9
Scene 1OCM41316.4313.76.87
Start IIIC-MAP39294.6292.1
Scene 2OCM57386.2382.918.23
Start IC-MAP61315.7313.1
Scene 2OCM541174.81163.69.82
Start IIC-MAP581059.41049.3
Scene 2OCM621096.81086.46.99
Start IIIC-MAP591020.11010.5

Share and Cite

MDPI and ACS Style

Zhao, Z.; Bi, L. A New Challenge: Path Planning for Autonomous Truck of Open-Pit Mines in The Last Transport Section. Appl. Sci. 2020, 10, 6622. https://0-doi-org.brum.beds.ac.uk/10.3390/app10186622

AMA Style

Zhao Z, Bi L. A New Challenge: Path Planning for Autonomous Truck of Open-Pit Mines in The Last Transport Section. Applied Sciences. 2020; 10(18):6622. https://0-doi-org.brum.beds.ac.uk/10.3390/app10186622

Chicago/Turabian Style

Zhao, Ziyu, and Lin Bi. 2020. "A New Challenge: Path Planning for Autonomous Truck of Open-Pit Mines in The Last Transport Section" Applied Sciences 10, no. 18: 6622. https://0-doi-org.brum.beds.ac.uk/10.3390/app10186622

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