Download PDF
Research Article  |  Open Access  |  26 May 2025

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Views: 43 |  Downloads: 5 |  Cited:  0
Intell. Robot. 2025, 5(2), 450-73.
10.20517/ir.2025.23 |  © The Author(s) 2025.
Author Information
Article Notes
Cite This Article

Abstract

To address the motion planning challenges in multi-arm cooperative operations of tunnel rock drilling robots, we establish forward/inverse kinematics models for drilling arms using an enhanced Denavit-Hartenberg method combined with radial basis function neural networks. An improved genetic algorithm (IGA) is developed, integrating heuristic crossover operators, adaptive mutation operations, and local neighborhood search mechanisms to optimize multi-arm trajectories with the objective of minimizing end-effector travel distance. A joint-space collision avoidance strategy is proposed using an enhanced artificial potential field (IAPF) method that incorporates both attractive potential fields and repulsive potential functions. Simultaneously, quintic B-spline-based trajectory planning ensures smooth motion continuity during collaborative drilling operations. Experimental validation demonstrates that the IGA-IAPF integration achieves 37.2% reduction in collision probability compared to conventional methods, while maintaining joint angular accelerations below 0.25 rad/s2 for all manipulators.

Keywords

Multi-arm, inverse kinematics, cooperative path planning, trajectory optimization

1. INTRODUCTION

The deployment of large-scale heavy-duty hydraulic manipulators has seen significant expansion in mission-critical domains including extreme environment operations, complex task execution, and multi-arm collaborative systems. However, their motion control systems exhibit inherent challenges including high nonlinearity, strong dynamic coupling, trajectory discontinuity, and limited industrial applicability. Effective multi-manipulator coordination must incorporate optimal task-space path planning with real-time collision prediction capabilities. This context establishes coordinated motion planning for multi-link heavy-duty hydraulic manipulators as an emerging research frontier in industrial automation, with substantial engineering implications[1-3].

Precise regulation of motion parameters and coordinated trajectory planning for multi-degree-of-freedom (multi-DOF) robotic arms constitute fundamental requirements for intelligent control architectures in multi-link large-scale heavy-duty hydraulic manipulator systems. Zheng et al. discussed the global energy optimization problem of a 3-DOF hydraulic manipulator, and a dynamic programming (DP) algorithm was proposed to optimize the global energy[4]. Deng et al. used radial basis function neural network (RBFNN) to estimate the unknown joint coupling dynamics of n-DOF hydraulic manipulator, and used error sign feedback robust integration (RISE) to deal with RBFNN reconstruction error to limit joint tracking error and achieve stable control of prescribed tracking performance[5]. Su et al. derived the kinematic constraint equation of multi-manipulator cooperation, simulated the trajectory of synchronous motion and relative motion of the manipulator, and analyzed the influence of external load on the position and attitude of the end effector of the manipulator[6]. Based on DH kinematics and Newton-Euler dynamics model, Baressi Šegota et al. used genetic algorithm and simulated annealing evolutionary algorithm to optimize the path of the robot manipulator and reduce the joint torque[7].

In the multi-manipulator cooperative path planning problem, how to determine the global optimal path under the mutual constraint relationship between the manipulators and avoid the interference collision is also a key problem in the motion planning of multi-task large-scale heavy-duty manipulators. Yang et al. proposed a collision avoidance trajectory planning method for the dual-robot system based on a modified artificial potential field (APF) algorithm[8]. The trajectory solution time of the modified APF algorithm is greatly reduced compared with the traditional APF and rapidly exploring random tree (RRT) algorithm. Liu et al. used the improved particle swarm optimization algorithm to solve the problem, which ensures that the optimal planning of the trajectory is realized under the premise of satisfying the kinematics and dynamics constraints of the manipulator by establishing a multi-objective optimization model[9]. Jin et al. developed a feedback compensation method to avoid dynamic singularities on the trajectory planning of space robots[10]. Meng et al. presented a genetic algorithm based on task directed graph (TDG-GA) to achieve the optimal task allocation and multi-stage path planning of robots[11]. Based on the fast exploration random tree algorithm (GA_RRT), a dual-arm robot obstacle avoidance path planning method was proposed to achieve dynamic collision avoidance, and the effectiveness of the algorithm was proved by simulation[12,13]. Zhang et al. transformed the motion planning problem of redundant dual-arm robots into a constrained convex quadratic programming problem for optimal solution to ensure the optimality of the solution[14]. Mateu-Gomez et al. proposed a method to coordinate robot manipulators by selecting the optimal operation sequence and optimal trajectory planning based on Markov decision process[15]. Li et al. proposed a multi-round cooperation strategy with multiple synchronous starting points to accommodate uncertain execution delays by separating the space of the dual-robot printing area using the rectangular envelope region and a two-dimensional directed line segment, to avoid the potential collision risk of dual-robot[16]. Xu et al. introduced a high-precision motion planning method based on dual Jacobi iterative inverse solution method, multi-strategy sampling mechanism, coupled with a forward kinematics error compensation model, to improve the positioning accuracy[17].

Chu et al. determined the continuous and smooth trajectory of the end effector of the manipulator by polynomial interpolation method and optimized the collision-free trajectory by multiplier penalty method, and the effectiveness was proved based on the numerical results of a three-arm spatial robot system[18]. Kawabe et al. proposed a combined method for Q-learning and RRT for the trajectory planning problem[19]. The planned trajectories are able to guarantee a certain degree of optimality and reduce the time required to generate the motion trajectory. Liu et al. and Ni et al. established the motion characteristics mapping relationship between the operation space and the joint space of the parallel robot and obtained the time optimal trajectory planning of polynomial interpolation based on the improved particle swarm optimization algorithm[20,21]. Chen et al. proposed a new probabilistic roadmap sampling strategy to improve the sampling density at the narrow channel of free space and realize the effective obstacle avoidance of the manipulator in a cluttered environment[22]. Liu et al. proposed a multi-robotic arm path planning algorithm deep deterministic policy gradient RRT (DDPG-RRT) combined with deep reinforcement learning to reduce the average planning time and the total average path length[23]. Sun et al. incorporated a real-time multi-arm coordination strategy that seamlessly integrates the trajectory modulation method with an extended reactive approach to empower multiple robotic arms operating within a shared workspace to dynamically regulate their movements and execute tasks simultaneously in a human-desired manner while reactively avoiding mutual collisions[24]. Dio et al. presents a time-optimal path parameterization method for cooperative multi-arm robotic systems manipulating heavy objects with third-order constraints based on a problem reformulation as a sequential linear program[25].

Based on the above literature research and analysis, it can be found that some scholars have carried out basic research on the kinematic model and motion planning of the multi DOF manipulator, which provides a theoretical and methodological reference to the joint motion path and trajectory planning of the multi-joint drilling arm of the rock drilling robot in this study. However, the following aspects need to be further improved. (1) The accuracy of the inverse kinematics parameters of the redundant DOF manipulator with specified performance requirements is always a prerequisite for the precise and stable control of the manipulator; (2) Multi-task sequencing and path planning with optimal efficiency and collision avoidance need to be considered simultaneously for multi-manipulator cooperative operation; (3) The stability of multi-DOF large-scale heavy-duty hydraulic manipulators in large-scale motion trajectory planning still needs to be improved. To this end, this paper mainly focuses the following on on-site innovative application research. (1) Through the field deployment of pre-trained RBFNN, the accuracy of kinematic parameters of redundant DOF manipulators with specific performance requirements is improved; (2) Heuristic crossover, mutation operation and neighborhood search are used to improve the search speed and global optimization ability of path planning; (3) The joint space of the drilling boom is selected as the search space of multi-arm cooperative obstacle avoidance path planning to prevent falling into local optimization and avoid singular solutions.

The rest of this paper is organized as follows: Section 2 introduces the structure and kinematics of the multi-DOF manipulator. In sections 3, the multi-task optimization and anti-collision path planning of multi drilling arms cooperative operation are provided. In section 4 and section 5, the numerical simulation results and the experimental results are described in detail. Finally, section 6 summarizes the paper.

2. SYSTEM MODEL

2.1. Structure of drilling arms

Figure 1A illustrates the system architecture of the multi-arm rock drilling robot, with three identical 7-DOF drilling arms. Each drilling arm [Figure 1B] features an optimized kinematic configuration comprising five revolute joints and two prismatic joints arranged in series-parallel hybrid topology.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 1. Structure of multi-arm rock drilling robot and drilling arm. (A) Rock drilling robot; (B) Multi-DOF drilling arm. DOF: Degree-of-freedom.

2.2. Kinematics of drilling arms

The modified Denavit-Hartenberg (D-H) method is used to establish the kinematics model of drilling arms based on the mechanical structure model. This approach establishes transformation matrices and closed-form kinematic equations for adjacent joint coordinate systems. RBFNNs are subsequently employed to determine inverse kinematic solutions, with model validation achieved through comparative analysis of numerical simulations and experimental trajectory data.

Firstly, the joint coordinate system of the drilling arm is established. Then, the coordinate relationship and kinematics model of each drilling arm of the multi-arm rock drilling robot are established, as shown in Figure 2.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 2. Drilling arm motion diagram of multi-arm rock drilling robot.

Figure 2 demonstrates structural homogeneity across the three 7-DOF drilling arms, exhibiting identical kinematic configurations in the multi-arm system. This structural uniformity enables focused kinematic investigation of the central drilling arm as the representative unit. Utilizing the modified D-H convention, we derive homogeneous transformation matrices between successive joints, mathematically expressed in

$$ { }_{i+1}^{i} \boldsymbol{T}=\left[\begin{array}{cccc}c_{i+1} & -s_{i+1} & 0 & a_{i} \\c_{\alpha_{i}} s_{i+1} & c_{i+1} c_{\alpha_{i}} & -s_{\alpha_{i}} & -s_{\alpha_{i}} d_{i+1} \\s_{\alpha_{i}} s_{i+1} & c_{i+1} s_{\alpha_{i}} & c_{\alpha_{i}} & -c_{\alpha_{i}} d_{i+1} \\0 & 0 & 0 & 1\end{array}\right] $$

where si = sinθi, ci = cosθi, $$ s_{\alpha_i} $$ = sinαi, $$ c_{\alpha_i} $$ = cosαi.

Simultaneously, the complete D-H parameter set [Table 1] is derived through systematic analysis of kinematic constraints between adjacent links and their coordinate frames.

Table 1

Parameters of each joint of the drilling arm

Name of joint Connecting rod i αi -1 ai -1/mm θi di/mm Joint variable Initialization value
Swing joint 1 0-1 0 a 0 θ 1 d 1 θ 1
Pitching joint 2 1-2 -90 a 1 θ 2 d 2 θ 2 -90°
Telescopic joint 3 2-3 -90 a 2 0 d 3 d 3 L 1
Roll joint 4 3-4 0 0 θ 4 0 θ 4
Pitching compensation 5 4-5 90 0 θ 5 d 5 θ 5 90°
Swing compensation 6 5-6 90 a 5 θ 6 d 6 θ 6 90°
Propulsion joint 7 6-7 90 a 6 0 d 7 d 7 L 2

Substituting the parameters and initial values of each joint of the drilling arm in Table 1 into the forward kinematics equation, the initial pose matrix of the drilling arm end effector can be obtained by

$$ { }_{7}^{0} \boldsymbol{T}_0={ }_{1}^{0} \boldsymbol{T}{ }_{2}^{1} \boldsymbol{T}{ }_{3}^{2} \boldsymbol{T}{ }_{4}^{3} \boldsymbol{T}{ }_{5}^{4} \boldsymbol{T}{ }_{6}^{5} \boldsymbol{T}{ }_{7}^{6} \boldsymbol{T}=\left[\begin{array}{cccc}0 & 0 & 1 & 10025 \\1 & 0 & 0 & 906.5 \\0 & 1 & 0 & 614 \\0 & 0 & 0 & 1\end{array}\right] $$

where $$ { }_{7}^{0} \boldsymbol{T}_0 $$ represents the initial pose matrix of the drilling arm end effector, and $$ { }_{i}^{i-1} \boldsymbol{T} $$ indicates the coordinate transformation matrix between the adjacent joints of the drilling arm.

3. METHODOLOGY

3.1. Inverse kinematics based on RBFNN

The drilling arm of the multi-arm rock drilling robot has seven DOFs, which belongs to the redundant manipulator, and the structure does not meet the Pieper criterion. At present, the mainstream inverse solution algorithms of manipulators can be divided into three categories: analytical method (such as geometric method and algebraic method), numerical method (such as Jacobian iteration and Newton method) and intelligent optimization algorithm (such as genetic algorithm and RBFNN). Among them, the analytical method is only applicable to the specific configuration manipulator that meets Pieper criterion, and the redundant/unstructured heavy-duty manipulator studied in this paper has poor adaptability; The numerical method is limited by the number of iterations, and it is easy to fall into local optimization for the high-dimensional planning space of multi-drilling manipulator cooperation. Intelligent optimization algorithm is suitable for complex constraints, but the calculation cost is high. In this paper, off-line training combined with high-performance airborne processor is used to solve the problem in the research of multi-arm cooperative path planning. Aiming at the special requirements of large load, strong coupling and high real-time in tunnel drilling scene, the introduction of RBFNN is mainly based on the following considerations: dynamic modeling ability, computational efficiency advantage and high-dimensional space generalization.

Since the joint 7 at the end of the drilling arm needs to be drilled perpendicular to the tunnel section, and it is a moving joint, it only needs to control the translation distance at the end of the drilling arm, so only the attitude of the first six joints needs to be determined. Therefore, in the inverse kinematics analysis of the drilling arm, it can be assumed that the joint 7 is fixed, i.e., d7 is a fixed value, and its initial value d7 = 4,022 mm. At this time, each drilling arm is simplified to six DOFs, and the simplified inverse solution results do not affect the actual drilling operation of the multi-arm rock drilling robot.

According to the drilling attitude and construction characteristics of the rock drilling robot within the allowable range of each joint variable of the drilling arm, to improve the prediction accuracy and improve the training speed, based on the Monte Carlo method, 10,000 sets of joint data T = [θ1 θ2 d3 θ4 θ5 θ6] of the drilling arm were randomly generated. The above data are substituted into the forward kinematics matrix equation of the drilling arm, and the pose matrix of the drilling arm end corresponding to each set of data is obtained. The obtained pose matrix is converted into RPY angle by RPY Euler angle transformation, so as to obtain the corresponding 10,000 sets of 6-DOF pose data P1 = [α β λ px py pz] of the end of the drilling arm of the rock drilling robot, and 8,800 sets of data as the inputs for the training data, and at the same time, the corresponding 8,800 sets of drilling arm joint data are set as the outputs, and 1,200 sets of data are used as test data, and they are trained by the three-layer RBFNN for prediction. The prediction errors of the variable values of each joint are obtained by comparing the sample input values selected from 1,200 sets of test data with the prediction values obtained by RBFNN, as shown in Figure 3. The RBFNN is used to predict 1,200 sets of data, and the maximum relative error in each joint is 0.62%.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 3. Prediction error of RBFNN algorithm. RBFNN: Radial basis function neural network.

3.2. Plan planning based on IGA

3.2.1. Optimization objective

The objective of optimization is to identify the shortest driving distance of the drilling arm end-effector, with the aim of planning the most efficient drilling path for the multi-arm rock drilling robot. This will enhance the effectiveness of the drilling operation and reduce both the construction time and the construction cost.

Upon completion of all drilling tasks by the end-effector of each drilling arm, the shortest possible moving distance of the end effector is designated as the optimization objective. The moving distance of the end effector is expressed as follows:

$$ D=\sum_{i=1}^{n-1}d_i\ \ \ (i=1,2,3\cdots ,n) $$

Where D represents the total moving distance of the drilling arm end effector, di signifies the distance between two adjacent hole positions, and n is the number of holes.

The fundamental problem with path planning can be summarized as follows: the end effector traverses all points, and each point can only be passed once, resulting in the sum of the paths taken being equivalent to the shortest distance. The objective of the path planning investigated in this paper is to find a path that traverses n holes, with each hole being passed through once, and without any crossover paths. The objective of optimization in the problem of path planning is given in

$$ \begin{array}{lll}\min D= & \sum_{i \neq i} d_{i j} x_{i j} & \\s.t. & \sum_{j \neq i} x_{i j}=1, \quad i, j \in V \\& \sum x_{i j}=n-1, \quad i, j \in V \\& x_{i j} \in\{0,1\}, \quad i, j \in V \\\end{array} $$

Where dij is the distance between two holes, and xij is the mathematical model variable. The first two constraints ensure that the path bifurcates during the optimization process, the third constraint ensures that each hole only undergoes one drilling, and the fourth constraint indicates that when the hole (i, j) is on the optimal path, xij = 1, otherwise, xij = 0.

3.2.2. Improved genetic algorithm

It is important to note that each drilling arm exhibits a random drilling path within its designated working space. To achieve the objective of optimizing the path planning of the multi-arm rock drilling robot, it is proposed that the genetic algorithm be utilized in this process. Considering the suboptimal local search ability, the propensity for premature maturation, and the local optimization of the conventional genetic algorithm, the initial step involves the selection of individuals exhibiting high adaptability in the population through the utilization of a tournament method. Subsequently, a heuristic crossover method is employed, inspired by the greedy heuristic, to perform crossover operations on the selected individuals. This approach is undertaken to yield more optimal evolutionary progeny and concurrently enhance the efficiency of the optimization search. Secondly, three methods of exchange, reversal and insertion are used to carry out the mutation operation, with the objective being to improve the population mutation ability and increase the population diversity. Finally, simulated annealing and local search based on large-scale neighborhood search are performed on the new population to improve the global optimization ability and avoid falling into local optimum in the solution process. The flow of improved genetic algorithm (IGA) is illustrated in Figure 4.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 4. Flow of the IGA. IGA: Improved genetic algorithm.

Based on IGA, the drilling arm path planning problem of the multi-arm rock drilling robot can be transformed into a directed graph G = (N, A) model with N points, where N = {1, 2, 3, …, n}, A = {(i, j)|i, jN}, the distance between the two adjacent holes (i, j) is dij. Firstly, the number of all holes in the tunnel section is coded as the problem parameter, and the chromosome coding of each hole is carried out by using the conventional non-repeating integer, that is, real number coding, as given in

$$ C=[v_1,v_2,v_3\cdots v_n],v_i\in\left \{1,2,3\cdots N \right \},v_i\neq v_j $$

The fitness function is a significant metric for evaluating the individual advantages and disadvantages of the population. In accordance with the principle of “Natural selection, survival of the fittest”, the greater the individual fitness value, the greater the adaptability to the environment and the higher the probability of survival. In accordance with the optimization objective of the path planning, the fitness function of the individual population is designed as the inverse of the objective function, as given in

$$ f(x)=1/\sum_{i=1}^{n-1}d_{i_{i-1}i} $$

3.2.3. Computational complexity of IGA

The time complexity of standard GA is usually expressed as

$$ O(G\times(N\times C+S+X+M)) $$

Where G is the iterations, N is the population size, C is the calculation time of individual fitness, S is the select operation time, X is the crossover operation time, and M is the mutation operation time.

Considering the aforementioned points, tournament selection, reverse crossover mutation and simulated annealing neighborhood search are adopted in order to optimize and improve the poor local search ability, premature maturation proclivity and local optimization of the traditional genetic algorithm. The time complexity of IGA and standard GA is illustrated in Table 2.

Table 2

Variable values for each joint of the drilling arm

Operation GA IGA
Fitness O (N × C) O (N × C)
Selection O (NlogN) O (N)
Crossover and mutation O (N) O (N)
Local search - O (G × N × C)

As demonstrated in Table 2, the overall time complexity of IGA is essentially equivalent to that of standard GA, with the exception of the augmentation of local complexity resulting from the enhancement of simulated annealing and local search based on large-scale neighborhood search in the local search module.

3.3. Multi-arm cooperative motion path planning based on IAPF

The drilling arm of the multi-arm rock drilling robot can be regarded as a multi-joint manipulator structure. It is evident that the prevailing path planning methodologies employed by the manipulator encompass a range of approaches, including RRT, A*, and the APF, amongst others. The construction of the gravitational potential field and the repulsion potential field enables the manipulator to move to the target point under the combined force of gravity and repulsion. The calculation required is relatively small, and as a result, the method is widely used in the path planning of manipulators and mobile robots.

The conventional APF is predicated on Cartesian space for the purpose of search. In the case of the redundant manipulator, it possesses redundant DOFs, and the pose of the manipulator is related to the movement of each joint. The calculation of the kinematic inverse solution of the manipulator at the corresponding momentary position must be conducted in real time. This process entails a substantial computational burden and exhibits suboptimal search efficiency. Moreover, given the redundant DOFs of the manipulator, the singular position solution of the manipulator can be obtained. It is evident that the conventional potential field function is enhanced by the introduction of a novel repulsive potential field function and gravitational potential field function. These functions facilitate the realization of an anti-collision cooperative drilling mechanism for the drilling arm, thereby preventing the APF from attaining a local optimal solution[26].

The joint space of the drilling arm is selected as the search space for path planning, and the angular displacements of the joints are continuous in the joint space, thereby ensuring that the singular solution is avoided. Within the joint space, the value of each joint variable in the present state of the drilling arm is designated as the initial attitude, and the value of each joint variable in the subsequent state of the drilling arm is sought. The total potential energy of disparate joint variable combinations is calculated to regulate the motion of the drilling arm.

3.3.1. Improvement of gravitational potential field function

The conventional potential field function exclusively restricts the distal extremity of the drilling arm, whereas the mobility of the drilling arm is governed by the entirety of its joints. It is imperative that the potential field function constrains each joint. In order to enhance the precision of the drilling arm’s control and ensure the feasibility of the planned trajectory, it is imperative to incorporate the potential energy into each joint of the drilling arm. The gravitational potential energy function is re-established in

$$ \begin{array}{l}U_{\text {att }}(i)=\left\{\begin{array}{ll}\frac{1}{2} \delta d\left(q_{i}, q_{\text {goal }}\right) & d\left(q_{i}, q_{\text {goal }}\right) \leq d_{\text {goal }}^{*} \\d_{\text {goal }}^{*} \delta d\left(q_{i}, q_{\text {goal }}\right)-\delta d_{\text {goal }}^{*} & d\left(q_{i}, q_{\text {goal }}\right)>d_{\text {goal }}^{*}\end{array}\right. \\U_{\text {att }}=\sum_{i=1}^{7} U_{\text {att }}(i)\end{array} $$

where δ is the gravitational gain, Uatt(i) is the gravitational potential energy of the drilling arm joint, Uatt is the sum of the potential energy of each joint of the drilling arm, qi is the current position of the drilling arm joint, qgoal is the target position of the drilling arm joint, d(qi, qgoal) is the distance from the current position of the drilling arm joint to the target position, and $$ d_{\text {goal }}^{*} $$ is the gravitational threshold.

The gravitational function, derived from the negative gradient of the gravitational potential field, is given in

$$ \begin{array}{l}F_{\text {att }}(i)=-\nabla U_{\text {att }}=\left\{\begin{array}{ll}\delta \left(q_{\text {goal }}-q_{i}\right) & d\left(q_{i}, q_{\text {goal }}\right) \leq d_{\text {goal }}^{*} \\\frac{d_{\text {goal }}^{*} \delta \left(q_{\text {goal }}-q_{i}\right)}{d(q_i,q_{\text{goal}})} & d\left(q_{i}, q_{\text {goal }}\right)>d_{\text {goal }}^{*}\end{array}\right. \\F_{\text {att }}=\sum_{i=1}^{7} F_{\text {att }}(i)\end{array} $$

where Fatt(i) is the gravitational force of the drilling arm joint, Fatt is the sum of the gravitational force of each joint of the drilling arm, and the meaning of the other parameters is the same as Equation (8).

3.3.2. Improvement of repulsion potential field function

In the traditional potential field, the repulsive force on the drilling arm is large when the drilling arm is near the target point. This results in the drilling arm not being able to reach the target point. To avoid excessive repulsive force around the target point, the traditional repulsive potential energy function is reconstructed. The novel repulsive force function is defined in

$$ \begin{array}{l}U_{\text {rep }}(q)=\left\{\begin{array}{ll}\frac{\lambda}{2}\left(\frac{1}{d\left(q_{i}, q_{\text {obs }}\right)}-\frac{1}{d_{\mathrm{A}}}\right) d\left(q_{i}, q_{\text {goal }}\right) & d\left(q_{i}, q_{\text {obs }}\right) \leq d_{\mathrm{A}} \\0 & d\left(q_{i}, q_{\text {obs }}\right)>d_{\mathrm{A}}\end{array}\right. \\U_{\text {rep }}=\sum_{i=1}^{7} U_{\text {rep }}(q)\end{array} $$

where Urep(q) is the repulsive potential energy of the drilling arm joint, Urep is the sum of the repulsive potential energy of each joint of the drilling arm, λ is the repulsive potential energy factor, qobs is the obstacle position, d(qi, qobs) is the distance between the current position and the obstacle qobs, d(qi, qgoal) is the distance from the current position of the drilling arm joint to the target position, and dA is the range of the repulsive potential energy of the obstacle.

The repulsive force function generated by the negative gradient of the repulsion potential field is as follows.

$$ \begin{array}{l}F_{\text {req }}(q)=\left\{\begin{array}{ll}F_{\text {req1 }}N_{\text{OR}}+ F_{\text {req2 }}N_{\text{RG}}& d\left(q_{i}, q_{\text {obs }}\right) \leq d_{\mathrm{A}} \\0 & d\left(q_{i}, q_{\text {obs }}\right)>d_{\mathrm{A}}\end{array}\right. \\F_{\text {req }}=\sum_{i=1}^{7} F_{\text {req }}(q)\end{array} $$

where Frep(q) is the repulsive force on the i-th joint of the drilling arm, Frep is the sum of the repulsive forces on all joints of the drilling arm, and NOR and NRG are two vectors, which represent the unit vectors of the distance from the drilling arm joint to the obstacle and the distance from the drilling arm joint to the target point, respectively. Frep1 and Frep2 shown in Figure 5 are the two component forces generated by the negative gradient after the improvement of the repulsive potential field function. The specific calculation method is given in

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 5. Improved repulsion diagram.

$$ \begin{array}{l}F_{\text {req1 }}=\lambda (\frac{1}{d(q_i,q_{\text{obs}})}-\frac{1}{d_{\text{A}}})\frac{1}{d^2(q_i,q_{\text{goal}})}1\\F_{\text {req2 }}=\frac{\lambda}{2}(\frac{1}{d(q_i,q_{\text{obs}})}-\frac{1}{d_{\text{A}}})^2d(q_i,q_{\text{goal}})\end{array} $$

As demonstrated in Figure 5, the direction of Frep1 is determined by the presence of an obstacle, with the direction of Frep2 being directed by the robot towards the target point. This aligns with the direction of gravitational force, thus avoiding both the unreachable target point and the local minimum problem.

3.3.3. Computational complexity of IAPF

The time complexity of traditional APF is usually expressed as O (M × N). In this instance, M is used to denote the steps involved in path planning, while N is used to denote the number of obstacles. It is evident from the fact that the IAPF primarily employs strategies involving piecewise potential field function optimization and solving space transfer. Consequently, for the manipulator with degree of freedom j, the time complexity of IAPF is O (M × N × j). It has been demonstrated that the sensitivity of the joint space constraint of a high-DOF manipulator can be reduced without an increase in complexity.

3.4. Smooth trajectory planning based on quintic B-spline curve

In light of the intricate and dynamic nature of the drilling arm’s operational environment, the expeditious, effective and dependable planning of obstacle avoidance trajectories assumes paramount importance. The B-spline function is extensively utilized in the domain of manipulator trajectory planning, owing to its superior local control properties and high computational efficiency, as determined by

$$ P(u)=\sum_{i=0}^nN_iF_{i,n}(u) $$

where Ni is a series of control points, Fi,n(u) is the B-spline weight function of order n, u is the sampling time interval, i is the sequence of B-spline function segments, and n is the number of control points.

The drilling arm is a large-scale, heavy-duty manipulator that is subjected to significant impact vibration loads. Consequently, joint trajectory planning methods based on traditional cubic B-spline curves are incapable of ensuring the continuity of the position and velocity of the joint. In contrast, quintic B-spline curves have the capacity to guarantee the continuity of the angle, angular velocity, angular acceleration, and angular jerk of each joint. Furthermore, these curves enable the specification of the angular velocities and angular acceleration of the starting and ending path points. The expression of the quintic B-spline curve can be derived from the aforementioned B-spline function, as given in

$$ P(u)=\frac{1}{120}\left[\begin{array}{llllll}u^{5} & u^{4} & u^{3} & u^{2} & u & 1\end{array}\right]\left[\begin{array}{cccccc}-1 & 5 & -10 & 10 & -5 & 1 \\5 & -20 & 30 & -20 & 5 & 0 \\-10 & 20 & 0 & -20 & 10 & 0 \\10 & 20 & -60 & 20 & 10 & 0 \\-5 & -50 & 0 & 50 & 5 & 0 \\1 & 26 & 66 & 26 & 1 & 0\end{array}\right]\left[\begin{array}{l}N_{i-1} \\N_{i} \\N_{i+1} \\N_{i+2} \\N_{i+3} \\N_{i+4}\end{array}\right] $$

where Ni is a series of control points, and u is the sampling time interval.

When the quintic B-spline curve is used to optimize the motion trajectory in the joint space of the drilling arm, the trajectory function of every joint θi(u) can be expressed as:

$$ \begin{aligned}\theta_{i}(u)= & \frac{1}{120}\left[\left(-N_{i-1}+5 N_{i}-10 N_{i+1}+10 N_{i+2}-5 N_{i+3}+N_{i+4}\right) u^{5}+\right. \\& \left(5 N_{i-1}-20 N_{i}+30 N_{i+1}-20 N_{i+2}+5 N_{i+3}\right) u^{4}+\left(-10 N_{i-1}+\right. \\& \left.20 N_{i}-20 N_{i+2}+10 N_{i+3}\right) u^{3}+\left(10 N_{i-1}+20 N_{i}-60 N_{i+1}+\right. \\& \left.20 N_{i+2}+10 N_{i+3}\right) u^{2}+\left(-5 N_{i-1}-50 N_{i}+50 N_{i+2}+5 N_{i+3}\right) u \\& \left.+\left(N_{i-1}+26 N_{i}+66 N_{i+1}+26 N_{i+2}+N_{i+3}\right)\right]\end{aligned} $$

To ensure the continuity of the running trajectory during the movement of the drilling arm, it is necessary to judge the continuity of the running trajectory of the drilling arm based on the quintic B-spline curve, and the continuity of the trajectory includes the displacement, velocity, acceleration and jerk continuity. The displacement, velocity, acceleration, and jerk of the ending point of the i-th trajectory segment and the starting point of the i+1-th trajectory segment are derived by substituting t = 0 and t = 1, and the result is given below.

$$ \left\{\begin{array}{l}\theta_{i+1}(0)=\theta_{i}(1)=\left(N_{i}+26 N_{i+1}+66 N_{i+2}+26 N_{i+3}+N_{i+4}\right) / 120 \\\dot{\theta}_{i+1}(0)=\dot{\theta}_{i}(1)=\left(-N_{i}-10 N_{i+1}+10 N_{i+3}+N_{i+4}\right) / 24 \\\ddot{\theta}_{i+1}(0)=\ddot{\theta}_{i}(1)=\left(N_{i}+2 N_{i+1}-6 N_{i+2}+2 N_{i+3}+N_{i+4}\right) / 6 \\\dddot{\theta}_{i+1}(0)=\dddot{\theta}_{i}(1)=\left(-N_{i}+2 N_{i+1}-2 N_{i+3}+N_{i+4}\right) / 2\end{array}\right. $$

where θi is the generalized displacement of the joints, $$ \dot{\theta}_{i} $$ is the generalized velocity of the joints, $$ \ddot{\theta}_{i} $$ is the generalized acceleration of the joints, and $$ \dddot{\theta}_{i} $$ is the generalized jerk of the joints.

It has been demonstrated that when the spatial motion trajectory of the drilling arm joint is optimized based on the quintic B-spline curve, the displacement, first-order, second-order, and third-order derivatives are equal at the transition points of the two adjacent trajectories. Consequently, it can be concluded that the displacement, velocity, acceleration, and jerk are all continuous at the transition points of the two adjacent trajectories. This evidence substantiates that the spatial motion trajectory of the drilling arm joint obtained by the quintic B-spline function is relatively smooth.

In the spatial motion trajectory planning of the drilling arm based on quintic B-spline curve, the complete trajectory curve is composed of m-1 segment curves, while the number of passing path points is set as m. The six control points, Ni-1 to Ni+4, corresponding to each segment, are determined uniquely. When the path point Pi is known during the motion process, the control points must be solved by m+4 equations. It is evident that the present analysis has yielded a total of m equations. However, four additional equations are required to ensure the comprehensive understanding of the subject matter. In order to ensure that the trajectory obtained aligns with the operational requirements of the drilling arm, it is necessary to set the velocity and acceleration of the motion trajectory curve of the drilling arm joint in the first and last sections to zero. This adjustment enables the derivation of Equation (17), which is given by:

$$ \left\{\begin{array}{l}\dot{\theta}_{1}(0)=\left(-N_{0}-10 N_{1}+10 N_{3}+N_{4}\right) / 24=0 \\\dot{\theta}_{m-1}(0)=\left(-N_{m-1}-10 N_{m}+10 N_{m+2}+N_{m+3}\right) / 24=0 \\\ddot{\theta}_{1}(1)=\left(N_{0}+2 N_{1}-6 N_{2}+2 N_{3}+N_{4}\right) / 6=0 \\\ddot{\theta}_{m-1}(1)=\left(N_{m-1}+2 N_{m}-6 N_{m+1}+2 N_{m+2}+N_{m+3}\right) / 6=0\end{array}\right. $$

where m is the number of passing path points.

Consequently, the equations for solving the control points have been derived, and by combining Equations (15) and (17), the control points can be determined by

$$ \left[\begin{array}{c}N_{0} \\N_{1} \\\vdots \\N_{m+1} \\N_{m+2} \\N_{m+3}\end{array}\right]=120\left[\begin{array}{cccccccc}1 & 26 & 66 & 26 & 1 & 0 & 0 & 0 \\0 & 0 & 1 & 26 & 66 & 26 & 1 & 0 \\\cdots & \cdots & \cdots & \cdots & \cdots & \cdots & \cdots & \cdots \\-5 & -50 & 0 & -5 & -50 & 0 & 50 & 5 \\20 & 40 & -120 & 40 & 20 & 0 & 0 & 0 \\0 & 0 & 0 & 20 & 40 & -120 & 40 & 20\end{array}\right]^{-1}\left[\begin{array}{c}P_{0} \\P_{1} \\\vdots \\0 \\0 \\0\end{array}\right] $$

where Ni is the control point, and Pi is the path point during the motion process.

4. SIMULATION VERIFICATIONS

4.1. Path planning simulation

The objective of this section is to identify the shortest moving distance of the drilling arm end based on the working area and the number of drilling tasks of each drilling arm of the multi-arm rock drilling robot. The drilling arm is analyzed by path planning and compared with the ant colony optimization algorithm (ACO)[27] and the adaptive genetic algorithm (AGA)[28]. The selection of appropriate algorithm parameters is determined by the problem to be solved, and this determination is made after five experiments. The main parameters of IGA and AGA are set as follows: the population is 50, the crossover probability is 0.95, the mutation probability is 0.05, and the iteration is 400. The main parameters of ACO are as follows: The pheromone heuristic factor is set as α = 1, heuristic function importance factor is β = 3, pheromone volatilization factor is ρ = 0.5, the ant number is m = 50, the total information amount is Q = 1, and the iteration number is Max = 400. In IGA, the probability of exchange mutation is pSwap = 0.2, the probability of reverse mutation is pReversion = 0.5, the probability of insertion mutation is pInsertion = 0.3, and the cooling factor is λ = 0.99.

A comprehensive comparison of the simulation results of the path planning of the three algorithms is presented in Figure 6. This figure illustrates the moving distance of the drilling arm end obtained by different algorithms. A comparison of the total moving distance of the end of the three drilling arms reveals that they are 5.39 and 10.84 m shorter than those of ACO and AGA, respectively. In comparison with ACO, the movement distances of the left, middle, and right drilling arms are reduced from 48.36, 66.79, and 45.88 m to 46.94, 64.09, and 44.61 m, respectively. The percentage of shortening is 3.03%, 4.21%, and 2.85%, respectively. In comparison with AGA, the movement distances of the three drilling arms are reduced by 7.14%, 6.99%, and 6.75%, respectively. Consequently, the proposed IGA exhibits substantial advantages in identifying the shortest path when compared with conventional path planning methodologies.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 6. Moving distances of drilling arms with different algorithms.

4.2. Multi-arm anti-collision simulation

The collision interference of the drilling arm of the multi-arm rock drilling robot primarily occurs between the middle drilling arm and the left and right drilling arms. The working area of the middle drilling arm can be divided into two sections, left and right, with the center line of the tunnel designated as the center. The area on the left side of the tunnel center line is identified as the potential collision interference zone during drilling operations with the left drilling arm, while the right side of the tunnel center line is designated as the potential collision interference area when drilling with the right drilling arm. In accordance with the drilling trajectory that was derived from the preceding planning stage, the collision-free trajectory planning of the drilling arms of the multi-arm rock drilling robot is subsequently executed. It has been determined that the drilling arms on the left and right are not identical to the drilling arm in the center. As a consequence, the drilling arms on the left and right continue to drill, while the drilling arm in the center ceases movement and functions as a static obstacle once the drilling task is complete. According to the starting and ending points of each drilling arm, the collision-free path planning simulation is carried out for the middle drilling arm and the left drilling arm, and the middle drilling arm and the right drilling arm, respectively. The drilling path planning of drilling arms, based on shortest moving distance optimization, is illustrated in Figure 7. The simulation results indicate that the total path planned by IAPF is 155.64 m, while that of RRT is 166.48 m. The result of the path planning process based on IAPF is 6.51% lower than that of the RRT method. Furthermore, the trajectory devised according to IAPF incorporates greater horizontal adjustment, a feature that is more conducive to the continuous and efficient operation of heavy-duty drilling arms.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 7. Drilling path planning of drilling arms based on shortest moving distance optimization. (A) IAPF; (B) RRT. IAPF: Enhanced artificial potential field; RRT: exploring random tree.

Furthermore, the distance between the enveloping bodies of each joint after the simplification of the drilling arm is sorted from large to small, and the shortest distance between the enveloping bodies when the two drilling arms are drilled cooperatively is extracted to determine whether there is a collision between the two drilling arms. As illustrated in Figure 8, the minimum distances between the enveloping bodies of the middle drilling arm and the left/right drilling arm are demonstrated when drilling cooperatively. As demonstrated in Figure 8, the minimum distances between the middle drilling arm and the left/right drilling arms are 984.6 and 580.8 mm, respectively, when the shortest moving distance of the drilling arms is designated as the optimization objective. Consequently, the drilling trajectory delineated by the IAPF method proves efficacious in ensuring the safety of the multi-arm drilling robot’s collaborative drilling operations.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 8. Minimum distance between drilling arms.

4.3. Trajectory planning simulation

Given the structural similarity between the three drilling arms of the rock drilling robot, the trajectory planning of the middle drilling arm is selected as a model to assess the viability of implementing the quintic B-spline curve in the trajectory planning of the drilling arm. To illustrate this process, we will examine the middle drilling arm. In its initial state, the arm is set to one of the hole positions, with coordinates (10025, 907, 614). The position coordinates of the selected target hole position are (9000, -3877, 6595), and the value of each joint variable of the drilling arm when the drilling arm reaches the target hole position is shown in Table 3.

Table 3

Variable values for each joint of the drilling arm

Drilling arm end position θ 1 θ 2 d 3/mm θ 4 θ 5 θ 6
(10025, 907, 614) 0 -90 5,598 0 90 90
(9000, -3877, 6595) -46.77 -134.67 8,486.38 0 134.67 136.77

In the construction process of the rock drilling robot, it is imperative that the drilling arm be constrained to drill perpendicular to the tunnel face. This ensures that the joint 4 remains unchanged in the initial state. The joint 7, designated as the end moving joint, is responsible for compensating for the distance between the tunnel face and the multi-arm rock drilling robot. Consequently, the joints 4 and 7 are not considered in the trajectory planning process. The focus is instead on the optimization and analysis of the motion trajectories of joints 1, 2, 3, 5, and 6. It should be noted that joints 1, 2, 5, and 6 are rotating joints, while joint 3 is a moving joint. The simulation results of the optimized trajectory are presented in Figure 9 below. As illustrated in Figure 9A, the displacement curve of each joint optimized by the quintic B-spline curve is a continuous and smooth curve. As illustrated in Figure 9B-D, the velocity, acceleration, and jerk curves of each joint during movement are continuous curves. The jerk curve is also referred to as the pulsation curve. This curve exerts a certain influence on the impact of the drilling arm movement process. In the event that the pulsation curve is discontinuous, it has the potential to exert a substantial impact on the drilling arm during movement, which may result in the drilling arm vibrating and the occurrence of other problems. These issues can affect the positioning accuracy of the drilling arm and potentially lead to fatigue damage. The pulsation curves of each joint post-optimization are continuous, thereby effectively mitigating the jitter impact. Consequently, the optimized spatial motion trajectory of the drilling arm joint proposed in this paper is substantiated. The simulation results verify the effectiveness of the quintic B-spline curve in trajectory planning applications of cooperative drilling arms.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 9. Trajectory planning of each joint of the drilling arm. (A) Displacements of the joints; (B) Velocities of the joints; (C) Accelerations of the joints; (D) Jerks of the joints.

5. EXPERIMENT RESULTS

To validate the proposed motion planning methods, a drilling hole path planning experiment and a drilling arm trajectory planning experiment are conducted on a three-arm drilling jumbo platform. The configuration of the experimental platform is illustrated in Figure 10. Firstly, the drilling paths of the drilling arms are randomly arranged according to the test site. In this arrangement, 40 holes are allocated for the left and right drilling arms, while 52 holes are allocated for the middle drilling arms. The coordinate truth values of paths and the truth positions of key joints are measured by means of an electronic total station. As illustrated in Figure 11, the frames depicting the continuous motion of the right drilling arm during the experiment are presented.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 10. The structure of the experimental multi-arm drilling jumbo platform.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 11. Continuous motion frames in planning experiment of the right drilling arm.

Due to the flexibility of large-scale heavy-duty drilling arms, the actual hole positions exhibit a slight offset from the theoretical values. It is important to note that the motion planning of drilling arms is based on the theoretical positions of drilling paths, while the moving distance of drilling arms is counted based on actual hole positions. The theoretical positions of drilling holes and the actual moving paths of drilling arms based on IGA are illustrated in Figure 12. The displacement trajectories of drilling arms, when operated with disparate optimization algorithms, are illustrated in Figure 13.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 12. Theoretical positions of drilling holes and actual moving paths of drilling arms based on IGA. IGA: Improved genetic algorithm.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 13. Moving distances of drilling arms with different algorithms.

As illustrated in Figure 12, the total moving distance obtained by the proposed IGA method is reduced by 4.84% and 4.59% compared with the ACO and AGA methods in actual path planning of drilling arms.

The movement of drilling arms is governed by a sequence of preset holes, as delineated by the IGA algorithm. In the drilling hole tracking process, it is imperative that the drilling arm be constrained perpendicular to the tunnel face, thereby ensuring the stability of the rolling joint 4. The angular displacements of each joint of the drilling arms are measured by means of an electronic total station and airborne sensors, as illustrated in Figure 14. The rolling joint 4 has undergone negligible modifications, with the exception of undergoing a specific angular adjustment to guarantee the precise positioning of the perforation. Consequently, the rotational angular velocity, angular acceleration, and angular jerk of joint 4 are not taken into account. The rotation angles of joints 1, 2, 5, and 6 are essentially confined to a range of ±40 degrees. The rotation angle of the medial drilling arm exhibits greater variability, as it is required to traverse a greater number of holes. In contrast, the rotation ranges of the lateral drilling arms are comparatively limited.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 14. Rotation angles of the rotational joints with different drilling arms.

Furthermore, the rotational angular velocity, angular acceleration, and angular jerk of each joint are obtained and displayed in Figure 15. These values are derived by taking the first, second, and third derivatives of the rotation angles of joints 1, 2, 5, and 6. It has been determined that the velocity, acceleration, and jerk curves of each joint that have been optimized by the quintic B-spline during movement are also continuous curves. Specifically, joints 1 and 2 are directly connected to the body of the rock drilling jumbo, resulting in reduced angular accelerations and angular jerks during large-scale movement of the drilling arms. This suggests that joints 1 and 2 are less susceptible to significant deflection deformation and buffeting effects, leading to enhanced stability. Joints 5 and 6 are closer to the end of the drilling arms, so they face more disturbances and uncertainties in the path of traversing multiple holes. These joints usually show greater angular acceleration and angular jerk. A comparative analysis of the dynamic performance of different drilling arms reveals that the left and right drilling arms exhibit greater variability in their dynamic indexes due to the necessity of larger angles of swing to achieve the positioning of the edge holes. In contrast, the middle drilling arm demonstrates reduced fluctuations in acceleration and jerk indexes, attributable to its comparatively smaller swinging angle. The experimental results also verify the effectiveness of the proposed methods in trajectory planning applications involving large-scale and heavy-duty cooperative multi-drilling arms.

Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

Figure 15. Angular velocities, angular accelerations and angular jerks of the rotational joints with different drilling arms.

6. CONCLUSIONS

(1) The modified D-H method is employed to establish the kinematic model of the multi-arm rock drilling robot. The inverse kinematic model of the drilling arm is constructed based on the RBFNN. The findings indicate that the maximum error in the drilling arm’s positioning is 2.94 mm, and the error remains below 3%, enhancing the precision in addressing the inverse kinematics solution of the large redundant DOFs and heavy-duty engineering manipulator.

(2) The IGA is proposed to optimize the paths of the multi-arm rock drilling robot by taking the shortest moving distance as the optimization objective. The simulation and experimental results demonstrate that, in comparison with ACO and AGA methods, the proposed IGA can effectively reduce the moving distance of the drilling arms in multi-hole drilling tasks, thereby enhancing efficiency and reducing energy consumption.

(3) A methodology for the spatial planning of anti-collision paths is hereby proposed for the purpose of facilitating cooperative drilling operations. This methodology is predicated on the IAPF method. When the drilling path obtained by the shortest distance is used for path planning, the shortest distances between the middle drilling arm and the left and right drilling arms are 984.6 and 580.8 mm, respectively.

(4) In addressing the significant impact of motion joints during the drilling operation of the multi-arm rock drilling robot, a spatial trajectory planning method has been developed. This method utilizes a quintic B-spline curve, aiming to enhance the stability of the drilling arm’s trajectory. Concurrently, it ensures the continuity of the running velocity, acceleration, and jerk curves of each joint. Through simulations and experiments, this method has been shown to effectively reduce the robust vibration of the drilling arm trajectory.

The advent of artificial intelligence, large models, edge computing, and other emerging technologies has precipitated a paradigm shift in the field of motion planning through learning-based methods. We are cognizant of the immense potential inherent in multi-arm path planning based on learning, and we are committed to the active expansion of our research on the method of motion planning based on learning for large-scale and cooperative multi-arm tunnel drilling robots.

DECLARATIONS

Authors’ contributions

Made substantial contributions to conception and design of the study and performed data analysis and interpretation: Cui, Y.; Cui, M.

Performed data acquisition, as well as providing administrative, technical, and material support: Pu, J.; Cui, M.; Hu, N.

Availability of data and materials

The data that support the findings of this study are available from the corresponding author upon reasonable request.

Financial support and sponsorship

This work was supported in part by the National Natural Science Foundation of China under Grant 12472038, in part by the Basic Research Program of Jiangsu under Grant BK20230688, and in part by the Research Fund for Doctoral Degree Teachers of Jiangsu Normal University of China under Grant 22XFRS011.

Conflicts of interest

All authors declared that there are no conflicts of interest.

Ethical approval and consent to participate

Not applicable.

Consent for publication

Not applicable.

Copyright

© The Author(s) 2025.

REFERENCES

1. Li, J.; Zhan, K. Intelligent mining technology for an underground metal mine based on unmanned equipment. Engineering 2018, 4, 381-91.

2. Reiter, A.; Muller, A.; Gattringer, H. On higher order inverse kinematics methods in time-optimal trajectory planning for kinematically redundant manipulators. IEEE. Trans. Ind. Inf. 2018, 14, 1681-90.

3. Cui, Y.; Liu, S.; Zhou, D.; Zhang, D. Position tracking and dynamic control of an innovative anchor beam supporting robot. Mech. Based. Des. Struct. Mach. 2023, 51, 721-39.

4. Zheng, S.; Ding, R.; Zhang, J.; Xu, B. Global energy efficiency improvement of redundant hydraulic manipulator with dynamic programming. Energy. Convers. Manag. 2021, 230, 113762.

5. Deng, W.; Zhou, H.; Zhou, J.; Yao, J. Neural network-based adaptive asymptotic prescribed performance tracking control of hydraulic manipulators. IEEE. Trans. Syst. Man. Cybern. Syst. 2023, 53, 285-95.

6. Su, C.; Zhang, S.; Lou, S.; et al. Trajectory coordination for a cooperative multi-manipulator system and dynamic simulation error analysis. Rob. Auton. Syst. 2020, 131, 103588.

7. Baressi Šegota, S.; Anđelić, N.; Lorencin, I.; Saga, M.; Car, Z. Path planning optimization of six-degree-of-freedom robotic manipulators using evolutionary algorithms. Int. J. Adv. Robot. Syst. 2020, 17, 172988142090807.

8. Yang, D.; Dong, L.; Dai, J. K. Collision avoidance trajectory planning for a dual-robot system: using a modified APF method. Robotica 2024, 42, 846-63.

9. Liu, S.; Sun, W.; Liu, Y.; et al. Multi-objective trajectory optimization algorithm for cooperative six-axis manipulator. In: 2024 7th International Conference on Mechatronics, Robotics and Automation (ICMRA), Wuhan, China. Sep 20-22, 2024. IEEE; 2024. pp. 84-9.

10. Jin, R.; Rocco, P.; Geng, Y. Cartesian trajectory planning of space robots using a multi-objective optimization. Aerosp. Sci. Technol. 2021, 108, 106360.

11. Meng, X.; Ding, Z. Research on multi-stage path planning for human-multi-robot collaboration assembly. In: 2024 5th International Conference on Artificial Intelligence and Computer Engineering (ICAICE), Wuhu, China. Nov 08-10, 2024. IEEE; 2024. pp. 1138-42.

12. Shi, W.; Wang, K.; Zhao, C.; Tian, M. Obstacle avoidance path planning for the dual-arm robot based on an improved RRT algorithm. Appl. Sci. 2022, 12, 4087.

13. Sun, F.; Chen, Y.; Wu, Y.; Li, L.; Ren, X. Motion planning and cooperative manipulation for mobile robots with dual arms. IEEE. Trans. Emerg. Top. Comput. Intell. 2022, 6, 1345-56.

14. Zhang, Y.; Jia, Y. Motion planning of redundant dual-arm robots with multicriterion optimization. IEEE. Syst. J. 2023, 17, 4189-99.

15. Mateu-Gomez, D.; Martínez-Peral, F. J.; Perez-Vidal, C. Multi-arm trajectory planning for optimal collision-free pick-and-place operations. Technologies 2024, 12, 12.

16. Li, M.; Li, P.; Wei, D.; et al. Research on dual-robot cooperative path planning for multi-material additive manufacturing. Int. J. Adv. Manuf. Technol. 2024, 135, 4229-44.

17. Xu, Q.; Lin, Y. Research on high-precision motion planning of large multi-arm rock drilling robot based on multi-strategy sampling rapidly exploring random tree. Sensors 2025, 25, 2654.

18. Chu, X.; Hu, Q.; Zhang, J. Path planning and collision avoidance for a multi-arm space maneuverable robot. IEEE. Trans. Aerosp. Electron. Syst. 2018, 54, 217-32.

19. Kawabe, T.; Nishi, T. A flexible collision-free trajectory planning for multiple robot arms by combining Q-learning and RRT. In: 2022 IEEE 18th International Conference on Automation Science and Engineering (CASE), Mexico City, Mexico. Aug 20-24, 2022. IEEE; 2022. pp. 2363-8.

20. Liu, C.; Cao, G.; Qu, Y.; Cheng, Y. An improved PSO algorithm for time-optimal trajectory planning of Delta robot in intelligent packaging. Int. J. Adv. Manuf. Technol. 2020, 107, 1091-9.

21. Ni, S.; Chen, W.; Ju, H.; Chen, T. Coordinated trajectory planning of a dual-arm space robot with multiple avoidance constraints. Acta. Astronaut. 2022, 195, 379-91.

22. Chen, G.; Luo, N.; Liu, D.; Zhao, Z.; Liang, C. Path planning for manipulators based on an improved probabilistic roadmap method. Rob. Comput. Integr. Manuf. 2021, 72, 102196.

23. Liu, S.; Wu, Y.; Zhang, H. An improved RRT path planning method incorporating deep reinforcement learning for space multi-arm robot. In: Yadav S, Arya Y, Pandey SM, Gherabi N, Karras DA, editors. Proceedings of 3rd International Conference on Artificial Intelligence, Robotics, and Communication. Singapore: Springer Nature; 2024. pp. 225-37.

24. Sun, D.; Liao, Q. Real-time coordination of multiple robotic arms with reactive trajectory modulation. IEEE. Trans. Robot. 2025, 41, 200-19.

25. Dio, M.; Graichen, K.; Völz, A. Time-optimal path parameterization for cooperative multi-arm robotic systems with third-order constraints. In 2024 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Abu Dhabi, United Arab Emirates. Oct 14-18, 2024. IEEE; 2024. pp. 3043-8.

26. Wu, Z.; Dai, J.; Jiang, B.; Karimi, H. R. Robot path planning based on artificial potential field with deterministic annealing. ISA. Trans. 2023, 138, 74-87.

27. Morin, M.; Abi-zeid, I.; Quimper, C. Ant colony optimization for path planning in search and rescue operations. Eur. J. Oper. Res. 2023, 305, 53-63.

28. Cui, H.; Qiu, J.; Cao, J.; Guo, M.; Chen, X.; Gorbachev, S. Route optimization in township logistics distribution considering customer satisfaction based on adaptive genetic algorithm. Math. Comput. Simul. 2023, 204, 28-42.

Cite This Article

Research Article
Open Access
Smooth and efficient motion planning of large-scale and cooperative multi-arm tunnel drilling robot

How to Cite

Download Citation

If you have the appropriate software installed, you can download article citation data to the citation manager of your choice. Simply select your manager software from the list below and click on download.

Export Citation File:

Type of Import

Tips on Downloading Citation

This feature enables you to download the bibliographic information (also called citation data, header data, or metadata) for the articles on our site.

Citation Manager File Format

Use the radio buttons to choose how to format the bibliographic data you're harvesting. Several citation manager formats are available, including EndNote and BibTex.

Type of Import

If you have citation management software installed on your computer your Web browser should be able to import metadata directly into your reference database.

Direct Import: When the Direct Import option is selected (the default state), a dialogue box will give you the option to Save or Open the downloaded citation data. Choosing Open will either launch your citation manager or give you a choice of applications with which to use the metadata. The Save option saves the file locally for later use.

Indirect Import: When the Indirect Import option is selected, the metadata is displayed and may be copied and pasted as needed.

About This Article

© The Author(s) 2025. Open Access This article is licensed under a Creative Commons Attribution 4.0 International License (https://creativecommons.org/licenses/by/4.0/), which permits unrestricted use, sharing, adaptation, distribution and reproduction in any medium or format, for any purpose, even commercially, as long as you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons license, and indicate if changes were made.

Data & Comments

Data

Views
43
Downloads
5
Citations
0
Comments
0
2

Comments

Comments must be written in English. Spam, offensive content, impersonation, and private information will not be permitted. If any comment is reported and identified as inappropriate content by OAE staff, the comment will be removed without notice. If you have any queries or need any help, please contact us at [email protected].

0
Download PDF
Share This Article
Scan the QR code for reading!
See Updates
Contents
Figures
Related
Intelligence & Robotics
ISSN 2770-3541 (Online)

Portico

All published articles are preserved here permanently:

https://www.portico.org/publishers/oae/

Portico

All published articles are preserved here permanently:

https://www.portico.org/publishers/oae/