Next Article in Journal
Developing a Novel Adaptive Double Deep Q-Learning-Based Routing Strategy for IoT-Based Wireless Sensor Network with Federated Learning
Previous Article in Journal
Filamentary Convolution for SLI: A Brain-Inspired Approach with High Efficiency
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Obstacle-Avoidance Planning in C-Space for Continuum Manipulator Based on IRRT-Connect

1
State Grid Electric Power Research Institute of Liaoning Electric Power Co., Ltd., Shenyang 110000, China
2
College of Electrical Engineering, Sichuan University, Chengdu 610065, China
*
Author to whom correspondence should be addressed.
Sensors 2025, 25(10), 3081; https://doi.org/10.3390/s25103081
Submission received: 9 April 2025 / Revised: 8 May 2025 / Accepted: 9 May 2025 / Published: 13 May 2025
(This article belongs to the Section Sensors and Robotics)

Abstract

:
Aiming at the challenge of trajectory planning for a continuum manipulator in the confined spaces of gas-insulated switchgear (GIS) chambers during intelligent operation and maintenance of power equipment, this paper proposes a configuration space (C-space) obstacle-avoidance planning method based on an improved RRT-Connect algorithm. By constructing a virtual joint-space obstacle map, the collision-avoidance problem in Cartesian space is transformed into a joint-space path search problem, significantly reducing the computational burden of frequent inverse kinematics solutions inherent in traditional methods. Compared to the RRT-Connect algorithm, improvements in node expansion strategies and greedy optimization mechanisms effectively minimize redundant nodes and enhance path generation efficiency: the number of iterations is reduced by 68% and convergence speed is improved by 35%. Combined with polynomial-driven trajectory planning, the method successfully resolves and smoothens driving cable length variations, achieving efficient and stable control for both the end-effector and arm configuration of a dual-segment continuum manipulator. Simulation and experimental results demonstrate that the proposed algorithm rapidly generates collision-free arm configuration trajectories with high trajectory coincidence in typical GIS chamber scenarios, verifying its comprehensive advantages in real-time performance, safety, and motion smoothness. This work provides theoretical support for the application of continuum manipulator in precision operation and maintenance of power equipment.

1. Introduction

With the continuous growth of electrical loads and consumer populations, the power industry has entered a phase of rapid development, accompanied by extensive deployment of generation, transmission, transformation, distribution, and consumption infrastructure. Consequently, the operation, maintenance, and inspection of critical power equipment have become pivotal in ensuring grid stability [1,2].
In confined maintenance environments such as gas-insulated switchgear (GIS), traditional rigid manipulators prove ill-suited for compact configurations due to their mechanical constraints. In contrast, cable-driven continuum manipulators demonstrate exceptional suitability for such inspection scenarios by leveraging their slender profile, redundant degrees of freedom, and enhanced adaptability [3].
Similar to rigid manipulators, investigating methods to minimize temporal costs in path planning and motion expenditure remains critically significant for inspection and maintenance tasks involving continuum manipulators. However, while the redundant degrees of freedom inherent to continuum manipulators enhance their maneuverability in confined environments, they concurrently increase the complexity of motion planning problems [4,5]. This necessitates the development of a robust trajectory planning methodology that explicitly accounts for the structural characteristics and kinematic constraints of continuum manipulators.
For conventional rigid manipulators, extensive research exists on path planning solutions employing genetic algorithms [6], ant colony optimization [7], and artificial potential field methods [8]. However, the redundancy characteristics of continuum manipulators have predominantly focused current investigations on imitation learning [9], optimization-based approaches [10], and reinforcement learning techniques [11]. Recent advancements in sampling-based planners have also introduced improved probabilistic roadmap (PRM) variants for complex multi-agent systems. For instance, Ref. [12] proposed a hierarchical PRM framework for multi-UAV path planning in cluttered 3D environments, demonstrating enhanced computational efficiency through obstacle decomposition, while Ref. [13] developed a congestion-aware multi-robot cooperative PRM optimizer to balance coverage and collision risks in dynamic settings. Despite these innovations, attempts to adapt classical PRM [14] or rapidly exploring random tree (RRT) [15] methods to continuum manipulators (e.g., in minimally invasive surgical robots [16,17]) still suffer from excessive redundant nodes that induce body distortion phenomena during deployment.
Most existing methods primarily conduct planning in Cartesian space with weak interaction between joint configurations and the environment. In recent years, some scholars have chosen to map obstacles from Cartesian space to the configuration space (C-space) [18], thereby providing more efficient solutions for tasks requiring arm-shape collision avoidance, eliminating extensive inverse kinematics computations and improving solving efficiency. However, due to the lack of effective mapping between the configuration space of cable-driven continuum manipulator and obstacle maps, planning efficiency cannot meet operational maintenance requirements.
In summary, this paper focuses on cable-driven continuum manipulators and proposes a C-space obstacle-avoidance trajectory planning method suitable for multi-segment continuum manipulators. The method addresses rapid shape collision detection, combines step-by-step optimization and greedy strategies to effectively improve solving efficiency and reduce node count, and further optimizes and smooths the driving trajectory. By employing MATLAB, CoppeliaSim Edu V4.2.0, and physical hardware co-simulation, both simulations and experiments demonstrate the algorithm’s rapidity and the accuracy of arm-shape planning.

2. Machine Design

Currently, existing actuation methods for continuum manipulators include individual cable/tendon-driven systems, shape memory alloy actuation, pneumatic artificial muscle actuation, and hybrid actuation based on electroactive reactants and fluids. Due to the narrow and complex internal environment of GIS chambers, the designed actuation mechanism requires miniaturization to enable the manipulator to better perform various tasks. Compared to other solutions, the cable-driven approach utilizes micromotors to control manipulator motion, which meets miniaturization design requirements, thus selecting cable-driven actuation for continuum manipulators. The designed actuation mechanism, as shown in Figure 1, consists of micro DC motors, gear reducers, precision bearings, couplings, ball-bearing slides, linear guide rails, lead screws, drive cables, and fixed terminals. The actuation mechanism has dimensions of 140 mm × 50 mm × 42 mm and can be directly mounted onto the mobile platform of GIS chamber maintenance robots.
The continuum body, as the core structure of the manipulator, must be designed to ensure motion in complex environments through bending and rotation. Inspired by the universal joint principle, a continuum manipulator body structure incorporating universal joint units is designed, as shown in Figure 1. This structure features a hollow cylindrical design with an outer diameter of 20 mm, inner diameter of 10 mm, and total length of 304 mm, with an internal spring installed for support. The continuum body comprises two continuous segments and two translational segments. Each continuous segment consists of multiple sets of universal joint units connected in series, enabling bending and rotational motion, while the translational segments are used for mounting actuators or securing drive cables. Drive cable through-holes are reserved on the circumferential cross-section of the continuum body.

3. Problem Description and Kinematics Analysis

3.1. Problem Description

Continuum manipulator motion planning essentially involves generating continuous actuator trajectories from a starting point to a target point within static or dynamic workspaces; these actuator trajectories are typically continuous functions of time.
The entire configuration space C is composed of the free configuration space C f r e e and the obstacle configuration space C o b s . Given the initial virtual joint configuration q i n i t q i n i t C f r e e and the target virtual joint configuration q g o a l q g o a l C f r e e of continuum manipulator 𝒜 , the path planning aims to find a configuration sequence Q from q i n i t to q g o a l that satisfies kinematic collision-free constraints, i.e.,
Q = q 0 , q 1 , q 2 , q i , i = 0 , 1 , 2 , , k s . t . q 0 = q i n i t , q k = q g o a l q i C f r e e
The point-to-point motion planning problem for continuum manipulators can be described as follows. In complex GIS environments, given the initial configuration q i n i t and target configuration q g o a l of the continuum manipulator, a continuous function is obtained mapping l : [ 0 , t f ] L for the drive cable trajectory with respect to time t , such that the joint configuration satisfies q L 0 = q i n i t , q L t f = q g o a l , and for any time t [ 0 , t f ] , q L t C f r e e . The virtual joint configuration q L t at any time t is derived from the two-segment continuum manipulator’s forward kinematics relationship F K 1 .
As shown in Figure 2, after obtaining the obstacle-avoidance configuration, the inverse kinematics (IK) from the virtual joint space to drive space is utilized to derive the drive cable variation time sequence L t , i.e.,
L t = L q t 0 , , L q t 1 , , L q t f
where L q t i = Δ l 1 1 q t i ,   Δ l 1 2 q t i ,   Δ l 1 3 q t i ,   Δ l 2 1 q t i ,   Δ l 2 2 q t i ,   Δ l 2 3 q t i represents the variation amounts of six driven cables from their original lengths at the corresponding time instances. Here, q t i denotes the joint configuration q i reached at time t i .

3.2. Kinematics Analysis of Continuum Manipulators

For the cable-driven continuum manipulator, a geometric model based on the PCC (Piecewise Constant Curvature) assumption is established, introducing virtual joint-space variables α , β to represent the rotation angle and bending angle of a single segment. Under this framework, the kinematic model of the cable-driven continuum manipulator comprises two parts: the mutual mapping between the drive space (composed of all drive cables) and the artificially introduced virtual joint space, and the mutual mapping between the virtual joint space and the manipulator’s end-effector workspace. The forward kinematics relationships F K include the mapping from the drive space to virtual joint space F K 1 and from the virtual joint space to workspace F K 2 . The inverse kinematics relationships I K consist of the mapping from the workspace to virtual joint space I K 2 and from the virtual joint space to drive space I K 1 . As shown in Figure 2, the subscripts i in the first two spaces denote the i -th continuum segment, while the superscript j indicates the number of drive cables required for that segment, which can be 3 or 4.
The geometric model of the two-segment continuum manipulator is shown in Figure 3. According to the designed prototype structure, the manipulator body comprises two continuous segments and two translational segments. The base coordinate system O 0 is established at the center of the base of the first continuous segment. The coordinate system O 1 is established at the center of the end of the first continuous segment. The base coordinate system O 2 of the second continuous segment is established at the end of the translational segment of the first continuous segment. The end coordinate system O 3 of the second continuous segment is established at the end of the second continuous segment, and finally, the workspace coordinate system O 4 of the robot is established at the center of the translational segment at the end of the second continuous segment. Among these, the x-axis positive direction of the base coordinate system O 0 points toward the first drive cable through-hole; the z-axis positive direction is perpendicular to the xy-plane of the base coordinate system and upward, while the y-axis positive direction follows the right-hand rule. The x-y-z-axes of all other coordinate systems align with those of the base coordinate system O 0 . In the diagram, β 1 and β 2 represent the bending angles of the first and second segments relative to their respective base coordinate system planes, while α 1 and α 2 denote the rotation angles relative to the x-axis of their own base coordinate systems. The two-segment continuum manipulator is driven by three drive cables per segment, resulting in six through-holes arranged at 60-degree intervals counterclockwise from the x-axis in the base coordinate system O 0 . These through-holes drive the motion of the two-segment continuum manipulator, where holes numbered l 1 1 ~ l 1 3 correspond to the drive cable through-holes for the first continuous joint, l 2 1 ~ l 2 3 correspond to those for the second continuous joint, and r denotes the distance from the base coordinate system center to the drive cable through-holes.

4. Inverse Kinematics Solving Based on IRRT-Connect

4.1. Algorithm Theory

Compared to the traditional RRT algorithm, RRT-Connect employs a dual-tree expansion mechanism, initiating from both the start and goal points as root nodes. Each tree extends toward the other’s direction through alternating expansion, effectively reducing planning time. Furthermore, the incorporation of heuristic steps significantly improves search speed, particularly demonstrating enhanced performance in navigating narrow passages. The principle is illustrated in Figure 4.
This section proposes an improved algorithm based on RRT-Connect for a two-segment continuum manipulator to address PTP motion planning in GIS complex cavity environments. The path planning operates in the virtual joint configuration space C of the manipulator, where q = α 1 , β 1 , α 2 , β 2 represents any configuration in C , and ε denotes the step length during RRT-Connect expansion. To address the computational inefficiencies caused by redundant nodes, the method introduces a maximized step length strategy. This is further enhanced by stepwise optimization to reduce the number of sampling nodes, along with modified pruning and collision detection mechanisms specifically adapted to the kinematic characteristics of the continuum manipulator. These refinements collectively improve memory utilization and algorithmic adaptability in complex cavity environments. The flow of the improved algorithm is shown in Table 1.

4.2. Step Optimization

When invoking the Connect() function for target tree T g expanding toward start tree T i extending only a fixed step length ε may result in multiple sampling points along this direction in T g . In reality, only the farthest sampling point in that direction is required. This situation creates numerous redundant points in T g , causing unnecessary memory waste. To resolve this issue, the single collision detection is replaced with multiple collision detections, ensuring that leaf nodes achieve the maximum feasible step length during directional expansion, thereby maximizing the step length.
When determining the new sampling point q n e w , the single collision detection with step length ε is replaced by four sequential collision detections at 0.5 ε ,   ε ,   1.5 ε ,   2 ε . This method effectively reduces the number of leaf nodes in the random expansion tree, thereby mitigating memory consumption.
q n e w = q n e a r e s t + ε q r a n d q n e a r e s t q r a n d q n e a r e s t
Simultaneously, the specific value of step length ε directly impacts both node quantity and solution efficiency. Therefore, a step-prior selection strategy is incorporated during the four-step greedy expansion: the difference in variation between the initial configuration q i n i t and target configuration q g o a l is precomputed before algorithm iteration to further determine the value of ε . The variation difference D q is defined as the sum of the absolute values of each element of the vector, as follows:
D q = i = 1 4 q g o a l i q i n i t i
Based on the practical requirements of path planning for a two-segment continuum manipulator in GIS complex cavity environments, the step length ε is coupled with the variation value D q . The pre-selection scheme for the step length is shown in Equation (5):
ε = 2 × Δ , D q T h r e s h o l d 1 1.6 × Δ , T h r e s h o l d 1 > D q T h r e s h o l d 2 Δ , 0 < D q < T h r e s h o l d 2
where ε is the determined step length, Δ is the reference length, and T h r e s h o l d 1 and T h r e s h o l d 2 are the different change thresholds.

4.3. Pruning Strategy

The pruning strategy can be described as follows: Taking the first waypoint (i.e., q init ) in the path planning sequence Q = q i n i t , q 2 , , q g o a l as the fixed point q f i x e d , we sequentially select a point q in reverse order from q g o a l , , q 2 to perform collision detection between q and q f i x e d . If the actual kinematic arm configuration connecting the two waypoints q and q f i x e d does not collide with obstacles, these two points can be directly connected. The successfully connected point q is then designated as the new fixed point q f i x e d . This process continues iteratively from q g o a l to the updated q f i x e d until the new fixed point can be directly connected to q g o a l .
Considering the challenges in visualizing pruning strategies in high-dimensional spaces, this paper illustrates the pruning concept using a two-dimensional schematic diagram, as shown in Figure 5.

4.4. Collision Detection

Since the path planning in this study operates within the virtual joint configuration space, the actual arm shape of the continuum manipulator can be derived using the forward kinematics relationship F K 2 q from the virtual joint space to the workspace. As shown in Figure 6, by equidistantly sampling points along the spine line of the actual arm shape based on bounding sphere positions, the spatial coordinates of all bounding spheres P 1 , P 2 , P 3 , , P i are obtained.
The environmental dimension-reduction strategy transfers 3D bounding sphere collision detection to a 2D plane. This strategy implements collision detection between two-segment continuum manipulators and GIS cavity interiors, as specifically shown in Figure 7. In the figure, R , r represent the GIS metal shell radius and internal conductive column radius, respectively, d t h r denotes the dangerous distance threshold, and R max ,   R min indicate the inner and outer boundary radii of the manipulator’s motion safety zone annulus.
The minimum and maximum distances between the bounding sphere model of the continuous manipulator and the O point of the GIS cavity center are as follows:
d min = min d 1 , d 2 , , d i d max = max d 1 , d 2 , , d i
The distance d i = O x y P i x y between the bounding spheres and the GIS cavity center must ensure whether both d min and d max lie within the annular safety zone formed by R min to R max .

4.5. Trajectory Planning Based on Driving Space

The IRRT-Connect algorithm obtains point-to-point path planning results for a two-segment continuum manipulator in GIS complex environments. Based on these results, further trajectory planning is required, with the trajectory planning outcomes directly serving as the underlying input for controlling the manipulator’s motion.
Driving-line trajectory planning involves two steps: (a) quintic polynomial interpolation within the virtual joint space; (b) deriving driving-line variation trajectories from the virtual joint-space planning results.
The virtual joint angle position change function is expressed as follows:
q i t = a i 0 + a i 1 t + a i 2 t 2 + a i 3 t 3 + a i 4 t 4 + a i 5 t 5 q ˙ i t = a i 1 + 2 a i 2 t + 3 a i 3 t 2 + 4 a i 4 t 3 + 5 a i 5 t 4 a q ¨ i t = 2 a i 2 + 6 a i 3 t + 12 a i 4 t 2 + 20 a i 5 t 3
By constraining the virtual joint angular position, velocity, and acceleration corresponding to the starting point at the initial time t 0 and the target point at the end time t f , the polynomial coefficients can be obtained as follows:
a i 0 = q i 0 a i 1 = q ˙ i 0 a i 2 = q ¨ i 0 2 a i 3 = q ¨ i f 3 q ¨ i 0 t f t 0 2 8 q ˙ i f + 12 q ˙ i 0 t f t 0 + 20 q i f q i 0 2 t f t 0 3 a i 4 = 3 q ¨ i 0 2 q ¨ i f t f t 0 2 + 14 q ˙ i f + 16 q ˙ i 0 t f t 0 + 30 q i f q i 0 2 t f t 0 4 a i 5 = q ¨ i f q ¨ i 0 t f t 0 2 6 q ˙ i f + 6 q ˙ i 0 t f t 0 + 12 q i f q i 0 2 t f t 0 5

5. Simulation Results and Analysis

The prototype model is set with the parameters of the continuum robot. The length of joint segment 1 is l 1 = 173 mm, the length of translation segment 1 is L 1 = 18 mm, the length of joint segment 2 is l 2 = 101 mm, and the length of translation segment 2 is L 2 = 12 mm. The distance r from the center of the base coordinate system to the center of the drive cable through-hole is 7.25 mm. The performance parameters of the computer used in the simulation are as follows: the CPU is Intel® CoreTM i7-10700, the memory (RAM) is 16 GB, the graphics card is NVIDIA GTX 1660 SUPER (From ASUS, Suzhou, China), and the MATLAB version is 2018a.

5.1. IRRT-Connect Algorithm Simulation

In the simulation, the data with a large difference between the initial and target configuration changes are selected as example ➀, and the data with a small difference are selected as example ➁.
The specific data of simulation example ➀: Posture from beginning to end (−195.35, 109.31, 110.14, 1.89, −0.78, −1.57)→(−195.35, −109.31, 110.14, −1.89, −0.78, 1.57), and corresponding start and end virtual joint variables (1.57, 2.36, 1.10, 3.93)→(1.57, 3.93, 1.10, 2.36). The specific data of simulation example ➁: Posture from beginning to end (−39.56, −77.83, 287.64, 0.06, 0.02, 0.33)→(−121.57, −156.58, 179.71, −1.23, −0.67, 1.45), corresponding start and end virtual joint variables (0.47, 4.08, 0.31, 0.16)→(1.10, 4.32, 0.94, 2.98). In the GIS cavity simulation environment, the basic RRT-connect algorithm and the IRRT-connect algorithm are used to carry out 100 planning experiments on two groups of instances, respectively, and the specific data are shown in Table 2. The last experimental planning results are shown in Figure 8. The results obtained from 100 planning experiments are as follows.

5.2. Drive Trajectory Smoothing Test

To validate the practical effectiveness of applying the quintic polynomial trajectory planning method to a two-segment continuum manipulator, a point-to-point motion case is selected for simulation testing, and the example parameters are set as follows. Virtual joint configuration q i n i t = 0.2 , 2 , 1.5 , 2.5 is the starting point of polynomial trajectory planning, q g o a l = 1.4 , 0.2 , 0.15 , 1.2 is the target point, and the speed constraint q ˙ i n i t = 0 ,   q ˙ g o a l = 0 and acceleration constraint q ¨ i n i t = 0 ,   q ¨ g o a l = 0 are set at the same time. The time from the starting point to the target point is 5 s, so t 0 = 0 ,   t f = 5 s . The results are shown in Figure 9.

5.3. Co-Simulation of MATLAB and CopeliaSim

The motion planning process from initial virtual joint variables (1.57, 2.36, 1.10, 3.93) to target virtual joint variables (1.57, 3.93, 1.10, 2.36) is accomplished using the improved RRT-Connect algorithm and quintic polynomial interpolation. As shown in Figure 10, the planned results (six driving cable sequences Δ l i j ) are transmitted in real time to the CoppeliaSim virtual simulation platform to control the two-segment continuum manipulator’s virtual model. To compare virtual simulation motion control effects, a 550 KV GIS cavity and two-segment continuum manipulator numerical simulation model are implemented in MATLAB. During motion control simulations, MATLAB numerical simulations and CoppeliaSim virtual model simulations are synchronized. As shown in Figure 11, the timing comparison between its bitwise numerical and virtual simulation motion control. The end trajectory comparison is shown in Figure 12

6. Experiment and Result Analysis

6.1. Experiment Preparation and Process

To verify the effectiveness of the proposed obstacle-avoidance planning algorithm, a GIS experimental environment as shown in Figure 13 is built. The experimental environment includes a two-stage continuous manipulator prototype, an electric control system, and a real 500 kV GIS tank. The electric control system uses STM32 (From STMicroelectronics, Shenzhen, China) embedded processor to drive and control six DC motors connected to the driving cables.
The prototype of the two-stage continuum manipulator is composed of a continuum body, a driving mechanism, and an electronic control module. The continuum body is made of nylon material by 3D printing. The electronic control module uses an STM32 chip as the underlying microcontroller to drive the micro DC motor which can control the expansion and contraction of the drive line. The experimental environment is 550 kV GIS equipment provided by State Grid Corporation.
In the GIS cavity application scenario, the schematic diagram of the point-to-point (PTP) motion control experiment for a two-segment continuum manipulator is shown in Figure 14. The CoppeliaSim platform achieves real-time communication with the underlying microcontroller STM32 (From STMicroelectronics, Shenzhen, China) via serial port. During synchronized simulations between MATLAB and CoppeliaSim, the target driving cable sequence Δ l 1 1 ,   Δ l 1 2 ,   Δ l 1 3 ,   Δ l 2 1 ,   Δ l 2 2 ,   Δ l 2 3 from CoppeliaSim is transmitted in real time to the STM32 microcontroller through the serial interface, enabling synchronous planning and control among all three systems.
The drive commands sent through the serial port reach the underlying microcontroller of the robot with a delay controlled within 35 ms, which is less than the motor execution frequency of 50 ms.

6.2. Analysis of Experimental Results

As shown in Figure 15, the comparative timing diagrams of virtual simulation and physical experiment motion control reveal that the physical continuum manipulator and simulation model exhibit broadly similar motion processes during PTP operations. Due to the narrow and complex internal structure of GIS equipment, existing measurement techniques cannot reliably capture the end-effector trajectory or virtual joint variables during point-to-point motion of the two-segment continuum manipulator. Experimental data acquisition is limited to real-time driving cable positional changes obtained from motor encoder feedback. Comparative analyses between target, simulated, and experimental positional values of the manipulator’s six driving cables are shown in Figure 16a,b. The diagrams indicate intermittent positional errors during experimental phases, potentially attributable to mechanical inaccuracies in the continuum body prototype causing motor stalling or inherent encoder errors in DC motors. Despite observed deviations, the results demonstrate the feasibility of deploying two-segment continuum manipulators for GIS cavity inspection and maintenance tasks, confirming that the proposed motion planning methodology achieves effective PTP motion planning and control in complex GIS cavity environments.

7. Conclusions

To address the collision-avoidance shape planning challenges in key-area fixed-point inspection tasks for GIS equipment maintenance, this study proposes a collision-avoidance planning method for continuum manipulators based on an improved RRT-Connect algorithm. The method transforms Cartesian-space collision avoidance into virtual joint-space obstacle evasion. First, a joint-space obstacle map is established, and the improved RRT-Connect algorithm enhances computational efficiency by reducing node quantity and expansion rate. Furthermore, polynomial-driven spatial trajectory planning calculates smooth driving-line variations to control the dual-segment continuum manipulator’s end-effector toward target positions. Simulation and experimental validation on a two-segment continuum manipulator demonstrates the proposed C-space collision-avoidance shape planning method achieves effective and rapid performance, laying the groundwork for real-time manipulator shape planning. For practical implementation, future work will incorporate end-effector motion constraints to extend from point-to-point obstacle-avoidance motion planning to continuous path motion planning, and to achieve wide constraints on end position without significantly increasing the planning time, thus further improving the operational efficiency of the continuum manipulator.

Author Contributions

Conceptualization, Q.X. and Y.C.; methodology, S.D.; software, Q.X.; validation, Y.L., J.L. and J.T.; formal analysis, Y.C.; investigation, J.L.; resources, J.T.; data curation, Y.L.; writing—original draft preparation, Y.L.; writing—review and editing, Q.X.; visualization, Y.L.; supervision, S.D.; project administration, J.L.; funding acquisition, J.T. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by State Grid Liaoning Electric Power Co., Ltd. Science and Technology Project Grant (Grant number: SGLNDK00SPJS2400108(2024YF-63)).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data are contained within this article. Further inquiries can be directed to the corresponding author.

Conflicts of Interest

Y.L., J.L. and J.T. are employed by the company State Grid Electric Power Research Institute of Liaoning Electric Power Co., Ltd. The remaining authors declare that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
IRRTImproved rapidly exploring random tree
GISgas-insulated switchgear
C-spaceconfiguration space
PRMprobabilistic roadmap

References

  1. The National Energy Administration. Releases 2022 National Power Industry Statistics [EB/OL]. 18 January 2023. Available online: https://www.nea.gov.cn/2023-01/18/c_1310691509.htm (accessed on 18 February 2024).
  2. IEA. Electricity Market Report 2023 [EB/OL]. 16 February 2023. Available online: https://www.iea.org/reports/electricity-market-report-2023 (accessed on 18 February 2024).
  3. Kolachalama, S.; Lakshmanan, S. Continuum Robots for Manipulation Applications: A Survey. J. Robot. 2020, 2020, 4187048. [Google Scholar] [CrossRef]
  4. Luo, M.; Li, E.; Zhang, A.; Tan, M.; Liang, Z. A Bioinspired Coiled Cable-Driven Manipulator: Mechatronic Design and Kinematics Planning with Multiconstraints. IEEE Trans. Mechatron. 2023, 28, 3155–3166. [Google Scholar] [CrossRef]
  5. Ma, C.; Zhao, T.; Xiang, G.; Ren, J.; Chen, Y.; Dian, S. End Positioning Control of Flexible Manipulator Based on Inverse Kinematics. J. Mech. Eng. 2021, 57, 163–171. [Google Scholar]
  6. Li, J.; Hu, Y.; Yang, S. A Novel Knowledge-Based Genetic Algorithm for Robot Path Planning in Complex Environments. IEEE Trans. Evol. Comput. 2025, 29, 375–389. [Google Scholar] [CrossRef]
  7. Hu, K.; Dong, Q.; Ma, Z.; Li, B.; Qi, T. Welding robot path planning based on ant colony algorithm. In Proceedings of the 2024 5th International Conference on Artificial Intelligence and Electromechanical Automation (AIEA), Shenzhen, China, 14–16 June 2024; pp. 13–18. [Google Scholar]
  8. Wang, L.; Sun, Z.; Wang, Y.; Wang, J.; Zhao, Z.; Yang, C.; Yan, C. A Pre-Grasping Motion Planning Method Based on Improved Artificial Potential Field for Continuum Robots. Sensors 2023, 23, 9105. [Google Scholar] [CrossRef] [PubMed]
  9. Mayer, A.; Müller, D.; Raisch, A. Demonstration-based programming of multi-point trajectories for collaborative continuum robots. IFAC-PapersOnLine 2019, 52, 513–518. [Google Scholar] [CrossRef]
  10. Greigarn, T.; Poirot, N.; Xu, X. Jacobian-based task-space motion planning for MRI-actuated continuum robots. IEEE Robot. Autom. Lett. 2018, 4, 145–152. [Google Scholar] [CrossRef] [PubMed]
  11. Graule, M.; McCarthy, T.; Teeple, C.; Werfel, J.; Wood, R. SoMoGym: A toolkit for developing and evaluating controllers and reinforcement learning algorithms for soft robots. IEEE Robot. Autom. Lett. 2022, 7, 4071–4078. [Google Scholar] [CrossRef]
  12. Fu, J.; Sun, G.; Liu, J.; Yao, W.; Wu, L. On hierarchical multi-UAV dubins traveling salesman problem paths in a complex obstacle environment. IEEE Trans. Cybern. 2023, 54, 123–135. [Google Scholar] [CrossRef] [PubMed]
  13. Fu, J.; Yao, W.; Sun, G.; Ma, Z.; Dong, B.; Ding, J.; Wu, L. Multirobot cooperative path optimization approach for multi-objective coverage in a congestion risk environment. IEEE Trans. Syst. Man Cybern. Syst. 2023, 54, 1816–1827. [Google Scholar] [CrossRef]
  14. Kavraki, L.; Kolountzakis, M.; Latombe, J. Analysis of probabilistic roadmaps for path planning. IEEE Trans. Robot. Autom. 1998, 14, 166–171. [Google Scholar] [CrossRef]
  15. Véras, L.; Medeiros, F.; Guimaráes, L. Systematic literature review of sampling process in rapidly-exploring random trees. IEEE Access 2019, 7, 50933–50953. [Google Scholar] [CrossRef]
  16. Chiluisa, A.; Van Rossum, F.; Gafford, J. Computational optimization of notch spacing for a transnasal ear endoscopy continuum robot. In Proceedings of the 2020 International Symposium on Medical Robotics, Atlanta, GA, USA, 18–20 November 2020; pp. 188–194. [Google Scholar]
  17. Wu, K.; Wu, L.; Ren, H. Motion planning of continuum tubular robots based on centerlines extracted from statistical atlas. In Proceedings of the 2015 IEEE/RSJ International Conference on Intelligent Robots and Systems, Hamburg, Germany, 28 September–2 October 2015; pp. 5512–5517. [Google Scholar]
  18. Qi, R.; Zhou, W.; Wang, T. An Obstacle Avoidance Trajectory Planning Scheme for Space Manipulators Based on Genetic Algorithm. ROBOT 2014, 36, 263–270. [Google Scholar]
Figure 1. Structural diagram of continuum manipulator.
Figure 1. Structural diagram of continuum manipulator.
Sensors 25 03081 g001
Figure 2. Kinematic mapping relationships of continuum manipulator.
Figure 2. Kinematic mapping relationships of continuum manipulator.
Sensors 25 03081 g002
Figure 3. The geometric model of the two-segment continuum manipulator.
Figure 3. The geometric model of the two-segment continuum manipulator.
Sensors 25 03081 g003
Figure 4. RRT-Connect schematic diagram.
Figure 4. RRT-Connect schematic diagram.
Sensors 25 03081 g004
Figure 5. Schematic diagram of pruning strategy.
Figure 5. Schematic diagram of pruning strategy.
Sensors 25 03081 g005
Figure 6. Collision model of continuum manipulator.
Figure 6. Collision model of continuum manipulator.
Sensors 25 03081 g006
Figure 7. Collision detection based on dimensionality-reduction strategy.
Figure 7. Collision detection based on dimensionality-reduction strategy.
Sensors 25 03081 g007
Figure 8. Comparison of planning results before and after RRT-connect algorithm improvement.
Figure 8. Comparison of planning results before and after RRT-connect algorithm improvement.
Sensors 25 03081 g008
Figure 9. Polynomial trajectory planning.
Figure 9. Polynomial trajectory planning.
Sensors 25 03081 g009
Figure 10. Motion control simulation program.
Figure 10. Motion control simulation program.
Sensors 25 03081 g010
Figure 11. Numerical simulation (top) and virtual simulation (bottom) motion control timing diagrams.
Figure 11. Numerical simulation (top) and virtual simulation (bottom) motion control timing diagrams.
Sensors 25 03081 g011
Figure 12. End trajectory comparison. (a) Tip trajectory comparison; (b) comparison of changes in spatial coordinates.
Figure 12. End trajectory comparison. (a) Tip trajectory comparison; (b) comparison of changes in spatial coordinates.
Sensors 25 03081 g012
Figure 13. Prototype and experimental environment.
Figure 13. Prototype and experimental environment.
Sensors 25 03081 g013
Figure 14. Prototype experimental control block diagram.
Figure 14. Prototype experimental control block diagram.
Sensors 25 03081 g014
Figure 15. Comparison of motion control between virtual simulation (top) and physical experiments (bottom).
Figure 15. Comparison of motion control between virtual simulation (top) and physical experiments (bottom).
Sensors 25 03081 g015
Figure 16. Driven cable comparison: (a) segment 1 driven cable comparison; (b) segment 2 driven cable comparison.
Figure 16. Driven cable comparison: (a) segment 1 driven cable comparison; (b) segment 2 driven cable comparison.
Sensors 25 03081 g016
Table 1. Algorithm pseudocode.
Table 1. Algorithm pseudocode.
RRT-Connect Planner for Continuum Manipulator (xinit, xgoal, Map)
1Ta.init(xinit);Tb.init(xgoal);
2for k = 1 to K do
3xrandSampleNode(Step Optimization):
4   if not(Extend(Ta, xrand)) = Trapped then
5      if (Connect(Tb, xnew)) = Reached then
6         Return PATH(Ta, Tb);
7      end if
8   end if
9    if   T a > T b then
10    SwapTrees(Ta, Tb);
11   end if
12end for
13PathPruning()
14Return Failure
Table 2. Comparison of RRT-connect algorithm improvement efficiency.
Table 2. Comparison of RRT-connect algorithm improvement efficiency.
ExampleAlgorithmAverage Number of IterationsAverage Number of Leaf NodesAverage Number of Path NodesAverage Number of Path Nodes
RRT-Connect15046190.017 s
IRRT-Connect481280.011 s
RRT-Connect2880.002 s
IRRT-Connect5540.002 s
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Lang, Y.; Liu, J.; Xiao, Q.; Tang, J.; Chen, Y.; Dian, S. Obstacle-Avoidance Planning in C-Space for Continuum Manipulator Based on IRRT-Connect. Sensors 2025, 25, 3081. https://doi.org/10.3390/s25103081

AMA Style

Lang Y, Liu J, Xiao Q, Tang J, Chen Y, Dian S. Obstacle-Avoidance Planning in C-Space for Continuum Manipulator Based on IRRT-Connect. Sensors. 2025; 25(10):3081. https://doi.org/10.3390/s25103081

Chicago/Turabian Style

Lang, Yexing, Jiaxin Liu, Quan Xiao, Jianeng Tang, Yuanke Chen, and Songyi Dian. 2025. "Obstacle-Avoidance Planning in C-Space for Continuum Manipulator Based on IRRT-Connect" Sensors 25, no. 10: 3081. https://doi.org/10.3390/s25103081

APA Style

Lang, Y., Liu, J., Xiao, Q., Tang, J., Chen, Y., & Dian, S. (2025). Obstacle-Avoidance Planning in C-Space for Continuum Manipulator Based on IRRT-Connect. Sensors, 25(10), 3081. https://doi.org/10.3390/s25103081

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

Article Metrics

Back to TopTop