Abstract

To address the challenges of path planning for transmission line barrier operations in complex terrains, this paper proposes a solution based on multimachine collaborative control. A path-planning algorithm that integrates multiple classical algorithms and incorporates multiobjective optimization methods is constructed to handle the complexities of challenging terrains. Auction algorithm and genetic algorithm are adopted to achieve optimal load balance by dynamically adjusting task allocation. Simulation results show that the proposed method effectively enhances task execution efficiency, optimizes path planning, and reduces energy consumption in complex terrains and dynamic environments, while maintaining high-obstacle avoidance success rates and communication stability.

1 Introduction

As the complexity of power systems continues to increase, the safety and stability of transmission lines have become critical components in the power supply chain. Among the various tasks involved in the routine maintenance of transmission lines, barrier operations are of particular importance. These operations involve the installation of protective barriers around transmission lines to prevent external interference. However, in regions with complex terrain, traditional barrier operations face numerous challenges. The characteristics of complex terrains, such as steep slopes, dense vegetation, and variable landscapes, add significant difficulty to path planning, leading to reduced operational efficiency and increased operational risks. Path planning is a key technology in barrier operations, especially in complex terrain, where it must account for not only the topography and obstacle distribution but also the safety and efficiency of the operation path. The complexity of this process makes the development of efficient path-planning methods central to solving these issues. Therefore, researching optimal path planning for barrier operations in complex terrain is a crucial topic in the field of transmission line maintenance technology.

In recent years, the development of unmanned aerial vehicles (UAVs) and unmanned ground vehicles (UGVs) has provided new solutions for automated transmission line maintenance. When facing barrier operations in complex terrain, the operational capacity of a single device is limited, making it difficult to address the diverse environmental challenges and the complexities of path planning. To this end, multimachine collaborative control technology has emerged, enabling the distributed processing of complex tasks through the coordinated operation of multiple devices. This technology not only improves task execution efficiency but also reduces the risk of single-point failures, ensuring the stability and continuity of operations in complex terrain. Under the collaborative control of a multimachine system, the optimization of path planning becomes particularly critical. The cooperation among multiple machines allows for a broader coverage of barrier operations, the avoidance of terrain obstacles, and the flexible adjustment of paths in dynamic environments. Researching efficient path planning and optimization methods, in combination with multimachine collaborative control technology, not only enhances the success rate of barrier operations in complex terrain but also optimizes resource allocation and reduces operational costs.

Previous research has made some progress in the automation of path planning for transmission line barrier operations. Some path-planning methods have primarily focused on two-dimensional (2D) path planning and have been optimized for operations under simple terrain conditions. These studies have demonstrated certain advantages in terms of algorithm efficiency and feasibility, such as the use of heuristic algorithms and dynamic programming methods, which have enabled automated path planning and effective barrier operations in simple terrains [1–5]. However, as transmission lines extend into increasingly complex terrains, existing methods have shown limitations in addressing the challenges of multidimensional complex terrains, real-time dynamic changes, and environmental uncertainties [6–10]. First, previous methods have struggled to meet the demands of three-dimensional (3D) path planning in complex terrains, particularly in scenarios involving significant terrain variations, dense obstacles, and randomly occurring obstructions, where existing algorithms lack robustness and adaptability [11–15]. Second, many studies have overlooked the coordination mechanisms and resource allocation issues in multidevice collaborative operations, leading to inefficiencies in multimachine system collaboration in practical applications [16–20]. Additionally, existing research has yet to propose effective solutions for real-time path adjustments and obstacle avoidance in dynamic environments, limiting the flexibility and response speed of systems in actual operations [21, 22]. In response to these shortcomings, this study aims to make improvements from multiple perspectives to provide a more comprehensive and efficient solution for the automated path planning of transmission line barrier operations. The proposed system architecture enables transmission line barrier operations in complex terrains through multiagent collaborative control. The hardware system, consisting of drones, ground robots, and sensors, maintains stable communication and energy optimization via a MESH network and intelligent energy management system. The software system employs an auction-based task allocation algorithm, along with state synchronization and fault detection mechanisms, ensuring dynamic task optimization and efficient coordination among devices. Path planning integrates A*, Rapidly exploring Random Tree (RRT), and multiobjective optimization algorithms to respond to complex environments in real time. The entire system is simulated and validated using the robot operating system (ROS) and Gazebo platforms, achieving multidevice coordination and path optimization.

2 Design of multimachine collaborative control system

2.1 Hardware system design

The hardware system design encompasses the selection of UAVs and UGVs, sensor configuration, communication network construction, and energy management system design. First, to address the challenges posed by complex terrain features such as steep slopes, dense forests, and bodies of water, a combination of various UAVs and UGVs with different movement modes is employed. In rugged terrain and forested areas, multirotor UAVs are chosen for their excellent hovering and low-speed flight capabilities, making them suitable for high-precision positioning and obstacle avoidance. The selected UAVs should have a payload capacity of 5–10 kg to carry various sensor equipment and flight duration of at least 30–60 min to ensure operational continuity. UGVs, on the other hand, should be equipped with strong obstacle-crossing abilities and high stability, such as UGVs with a tracked structure, to meet the demands of complex terrain.

Second, in terms of sensor selection and configuration, emphasis is placed on the integration and cooperation of devices such as LiDAR, vision sensors, high-precision GPS, and inertial measurement units (IMU). LiDAR is critical for achieving high-precision 3D environmental perception, with scanning accuracy at the centimeter level and a detection range of 100–200 m, to handle obstacle identification and environmental modeling in complex terrains. The combination of vision sensors and LiDAR can provide rich environmental information, aiding the implementation of simultaneous localization and mapping (SLAM) algorithms. The integration of high-precision GPS with IMU offers centimeter-level positioning accuracy, ensuring precise navigation of UAVs or UGVs in complex terrains.

Given the potential impact of complex terrain on signal transmission, selecting the appropriate communication technology is crucial. This study employs MESH network architecture, forming a self-organizing network through multinode interconnection to enhance system robustness and coverage. Each device node is equipped with a 2.4 GHz or 5.8 GHz radio module and a LoRa long-range communication module to maintain stable data transmission in nonline-of-sight or signal-blocked areas. The AODV dynamic routing protocol is used for multihop transmission of data packets, reducing the impact of single-point failures on the entire system (Fig. 1). Finally, to meet the demands of long-duration operations in complex terrain, this study adopts a modular battery system, equipped with solar-charging devices for real-time energy replenishment in the field. Each UAV is equipped with at least two battery packs, supporting quick replacement and online monitoring of battery status. An intelligent energy management algorithm is employed to optimize energy consumption and task allocation across devices.

AODV dynamic routing protocol used for multihop transmission of data packets in communication network construction of hardware system design.
Figure 1

AODV dynamic routing protocol used for multihop transmission of data packets in communication network construction of hardware system design.

2.2 Software system design

This study proposes an innovative software system architecture that encompasses task allocation, state synchronization, fault detection, and recovery, and builds a multimachine collaborative simulation and control platform based on the ROS.

Given the diversity and unpredictability of complex terrain, task allocation must consider the actual capabilities, current status of each device, and the constraints of the operational environment. Therefore, as shown in Fig. 2, this paper adopts a task allocation algorithm based on auction mechanism. Each device generates task bids based on its own status, such as battery level, current location, and load capacity, and tasks are dynamically allocated through a central controller or distributed controllers. The auction mechanism is designed based on Nash equilibrium theory in game theory, ensuring that in each allocation, devices complete tasks in the most optimal manner, maximizing the overall efficiency of the system. The specific task allocation model is expressed as:

(1)
Auction mechanism used for task allocation algorithm in software system design.
Figure 2

Auction mechanism used for task allocation algorithm in software system design.

where xij is the decision variable for task allocation to device i and uij is the utility function resulting from task allocation. This model is solved using linear programming (LP) or integer LP (ILP) to obtain the optimal task allocation scheme.

Since multiple devices operate simultaneously, real-time synchronization of status information is key to ensuring successful collaboration. This study adopts a distributed state synchronization algorithm, combining Kalman filters with the Precision Time Protocol (PTP), ensuring that position, speed, environmental information, and other state data of each device are shared with high accuracy and low latency in different environments. The state synchronization mathematical model can be described as:

(2)

where sk is the state estimate of the device, A is the state transition matrix, B is the control input matrix, K is the Kalman gain, zk ​is the measurement value, and H is the measurement matrix.

For fault detection and recovery mechanisms, a fault diagnosis and recovery method based on deep learning and model predictive control (MPC) is introduced. To respond swiftly to faults and restore system functionality, a convolutional neural network (CNN) is employed for real-time fault detection, combined with MPC for postfault action adjustments. The fault diagnosis model can be expressed as:

(3)

where X is the input sensor data, fc(X) is the score function for class c, and y is the fault category.

To achieve collaborative control among multiple machines, this study integrates various control algorithms into the ROS system, utilizing ROS services and actions mechanisms to support the allocation and coordination of complex tasks. In this process, the master node is responsible for global task scheduling and monitoring, while each device node independently executes the allocated tasks.

The simulation platform is built on the deep integration of Gazebo and ROS. ROS is used for task allocation, state synchronization, and path planning within the multiagent system, while Gazebo is utilized to create complex 3D environments and simulate sensor data and physical motion. During the simulation, the ROS–Gazebo interface ensures seamless connection between ROS nodes and the simulation environment, with functions such as motion control of devices, sensor data collection, and environmental perception directly interacting with the simulation environment through ROS commands. This architecture allows real-time verification of control algorithms and parameter adjustments during simulation. Suppose a particular path-planning algorithm needs to be validated. The Gazebo simulation platform can generate multiple potential paths in a virtual complex terrain and optimize the path according to the following objective function:

(4)

where Li ​is the path length, Ei is the energy consumption, Ti is the time consumed, and α, β, and γ are the corresponding weight coefficients.

Additionally, the simulation platform integrates various sensor simulation functions, including LiDAR, cameras, IMU, etc. The data from these sensors are transmitted to the control algorithms through the ROS messaging mechanism, used for environmental modeling and state estimation.

3 Path planning in complex terrain

3.1 Terrain modeling and analysis

Accurate terrain modeling is essential not only for guiding the motion decisions of UAVs or UGVs but also for providing crucial environmental information for multimachine collaborative operations. This study introduces an innovative terrain modeling and analysis method based on multisource data fusion and high-precision algorithms, aiming to obtain precise and detailed terrain descriptions in various complex environments.

This study employs a combination of remote sensing data, LiDAR scanning, and UAV photogrammetry to comprehensively capture the terrain features of the operational area. Remote sensing data, mainly obtained from satellite images or aerial photos, provide a broad overview of the terrain. LiDAR scanning offers detailed terrain sampling, with point cloud data spatial resolutions ranging from 1 to 10 cm, depending on the scanning distance and laser settings. UAV photogrammetry generates digital elevation models (DEMs) from multiangle aerial images, typically with a resolution of less than 1 meter, suitable for high-precision terrain modeling in small areas. The fusion of multisource data constructs a comprehensive and high-precision terrain model, providing a reliable foundation for subsequent analyses.

During data fusion, it is first necessary to unify the coordinates and correct the accuracy of the data from different sources. To ensure the accuracy of the terrain model, a multisource data fusion algorithm based on weighted least squares is adopted (Fig. 3). Assuming there are n terrain data sets from different sensors, denoted as D1, D2, …, Dn, data fusion can be achieved by minimizing the following objective function:

(5)
An innovative terrain modeling and analysis method based on multisource data fusion and high-precision algorithms.
Figure 3

An innovative terrain modeling and analysis method based on multisource data fusion and high-precision algorithms.

where wi is the weight of the ith data set and M is the fused terrain model. The choice of wi is based on the accuracy and signal-to-noise ratio of the data set, with higher weights indicating higher data reliability.

Path planning in complex terrain must consider various factors such as slope, aspect, obstacle distribution, and vegetation cover. These features can be analyzed through DEM and digital surface models (DSM). Slope and aspect can be calculated using the following formulas:

(6)
(7)

where ∂z/∂x and ∂z/∂y are the partial derivatives of elevation with respect to the x and y directions, calculated using the elevation values of DEM grid points.

Obstacle detection primarily relies on processing LiDAR point cloud data. By calculating the normal vector of a point cloud and the distance differences with surrounding points, ground, and nonground objects such as trees and towers can be effectively distinguished, thus constructing an obstacle distribution map. This process can be achieved using the following algorithm:

(8)

where N represents the neighborhood of a point pi in the point cloud, p0 is the centroid of the neighborhood, and n is the normal vector of the point.

The results of terrain analysis are visualized and further analyzed using Geographic Information System (GIS) tools. The generated terrain feature maps are overlaid with the planned paths to identify potential risk areas and refine the path-planning schemes. GIS tools also enable real-time interactive analysis of 3D terrain, providing robust support for autonomous operations in complex terrains.

3.2 Path-planning algorithm construction

Traditional path-planning algorithms such as A*, Dijkstra, and RRT perform well in 2D or simple 3D environments, but a single algorithm may struggle to meet the multidimensional planning requirements in highly complex terrains. Therefore, this study proposes a novel path-planning algorithm that integrates multiple classical algorithms and incorporates multiobjective optimization methods to address the challenges of multimachine collaborative operations in complex terrains (Fig. 4).

Path-planning algorithm construction by integrating multiple classical algorithms and incorporating multiobjective optimization methods.
Figure 4

Path-planning algorithm construction by integrating multiple classical algorithms and incorporating multiobjective optimization methods.

First, global path planning relies on a combination of A* and Dijkstra algorithms. The A* algorithm effectively reduces the computation time of the search path through a heuristic function, with its evaluation function as follows:

(9)

where g(n) represents the actual cost from the start point to node n and h(n) is the estimated cost from node n to the destination. To enhance the algorithm’s adaptability, the heuristic function h(n) is designed to incorporate terrain features such as slope and obstacle density, preventing the algorithm from failing in steep terrains or densely obstructed areas.

The Dijkstra algorithm, being a nonheuristic shortest path algorithm, does not rely on an estimation function when calculating paths, ensuring that the global optimum is found. In practical applications, a dual-layer path-planning mechanism can be formed by combining the rapid convergence of the A* algorithm with the global optimality of the Dijkstra algorithm. In the preliminary path generation stage, the A* algorithm provides initial path candidates for the multimachine system through rapid convergence. In the path optimization stage, the Dijkstra algorithm further optimizes the initial path globally to ensure its reliability in complex terrains.

Additionally, to improve the adaptability and robustness of the path-planning algorithm in practical applications, the RRT algorithm is introduced. The RRT algorithm excels in path exploration in high-dimensional spaces, with its core idea being the construction of a search tree through randomly generated nodes. Given the characteristics of complex terrain, an improved RRT algorithm, termed terrain-constrained RRT (TC-RRT), is adopted. TC-RRT takes terrain features and physical constraints into account during random extension, using the following formula to screen path nodes:

(10)

where ∇zn ​is the slope of node n, τz is the slope threshold, and σz ​is a parameter controlling the sharpness of the constraint function.

To fully consider various factors in path planning, such as path length, energy consumption, obstacle avoidance, and operation time, the Nondominated Sorting Genetic Algorithm II (NSGA-II) is introduced as a multiobjective optimization method. During the optimization, the following objective function is defined:

(11)

where L(P) represents path length, E(P) is energy consumption, O(P) is the obstacle avoidance cost, and T(P) is operation time. The NSGA-II algorithm converts the path-planning problem into a multiobjective optimization problem through nondominated sorting and uses genetic operations such as crossover and mutation to search for the Pareto optimal solution set in the multidimensional objective space. These Pareto solutions provide a series of alternative paths that balance different factors, allowing the scheduling system to select the optimal path under varying operational conditions.

The design of the path-planning algorithm must consider not only the performance of the algorithm itself but also its scalability and adaptability in complex terrains. Therefore, a path selection mechanism based on adaptive weighting is used in this study. In the initial stage, the weights of each objective are dynamically adjusted according to terrain conditions and operational requirements and continuously updated during path optimization to adapt to environmental changes and task demands. The weight adjustment formula is as follows:

(12)

where ωi is the weight of the i-th objective, ηi is the current objective value, and τi ​and σi are parameters controlling weight adjustment. Through adjustment, the path-planning algorithm can respond to environmental changes in real-time, ensuring efficient operation of the multimachine system in complex terrains.

4 Multimachine collaborative operation optimization

4.1 Task allocation and load balancing

This paper proposes an innovative task allocation and load-balancing mechanism based on auction algorithms and genetic algorithms (GAs), aiming to achieve optimal system load balance through dynamic task allocation adjustments. As discussed in Section 2.2, an auction algorithm-based task allocation mechanism is introduced to address the task allocation problem. The auction algorithm simulates a market bidding mechanism, where each device bids for tasks based on its current status and task requirements, leading to a rational task distribution. Suppose there are n devices and m tasks in the system. The bidding price of device i for task j, denoted as bij, can be calculated by the following formula:

(13)

where cij is the cost of device i executing task j, and pi is the current processing capacity of the device.

However, a single auction algorithm is insufficient to handle the optimization of multiobjective tasks in complex terrains. Therefore, a GA is incorporated to optimize task allocation (Fig. 5). The GA simulates the process of natural selection to search for a global optimum in the solution space. Specifically, the task allocation problem is first encoded into a chromosome representation, with each chromosome representing a task allocation scheme, and the gene sequence corresponding to the matching relationship between devices and tasks.

Code for task allocation optimization based on GA.
Figure 5

Code for task allocation optimization based on GA.

In the design of the fitness function for the GA, three factors are considered: task completion time, energy consumption, and load balance. The fitness function F(x) can be expressed as the following multiobjective optimization function:

(14)

where T(x) is the total task completion time, E(x) is the total energy consumption of the system, B(x) is the load balance, and ω1, ω2, and ω3 are the weight parameters for each objective. These weight parameters can be dynamically adjusted according to the actual situation to meet different operational needs.

To address emergencies in high-density complex environments, the load-balancing strategy can be optimized through dynamic load prediction, adaptive scheduling, distributed load balancing, and fault detection with task reallocation. These improvements enable real-time task allocation adjustments, rapid responses to device failures or overloads, and enhance the system’s load-balancing efficiency and effectiveness in handling emergency situations.

A dynamic task adjustment mechanism is employed to address contingencies such as device failures or path blockages. After each round of task allocation, the operating status of each device and task progress is monitored in real time. When a device failure or task blockage is detected, the allocation plan for uncompleted tasks is recalculated. The dynamic adjustment mechanism utilizes a predictive load-balancing algorithm, which predicts future load conditions by analyzing the historical data and current status of the devices, and reallocates tasks based on the prediction. The formula is as follows:

(15)

where Li(t + 1) is the predicted load of device i at time t + 1, Li(t) is the actual load at time t, α is the smoothing coefficient, and k is the number of devices involved in load balancing.

Moreover, in the load-balancing process, communication latency and energy consumption between devices need to be considered. Therefore, as shown in Fig. 6, a load-balancing strategy based on a distributed computing model is introduced. In this strategy, each device acts as a node, performing local calculations and exchanging load information with nearby devices to achieve global load balancing.

Load-balancing strategy based on a distributed computing model.
Figure 6

Load-balancing strategy based on a distributed computing model.

4.2 Real-time path adjustment and obstacle avoidance

To address the challenges of complex terrain and dynamic environments, this paper proposes an approach that combines SLAM technology with reinforcement learning to achieve efficient real-time path adjustment and obstacle avoidance.

As shown in Fig. 7, SLAM can simultaneously build a map and perform autonomous localization in an unknown environment, which is fundamental for real-time path planning and obstacle avoidance. The SLAM algorithm fuses data from multiple sensors such as LiDAR, visual sensors, and IMU, and utilizes methods like extended Kalman filter or particle filter for real-time environmental modeling and localization. The map update process in SLAM can be expressed by the following formula:

(16)
Principles of SLAM.
Figure 7

Principles of SLAM.

where mt is the map at time t, |${\mathrm{z}}_t^i$| is the sensor measurement data at time t, and |${\mathrm{H}}_t^i$| is the corresponding measurement matrix.

In real-time path adjustment, a dynamic programming algorithm based on the Bellman equation is introduced. The optimization objective of path adjustment is to minimize the total path cost while avoiding obstacles. Let S be the state space and A be the action space; the cost function for the path-planning problem is:

(17)

where J(s) is the path cost at state s, c(s,a) is the immediate cost of taking action a in state s, γ is the discount factor, and P(s’|s,a) is the probability of transitioning from state s to state s’ when action a is taken.

For autonomous obstacle avoidance in complex terrain, a reinforcement learning-based obstacle avoidance algorithm is employed. Reinforcement learning algorithms can gradually learn the optimal strategy through interactive learning, even without complete knowledge of the environment model. Specifically, the Q-learning updates the Q-value table, guiding the device to select the optimal obstacle avoidance action in different environmental states. The Q-value update formula is:

(18)

where α is the learning rate, r is the immediate reward, γ is the discount factor, s’ is the next state, and maxa’Q(s’,a’) is the maximum Q-value in the next state.

When combining SLAM with RL, the SLAM system first generates a local map of the current environment, and then the RL algorithm optimizes path planning and dynamic obstacle avoidance on that map. The policy update process in RL depends on the real-time environmental changes provided by SLAM. SLAM supplies continuous environmental state inputs to the RL algorithm, while RL provides action suggestions for path planning and obstacle avoidance. Through this integration, the system can adapt to real-time changes in complex dynamic environments, ensuring the efficiency and reliability of path planning.

Table 1

Simulation testing results of the three main stages

Testing stagesTm/minCp/unitsOs/%LbCd/msPl/%Ec/Wh
The first stage85.72105.361001583.48
The second stage47.8382.4593.270.8258.362.141347.26
The third stage62.1995.7889.440.7763.473.221478.62
Testing stagesTm/minCp/unitsOs/%LbCd/msPl/%Ec/Wh
The first stage85.72105.361001583.48
The second stage47.8382.4593.270.8258.362.141347.26
The third stage62.1995.7889.440.7763.473.221478.62
Table 1

Simulation testing results of the three main stages

Testing stagesTm/minCp/unitsOs/%LbCd/msPl/%Ec/Wh
The first stage85.72105.361001583.48
The second stage47.8382.4593.270.8258.362.141347.26
The third stage62.1995.7889.440.7763.473.221478.62
Testing stagesTm/minCp/unitsOs/%LbCd/msPl/%Ec/Wh
The first stage85.72105.361001583.48
The second stage47.8382.4593.270.8258.362.141347.26
The third stage62.1995.7889.440.7763.473.221478.62

To enhance the practicability and scalability of the obstacle avoidance algorithm, convolutional neural networks (CNN) are integrated to further improve the accuracy of Q-value estimation. CNN processes complex environmental inputs, such as images or point cloud data, and extracts high-dimensional features that are conducive to obstacle avoidance decisions. The Q-value estimation process can be expressed as:

(19)

where CNN(s) represents the feature representation of input state s, W is the network weight matrix, and b is the bias vector.

Moreover, to ensure real-time performance and efficiency in multimachine collaborative operations, a distributed path adjustment and obstacle avoidance mechanism are designed. Each device acts as an independent node, achieving rapid responses to the environment through local perception and decision-making, and coordinating obstacle avoidance among devices via low-latency communication protocols.

5 System simulation and verification

5.1 Simulation testing

The simulation-testing scenario is set in a mountainous region in Southwest China, characterized by complex terrain including mountains, canyons, forests, and multiple transmission lines crossing the area. The experiment assumes a transmission line length of 50 km, with significant elevation differences, where the highest altitude reaches 2000 m and the lowest is 500 m. The span of the transmission line towers is uneven, with an average span of 350 m and a maximum span of 700 m. The terrain data required for the experiment comes from real GIS data and publicly available terrain and environmental databases. GIS data provide high-resolution terrain information, while the terrain and environmental data supplement the elevation information. These data allow for the generation of a 3D simulation environment that closely resembles the actual terrain. Additionally, the geometric structure and location data of the transmission lines are based on actual line diagrams and equipment location data provided by the power company.

The simulation platform is built on ROS and the Gazebo simulation environment. The ROS version used is ROS Noetic, and the Gazebo version is Gazebo 11, both of which provide seamless integration with the latest robotic hardware and software. The simulation experiment is divided into three main stages, each progressively increasing the complexity of tasks to test the system’s performance in static, dynamic, and high-density complex environments. In the first stage, a single drone conducts inspections along the 50-km transmission line in a static environment, using SLAM technology for localization and map construction to verify its path planning and data collection capabilities. The second stage involves multimachine collaborative testing in a dynamic environment, with 10 drones and 2 UGVs operating in a simulation environment that includes randomly moving obstacles (speed 0.5–1.5 ms/s) and temporary no-fly zones (50 m × 50 m). This stage tests the system’s real-time path adjustment and collaborative operation effectiveness. The third stage involves testing in a high-density complex environment, increasing the number of drones to 15 and dividing them into three groups. By introducing denser obstacles and more frequent no-fly zone changes, this stage evaluates the system’s load-balancing and task-scheduling capabilities.

To comprehensively evaluate the system’s performance in simulation experiments, the assessment parameters include task completion time (Tm), path cost (Cp), obstacle avoidance success rate (Os), load balance (Lb), communication delay (Cd), packet loss rate (Pl), and average energy consumption (Ec).

5.2 Results analysis

The experimental results of Table 1 indicate that the multimachine collaborative control method proposed in this study demonstrates excellent performance across several key indicators in transmission line barrier operation path planning and optimization under complex terrain conditions. Regarding task completion time, the proposed method significantly reduced the completion time, especially in dynamic environments, from 85.72 min in the static single-machine environment to 47.83 min. This shows that multimachine collaborative operations can effectively improve task execution efficiency in response to environmental dynamics. However, in high-density complex environments, task completion time increased to 62.19 min due to the complexity of the environment and task density, but it still outperformed static single-machine operations.

The analysis of path cost and energy consumption further highlights the advantages of multimachine collaborative control. In the dynamic environment, the path cost decreased from 105.36 units to 82.45 units, and energy consumption was reduced to 1347.26 Wh per drone, indicating that this method can significantly reduce energy consumption through optimized paths and rational task distribution in dynamic environments. However, in high-density complex environments, path costs and energy consumption increased, reflecting that in more complex operational scenarios, multimachine collaborative control requires further optimization to maintain energy efficiency. The obstacle avoidance success rate showed that multimachine collaborative control exhibited a high-obstacle avoidance success rate when dealing with dynamic obstacles, although the success rate dropped to 9.44% in high-density complex environments, indicating that the system maintained high reliability. Simultaneously, the load balance slightly decreased in high-density complex environments, indicating that there was some uneven distribution of tasks among devices, which might be one of the reasons for the increase in energy consumption and path cost. Communication delay and stability analysis showed that the system’s communication network faced greater pressure in high-density complex environments, resulting in an average communication delay increase to 63.47 ms, and the packet loss rate increased to 3.22%. This indicates that optimizing the communication system’s performance in complex environments will be a crucial direction for future improvement in multimachine collaboration efficiency. The comparison of rate of change in the simulation test results of the second and third stages relative to those of the first stage is shown in Figs 8 and 9.

The rate of change in the simulation test results of the second and third stages relative to those of the first stage.
Figure 8

The rate of change in the simulation test results of the second and third stages relative to those of the first stage.

Comparison of the simulation test results of the second and third stages relative to those of the first stage.
Figure 9

Comparison of the simulation test results of the second and third stages relative to those of the first stage.

In the experiments on system robustness, the results showed that the multimachine collaborative control system demonstrated strong robustness in complex and dynamic environments (Figs 10-12). In the experiments conducted in dynamic environments, when unexpected equipment failures occurred, the system was able to reassign tasks within 3.47 s and continue operations despite the failure of a device, with the task completion time increasing by only 12.8%. In the event of a communication interruption, the system could continue running through local decision-making mechanism and resume normal communication after a 2.89-s delay, maintaining a packet loss rate at a relatively low 3.17%, indicating that the system can effectively handle communication network fluctuations. In high-density complex environment experiments, the system quickly adapted to sudden changes in the environment, such as new obstacles or temporary no-fly zones. After detecting environmental changes, the path cost increased by only 7.23%, energy consumption by 9.54%, and the obstacle avoidance success rate remained at 88.45%, demonstrating the system’s high adaptability in complex environments. Nevertheless, the load balance slightly decreased to 0.75 after sudden events, indicating that task distribution was somewhat affected, but overall tasks were still successfully completed. Moreover, in addition to local decision-making mechanism, there are two other methods can be employed in further studies to enhance the performance of the system in the event of sensor failure or communication disruption: a multilayer sensor redundancy and backup communication links can be introduced to ensure the transmission of critical task data; by integrating fault prediction and proactive recovery strategies, the system can rapidly adjust task allocation through MPC, ensuring continued efficient operation.

The rate of change in the second-stage simulation test results when the primary sensors of 1, 2, and 3 UAVs fail, respectively.
Figure 10

The rate of change in the second-stage simulation test results when the primary sensors of 1, 2, and 3 UAVs fail, respectively.

The rate of change in the second-stage simulation test results when the communication of the main control node is interrupted for 3, 5, and 10 s, respectively.
Figure 11

The rate of change in the second-stage simulation test results when the communication of the main control node is interrupted for 3, 5, and 10 s, respectively.

The rate of change in the second-stage simulation test results when the combination of random moving obstacle speed and temporary no-fly zone size is set to 0.5 m/s and 50 m × 50 m (S1), 1.0 m/s and 75 m × 75 m (S2), and 1.5 m/s and 100 m × 100 m (S3), respectively.
Figure 12

The rate of change in the second-stage simulation test results when the combination of random moving obstacle speed and temporary no-fly zone size is set to 0.5 m/s and 50 m × 50 m (S1), 1.0 m/s and 75 m × 75 m (S2), and 1.5 m/s and 100 m × 100 m (S3), respectively.

Regarding the dynamic adaptability of the collaborative mechanism, the results show that the adaptability of the multimachine system in dynamic environments is closely related to task prioritization and information-sharing mechanisms. In dynamic environments, when one task changes unexpectedly, such as urgent repair task, the system can adjust task priorities and replan paths within 2.34 s, ensuring that critical tasks are prioritized. Furthermore, dynamic adjustments in scheduling strategies allow the system to maintain 93.56% operational efficiency during sudden incidents (Fig. 13). In terms of information sharing, the experiments showed that in the face of network condition fluctuations or communication load changes, the system can dynamically adjust communication frequency and bandwidth allocation, maintaining information transmission stability. When the communication load increased by 20.0%, the transmission delay only increased by 0.89 s, and the packet loss rate only increased by 2.47%, indicating that the system’s collaborative capabilities and information-sharing efficiency were effectively maintained in dynamic environments (Fig. 14). The experimental results suggest that task-priority-based scheduling strategies and dynamically adjusted information-sharing mechanisms significantly enhance the multimachine system’s adaptability in complex and dynamic environments, ensuring the continuity of task execution and overall system collaboration efficiency. The optimal method for maintaining system stability under high communication load is adaptive communication frequency adjustment. Based on the current network load, the system dynamically adjusts communication frequency and bandwidth allocation. By monitoring communication traffic and delay, the system can automatically select the optimal frequency band and communication frequency.

The rate of change in the second- and third-stage simulation test results when one task changes unexpectedly.
Figure 13

The rate of change in the second- and third-stage simulation test results when one task changes unexpectedly.

The rate of change in the second- and third-stage simulation test results when the communication load increased by 20.0%.
Figure 14

The rate of change in the second- and third-stage simulation test results when the communication load increased by 20.0%.

Comparative analysis shows significant differences in the efficiency and complexity of the path-planning algorithm under different environments (Fig. 15). The average computation time in dynamic environments was 1.83 s, demonstrating high efficiency, while in high-density complex environments, computation time increased to 2.67 s, indicating that the increased complexity of the environment led to higher computational demands. The time complexity of the algorithm also increased from O(n\log n) to O(n2), reflecting the rise in computational complexity in complex environments. When handling dynamic changes, the system’s response time to dynamic obstacles was 1.12 and 1.48 s when setting up temporary no-fly zones, demonstrating the algorithm’s flexibility. In high-density complex environments, CPU usage was 78.34% and memory usage was 64.57%, indicating that complex environments increased system resource demands. The number of path optimization iterations in high-density environments also increased from 15.42 to 23.89, further adding to the computational burden. Overall, the algorithm is effective in complex environments, but as environmental complexity increases, computational complexity and resource utilization rise significantly, imposing higher requirements on system robustness and real-time performance.

The rate of change in the average computation time (a1), CPU usage (b1), memory usage (c1), and path optimization iteration (d1) of the second- and third-stage relative to those of the first stage.
Figure 15

The rate of change in the average computation time (a1), CPU usage (b1), memory usage (c1), and path optimization iteration (d1) of the second- and third-stage relative to those of the first stage.

From the above, it can be known that, in high-density complex environments, the multiagent collaborative control system faces limitations such as load imbalance, increased communication delays, rising computational complexity, and higher energy consumption. To optimize system performance, adaptive task allocation, distributed scheduling, improved communication networks and dynamic routing protocols, parallelized path-planning algorithms, and energy-aware scheduling can be employed. Additionally, by integrating deep learning and reinforcement learning techniques, the system can enhance the intelligence of path planning and task allocation. A hybrid architecture combining centralized and distributed control can further improve the system’s efficiency, robustness, and energy efficiency in complex environments.

An application case involves the execution of transmission line barrier operations in the mountainous regions of Southwest China. This area is characterized by complex natural terrain, including steep mountains, valleys, and forests. The total length of the transmission line is approximately 50 km, with significant elevation differences, ranging from a maximum altitude of 2019 m to a minimum of 504 m. In this practical application, five drones and two ground robots were selected to participate in the task, equipped with LiDAR, visual sensors, and high-precision GPS systems for environmental sensing and path planning. The results indicated a task completion time of 49.32 min, a path cost of 85.42 units, an obstacle avoidance success rate of 91.23%, a load-balancing index of 0.82, a communication delay of 58.12 ms, and an average energy consumption of 1225.67 Wh per drone. In this case, the multiagent collaborative control system successfully completed the transmission line barrier operations in a complex terrain. Both the task completion time and path cost showed significant improvements over traditional single-agent operations. The system’s obstacle avoidance success rate and load balancing index demonstrated high efficiency and stability. However, the communication delay slightly increased, possibly due to signal blockage in the mountainous region. Overall, the energy consumption performance was favorable, indicating the system’s advantages in resource allocation and energy management.

6 Conclusion

This study focuses on the path planning and optimization of transmission line barrier operations in complex terrains, proposing a solution based on multimachine collaborative control. First, a 3D path-planning algorithm was developed to adapt to terrain variations, improving the system’s environmental adaptability. Second, task allocation and load balancing among devices were optimized using multimachine collaborative control technology, enhancing operational efficiency and system stability. Finally, real-time path adjustment and obstacle avoidance strategies in dynamic environments were introduced to ensure the system’s flexibility in responding to sudden changes. The simulation test results show that multimachine collaborative control significantly improves task completion efficiency, reduces path costs and energy consumption in complex and dynamic environments, and demonstrates clear advantages in dynamic conditions. Moreover, in the face of unexpected equipment failures and communication interruptions, the multimachine system can quickly adjust task allocation and communication strategies, maintaining high operational efficiency and system stability. In high-density complex environments, although communication delay and load balance decreased, the system was still able to effectively respond to environmental changes, ensuring task execution continuity. Overall, the methods proposed in this study not only provide a feasible solution for transmission line barrier operations in complex terrains but also offer valuable insights into further optimizing multimachine collaborative control systems in practical applications. While the multiagent system can adapt to dynamic changes, load balancing and communication stability deteriorated in high-density environments, leading to increased energy consumption and path costs due to load imbalance and communication delays. Future research should focus on enhancing the performance of multiagent collaborative control systems through intelligent fault detection and prediction, optimization of adaptive task allocation and redundancy mechanisms, improvements to distributed communication protocols, and dynamic load balancing optimization. The integration of advanced machine learning models can predict and detect system faults in advance, ensuring task continuity. Additionally, the use of edge computing and optimized communication protocols can mitigate the impact of communication disruptions, while dynamic load balancing helps rapidly adjust resource allocation, ensuring efficient and stable system operation in complex environments.

Author contributions

Dan Zhu (Conceptualization [equal], Data curation [equal], Formal Analysis [equal], Investigation [equal], Methodology [equal], Validation [equal], Visualization [equal], Writing—original draft [equal]) and Jianguo Gao (Data curation [equal], Formal Analysis [equal], Funding acquisition [equal], Methodology [equal], Project administration [equal], Software [equal], Supervision [equal], Validation [equal], Writing—original draft [equal], Writing—review & editing [equal]).

Conflict of interest

None declared.

Funding

Science and technology project of Shuozhou Power Supply Company of State Grid Shanxi Electric Power Company ``Research and Application of Multi-machine Collaborative Control'' (No.:5205F0240008).

References

[1]

Ahmed
MF
,
Mohanta
JC
,
Sanyal
A
. et al.
Path planning of unmanned aerial systems for visual inspection of power transmission lines and towers
.
IETE J Res
2024
;
70
:
3259
79
. .

[2]

Wang
B
,
Du
X
,
Wang
Y
. et al.
Multi-machine collaboration realization conditions and precise and efficient production mode of intelligent agricultural machinery
.
Int J Agri and Biol Eng
2024
;
17
:
27
36
. .

[3]

Panda
M
,
Das
B
,
Subudhi
B
. et al.
A comprehensive review of path planning algorithms for autonomous underwater vehicles
.
Int J Autom Comput
2020
;
17
:
321
52
. .

[4]

Hu
H
,
Yang
X
,
Xiao
S
. et al.
Anti-conflict AGV path planning in automated container terminals based on multi-agent reinforcement learning
.
Int J Prod Res
2023
;
61
:
65
80
. .

[5]

Li
H
,
Liu
W
,
Yang
C
. et al.
An optimization-based path planning approach for autonomous vehicles using the DynEFWA-artificial potential field
.
IEEE Trans Intell Vehicles
2021
;
7
:
263
72
. .

[6]

Chen
J
,
Du
C
,
Zhang
Y
. et al.
A clustering-based coverage path planning method for autonomous heterogeneous UAVs
.
IEEE Trans Intell Transp Syst
2021
;
23
:
25546
56
. .

[7]

Disyadej
T
,
Kwanmuang
S
,
Muneesawang
P
. et al.
Smart transmission line maintenance and inspection using mobile robots
.
Advances in Science, Technology and Engineering Systems Journal
2020
;
5
:
493
500
. .

[8]

Gulski
E
,
Jongen
R
.
Condition based maintenance of transmission power cables
.
IEEE Transactions on Power Delivery
2021
;
37
:
1588
97
. .

[9]

Jensen-Nau
KR
,
Hermans
T
,
Leang
KK
.
Near-optimal area-coverage path planning of energy-constrained aerial robots with application in autonomous environmental monitoring
.
IEEE Trans Autom Sci Eng
2020
;
18
:
1453
68
. .

[10]

Li
J
,
Xiong
Y
,
She
J
. et al.
A path planning method for sweep coverage with multiple UAVs
.
IEEE Internet Things J
2020
;
7
:
8967
78
. .

[11]

Luo
Y
,
Yu
X
,
Yang
D
. et al.
A survey of intelligent transmission line inspection based on unmanned aerial vehicle
.
Artif Intell Rev
2023
;
56
:
173
201
. .

[12]

Tummala
AS
,
Alluri
HK
,
Ramanarao
PV
.
Optimal control of DFIG wind energy system in multi-machine power system using advanced differential evolution
.
IETE J Res
2020
;
66
:
91
102
. .

[13]

Karur
K
,
Sharma
N
,
Dharmatti
C
. et al.
A survey of path planning algorithms for mobile robots
.
Vehicles
2021
;
3
:
448
68
. .

[14]

Wei
W
,
Gao
F
,
Scherer
R
. et al.
Design and implementation of autonomous path planning for intelligent vehicle
.
Journal of Internet Technology
2021
;
22
:
957
64
. .

[15]

Puente-Castro
A
,
Rivero
D
,
Pazos
A
. et al.
A review of artificial intelligence applied to path planning in UAV swarms
.
Neural Comput & Applic
2022
;
34
:
153
70
. .

[16]

Yu
L
,
Zhou
S
,
Huang
S
.
Trajectory optimization of the redundant manipulator with local variable period under multi-machine coordination
.
Robotica
2023
;
41
:
292
305
. .

[17]

Manzinger
S
,
Pek
C
,
Althoff
M
.
Using reachable sets for trajectory planning of automated vehicles
.
IEEE Transactions on Intelligent Vehicles
2020
;
6
:
232
48
. .

[18]

Wang
H
,
Lu
B
,
Li
J
. et al.
Risk assessment and mitigation in local path planning for autonomous vehicles with LSTM based predictive model
.
IEEE Trans Autom Sci Eng
2021
;
19
:
2738
49
. .

[19]

Fusic
SJ
,
Sitharthan
R
.
Improved RRT* algorithm-based path planning for unmanned aerial vehicle in a 3D metropolitan environment
.
Unmanned Systems
2024
;
12
:
859
75
. .

[20]

Evangelista Araujo Neto
J
,
Castro
CA
.
Optimal maintenance scheduling of transmission assets in the Brazilian electric system
.
J Control Autom Electr Syst
2021
;
32
:
482
91
. .

[21]

Karpas
E
,
Magazzeni
D
.
Automated planning for robotics
.
Annual Review of Control, Robotics, and Autonomous Systems
2020
;
3
:
417
39
. .

[22]

Yao
Z
,
Jiang
H
,
Cheng
Y
. et al.
Integrated schedule and trajectory optimization for connected automated vehicles in a conflict zone
.
IEEE Trans Intell Transp Syst
2020
;
23
:
1841
51
. .

This is an Open Access article distributed under the terms of the Creative Commons Attribution License (https://creativecommons.org/licenses/by/4.0/), which permits unrestricted reuse, distribution, and reproduction in any medium, provided the original work is properly cited.