1. Introduction
With the advent of Industry 4.0, industrial automation technology has been rapidly evolving. Due to their superior flexibility, accuracy, and reliability, robotic arms are widely used in various fields such as welding, material handling, and assembly processes [
1]. However, in practical applications, robotic arms typically follow predefined paths or rely on manual operation by skilled personnel. These control methods exhibit clear limitations, especially in complex environments with numerous obstacles, where they struggle to effectively avoid collisions [
2]. An effective obstacle avoidance path planning algorithm for robotic arms can significantly reduce equipment damage and downtime caused by collisions, thereby improving overall operational efficiency [
3]. For example, in human–machine collaboration, Dai et al. [
4] proposed a novel robotic arm trajectory planning framework (DMP-PSO), which combines Dynamic Motion Primitives (DMP) with Particle Swarm Optimization (PSO) to autonomously generate various robotic arm trajectories that include obstacle avoidance paths. Meanwhile, the risk of encountering singularities and obstacles during robotic arm operation is extremely high. In order to solve this key problem, Wu et al. [
5] proposed a novel improved scheme for the Fast Moving Tree (FMT) algorithm, which cleverly enables it to navigate in complex terrains of Cartesian space with unprecedented precision. As a critical aspect of intelligent robotic arm control, the primary objective of obstacle avoidance path planning is to enable the arm to bypass environmental obstacles and plan an optimal path—one that is shorter and contains fewer nodes—while adhering to the kinematic and dynamic constraints of the arm [
6].
Obstacle avoidance path planning fundamentally represents a multi-objective optimization problem. Current optimization methods often suffer from high computational complexity, large search spaces, and limited efficiency, making it difficult to achieve globally optimal solutions [
7]. To address these challenges, various algorithms have been proposed, such as the rapidly-exploring Random Tree (RRT) [
8], Artificial Potential Field (APF) [
9,
10], and A* algorithm [
11]. Among them, the APF algorithm offers simple implementation and real-time performance, making it widely adopted. However, as a method that constructs virtual attractive and repulsive forces to guide the robot’s movement, it is prone to getting trapped in local optima or oscillating—especially near the goal when obstacles are present [
12]. The RRT algorithm is characterized by fast and random spatial sampling and does not require environment modeling, providing comprehensive spatial exploration. However, due to its random search direction, it tends to converge slowly, consume excessive time, and generate many invalid nodes in complex environments [
13]. The traditional A* algorithm is known for its simple principles and fast computation. Nonetheless, it suffers from exponential spatial expansion. As the map size increases, the computational load and memory usage grow significantly, especially in three-dimensional space, where A* exhibits long runtimes and poor path-finding efficiency [
14].
Despite their strengths, these algorithms face notable limitations when dealing with multi-objective, multi-constraint optimization problems in complex environments, making it difficult to effectively find the shortest path. Since obstacle avoidance path planning is essentially an NP-hard problem, the computational complexity of finding an optimal solution is considerable. Metaheuristic algorithms, which simulate intelligent behaviors observed in nature, offer a promising alternative. These algorithms strike a balance between local search and global exploration and can approach the global optimum within limited computation time [
15]. Hence, metaheuristics demonstrate strong adaptability and problem-solving capabilities in obstacle avoidance path planning and have become a practical tool for tackling such complex optimization challenges.
The African Vulture Optimization Algorithm (AVOA) is a typical population-based metaheuristic, inspired by the foraging behavior of African vultures. It addresses optimization problems by effectively balancing exploration and exploitation strategies [
16]. In recent studies, AVOA has been successfully applied to a variety of domains. For instance, Amylia A. proposed a Cauchy Opposition-Based AVOA to address path planning for unmanned aerial vehicles in three-dimensional environments [
17,
18] improved AVOA to minimize production cycles and delays in multi-objective flexible job shop scheduling with dual resource constraints. Ref. [
19] proposed an optimized hybrid renewable energy system configuration based on AVOA to reduce power loss probability and improve system reliability. Ref. [
20] introduced a quantum-inspired AVOA with an elite mutation strategy, improving both accuracy and convergence in production scheduling problems. Ref. [
21] enhanced AVOA using representative vulture selection, rotational flight, and accumulation strategies, effectively mitigating slow convergence and local stagnation issues. These advancements have substantially improved AVOA’s performance and demonstrated its applicability and effectiveness across various optimization tasks.
In addressing the challenge of obstacle avoidance and optimal path planning for robotic arms, this paper proposes a novel Cauchy Chaos-based African Vulture Optimization Algorithm (CC-AVOA). By introducing Cauchy mutation and logistic chaos mapping, the algorithm enhances population diversity and strengthens the ability to escape local optima, resulting in faster convergence. To verify the effectiveness of the proposed CC-AVOA, simulations were conducted in two-dimensional, three-dimensional, and robotic arm environments using MATLAB. The performance of CC-AVOA was compared against other algorithms. The simulation results show that CC-AVOA generates obstacle avoidance paths with fewer nodes and shorter lengths than other methods, demonstrating its practicality and effectiveness for robotic arm obstacle avoidance path planning.
2. Improvement of African Vulture Optimization Algorithm
2.1. African Vulture Optimization Algorithm
AVOA has attracted widespread attention for its simplicity, flexibility, and efficiency. The algorithm has been applied to many optimization problems by introducing strategies such as adaptive weights and spiral search to achieve a balance between exploration and exploitation [
22]. Vultures hunt by circling to search for prey and adjusting their altitude, demonstrating a coordinated balance between global and local search capabilities. Inspired by this behavior, the algorithm evaluates the fitness function of the initial population to divide it into groups: the best solution is selected as the optimal vulture, the second-best as the sub-optimal vulture, and the remaining individuals form the rest of the population. During each iteration, the other individuals update their positions by moving toward or replacing the optimal or sub-optimal vulture.
The simulation of the AVOA is completed based on the hunting behavior of vultures through the following steps.
2.1.1. Initialization
In the proposed CC-AVOA algorithm, each individual represents a candidate path from the start point to the target point, encoded as a sequence of control points , where and denote the fixed start and goal points, respectively, and are the intermediate control points to be optimized. These intermediate control points constitute the decision variables of the optimization process.
During initialization,
N vultures (candidate paths) are randomly generated within the feasible workspace boundaries. The coordinates of the intermediate control points are initialized within the predefined range
, as expressed in Equation (1):
where
D denotes the dimension of each search agent, and
N refers to the population size. The parameters
and
represent the upper and lower limits of the
search dimension, respectively, while
is a uniformly distributed random vector within the interval [0, 1].
2.1.2. Phase 1: Population Grouping
The AVOA algorithm begins by creating an initial random population, after which the fitness values of all candidate solutions are computed. The top-performing solution is designated as the leading vulture in group one, while the second-best solution becomes the primary vulture in group two. The remaining solutions are allocated to group three. Since the dominant vultures in the first two groups influence the movement patterns of others, Equation (2) is formulated to determine which vultures will adjust their trajectories in the current optimization cycle.
where
denotes the best vulture selected,
means the first best vulture, and
means the second best vulture.
and
represent two arbitrary values that fall within the range of 0 to 1 and their sum must be equal to 1. The probability of selecting the best solution from each group is obtained according to the Roulette wheel mechanism, and its calculation formula is shown in Equation (3).
In this equation, represent the fitness values of the vultures in the first and second groups, respectively, and n denotes the total fitness of both groups.
2.1.3. Phase 2: The Starvation Rate of Vultures
When the vulture population feels “satisfied,” they have sufficient energy to search for food over longer distances. However, when they are “hungry,” due to a lack of energy, they become more aggressive and tend to move closer to other vultures that have food, rather than continuing to search independently. Therefore, this behavior can be utilized to describe the shift from the “exploration phase” to the “exploitation phase.” The hunger level of vultures can be represented by Equation (4).
where
represents a number ranging from 0 to 1, and
Z denotes a value that randomly varies between −1 and 1, updating with each iteration. The calculation formula of
t is expressed by Equation (5):
where
represents the current number of iterations,
represents the maximum number of iterations,
h is a random number between [−2, 2], and
used to control the weight of the exploration phase. As the number of iterations increases, the parameter representing hunger
will gradually decrease. When
, the vulture enters the “exploration phase” and searches for new food sources in different locations; when
, the vulture enters the “exploitation phase” and concentrates on searching for food in nearby areas.
2.1.4. Phase 3: Exploration Stage
The exploration phase forms the backbone of the AVOA, aiming to emulate the behavior of vultures in the wild as they fly extensively to locate potential food sources. In the process of tackling optimization problems, the main responsibility of this phase is to carry out an extensive global search, traversing various regions of the solution space to prevent the algorithm from becoming trapped in local optima prematurely.
In the exploration phase, the vulture updates its position by randomly selecting two search strategies. The specific strategy is determined by a random parameter
.
lies within the interval [0, 1], and the randomly generated value
is taken from [0, 1]. The position update of the vulture is expressed by Equation (6):
represents the position of the vulture in the
th iteration, and
denotes the position of the optimal vulture selected in the
ith iteration as per Equation (2).
is the saturation rate of the vulture as defined in Equation (3).
and
represent the upper and lower bounds of the variable, respectively.
is a random number within the interval
, and
as a mechanism to enhance dispersion and explore various search regions.
represents the distance between the vulture and the current best solution, as defined in Equation (9).
Among them, X is a random value in [0, 2], which is used to increase the diversity of exploration behavior, and is the position of the ith vulture.
2.1.5. Phase 4: Exploitation (First Stage)
In AVOA, the first stage of the development phase mainly simulates the fine search behavior of vultures when approaching the target area. When the saturation rate of the vultures is in [0.5, 1], the algorithm enters the development phase. In this stage, the behavior of the vultures is divided into two strategies: siege tactics and rotation flight, and the specific selection is controlled by random parameters.
The parameter
is used to control the strategy selection of the vulture’s behavior.
and
are taken from [0, 1]. When
, the siege tactic is selected; otherwise, the rotation flight is selected. The position update rule can be expressed by Equations (10) and (11):
Among them,
represents the position of the
ith vulture in the next iteration,
represents the position update factor of the current vulture,
is the hunger rate,
in the range [0, 1].
represents the distance between the vulture and the current optimal position, and the calculation method is shown in Equation (12):
denotes the position of the ith vulture. By introducing the random factor , the algorithm enhances the randomness and diversity of the search area.
Where
and
are rotation interference factors, which are defined by Equations (13) and (14):
and are random numbers in the range of [0, 1], which are used to increase the perturbation of position updates. By introducing sine and cosine functions, the algorithm can simulate the vulture’s fine search near the target and improve the search efficiency in the development phase.
2.1.6. Phase 5: Exploitation (Second Stage)
In the development stage of AVOA, when the vultures’ satiety rate
is less than 0.5, it indicates that most vultures in the population have reached saturation. However, the two most outstanding vultures are hungry due to long-term high-intensity activities, and they need to quickly gather and attack available food sources. In this case, the vultures will gather or attack around the same target food source. In order to adjust the behavior pattern of vultures, parameter
is introduced, and its value range is [0, 1]. In each iteration, Compare the values of
and
to determine whether the vulture should engage in a gathering or attacking behavior, expressed by Equations (15) and (16):
where
represents the vulture’s satiety, the distance between the vulture and the most successful vulture in any group is represented by
, and
and
represent the contributions of the best individuals from the first and second groups of vultures, respectively, defined by Equations (17) and (18):
and represent the most successful vultures in the first and second groups.
The efficiency of the AVOA was increased using the Lévy flight mechanism, which is derived using the Equation (19):
and
v are both within the range [0, 1], generating large step transitions with randomness.
is usually set to 1.5, representing the parameter of the
distribution.
is defined by Equation (20):
In which
2.2. Algorithm Improvement
2.2.1. Chaotic Mapping
The original Vulture Optimization Algorithm employs a random distribution of the vulture population, which leads to an uneven initial distribution and poor diversity. This results in slow convergence of the algorithm, low precision of convergence, and diminished search performance. To address this issue, chaotic mapping can serve as an effective solution. Chaos generally refers to deterministic yet apparently random behavior found in nonlinear dynamic systems. It has distinct properties that allow it to produce sequences that are regular, unpredictable, ergodic, and non-repetitive. The main idea of chaotic mapping is to replace random initial variables with chaotic variables to improve the algorithm’s ability to explore and optimize the search space. This approach helps maintain population diversity, allowing optimization algorithms to escape local optima and improve their overall exploratory capacity. Chaotic initialization is introduced to enhance population diversity and improve global exploration during the optimization process. Its role is limited to the solution search stage and does not directly affect actuator smoothness, torque continuity, or control stability. There are numerous chaotic mappings available in the field of optimization, and this study utilizes the Logistic map, a simple nonlinear equation that describes the dynamics of population growth, as represented by Equation (21)
In the equation, represents the population size of the nth generation, with values ranging between [0, 1]. is the control parameter, indicating the population growth rate.
When , the population size gradually tends towards a stable value. When , the system exhibits periodic oscillations. When , the system enters a chaotic state, exhibiting complex, seemingly random behavior.
In the chaotic state, the sequence generated by the Logistic mapping can be uniformly distributed across the entire defined domain, possessing good ergodicity.
2.2.2. Cauchy Mutation
The AVOA is known for its simplicity, low computational cost, and ease of implementation. However, it also has limitations. Firstly, the switch from exploration to exploitation in AVOA depends on probabilistic strategies, which may cause an imbalance between these two phases. Secondly, although the enhanced exploration phase speeds up convergence, it can reduce the algorithm’s global search capability, increasing the risk of getting trapped in local optima.
To strengthen AVOA’s global search capability and reduce its tendency to get stuck in local optima, this study incorporates a Cauchy mutation strategy. Cauchy mutation is a stochastic perturbation method based on Cauchy distribution, the core idea of which is to use the long-tail characteristics of Cauchy distribution to conduct a large-scale random search in the search space, so as to significantly improve the probability of finding the global optimal solution. The expression of the Cauchy density function is shown in Equation (22).
In which
is the location parameter,
a is the scale parameter, and
x is the independent variable in the Cauchy distribution, used to describe the shape of the probability density function. The Cauchy mutation operation is usually implemented by Equation (23):
In which,
is the standard Cauchy distribution random variable, which can be generated through Equation (24):
Here, is a random number within the interval [0, 1].
Through the long-tail feature, Cauchy mutation can produce a larger step size, which helps to explore a wider search space, At the same time improves the possibility of finding the global optimal solution. By introducing random perturbations, the population is prevented from converging prematurely and the diversity of the population is maintained.
2.3. Improved Algorithm Steps
To enhance the global optimization capability of the African Vulture Optimization Algorithm and improve its ability to escape local optima in obstacle avoidance path planning, this paper introduces a Cauchy mutation strategy and a Logistic chaotic mapping mechanism. These modifications aim to increase population diversity and improve the distribution of initial solutions. Based on the specific requirements of robotic arm path planning, a custom path fitness function is designed to simultaneously optimize path length and obstacle avoidance performance. The detailed steps of the improved algorithm are as follows:
Step 1. Set the optimization algorithm and the robot arm path planning related parameters: Set the vulture population to N and the maximum number of iterations to . Set the scale parameter of the Cauchy mutation in . Set the Logistic chaos mapping control parameter . Set the starting point and end point of the robot arm.
Step 2. The population is initialized using the Logistic chaos mapping, as shown in Equation (21), and normalized to the search space to serve as candidate solutions for the initial robotic arm path.
Step 3. Define the fitness function to optimize both path length and obstacle avoidance performance:
where
denotes the total path length,
represents the collision penalty term, and
is the newly introduced dynamic penalty term, which is used to evaluate the torque demand, thermal load, and energy consumption of the joint actuators along the planned path.The fitness function adopted in this study consists of path length and collision penalty terms. This formulation is intentionally designed to evaluate geometric feasibility and obstacle-avoidance performance at the motion planning level.
The collision penalty term
is introduced to penalize infeasible paths that intersect with obstacles, and is defined as
where
M is a sufficiently large positive constant.
The weighting coefficients and are used to balance path optimality and collision avoidance. In this study, is deliberately set much larger than to strictly prioritize collision avoidance, ensuring that any infeasible path is heavily penalized and excluded from the optimization process. The values of and are determined through preliminary parameter tuning experiments, which verify that all generated paths remain collision-free while still favoring shorter path lengths.
Step 4. Select the current optimal path and the second best path as search guiding individuals.
Step 5. In each iteration process, the African vulture optimization algorithm updates the swarm position by simulating the foraging and encircling behaviors of vultures. To prevent the algorithm from falling into local optimality and to enhance the diversity of the swarm, Cauchy mutation is performed on each individual after position updating. Compared to Gaussian mutation, it can more easily escape from local optimality, thereby improving the global search capability.
Step 6. Calculate whether the new path avoids obstacles. If the path collides with obstacles, adjust the path. If the path is reasonable, calculate the fitness value and retain the optimal solution.
Step 7. After the iteration, return to the optimal path.
The obstacle avoidance path planning algorithm flow chart is shown in
Figure 1.
3. Simulation Results and Analysis
To verify the performance advantages of the proposed CC-AVOA algorithm in obstacle avoidance path planning, simulations were conducted in both two-dimensional and three-dimensional scenarios.Due to the use of population-based optimization and iterative search, the proposed CC-AVOA is primarily designed for offline or semi-offline path planning scenarios. The selected population size and iteration count prioritize solution quality and robust obstacle avoidance rather than strict real-time performance. The simulations parameters are set as follows: the population size is N = 50, the maximum number of iterations is T = 500 and agent dimension is D = 40. These parameters are set with reference to the general configuration in related metaheuristic path planning research and are determined in combination with the results of preliminary experiments, so as to balance the solution accuracy and computational cost. The two-dimensional environment includes cases with both sparse and dense obstacle distributions, while the three-dimensional environment features a moderate level of obstacle complexity. In these scenarios, CC-AVOA is compared with the AVOA, RRT, and A* algorithms. The overall performance of each algorithm is evaluated based on three key metrics: path length, computation time, and the number of path nodes.All simulations were performed using MATLAB 2024a on a hardware platform equipped with an Intel Core i7-10700 CPU (2.90 GHz) and 32 GB of RAM.
3.1. Two-Dimensional Obstacle Avoidance Simulation
In the two-dimensional scenario, the simple scene and the complex scenario are set according to the number of obstacles. The two-dimensional scenario planning area is 50 × 50, the starting point is (0, 0), and the target point is (50, 50). The planning result of simple scenario A is shown in
Figure 2, The circles represent obstacles, the planned path is shown by a solid line, which is used to verify fundamental functionality of the algorithm under basic scenario.
In scenario A, the CC-AVOA algorithm demonstrates superior performance in both path length and number of path nodes owing to its Cauchy mutation strategy and vectorized computation. In contrast, the standard AVOA algorithm tends to converge to local optima, resulting in significantly extended final path lengths. Due to its stochastic sampling mechanism, the RRT algorithm generates less smooth trajectories with excessive nodes in two-dimensional environments. Meanwhile, the A* algorithm performs poorly in non-grid settings, exhibiting circuitous detours and low algorithmic efficiency.
Due to the high degree of randomness in the paths generated by the algorithms, this paper conducted fifty experiments for each algorithm, using their average values as the final data. The simulation data of scenario A is shown in
Table 1.
As shown in
Table 1, in a basic two-dimensional environment, the CC-AVOA algorithm achieved a reduction in path length by
,
, and
compared to the AVOA, A*, and RRT algorithms, respectively. Additionally, it significantly decreased the number of path nodes by
,
, and
. Although its runtime was
shorter than that of AVOA, it was
and
longer than A* and RRT, respectively. These results indicate that the proposed algorithm offers clear improvements in path quality, particularly in minimizing the number of path nodes.
The planning result of complex scenario B is shown in
Figure 3. The starting point is (0, 0) and the end point is (50, 50). In this scenario, the Logistic chaotic mapping is employed to initialize the population, thereby achieving a more uniform distribution of the population. Additionally, the stochastic perturbation mechanism based on the Cauchy distribution can effectively help the algorithm escape from local optimal solutions. Combined with CC-AVOA’s intelligent search strategy, the algorithm’s obstacle avoidance performance remains optimal in complex environments.
The simulation data for Scenario B is shown in
Table 2.
According to the data in
Table 2, in complex two-dimensional scenarios, compared with the AVOA, A*, and the RRT algorithm, the path length of the CC-AVOA was shortened by 0.71%, 6.57%, and 16.09%, respectively, and the path nodes was reduced by 12.50%, 81.08%, and 92.13%, respectively. However, the running time was reduced by 6.86% compared with AVOA, increased by 1.82% compared with A*, and increased by 22.31% compared with RRT.
These data show that the improved algorithm still has certain advantages in path optimization even in complex obstacle scenarios, and performs outstandingly in reducing path length and number of nodes. However, in running time, compared with A* and RRT, CC-AVOA has certain computational overhead, but it still has certain efficiency improvements compared with AVOA.
3.2. Three-Dimensional Obstacle Avoidance Simulation
Through the path planning simulation in the above two-dimensional scenario, the effectiveness of CC-AVOA in path search and redundancy reduction was verified. However, the actual robot arm operation environment is three-dimensional. Algorithms that perform well in two dimensions may have unforeseen problems in three dimensions, such as the curse of dimensionality and increased complexity of collision detection. Therefore, its path planning must consider the complexity of three-dimensional space. Although path planning in two-dimensional space can serve as the basis for theoretical verification, it must be extended to three dimensions in practical applications to deal with obstacles in real environments.
In the three-dimensional scenario with a planning area of 50 × 50 × 50 units, the starting point is set at (0, 0, 0) and the target point at (50, 50, 50). As illustrated in
Figure 4, the obstacle avoidance results of each algorithm in three-dimensional space demonstrate that the Cauchy perturbation mechanism in CC-AVOA enhances its ability to escape local optima, making it more effective at identifying shorter paths. The randomness of RRT expansion is more obvious. In order to ensure the search coverage, a large number of unnecessary nodes will be generated, resulting in redundancy. The A* algorithm tends to expand gradually in complex environments, resulting in dense nodes in the path, especially in areas with dense obstacles. The number of nodes increases significantly.
According to
Table 3, in terms of the number of path nodes, CC-AVOA reduced by 76.79%, 70.45% and 31.58% compared with RRT, A* and AVOA. In terms of path length, CC-AVOA shortened by 16.16%, 2.91% and 1.03% compared with RRT, A* and AVOA, respectively. However, the running time of CC-AVOA increased compared with RRT and A*, increasing by 41.62% and 12.69%, respectively, but compared with AVOA, the running time decreased by 3.94%, indicating that the algorithm has a slightly increased computational cost while optimizing the obstacle avoidance path. It can be seen that CC-AVOA can still effectively reduce the path nodes and path length in the three-dimensional map scenario.It should be emphasized that all comparative algorithms, including RRT, A*, AVOA, and the proposed CC-AVOA, are evaluated at the geometric path-planning level. The comparison focuses on geometric performance metrics such as path length, number of nodes, and planning time, in order to isolate the influence of different planning strategies.After path planning, all generated paths from different algorithms can be processed using the same joint-space trajectory generation and smoothing framework described in
Section 4.5. This unified post-processing ensures that actuator-related constraints and servo execution requirements are handled consistently, independent of the planning algorithm.
4. Algorithm Verification
4.1. Robotic Arm
This paper uses the FANUC R-2000iC/165F robotic arm as the subject for algorithm verification. A mechanical arm model is constructed using the D-H modeling method, as shown in
Figure 5. The specific parameters of the model are presented in
Table 4. The joint coordinate system of the robotic arm is illustrated in
Figure 6.
When modeling, first determine the D-H parameters of the adjacent links, and then perform matrix operations. The D-H parameter table of the robot arm is shown in
Table 4, where
i represents the link serial number, link length
is the common normal length between two rotating joint axes; link twist angle
is the angular displacement of the two joint axes; link offset
is the perpendicular offset between two adjacent joints, that is, the offset distance along the z-axis; joint angle
is the rotation of the i-th joint relative to its initial position.
The coordinate system of the robot arm is established using the D-H coordinate system parameters. The final D-H transformation matrix needs to satisfy Equation (28):
represents the homogeneous transformation matrix from
to
. By substituting the corresponding parameters from the DH parameters into Equation (28), the corresponding transformation matrix is obtained, which is then used to calculate
, as shown in Equation (29).
In Equation (29),
represents
and
represents
.
denotes the overall transformation matrix from the robot base to the end effector, in the form of the matrix obtained through Equation (30).
4.2. Collision Detection
Collision detection for robotic arms involves assessing the positional relationship between the arm and obstacles within the workspace to determine the distance between them. Given that path planning for robotic arms involves interactions between rigid bodies, spatial geometric envelopes can be employed to simplify the models of both the obstacles and the robotic arm. By transforming the collision detection problem into a matter of assessing the relationship between cylindrical and spherical shapes, the computational load is significantly reduced, thereby enhancing the efficiency of the algorithm [
23]. The use of spherical and cylindrical envelopes represents a conservative geometric approximation of robot links. Since the envelope fully contains the true link geometry, any collision detected by the simplified model guarantees collision avoidance for the actual robot structure. The approximation error therefore manifests as a potential reduction of the reachable workspace rather than a loss of safety. The next step will be to investigate more accurate collision models based on mesh-level geometry or swept volume analysis, in order to further reduce conservatism when more computational resources are available.
The simplified collision detection model is shown in
Figure 7. To facilitate calculations, the collision detection between the robotic arm link and the sphere is converted into the positional relationship between a line segment and a sphere.
Let the shortest distance from point to line PQ be R. The positional relationship between the link and the spherical obstacle is as follows:
(1) If , then no collision occurs between the robotic arm’s links and the spherical obstacle.
(2) If , there are the following two situations:
If , the robot arm’s connecting rod will collide with the spherical obstacle. In other cases, no collision will occur.
4.3. Robotic Arm Obstacle Avoidance Path Planning
This paper verifies the performance of the CC-AVOA algorithm through systematic simulation experiments. First, the path planning test results under conventional scenarios indicate that the algorithm demonstrates significant advantages in path search efficiency and redundant node elimination. To further evaluate the applicability of the algorithm in complex environments, this study constructs a robotic arm motion planning scenario with three-dimensional obstacles based on the robot simulation toolbox. The practical application value of the CC-AVOA algorithm in robotic arm obstacle avoidance path planning is validated through comparative experiments. This paper verified the effectiveness of CC-AVOA in obstacle avoidance path planning through path planning in conventional scenarios, but it did not consider whether the links of the robotic arm would collide with obstacles when the end effector moves along two adjacent nodes. Therefore, the robot simulation toolbox is used to adopt spatial spatial geometric envelopes to simplify the models of obstacles and the robotic arm, ensuring that the distance from the path points generated by CC-AVOA to the origin of obstacles does not exceed the diameter of the robotic arm links, thereby preventing collisions between the robotic arm links and obstacles.
The starting point coordinates of the robot are set to (−500, 1200, 600) and the end point coordinates are set to (300, 200, 2500). Since the bounding sphere collision detection model is adopted, the obstacle is equivalent to a sphere. Therefore, this paper sets spherical static obstacles with different radii in the environment and arranges the obstacles on the path of the robot moving to the target point.
In order to verify the key importance of the obstacle avoidance path planning algorithm in the motion control of the robot arm,
Figure 8 shows the behavior of the robot arm without any such algorithm. The initial position shown in
Figure 8a,b presents the motion trajectory, with the red line indicating the path of the robot arm. Due to the lack of an effective path planning strategy, the robot arm cannot avoid static obstacles during the motion, resulting in collisions between the robot arm and the obstacles.
Under the premise of keeping the initial state of the robotic arm unchanged, this study integrates the AVOA-based obstacle avoidance path planning algorithm into the motion control process of the robotic arm.
Figure 9 illustrates the obstacle avoidance path of the robotic arm as determined by the AVOA algorithm. Although the robotic arm successfully bypassed obstacles and reached the endpoint, the search process of the AVOA algorithm has a high degree of randomness, especially in environments with dense obstacles or complex search spaces. This can result in a path with more nodes and, consequently, a longer path, potentially leading to a zigzag trajectory. If the robotic arm moves according to such a path, it may cause additional stress on its joints, thereby reducing the operational efficiency and service life of the robotic arm.
Since the path generated by AVOA is tortuous, it is easy to cause a sudden change in the speed and acceleration of the robot arm during movement, which in turn affects the operating performance and structural stability. Therefore, it is not suitable for robot arm obstacle avoidance path planning. In contrast, CC-AVOA improves the continuity of the path by introducing the Cauchy distribution function and Logistic chaotic mapping, and effectively reduces path fluctuations and turns. As shown in
Figure 10, making the speed and acceleration changes during the movement of the robot arm more stable, thereby reducing the impact on the joints.
To further verify that the number of path nodes of CC-AVOA in the robot arm obstacle avoidance path planning is less than that of AVOA, Based on the presentations in
Figure 9 and
Figure 10, this paper extracts the velocity and acceleration change curves of the six joints of the robotic arm under the AVOA and CC-AVOA path planning algorithms, respectively, and conducts a comparative analysis. Since the two bottom joints do not participate in the movement during the exercise, the relevant curves overlap.
As can be seen from
Figure 11 and
Figure 12, there are many broken line segments in the path nodes based on AVOA, which leads to drastic fluctuations in the joint angular velocity and instantaneous mutations in acceleration during the movement of the robot arm, which has an adverse effect on the mechanical structure and running time of the robot arm. The path generated based on CC-AVOA is smooth and continuous, making the velocity and acceleration change curves of the joints tend to be stable as a whole, the fluctuation range is significantly reduced, and the number and amplitude of peaks are also greatly reduced. Further analysis shows that, compared to AVOA, the maximum joint jerkiness of the CC-AVOA planning path is reduced by an average of about
, and the frequency domain components of its motion commands are more concentrated within the bandwidth of a typical servo system, thereby reducing the risk of triggering structural resonance and exceeding the controller’s tracking capability. The robot arm maintains good movement continuity throughout the movement process, significantly reducing the impact load on the robot arm links. Meanwhile, since joints 4 and 6 remain stationary throughout the entire movement, the velocity and acceleration of the motion curve of this joint are 0. Therefore, in
Figure 11 and
Figure 12, the motion curves of joints 4 and 6 coincide at point 0.
The results show that CC-AVOA generates fewer path nodes and smoother paths while maintaining good obstacle avoidance capabilities, providing a better path planning solution for the efficient and safe operation of the robot arm in complex environments. This further verifies the application value and engineering feasibility of CC-AVOA in actual robot arm obstacle avoidance tasks.
4.4. Dynamic Feasibility Analysis with Integrated Actuator Constraints
To ensure that the paths planned by the CC-AVOA framework are not only collision-free in the geometric space but also dynamically feasible and safe for real industrial manipulators, actuator-level constraints—including joint torque, velocity, and acceleration limits—are explicitly integrated into the path optimization framework in this section.
4.4.1. Manipulator Dynamic Model
The required joint torques along a given trajectory are computed using the Recursive Newton–Euler Algorithm (RNEA). This dynamic model accounts for link masses, inertia tensors, center-of-mass locations, and the payload at the end effector, which is assumed to be either the rated payload or zero payload for baseline evaluation. For the FANUC R-2000iC/165F industrial manipulator, the Denavit–Hartenberg (D–H) parameters are listed in
Table 4, while the link mass and inertia parameters are obtained from the manufacturer’s technical specifications.
The dynamic equation of the
i-th joint can be expressed as
where
denotes the driving torque of joint
i, and
,
, and
represent the joint position, velocity, and acceleration, respectively. The gravity-related term is a dominant component of the joint torque, particularly during low-speed motion or static holding phases. Specifically, the recursive Newton–Euler algorithm is adopted, and the driving torque
of joint
i is calculated by the following formula:
where
is the unit vector of the joint axis,
is the inertia tensor of link
i at its center of mass,
is the mass of the link, and
is the vector from joint
i to the center of mass of the link.
,
, and
are the angular velocity, angular acceleration, and linear acceleration of the link, respectively, which are derived recursively from the base through forward recursion.
and
are the viscous friction and Coulomb friction coefficients, respectively. The mass, center of mass, and inertia parameters of each link are set with reference to the technical manual of FANUC R-2000iC/165F.
4.4.2. Actuator Constraint Modeling
Each joint actuator is subject to inherent physical limitations that must be respected during path planning, including the peak torque constraint , the continuous (thermal) torque constraint , the velocity constraint , and the acceleration constraint , where and are obtained from the specifications of the FANUC servo motors and gear reducers.
4.4.3. Integration of Constraints into the CC-AVOA Fitness Function
The original fitness function
optimizes only the geometric path length and collision avoidance. To incorporate dynamic feasibility, it is extended to a weighted multi-objective formulation:
where
and
retain the same definitions as in the original framework. The newly introduced dynamic penalty term
is defined as
In this formulation, and denote the peak and root-mean-square torques of joint i along the trajectory, respectively, which characterize the instantaneous loading and long-term thermal stress of the actuator. The mechanical energy consumption of joint i is approximated as , where is a reference energy value used for normalization. The weighting coefficients are set to , , and , thereby prioritizing the avoidance of peak torque violations during optimization.
For each candidate path P generated by CC-AVOA, a quintic polynomial interpolation is first employed to generate time-parameterized position, velocity, and acceleration profiles. These trajectories are then mapped into the joint space via inverse kinematics to obtain , , and . Subsequently, the RNEA is applied to compute the joint torques , and the dynamic penalty term is evaluated. Any candidate path that violates hard actuator constraints is assigned a prohibitively large penalty value, ensuring its elimination during the optimization process.
4.5. Joint-Space Optimization and Redundancy-Aware Trajectory Generation
The CC-AVOA algorithm generates a sequence of collision-free path points in Cartesian space. However, to execute these paths on a real industrial manipulator, the Cartesian path must be converted into a joint-space trajectory while addressing kinematic redundancy, joint limit avoidance, and singularity prevention. This subsection presents the detailed transformation and optimization procedure.
4.5.1. Conversion from Cartesian Path Points to Joint-Space Trajectory
Given a Cartesian path point sequence generated by CC-AVOA, , where each point consists of the end-effector position and orientation, the inverse kinematics (IK) solver of the FANUC R-2000iC/165F manipulator is used to compute the corresponding joint configuration .
Since the manipulator has six degrees of freedom, multiple inverse kinematic solutions may exist for a given end-effector pose. The following criteria are employed to select the optimal solution.
Continuity Priority
For the first waypoint , select the solution that is closest to the current configuration of the manipulator. For subsequent waypoints , select the solution with the smallest Euclidean distance to the joint angles of the previous waypoint , so as to minimize the joint motion amplitude and ensure smooth movement.
Joint Limit Avoidance
Among the candidate solutions obtained in the previous step, priority is given to configurations whose joint angles are far from the software joint limits
. A joint-limit proximity penalty function is defined as
where
denotes the midpoint of the
i-th joint range. This penalty increases rapidly as a joint approaches its limits.
Singularity Avoidance
Calculate the Jacobian matrix
corresponding to each candidate solution. Evaluate the proximity to singularities by its minimum singular value
or manipulability
. Define a singularity penalty function:
where
is a small positive number to prevent division by zero. When
approaches 0, the penalty value approaches 1.
4.5.2. Joint Space Trajectory Optimization and Smoothing
After obtaining the discrete joint waypoint sequence via inverse kinematics, it is necessary to convert these discrete configurations into a continuous, time-parameterized joint trajectory suitable for industrial servo execution. Discrete joint waypoints cannot be directly executed by servo drives and must be transformed into smooth trajectories that satisfy kinematic continuity and actuator-related motion constraints.
In this work, a quintic polynomial interpolation strategy is adopted for joint-space time parameterization. For each joint
i and each trajectory segment between adjacent waypoints
k and
(
), the joint motion is described by a quintic polynomial:
where
denotes the motion duration of the
k-th segment.
The polynomial coefficients – are uniquely determined by enforcing position, velocity, and acceleration boundary conditions at both ends of each segment:
Position constraints: , ;
Velocity constraints: , ;
Acceleration constraints: , .
To ensure smooth start-stop behavior, the initial and terminal velocities and accelerations are set to zero, i.e., and . Velocity and acceleration continuity at intermediate waypoints is enforced by and , which leads to a tridiagonal linear system that can be solved efficiently. The segment duration is determined based on joint velocity and acceleration limits and the distance between adjacent waypoints. Specifically, a theoretical minimum motion time is first computed to satisfy joint kinematic constraints, and then appropriately extended according to task requirements to avoid aggressive motions and ensure smooth dynamic behavior. This time allocation strategy prioritizes execution feasibility and servo compatibility rather than strict time optimality.
The resulting continuous joint trajectory , together with its velocity and acceleration profiles, can be directly transmitted to the industrial robot controller, or further converted into velocity or torque commands depending on the control architecture. In practical execution, the industrial controller applies internal motion smoothing and bandwidth-limited servo control, which inherently enforces drive-level constraints.
To further enhance trajectory smoothness and dynamic performance, a local joint-space optimization layer is introduced as a post-processing step. Taking the discrete joint waypoints
as the initial solution, a quadratic programming (QP) problem is formulated to minimize joint acceleration and jerk while enforcing collision avoidance, joint limit constraints, and singularity avoidance:
where
is a weighting factor. Collision avoidance constraints are evaluated via forward kinematics, and joint limits and singularity proximity are explicitly enforced. This optimization layer acts as a polishing step that refines the rough joint-space path generated by CC-AVOA without altering its collision-free topology. Through quintic polynomial time parameterization and joint-space optimization, the generated trajectories are continuous in position, velocity, and acceleration, with bounded jerk, fully satisfying the execution requirements of industrial servo systems.
4.5.3. Closed-Loop Optimization Process Integrated into CC-AVOA
The original CC-AVOA only evaluates fitness in the Cartesian space. The improved framework forms a “dual-loop optimization” structure: Outer loop (CC-AVOA): Explore and optimize the waypoint sequence
P in the Cartesian space. Inner loop (joint space processor): For each candidate path
P generated by the outer loop: Execute the inverse kinematics solving and configuration selection in
Section 4.5.1. Execute the joint trajectory smoothing optimization (QP) in
Section 4.5.2. Pass the optimized joint trajectory to the dynamic model in
Section 4.4, and calculate the dynamic penalty
. Synthesize the geometric length
, collision penalty
, and dynamic penalty
to compute the total fitness
, and return it to the outer loop.
4.5.4. End-Effector Attitude Constraint Handling
For tasks requiring a specified end-effector attitude, the waypoint should include the target attitude . The inverse kinematics solution must satisfy both position and attitude constraints. For tasks where the attitude can be freely planned, the end-effector attitude can be treated as an optimization variable. For example, in CC-AVOA, the encoding of each waypoint can be extended to . While optimizing the position, the algorithm also searches for the optimal attitude sequence that reduces joint loads and avoids manipulator singularities.
4.5.5. Planner–Controller Interface and Execution Strategy
The proposed CC-AVOA framework operates as a high-level motion planner and does not replace the embedded servo controllers of industrial manipulators. Instead, it interfaces with the robot controller through a standard trajectory execution pipeline that is fully compatible with industrial practice. Specifically, CC-AVOA generates a collision-free path in Cartesian space, which is then mapped into joint space via inverse kinematics. The resulting discrete joint waypoints are further converted into a time-parameterized continuous joint trajectory using quintic polynomial interpolation, as described in
Section 4.5.2. The final output of the planner is a joint position trajectory
, together with its corresponding velocity
and acceleration
profiles.
In practical implementation, the generated joint position trajectory is transmitted to the industrial robot controller in position control mode, which is the standard execution mode for FANUC robots. The low-level servo loops, including velocity and torque control, remain fully handled by the proprietary controller of the robot, ensuring closed-loop stability, disturbance rejection, and tracking robustness. It should be emphasized that CC-AVOA does not directly output torque commands, nor does it interfere with the internal control architecture of the robot. By operating at the trajectory level and respecting joint limits, velocity, acceleration, and jerk constraints, the proposed planner guarantees compatibility with industrial controllers while avoiding any adverse impact on control stability.
5. Experiment
In the robotic arm experiments presented in this chapter, the obstacle avoidance path planning is performed in Cartesian space. The CC-AVOA algorithm generates a sequence of collision-free Cartesian path points within the robot workspace, which are subsequently converted into joint trajectories for execution on the robot controller. To further verify the feasibility and reliability of the CC-AVOA-based obstacle avoidance path planning method for manipulators proposed in this paper in real industrial applications, comparative experiments are conducted on both the RoboGuide version 9.03 industrial simulation platform and the FANUC R-2000iC/165F physical manipulator experimental platform in this chapter. Different from the two-dimensional and three-dimensional simulations in the Matlab R2025a environment, the experiments in this chapter aim to validate the implementability, obstacle avoidance stability, and execution consistency of the algorithm in industrial-grade robot systems. RoboGuide can accurately simulate the kinematics, speed planning, and collision detection of the FANUC controller, with the consistency between its simulation results and the physical manipulator exceeding 95%. After verification in RoboGuide, physical experiments are carried out on the real manipulator to test the final feasibility of the algorithm in actual industrial environments.
5.1. RoboGuide Experimental Platform
To validate the proposed method under industrial-relevant conditions, the built-in manipulator model in RoboGuide is adopted, with link parameters and joint limits consistent with the physical equipment. Within the manipulator’s workspace, six spherical obstacles (each with a radius of 6 cm) and one cuboid obstacle (dimensions: 43.8 cm × 11.6 cm × 32.1 cm) are deployed. The size and position of the obstacles are identical to those in the laboratory to ensure experimental comparability. Subsequently, the path points generated by the CC-AVOA algorithm are imported into RoboGuide. The Cartesian path points generated by the CC-AVOA algorithm are transformed into joint-space trajectories using the inverse kinematics solver provided by the RoboGuide platform. When multiple inverse kinematics solutions are available, the configuration closest to the previous joint state is selected to ensure motion continuity and avoid sudden joint changes. During trajectory execution, joint limits defined by the FANUC controller are strictly enforced. In addition, configurations close to kinematic singularities are avoided by maintaining sufficient clearance in the workspace, ensuring stable and safe robot motion throughout the execution process. The manipulator trajectory is executed, and the actual path is recorded as illustrated in
Figure 13.
In the figure, P [1] and P [8] correspond to the starting point and ending point of the obstacle area, respectively, while P [2]–P [7] are obstacle avoidance path points automatically generated by the algorithm. The coordinate systems of P [1]–P [8] are shown in
Table 5, By calculating the distance from each path point to the obstacles, it is found that the shortest distance from the path points to the center of the spherical obstacles is 126.4 mm, which is greater than the radius of the spheres. Meanwhile, the distance from P [7] to the surface of the cuboid obstacle is 1.12 mm. Therefore, the trajectory generated by the algorithm effectively avoids all obstacles throughout the entire movement process and finally reaches the target position smoothly, verifying its effectiveness and stability in obstacle avoidance planning.
5.2. Physical FANUC Robotic Arm
In RoboGuide simulation and physical FANUC robotic arm experiments, the discrete path point sequence generated by CC-AVOA is first converted into a time-continuous joint trajectory
using the aforementioned fifth-order polynomial interpolation method. This trajectory is uploaded to the controller in the form of a position command sequence through the FANUC KAREL programming interface or standard TP program, and is then tracked and executed in real time by the controller’s internal servo loop. Meanwhile, the goal of physical robot experiments is to verify the feasibility of executing planned trajectories and the correctness of motion on actual industrial robotic arms, rather than to conduct detailed actuator-level performance evaluations. The actual motion trajectory of the robot arm is shown in
Figure 14.
The same trajectory was executed consistently in both simulation and physical experiments, indicating reliable transferability from planning to execution; therefore, the FANUC robotic arm can strictly follow the planned path to complete obstacle avoidance movements, and no collisions or shutdown alarms are triggered throughout the complex spatial environment composed of obstacles. This paper further demonstrates through joint verification using RoboGuide simulation and physical robotic arm experiments that the proposed algorithm not only exhibits good planning capabilities in theoretical simulations, but also has practical engineering application value, enabling stable and reliable obstacle avoidance control in real industrial scenarios. Future work will consider additional robustness assessments under minor perturbations of different obstacle layouts and obstacle locations to further evaluate the adaptability of the proposed method.
6. Conclusions and Prospects
This paper proposes the CC-AVOA algorithm to address the problems of low success rate, excessively long obstacle-avoidance paths, and a large number of invalid nodes encountered in robotic arm path planning within complex environments. To verify the effectiveness of the proposed method, extensive simulations were conducted in two-dimensional, three-dimensional, and robotic arm scenarios. The performance of CC-AVOA was systematically compared with AVOA, RRT, and A* algorithms. The results demonstrate that CC-AVOA achieves superior performance in terms of path length and node number optimization, indicating improved path quality and global search capability.
Furthermore, joint verification was carried out using the RoboGuide industrial simulation platform and a FANUC industrial robotic arm equipped with electrically actuated, gear-driven joints. Experimental results show that the robotic arm can accurately track the planned trajectories and successfully avoid obstacles, confirming the feasibility and deployability of the proposed CC-AVOA framework under standard industrial execution conditions. It should be noted that the current validation focuses on electrically actuated industrial manipulators with conventional drive systems. Different actuator technologies, such as harmonic drives, series elastic actuators, and hydraulic actuation systems, exhibit distinct dynamic characteristics and constraint profiles. While the core CC-AVOA planning framework remains applicable at the motion planning level, extending it to such systems requires appropriate actuator-specific constraint modeling, which is identified as an important direction for future research. Future work will focus on extending the CC-AVOA framework to multi-objective path planning scenarios, incorporating posture-cooperative planning and wrist joint protection mechanisms. In addition, the framework will be further developed for joint-space trajectory optimization, with particular emphasis on coordinated optimization of joint velocity and acceleration profiles under obstacle-avoidance constraints, thereby enhancing motion smoothness and dynamic feasibility in practical industrial applications.