Next Article in Journal
Detecting SPIT Attacks in VoIP Networks Using Convolutional Autoencoders: A Deep Learning Approach
Next Article in Special Issue
Machine Learning-Based Shoveling Trajectory Optimization of Wheel Loader for Fuel Consumption Reduction
Previous Article in Journal
Cataclastic Characteristics and Formation Mechanism of Dolomite Rock Mass in Yunnan, China
Previous Article in Special Issue
RRT*-Fuzzy Dynamic Window Approach (RRT*-FDWA) for Collision-Free Path Planning
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Real-Time Obstacle Avoidance Motion Planning of Industrial Robotic Arm Based on Artificial Potential Field Method in Joint Space

School of Mechanical Science and Engineering, Huazhong University of Science and Technology, Wuhan 430074, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2023, 13(12), 6973; https://doi.org/10.3390/app13126973
Submission received: 7 May 2023 / Revised: 4 June 2023 / Accepted: 7 June 2023 / Published: 9 June 2023
(This article belongs to the Special Issue Advances in Robot Path Planning, Volume II)

Abstract

:
The artificial potential field method is a highly popular obstacle avoidance algorithm which is widely used in the field of industrial robotics due to its high efficiency. However, the traditional artificial potential field method has poor real-time performance, making it less suitable for modern factory work patterns, and it is difficult to handle situations when the robotic arm encounters singular configurations. In this paper, we propose an improved artificial potential field method in joint space, which effectively improves the real-time performance of the algorithm, and still performs well when the robotic arm falls into a singular configuration. This method solves the gradient of the repulsive potential field in advance by defining the shortest distance from each joint of the robotic arm to the obstacle, and only needs to calculate potential field function once per cycle, which significantly reduces the calculation time. In addition, when a robotic arm falls into a local minimum position in potential field, the algorithm adds a virtual obstacle to make it leave the position, while this virtual obstacle does not require additional input information. Experimental results show that the algorithm obtains short movement paths and requires very little computing time in the face of different obstacles.

1. Introduction

The utilization of robotic manipulators enhances the efficiency and automation of industrial manufacturing processes. In the 3c industry (computer, communication, consumer electronics), rapidly updated products and complex production patterns require highly flexible robotic arms to complete tasks. In the process of performing the task, the robotic arm may collide with obstacles, so a real-time obstacle avoidance algorithm is needed to control the robotic arm [1,2,3,4,5,6].
The obstacle avoidance algorithm is widely studied in the field of robot motion planning, and it is a computational method to find the path from the starting point to the target point without colliding with obstacles when the robotic manipulator is working in an environment with obstacles. At present, researchers have proposed various obstacle-avoidance algorithms, such as genetic algorithm, rapidly exploring random tree (RRT), and probabilistic roadmap (PRM). However, they all have limitations in practical applications [7].
The RRT algorithm begins by selecting the starting point as the root node and proceeds to generate a randomly expanded tree structure by iteratively sampling and adding leaf nodes, and the shortest path from the starting point along the leaf node to the target position is the obstacle avoidance path. Nevertheless, the calculation speed of RRT is slow, and the smoothness of the trajectory obtained by this algorithm is unsatisfactory, which makes the manipulator shake easily [8]. The genetic algorithm finds an intermediate point with position and velocity information, and connects the starting position to the intermediate point and the intermediate point to the target position through two polynomial paths. The two paths are concatenated to obtain an obstacle avoidance path. Although the genetic algorithm can obtain a smooth obstacle avoidance trajectory, the computational efficiency is very low [9,10]. The PRM algorithm establishes a complete undirected graph by sampling and collision detection, and then obtains a feasible obstacle avoidance path through a graph search algorithm (such as the A* algorithm). However, the process of establishing the map using the PRM algorithm is complex and time-consuming. Moreover, the connection between two nodes in the undirected graph does not take into account the robot’s motion model [11,12]. Although the above algorithms can obtain obstacle avoidance trajectories, their real-time performance is weaker than the artificial potential field method. This paper only discusses the artificial potential field method.
The artificial potential field (APF) method is a widely recognized motion planning strategy in the field of robotics. In 1986, Oussama Khatib first proposed the artificial potential field method (APF) for the motion planning of robots [13]. The APF method extensively borrows the concept of potential fields from physics and transforms the path planning problem of robots or moving objects into a problem of searching for the optimal path in a virtual potential field. The core idea is to consider the target location as an attractive source and obstacles or infeasible areas as repulsive sources. High potential fields are assigned around obstacles, while low potential fields are assigned around the target location. By calculating the forces and directions, the APF guides the robot or object to move along the direction of decreasing potential energy, thereby achieving the goal of avoiding obstacles and reaching the target location.
The APF method is characterized by its simplicity, intuitiveness, ease of implementation, and real-time capabilities. As a result, it has been widely applied in the industrial field. For example, in automated warehousing systems, robots utilize the APF method to navigate around obstacles and find the shortest path based on the layout and obstacle positions within the warehouse. This potential field guidance enables them to efficiently and swiftly accomplish tasks such as cargo handling [14,15]. In the field of autonomous driving, the APF method establishes a potential field within the road network. It considers other vehicles, pedestrians and obstacles as repulsive sources while regarding the target destination as an attractive source. This enables vehicles to navigate to their destination safely and smoothly [16,17]. In multi-agent cooperation, the APF method guides robots to avoid collisions and collaboratively accomplish complex production tasks. It achieves this by considering robots and target positions as attractive sources, and other robots as repulsive sources [18,19]. These application cases highlight the significant role of the APF method in achieving efficient, safe, and flexible industrial operations.
The coordinate systems of the APF method can be divided into two categories: Cartesian space and joint space. If attraction and repulsion forces are calculated in Cartesian space, the coordinate system for this method is the Cartesian space. If attraction and repulsion forces are calculated in joint space, the coordinate system for this method is the joint space.
In studies based on Cartesian space, Hui Zhang et al. proposed an obstacle avoidance strategy for the dual-arm robot by improving the potential field into a velocity field [20]. Sun-Oh Park et al. proposed a numerical method based on a Jacobian matrix to solve the obstacle avoidance problem of a redundant robotic arm [21]. All the above obstacle avoidance strategies in Cartesian space need to be mapped to joint space, and the inverse of the Jacobian matrix cannot be solved when the robotic arm falls into a singular configuration. In studies based on joint space, Lufeng Luo et al. uses a sampling method to generate anti-collision path points [22]. Anoush Sepehri et al. used a numerical method to solve the gradient of potential field [23]. All of the above obstacle avoidance strategies in joint space require the multiple calculations of the potential field function, so the real-time performance is low. In Section 3, we introduced these above algorithms and compared them with the algorithm in this paper.
In an intelligent workshop, the robotic arm is required to grip the workpieces on the conveyor belt and move them to the target position without collisions. Due to the uncertain initial position of the workpieces, a real-time obstacle avoidance algorithm is needed. This paper proposes an improved artificial potential field method specifically designed for the aforementioned industrial scenario. The algorithm generates a suitable trajectory for the robotic arm, so that it can start from any specified starting point and reach the target point without colliding with obstacles in the process. We propose a way to calculate the shortest distance from the obstacle to the joint of the robotic arm, whereby an analytic formula for the gradient of repulsive potential field can be solved in advance. In addition, we propose a way to make the robotic arm jump out of the local minimum.
The contributions of this study are novel and unique in various aspects. (1) Compared with the APF method in Cartesian space, this algorithm does not need to calculate the inverse of the Jacobian matrix. (2) Compared with others’ studies on the APF method in joint space, this algorithm only needs to calculate the potential field function once during each cycle. Therefore, the algorithm has a very high real-time performance. (3) In addition, the algorithm provides an effective way to avoid the robotic arm falling into the local optimum by introducing a virtual obstacle, which does not need additional information.
The subsequent sections of this paper are structured as follows: in Section 2, the D-H parameters and kinematic model of the robot are presented. Section 3 describes the principle and flow of the algorithm, which is the focus of this paper. In Section 4, the simulations and experiments are presented. Section 5 discusses the advantages and disadvantages of the algorithm proposed in this paper compared to other algorithms. Section 6 summarizes the conclusions.

2. Kinematics Model of n-DOF Robot

It is firstly necessary to establish the kinematics model of the robotic manipulator to prevent collision.
To describe the structure and coordinate system of robot, we used 1-n to represent each joint of the manipulator, and x1y1z1-xnynzn to represent the coordinate systems of each link. We used the modified D-H parameter method to establish the kinematics model of the robotic manipulator. Equation (1) describes the relationship between any two adjacent joints.
T i 1 i = R o t x i 1 α i 1 × T r a n s x i 1 a i 1 × R o t z i θ i × T r a n s z i d i = C θ i S θ i C α i 1 S θ i S α i 1 0 S θ i C θ i C α i 1 C θ i S α i 1 0 0 S α i 1 C α i 1 0 a i 1 S α i 1 d i C α i 1 d i 1
where θ i represents the angle of rotation of the i-th joint, S θ i = s i n θ i , C θ i = c o s θ i , and T i 1 i ,   i = 1,2 , , n is the homogeneous transformation matrix built from D-H parameters. If the D-H parameters of the n-DOF robot are known, the homogeneous transformation matrix of each link can be obtained by substituting these parameters into Equation (1), so that the coordinate system transformation from the base to the end of the manipulator can be expressed as Equation (2):
T n 0 = T 1 0 × T × T 3 2 × × T n n 1 2 1
T n 0 represents the position and orientation of the end-effector in Cartesian space, and it can be expressed as (3):
T n 0 = n x n y n z 0 o x o y o z 0 a x a y a z 0 p x p y p z 1
where n, o, a denote the orientation and p denotes the position. Our industrial background involves a robotic arm gripping objects on a conveyor belt in workshops and moving them to the end position. In order to maintain a stable grip and prevent object dropping, the robotic arm’s end-effector should predominantly move along the z axis of Cartesian space when approaching and placing the objects [24]. According to the requirements of the industrial task, the positions and orientations of both the starting point and the endpoint of the task are known. The Cartesian coordinates of the task starting point and goal point can be mapped to joint space by inverse kinematics.
As evidenced from (1) and (2), the position of joint i depends on a series of variables related to joint angles θ i ,   i = 1 , , n , with these variables ranging from θ 1 to θ i 1 , so the position of joint i can be expressed as x ( θ ) , y ( θ ) , z ( θ ) .

3. Improved Artificial Potential Field Method Based on Joint Space

3.1. Traditional Artificial Potential Field Algorithm

In APF, the robotic arm is subjected to two forces when moving to the target point. One force is the attractive force that pulls the robot towards the target position, while the other force is the repulsive force exerted by obstacles on the robot. Under the combined force of these two forces, the robotic arm can quickly reach the target position without colliding with obstacles in this process. The force analysis of the robotic arm in the potential field is shown in Figure 1. The force on each joint and link of the robotic arm is shown in Figure 2.
F r e p represents the repulsive force; F a t t represents the attractive force; and F n is the combined force of the two forces, which makes the manipulator reach the target position.
The attraction field produced by F a t t can be obtained by Equation (4):
U a t t θ 1 , , θ n = 1 2 μ d 2 q , q g o a l
where U a t t θ 1 , , θ n is the attraction field, μ is the correction coefficient of the attractive potential field, q represents the current position configuration of the robot, q g o a l represents the position configuration of the robot when reaching the target position, and d q , q g o a l is the distance between the robot and the target position.
The repulsive potential field produced by F r e p can be obtained by Equation (5):
U r e p θ 1 , , θ n = 1 2 k 1 d q , q o b s 1 d 0 2 , d q , q o b s d 0 0 , d q , q o b s > d 0
where U r e p θ 1 , , θ n is the repulsive potential field, k is the correction coefficient of the repulsion potential field, q o b s represents the position configuration of the robot when colliding with an obstacle, d q , q o b s is the real-time distance between the robotic arm and the obstacle, and d 0 represents the influence radius of the obstacle. When d q , q o b s > d 0 , the repulsion field will not affect the movement of the robot.
The total potential energy function can be expressed as Equation (6):
U θ 1 , , θ n = U a t t θ 1 , , θ n + U r e p θ 1 , , θ n

3.2. The Gradient of the Potential Field Function

The potential energy function is only dependent on joint angles θ 1 , , θ n for a robotic arm. We use the gradient descent method to minimize the potential energy function and determine a set of angles so that the robotic arm can reach the target position in the direction of the fastest potential energy descent without a collision with obstacles.
The attraction F a t t is the negative of the gradient of the attraction potential field U a t t , and it can be expressed as (7):
F a t t = U a t t θ 1 , , θ n = μ d q , q g o a l d ( q , q g o a l )
q is the current position configuration of the robot, and q g o a l is the position configuration of the robot when reaching the goal position. If the manipulator is entirely composed of revolute joints, q can be assumed to be θ 1 , , θ n , and q g o a l can be assumed to be θ 1 , , θ n . Then, d q , q g o a l can be expressed as (8):
d q , q g o a l = i = 1 n θ i θ i 2
If the manipulator comprises both prismatic joints (from joint 1 to joint j) and revolute joints (from joint j + 1 to joint n), in this case, q can be assumed to be d 1 , , d j , θ j + 1 , , θ n , qgoal can be assumed to be d 1 , , d j , θ j + 1 , , θ n , and we assign a weight ω 1 to the prismatic joint and a weight ω 2 to the revolute joint to eliminate the units of nonhomogeneous form. Then, d q , q g o a l can be expressed as (9):
d q , q g o a l = ω 1 × i = 1 j d i d i 2 + ω 2 × i = j + 1 n θ i θ i 2
The repulsive force F r e p is the negative of the gradient of the repulsive potential field U r e p can be expressed as (10):
F r e p = U r e p θ 1 , , θ n = k 1 d q , q o b s 1 d 0 1 d 2 ( q , q o b s ) d q , q o b s , d q , q o b s d 0 0 , d q , q o b s > d 0
We use the gradient descent to minimize the potential energy function in Equation (6). Equation (11) presents the generalized formula utilized for the sth iteration of gradient descent. and Equation (12) shows how the learning rate λ is calculated. q s represents the position configuration of the robot arm at the sth cycle.
q s = q s 1 λ × U θ 1 , , θ n
λ = ϵ 1 + ϵ 2 × d q , q g o a l + ϵ 3 × d q , q o b s
The learning rate λ is dynamic, and it depends on the distance between the end-effector and goal point and the distance between the joints of robot and obstacle. ϵ 1 , ϵ 2 , ϵ 3 are positive constants. ϵ 1 specifies the basic learning rate and ϵ 2 , ϵ 3 specify the sensitivity to the position of manipulator. As the end-effector approaches the goal point and the joint of the robot approaches the obstacle, the learning rate decreases. This is performed to avoid collision with obstacles and reach the goal point more accurately. If faster algorithm execution is desired, the values of ϵ 1 , ϵ 2 , and ϵ 3 can be increased accordingly. In this paper, ϵ 1, ϵ 2 , and ϵ 3 are adjusted within the range of 0.5–1.
The gradient of the attractive potential field is easy to calculate, while the gradient of the repulsive potential field is difficult to calculate, because the shortest distance d q , q o b s between the robotic arm and the obstacle is difficult to calculate. This section focuses on the calculation of the shortest distance d q , q o b s when facing different obstacles.
There are two types of obstacles on the factory assembly line usually, which are obstacles with complex shapes and obstacles with regular shapes. The obstacle can be simulated using the ball envelope method [25], as shown in Figure 3 and Figure 4.
The parameters describing the obstacle are a , b , c , r , where a, b, c represent the spatial location coordinates of the obstacle and r represents the radius of the ball envelope obstacle.
For an obstacle with a complex shape, it can be enveloped by a single sphere. According to the conclusion of Section 2, the position configuration coordinates of q are determined by a series variable of the joint angle, and can be solved by kinematics. Therefore, the coordinates of q can be expressed as q : { x ( θ ) , y ( θ ) , z ( θ ) } . Then, the shortest distance between the joint of the robot and the obstacle can be expressed as (13):
d q , q o b s = x ( θ ) a 2 + y ( θ ) b 2 + z ( θ ) c 2 r 1 r 2
where r1 denotes the radius of the enveloping obstacle sphere and r2 denotes the thickness of the joint.
For an obstacle with a regular shape, it can be enveloped by a series of spheres whose coordinate parameters are denoted by a i , b i , c i , r i . The distance between the joint and the nearest sphere is the shortest distance d ( q , q o b s ) between the joint and the obstacle with a regular shape. In order to make the motion of the robotic arm smooth, the manipulator receives repulsive forces from the two sources, one is the nearest ball, and the other is the ball adjacent to the nearest ball.
On the left side of Figure 5, ball 2 is closest to the joint, and the robotic arm is subject to the repulsive force of ball 2 and the adjacent ball 1. When the robotic arm moves to the next state, as shown in the right side of Figure 5, ball 3 is closest to the joint and the robot is subject to the repulsive force of ball 3 and the adjacent ball 2.
The derivative of Equation (13) can lead to Equation (14):
d q , q o b s = x a x θ θ + y b y θ θ + z c z θ θ x a 2 + y b 2 + z c 2
The analytic formula of the gradient of the repulsive potential field U r e p can be obtained by substituting Equations (13) and (14) into Equation (10), and it is determined by the series variable of the joint angle. This algorithm has a very high real-time performance because it only needs to calculate the potential field function once per cycle.

3.3. The Virtual Obstacle

Sometimes, the robotic arm has not reached the target, but the resultant force is zero. At this time, the robotic arm falls into the local minimum state, and it can be expressed as (15):
U θ 1 , , θ n = F a t t + F r e p = 0
We make the robotic arm jump out of the local minimum state by adding a virtual obstacle. In Figure 6, we treat the center of the ball which envelops the obstacle as a virtual obstacle, and q1 is the position configuration of the robot when colliding with the center of the ball. The position coordinates of this virtual obstacle come from the obstacle, so there is no need to introduce additional information. F r e p _ v i r is the repulsive force generated by q1 when the robot is trapped in a local minimum state, and it is calculated as shown in (16) and (17).
F r e p _ v i r = k 1 d q , q 1 1 d 0 1 d 2 q , q 1 d q , q 1
d q , q 1 = x θ a 2 + y θ b 2 + z θ c 2
To ensure successful obstacle avoidance, the repulsion coefficient k of the virtual obstacle is set to 1–103 times the general obstacle, and the influence radius of the virtual obstacle is set as 1.5–3 times that of general obstacles [26].

3.4. Joint Angle Constraints

Typically, each joint of a robotic arm has angle limitations. To ensure that the joint angles of the robotic arm do not exceed their respective limits during obstacle avoidance, the algorithm proposed in this paper must satisfy the following requirements.
Taking an n-degree-of-freedom robotic arm as an example, we assume that the joint angle limits for each joint of the robotic arm are in the range of [ θ i _ m i n , θ i _ m a x ].
Solution 1: In the first step of the algorithm, the initial and target positions of the robotic arm can be transformed from Cartesian space to joint space using inverse kinematics. q s t a r t can be assumed to be θ 1 , , θ n and q g o a l can be assumed to be θ 1 , , θ n . Due to the existence of multiple solutions in inverse kinematics, it is necessary to select an appropriate solution in this step, ensuring that θ i _ m i n < θ i < θ i _ m a x and θ i _ m i n < θ i < θ i _ m a x .
Solution 2: The algorithm imposes limitations on the magnitude of attraction Fatt and repulsion forces Frep during the computation (such as F a t t 0.1 , F r e p 0.1 ). This serves to prevent the joint angles from exceeding the constraint range.
Solution 3: During obstacle avoidance, it is possible that the strong repulsive force from an obstacle may cause one of the joint angles of the robotic arm to exceed the specified limit. In the case depicted in Figure 7, we can appropriately reduce the repulsive force by adjusting the repulsion coefficient k. This allows the robotic arm to complete the obstacle avoidance task while ensuring that the joint angles remain within the allowed range.

3.5. Algorithm Comparison

The flowchart of the artificial potential field algorithm in joint space is shown in Figure 8, and the pseudocode is shown in Algorithm 1. The values of ε 1 , ε 2 , and ε 3 can be adjusted appropriately according to the requirements. It can be seen that each iteration only requires the calculation of the potential field function once from the algorithm flowchart. The configuration at the starting position and the target position are obtained by inverse kinematics. In order to obtain a smooth obstacle avoidance trajectory, the values of F r e p and F r e p _ v i r are limited to less than ε 3 .
Algorithm 1 The pseudocode of the algorithm.
Algorithm 1: Improved artificial potential field
1: Set Start position: qstart and Goal position: qgoal
2: q s t a r t = θ 1 , , θ n s t a r t , q g o a l = θ 1 , , θ n g o a l by inverse kinematics
3: While d ( q , q g o a l ) > ε 1  %Determine whether the target point has been reached
4: For i = 1 : n %Calculate the attraction and repulsive forces on each joint
5: F a t t ( i ) = μ d q , q g o a l ; d q , q o b s = x ( θ ) a 2 + y ( θ ) b 2 + z ( θ ) c 2 r 1 r 2
6: F r e p ( i ) = k 1 d q , q o b s 1 d 0 1 d 2 ( q , q o b s ) d q , q o b s , d q , q o b s d 0 0 , d q , q o b s > d 0
7:  if F r e p > ε 3   F r e p = ε 3 end %Ensure smooth trajectory
8: F a t t = s u m ( F a t t ( i ) ), F r e p = s u m ( F r e p ( i ) ) end
9:   U ( θ 1 , , θ n ) = F a t t + F r e p
10:    if U ( θ 1 , , θ n ) < ε 2  %Determine whether the robot falls into local optimum
11:     d q , q 1 = x ( θ ) a 2 + y ( θ ) b 2 + z ( θ ) c 2
12:    F r e p _ v i r = k 1 d q , q 1 1 d 0 1 d 2 q , q 1 d q , q 1  %adding a virtual obstacle
13:    U ( θ 1 , , θ 6 ) = F a t t + F r e p + F v i r _ r e p end
14: λ = ϵ 1 + ϵ 2 × d q , q g o a l + ϵ 3 × d q , q o b s  %Determine iteration step size
15: q s = q s 1 λ × U θ 1 , , θ n  %Update joint angles using gradient descent method
16: end

3.5.1. Comparison with APF Algorithm in Cartesian Space

This type of method [20] calculates repulsion and attraction in Cartesian space, and maps the resultant force from Cartesian space to joint space using the Jacobian matrix. The process of this type of method is as Algorithm 2 follows:
Algorithm 2: APF in Cartesian space
STEP1: Calculate the coordinates of each joint using kinematics
STEP2: Calculate attraction Fa and repulsive forces Fr in the Cartesian space, and convert them into the velocity  V = [ v x , v y , v z ]  of the end-effector
STEP3: Calculate the Jacobian matrix  J ( q ) and its inverse  J 1 ( q )
STEP4: Converting velocity V into joint space using Jacobian matrix  q ˙ = J 1 ( q ) V
STEP5:  q s + 1 = q s + h × q ˙  %h is the iteration step size
The coordinate system of this method is constantly transformed between Cartesian space and joint space, and this method cannot solve the inverse matrix of the Jacobian matrix when the robotic arm falls into a singular configuration ( J ( θ ) = 0 ). Because the algorithm in this paper is directly in joint space so that it does not require STEP3 and STEP4. It has much higher real-time performance and efficiency than the APF algorithm in Cartesian space.

3.5.2. Comparison with APF Algorithm Using a Sampling Method

This type of methods [22] uses a sampling method to calculate the fastest decreasing direction of the potential field function. Its process is as Algorithm 3 follows:
Algorithm 3: APF using a sampling method
STEP1: Each joint angle  θ i  has three variations in the next moment
For example:  θ 1 θ 1 h , θ 1 , θ 1 + h  %h is the iteration step size
STEP2: Calculate all cases of U ( θ )  and find the lowest value of  U ( θ )
% θ = [ θ 1 , θ 2 , θ 3 , , θ n ] The joint angle  θ  changes to  θ  along the negative gradient direction of the potential field function.
STEP3: Update joint angle from  θ  to  θ
This type of method needs to calculate the potential field function 3 n times in each cycle, while our algorithm only needs to calculate the potential field function once in each cycle. Thus, the algorithm in this paper has a higher real-time performance.

3.5.3. Comparison with APF Algorithm Using a Numerical Method

This type of method [23] uses the Euler method to calculate the gradient of the potential field function, as shown in Equations (18) and (19):
U ( θ 1 , θ n ) = ( U θ 1 , , U θ n )
U θ i = U ( θ i + h , θ n ) U ( θ i h , θ n ) 2 h
h is the iteration step size. This method requires calculating the potential field function twice to obtain the gradient direction of a joint angle, and each cycle requires calculating the gradient of six joint angles. Therefore, the method requires 2n calculations of the potential field function per cycle, while our algorithm only needs to calculate the potential field function once in each cycle. Thus, the algorithm in this paper has a higher real-time performance.

4. Experiment and Result

In this paper, the ROCR6 is our research object. ROCR6 is a six-axis robotic arm developed by a Chinese company, Si Valley. Figure 9 shows the structure and coordinate system of the robot, and Table 1 shows the modified D-H parameters of the 6-DOF robot.
We performed kinematic simulations in Simscape in Matlab, and these simulations were divided into two cases, namely obstacle avoidance for a sphere and obstacle avoidance for a rectangular beam. To demonstrate the real-time capability of our algorithm in this paper, we compared it with the algorithms discussed in Section 3.5. Additionally, we compared it with the genetic algorithm to showcase the performance of the results obtained by our algorithm.

4.1. The Obstacle Avoidance for a Sphere

Table 2 shows the task information and the parameter details of the spherical obstacle. The motion process of the robotic arm using the APF algorithm is shown in Figure 10, where the red trajectory represents the running trajectory of the middle joint and end-effector. The change in each joint angle using the improved APF algorithm is shown in Figure 11, and the change in each joint angle using the genetic algorithm is shown in Figure 12, and their operation indexes are shown in Table 3. Table 4 compares the running time of our algorithm with each of the algorithms in Section 3.5.

4.2. The Obstacle Avoidance for a Rectangular Beam

Table 5 shows the parameter details of the rectangular beam. The motion process of the robotic arm using the APF algorithm is shown in Figure 13, where magenta trajectory represents the running trajectory of the middle joint and end-effector. The change of each joint angle using the improved APF algorithm is shown in Figure 14, the change of each joint angle using genetic algorithm is shown in Figure 15, and their operation indexes are shown in Table 6. Table 7 shows the running time of each algorithm.

4.3. Experimentation in the Real World

The improved APF algorithm has now been tested in the real world for the rectangular beam obstacle in Section 4.2. Figure 16 shows each joint of the real robotic arm and the obstacle. Figure 17 shows the experimental result in the real world, and the robot avoids the obstacle and reaches the target position.

5. Discussions

In smart factories, trajectory planning algorithms require high real-time capability to adapt to complex and dynamic industrial tasks. The algorithm proposed in this paper meets this requirement by demonstrating an excellent real-time performance. As evident in Table 4 and Table 7, the improved artificial potential field method presented in this paper outperforms other APF methods in terms of real-time performance, as it can complete trajectory planning tasks within a mere 0.4 s.
The algorithm should strive to compute excellent trajectories, as excellent trajectories can save the energy consumed by the robotic arm, reduce the impacts during motion, and enhance the operational efficiency. From Table 4 and Table 7, it can be observed that the algorithm presented in this paper exhibits smaller joint angle variations compared with the genetic algorithm. This indicates that using the algorithm proposed in this paper can reduce the energy consumption during the operation of the robotic arm. However, the algorithm proposed in this paper still has some drawbacks. In comparison to the genetic algorithm, this algorithm may cause the robotic arm’s end effector to move slightly further, thereby reducing the efficiency of the robotic arm’s operation. Additionally, the smoothness of the paths obtained by this algorithm is lower than that of the genetic algorithm, which may result in a greater impact on the robotic arm. Lastly, taking the rectangular beam obstacle in Section 4.2 as a case study, we conducted real-world testing using the algorithm presented in this paper. It can be observed that the robotic arm can effectively avoid obstacles.

6. Conclusions

Robotic arms are widely used in factory assembly lines. A real-time obstacle avoidance algorithm that can adapt to changes in the starting position and goal position at any time is needed. In this paper, we propose an improved artificial potential field method in joint space, which can realize the real-time obstacle avoidance of the robotic arm. The experimental results show that the algorithm can achieve good performance under different obstacles. The algorithm completes the computation very quickly, and the performance of the obstacle avoidance trajectory obtained by this algorithm is higher than the trajectory obtained by genetic algorithm. Its main advantages are as follows:
  • The algorithm prevents the transformation of coordinate system from Cartesian space into joint space, and the robotic arm still performs well when it is caught in a singular configuration.
  • The algorithm can solve the gradient expression of repulsive potential field in advance. The potential field function only needs to be calculated once during each iteration, and the calculation efficiency is very fast.
  • The algorithm proposes an effective method to prevent the robotic arm falling into a local minimum state without introducing additional information.
In future work, we will further improve this algorithm to make the motion trajectory smoother. In addition, the algorithm can obtain the angle, velocity, and acceleration information of each joint during operation. We intend to combine this algorithm with dynamics to control robotic arms in the future.

Author Contributions

Y.C.: Conceptualization, Writing—original draft, Data curation, Formal analysis, Validation. L.C.: Writing—Review and editing, Conceptualization, Data curation, Formal analysis, Validation. J.D.: Writing—review and editing, Conceptualization, Data curation, Formal analysis, Validation. Y.L.: Writing—review and editing. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the National Key R&D Program of China, grant number (2019YFB1706501).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Xu, F. Research and Development of Control Technology of Visual Guided Grasping Robot. Master’s Thesis, Jiangnan University, Jiangsu, China, 2014. [Google Scholar]
  2. Ghadge, K.; More, S.; Gaikwad, P.; Chillal, S. Robotic ARM for pick and place application. Int. J. Mech. Eng. Technol. 2018, 9, 125–133. [Google Scholar]
  3. Pal; Raj, A.A.B.; Shinde, S.R. Performance study of different robotic manipulator systems designed for space debris management. In Proceedings of the 2020 5th International Conference on Communication and Electronics Systems (ICCES), Coimbatore, India, 10–12 June 2020; pp. 148–153. [Google Scholar]
  4. Yenorkar, R.; Chaskar, U.M. GUI based pick and place robotic arm for multipurpose industrial applications. In Proceedings of the 2018 Second International Conference on Intelligent Computing and Control Systems (ICICCS), Madurai, India, 14–15 June 2018; pp. 200–203. [Google Scholar]
  5. Grunwald, G.; Schreiber, G.; Albu-Schaffer, A.; Hirzinger, G. Touch: The direct type of human interaction with a redundant service robot. In Proceedings of the 10th IEEE International Workshop on Robot and Human Interactive Communication ROMAN, Paris, France, 18–21 September 2001; pp. 347–352. [Google Scholar]
  6. Nuchkrua, T.; Chen, S.-L. Precision contouring control of five degree of freedom robot manipulators with uncertainty. Int. J. Adv. Robot. Syst. 2017, 14, 1729881416682703. [Google Scholar] [CrossRef] [Green Version]
  7. Tang, J.; Liu, G.; Pan, Q. A Review on Representative Swarm Intelligence Algorithms for Solving Optimization Problems: Applications and Trends. IEEE/CAA J. Autom. Sin. 2021, 8, 1627–1643. [Google Scholar] [CrossRef]
  8. Wang, X.; Li, X.; Guan, Y.; Song, J.; Wang, R. Bidirectional Potential Guided RRT* for Motion Planning. IEEE Access 2019, 7, 95046–95057. [Google Scholar]
  9. Siar, M.V.S.; Fakharian, A. Energy effificiency in the robot arm using genetic algorithm. In Proceedings of the 2018 8th Conference of AI & Robotics and 10th RoboCup Iranopen International Symposium (IRANOPEN), Qazvin, Iran, 10 April 2018; pp. 14–20. [Google Scholar]
  10. Kalra, P.; Mahapatra, P.B.; Aggarwal, D.K. On the solution of multimodal robot inverse kinematic functions using real-coded genetic algorithms. In Proceedings of the IEEE International Conference on Systems, Man and Cybernetics. Conference Theme-System Security and Assurance, Washington, DC, USA, 8 October 2003; Volume 2, pp. 1840–1845. [Google Scholar]
  11. Noohi, E.; Moradi, H.; Parastegari, S.; Ahmadabadi, M.N. Object Manipulation Using Unlimited Rolling Contacts: 2-D Kinematic Modeling and Motion Planning. IEEE Trans. Robot. 2015, 31, 790–797. [Google Scholar] [CrossRef]
  12. Liu, C.; Xie, S.; Sui, X.; Huang, Y.; Ma, X.; Guo, N.; Yang, F. PRM-D* Method for Mobile Robot Path Planning. Sensors 2023, 23, 3512. [Google Scholar] [CrossRef] [PubMed]
  13. Khatib, O. Real-time obstacle avoidance for manipulators and mobile robots. Int. J. Robot. Res. 1986, 5, 90–98. [Google Scholar] [CrossRef]
  14. Yang, X.; Yang, W.; Zhang, H.; Chang, H.; Chen, C.-Y.; Zhang, S. A new method for robot path planning based artifificial potential field. In Proceedings of the IEEE 11th Conference on Industrial Electronics and Applications (ICIEA), Hefei, China, 5–7 June 2016; pp. 1294–1299. [Google Scholar]
  15. Zhu, Q.; Yan, Y.; Xing, Z. Robot path planning based on artifificial potential field approach with simulated annealing. In Proceedings of the 6th International Conference on Intelligent Systems Design and Applications, Jinan, China, 16–18 October 2006; pp. 622–627. [Google Scholar]
  16. Song, J.; Hao, C.; Su, J. Path planning for unmanned surface vehicle based on predictive artifificial potential field. Int. J. Adv. Robot. Syst. 2020, 17, 1729881420918461. [Google Scholar] [CrossRef] [Green Version]
  17. Chiang, H.-T.; Malone, N.; Lesser, K.; Oishi, M.; Tapia, L. Pathguided artifificial potential fifields with stochastic reachable sets for motion planning in highly dynamic environments. In Proceedings of the IEEE International Conference on Robotics and Automatio, Seattle, WA, USA, 26–30 May 2015; pp. 2347–2354. [Google Scholar]
  18. Zhong, X.; Tian, J.; Hu, H.; Peng, X. Hybrid Path Planning Based on Safe A* Algorithm and Adaptive Window Approach for Mobile Robot in Large-Scale Dynamic Environment. J. Intell. Robot. Syst. 2020, 99, 65–77. [Google Scholar] [CrossRef]
  19. Chen, X.; Huang, Z.; Sun, Y.; Zhong, Y.; Gu, R.; Bai, L. Online on-Road Motion Planning Based on Hybrid Potential Field Model for Car-Like Robot. J. Intell. Robot. Syst. 2022, 105, 7. [Google Scholar] [CrossRef] [PubMed]
  20. Zhang, H.; Zhu, Y.; Liu, X.; Xu, X. Analysis of Obstacle Avoidance Strategy for Dual-Arm Robot Based on Speed Field with Improved Artificial Potential Field Algorithm. Electronics 2021, 10, 1850. [Google Scholar] [CrossRef]
  21. Park, S.O.; Lee, M.C.; Kim, J. Trajectory Planning with Collision Avoidance for Redundant Robots Using Jacobian and Artificial Potential Field-based Real-time Inverse Kinematics. Int. J. Control Autom. Syst. 2020, 18, 2095–2107. [Google Scholar] [CrossRef]
  22. Luo, L.; Wen, H.; Lu, Q.; Huang, H.; Chen, W.; Zou, X.; Wang, C. Collision-Free Path-Planning for Six-DOF Serial Harvesting Robot Based on Energy Optimal and Artificial Potential Field. Complexity 2018, 2018, 3563846. [Google Scholar] [CrossRef] [Green Version]
  23. Sepehri, A.; Moghaddam, A.M. A Motion Planning Algorithm for Redundant Manipulators Using Rapidly Exploring Randomized Trees and Artificial Potential Fields. IEEE Access 2021, 9, 26059–26070. [Google Scholar] [CrossRef]
  24. Chen, S. Research on the Technology of Zero Moment Control and Collision Detection of Collaborative Robot. Ph.D. Dissertation, University of Science and Technology of China, Hefei, China, 2018. [Google Scholar]
  25. Cui, S. The Application of Bounding Volume Algorithm in Collision Detection of Medical VR. Master’s Thesis, Qingdao University, Qingdao, China, 2004. [Google Scholar]
  26. Wang, J.; Zhang, G.; Yang, F.; Jing, B. Improved artificial potential field method for robotic arm obstacle avoidance path planning. Comput. Eng. Appl. 2013, 49, 266–270. [Google Scholar]
Figure 1. The force of the robotic arm in the APF.
Figure 1. The force of the robotic arm in the APF.
Applsci 13 06973 g001
Figure 2. Force on each joint and link of the robotic arm.
Figure 2. Force on each joint and link of the robotic arm.
Applsci 13 06973 g002
Figure 3. The shortest distance d ( q , q o b s ) between the point on the joint and an obstacle with a complex shape.
Figure 3. The shortest distance d ( q , q o b s ) between the point on the joint and an obstacle with a complex shape.
Applsci 13 06973 g003
Figure 4. The shortest distance d ( q , q o b s ) between the point on the joint and an obstacle with a regular shape.
Figure 4. The shortest distance d ( q , q o b s ) between the point on the joint and an obstacle with a regular shape.
Applsci 13 06973 g004
Figure 5. The repulsive force on the robotic arm during movement.
Figure 5. The repulsive force on the robotic arm during movement.
Applsci 13 06973 g005
Figure 6. The repulsive force of a virtual obstacle to joint.
Figure 6. The repulsive force of a virtual obstacle to joint.
Applsci 13 06973 g006
Figure 7. Reducing F r e p to prevent the angle of joint i from exceeding the limit range.
Figure 7. Reducing F r e p to prevent the angle of joint i from exceeding the limit range.
Applsci 13 06973 g007
Figure 8. The flowchart of the algorithm.
Figure 8. The flowchart of the algorithm.
Applsci 13 06973 g008
Figure 9. The structure and coordinate system of the robot.
Figure 9. The structure and coordinate system of the robot.
Applsci 13 06973 g009
Figure 10. The motion process of the robotic arm using APF.
Figure 10. The motion process of the robotic arm using APF.
Applsci 13 06973 g010
Figure 11. Change of the joint angle using APF.
Figure 11. Change of the joint angle using APF.
Applsci 13 06973 g011
Figure 12. Change of the joint angle using genetic algorithm.
Figure 12. Change of the joint angle using genetic algorithm.
Applsci 13 06973 g012
Figure 13. The motion process of the robotic arm using APF.
Figure 13. The motion process of the robotic arm using APF.
Applsci 13 06973 g013
Figure 14. Change of the joint angle using APF.
Figure 14. Change of the joint angle using APF.
Applsci 13 06973 g014
Figure 15. Change of the joint angle using genetic algorithm.
Figure 15. Change of the joint angle using genetic algorithm.
Applsci 13 06973 g015
Figure 16. The experiment detail of the real robotic arm.
Figure 16. The experiment detail of the real robotic arm.
Applsci 13 06973 g016
Figure 17. The motion process of the real robotic arm. (a) depicts the motion of the robotic arm from 0 to 1 s. (a) depicts the motion of the robotic arm from 0 to 1 s. (b) depicts the motion of the robotic arm from 1 to 2 s. (c) depicts the motion of the robotic arm from 2 to 3 s. (d) depicts the motion of the robotic arm from 3 to 4 s.
Figure 17. The motion process of the real robotic arm. (a) depicts the motion of the robotic arm from 0 to 1 s. (a) depicts the motion of the robotic arm from 0 to 1 s. (b) depicts the motion of the robotic arm from 1 to 2 s. (c) depicts the motion of the robotic arm from 2 to 3 s. (d) depicts the motion of the robotic arm from 3 to 4 s.
Applsci 13 06973 g017aApplsci 13 06973 g017b
Table 1. Modified D-H parameters of the 6-DOF robot.
Table 1. Modified D-H parameters of the 6-DOF robot.
Joint θ i α i 1 a i 1   ( mm ) d i   ( mm )
1 θ 1 00122.3
2 θ 2 π / 2 π / 2 00
3 θ 3 0−2700
4 θ 4 π / 2 0−253123.3
5 θ 5 π / 2 0207.1
6 θ 6 π / 2 099.1
Table 2. The information of the spherical obstacle and the configuration of the robot.
Table 2. The information of the spherical obstacle and the configuration of the robot.
Spherical Obstacle and RobotInformation
Starting position[590,−131,112] (mm)
The configuration at the starting position 0.0130 , 1.0585 , 0.6853 0.1730,1.5780,1.5578 (rad)
Target position[104,−600,120] (mm)
The configuration at the target position 1.1953 , 1.0796 , 0.6122 0.1210,1.5780,0.3755 (rad)
Obstacle coordinates[250,−300,112] (mm)
Obstacle radius75 mm
Table 3. The performance of algorithms result.
Table 3. The performance of algorithms result.
AlgorithmImproved APFGenetic
Joint angle increment2.9510 (rad)10.8894 (rad)
Path length880.6657 (mm)895.9892 (mm)
Table 4. The run time of algorithms.
Table 4. The run time of algorithms.
AlgorithmRun Time
Improved APF0.3558 (s)
APF in Cartesian space8.8696 (s)
APF using a sampling method260.3108 (s)
APF using a numerical method6.2696 (s)
Table 5. The information of the rectangular beam and the configuration of the robot.
Table 5. The information of the rectangular beam and the configuration of the robot.
Rectangular Beam Obstacle and RobotInformation
Starting position[590,−131,110] (mm)
The configuration at the starting position 0.0130 , 1.0716 , 0.7080 0.2088,1.5780,1.5578 (rad)
Target position[104,−600,160] (mm)
The configuration at the target position 1.1953 , 1.0659 , 0.4804 0.0245,1.5780,0.3755 (rad)
Obstacle coordinates[250,−300,0] (mm)
Obstacle bottom edge60 × 60 (mm)
Obstacle height300 mm
Table 6. The performance of the algorithms.
Table 6. The performance of the algorithms.
AlgorithmImproved APFGenetic
Joint angle increment4.1690 (rad)10.1739 (rad)
Path length1246.6496 (mm)838.3892 (mm)
Table 7. The run time of algorithms.
Table 7. The run time of algorithms.
AlgorithmRun Time
Improved APF0.3912 (s)
APF in Cartesian space9.7521 (s)
APF using a sampling method286.2102 (s)
APF using a numerical method6.8694 (s)
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Chen, Y.; Chen, L.; Ding, J.; Liu, Y. Research on Real-Time Obstacle Avoidance Motion Planning of Industrial Robotic Arm Based on Artificial Potential Field Method in Joint Space. Appl. Sci. 2023, 13, 6973. https://doi.org/10.3390/app13126973

AMA Style

Chen Y, Chen L, Ding J, Liu Y. Research on Real-Time Obstacle Avoidance Motion Planning of Industrial Robotic Arm Based on Artificial Potential Field Method in Joint Space. Applied Sciences. 2023; 13(12):6973. https://doi.org/10.3390/app13126973

Chicago/Turabian Style

Chen, Yu, Liping Chen, Jianwan Ding, and Yanbing Liu. 2023. "Research on Real-Time Obstacle Avoidance Motion Planning of Industrial Robotic Arm Based on Artificial Potential Field Method in Joint Space" Applied Sciences 13, no. 12: 6973. https://doi.org/10.3390/app13126973

APA Style

Chen, Y., Chen, L., Ding, J., & Liu, Y. (2023). Research on Real-Time Obstacle Avoidance Motion Planning of Industrial Robotic Arm Based on Artificial Potential Field Method in Joint Space. Applied Sciences, 13(12), 6973. https://doi.org/10.3390/app13126973

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

Article Metrics

Back to TopTop