Next Article in Journal
Fractional Boundary Element Solution for Nonlinear Nonlocal Thermoelastic Problems of Anisotropic Fibrous Polymer Nanomaterials
Next Article in Special Issue
Description of Mesoscale Static and Fatigue Analysis of 2D Woven Roving Plates with Convex Holes Subjected to Axial Tension
Previous Article in Journal
High-Performance Krawtchouk Polynomials of High Order Based on Multithreading
Previous Article in Special Issue
Minimizing the Number of Distrustful Nodes on the Path of IP Packet Transmission
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Deep-Reinforcement-Learning-Based Motion Planning for a Wide Range of Robotic Structures

Institute of Automation and Computer Science, Brno University of Technology, 61600 Brno, Czech Republic
*
Author to whom correspondence should be addressed.
Computation 2024, 12(6), 116; https://doi.org/10.3390/computation12060116
Submission received: 25 March 2024 / Revised: 30 April 2024 / Accepted: 23 May 2024 / Published: 5 June 2024
(This article belongs to the Special Issue 10th Anniversary of Computation—Computational Engineering)

Abstract

:
The use of robot manipulators in engineering applications and scientific research has significantly increased in recent years. This can be attributed to the rise of technologies such as autonomous robotics and physics-based simulation, along with the utilization of artificial intelligence techniques. The use of these technologies may be limited due to a focus on a specific type of robotic manipulator and a particular solved task, which can hinder modularity and reproducibility in future expansions. This paper presents a method for planning motion across a wide range of robotic structures using deep reinforcement learning (DRL) algorithms to solve the problem of reaching a static or random target within a pre-defined configuration space. The paper addresses the challenge of motion planning in environments under a variety of conditions, including environments with and without the presence of collision objects. It highlights the versatility and potential for future expansion through the integration of OpenAI Gym and the PyBullet physics-based simulator.

1. Introduction

The significance of robot manipulators in engineering applications and scientific research has increased substantially in recent years. This surge can be attributed to the more frequent application of technologies such as autonomous robotics, physics-based simulation, etc. [1,2], within Industry 4.0 [3], along with the utilization of artificial intelligence techniques. As technology continues to advance, the convergence of robotics and artificial intelligence within the concept of Industry 4.0 holds immense promise. This requires a comprehensive exploration and understanding of the transformative potential inherent in these advancements.
The motion planning problem, shown schematically in Figure 1, is a fundamental and challenging research topic in industrial robotics. It involves generating a collision-free path or trajectory for various robotic structures to perform specific tasks while adhering to constraints and avoiding obstacles. The main objective is to determine an efficient path for the robotic manipulator R to move from its initial configuration θ s to the desired final configuration θ f and generate reference inputs for the motion control system. Traditionally, formulations of the motion planning problem for robotic manipulators rely on the concept of configuration space ( C or C-space) [4,5], representing all possible transformations based on the robot’s kinematics model.
The traditional task of planning trajectories for robots with a high number of degrees of freedom (DoF), such as industrial robots (typically four to seven DoFs), has undergone a significant revolution in motion planning with the development of sampling-based algorithms [6,7,8]. Representative examples of these algorithms include Rapidly Exploring Random Trees (RRTs) and Probabilistic Roadmaps (PRMs). Another approach to solving the path planning problem, which was tested in complex scenarios such as a social environment with a human as a dynamic obstacle [9], was developed based on fuzzy logic. The motion planning problem has also been addressed using evolutionary computation techniques, as discussed in the comprehensive review [10]. Such problems were even used to create benchmarking instances for evolutionary computation methods [11,12,13]. Another group of approaches ti solving the motion planning problem involves using reinforcement learning (RL) algorithms [14] to complete partial tasks within a specific area. In contrast to traditional methods, which often rely on pre-defined maps and algorithms, RL has emerged as a groundbreaking paradigm, revolutionizing path planning by allowing autonomous agents to learn and adapt their strategies through experience.
In recent years, the combination of deep neural networks (DNN) [15] and reinforcement learning, termed deep reinforcement learning (DRL) [16], has become a popular choice for end-to-end control in robotics research, where sequential actions are learned directly from raw input observations. This statement is supported by several review articles that address the research problem [17,18,19]. These articles highlight various research gaps that merit further investigation. One of the identified gaps is the lack of versatility of robotic structures used to teach specific skills. In addition, issues related to reliability and accuracy are frequently discussed in the articles. Future research directions include the exploration of safe navigation for robots, where they must autonomously navigate their environment without causing harm to themselves or encountering obstacles within the configuration space.
One of the fundamental areas of research in motion planning that utilizes RL algorithms involves navigating in structured environments with the objective of reaching predetermined [20,21] or randomly positioned targets [22,23,24,25,26]. However, these environments lack the presence of collision objects. Among the most commonly used algorithms for the presented problem are actor–critic model-free algorithms such as the Deep Deterministic Policy Gradient (DDPG) [27], the Twin Delayed Deep Deterministic Policy Gradient (TD3) [28], and the Soft Actor–Critic (SAC) [29], often used with an experience replay buffer [30]. Mobile platforms extended with robotic arms are used in addition to robotic arms to solve problems in this area. The research described in [31] presents the generation of robot base motions for mobile platform systems. However, collision detection within the environment is not considered in the approach presented in the article. Another article describes the use of RL algorithms, specifically DRL, to solve inverse kinematics problems in 7-DoF robotic manipulators [32]. The method employs Products of Exponentials as a forward kinematics computation tool and the Deep Q-Network as an inverse kinematics solver. The article notes a limitation of the proposed method in the inclusion of self-collision detection. Another approach integrates DRL to explore the length-optimal path in Cartesian space and to derive the energy-optimal solution to inverse kinematics [33]. This solution combines a so-called traditional path planner, which includes collision detections, and DRL to find the optimal solution for redundant robotic manipulator. The other one uses the base DRL to avoid collisions with humans in the working space of the robotic arm. The approach described in [34] proposes the safety shield in scenarios with a high probability of a collision.
DRL algorithms are also used in the field of robotics to solve complex tasks, such as grasping, pushing, and sliding objects within the environment. The approach described in [35] presents on-policy and off-policy RL algorithms for object manipulation tasks. The comparison indicates that when obtaining new experience is costly and computation power is not a concern, the off-policy method SAC may be preferable. Conversely, if data collection is less expensive, such as in simulations, the on-policy method Proximal Policy Optimization (PPO) can achieve better results. In another article, as described in [36], an effective approach is presented to use RL for robotic manipulation based on simulated locomotion demonstrations. The proposed approach has been evaluated on 13 tasks using the 7-DoF Fetch robotic arm. One limitation of the method is its inability to avoid potential collisions with objects. On the other hand, the approach described in [37] presents a new automated method for complex object manipulation in environments with obstacles. The method is based on hindsight goal generation and its extensions. Valuable hindsight goals are selected by balancing graph-based diversity and proximity metrics. The results are demonstrated using the Kuka collaborative robotic manipulator with 7-DoF. DRL algorithms are also used as tools in robotics research to enable closed-loop dynamic control for soft robotic manipulators [38]. This adoption of DRL algorithms reflects a wider trend in robotics research, where various construction structures, including conventional “standard” robotic manipulators, low-budget, or even self-made robots, are increasingly being used for control tasks. This trend demonstrates the increasing recognition of the effectiveness of DRL in managing complex control issues across diverse robotic platforms, promoting innovation, and expanding the availability of advanced control methods within the field.
The primary motivation of this paper is to improve the versatility of DRL methods in robotic applications to a wide range of robotic structures, which was identified as one of the major research gaps in contemporary reviews [17,18,19]. Although the use of DRL methods in the field of industrial robotics is growing in popularity, the implementation of these methods on various robotic structures, as well as reaching targets in environments with the presence of collision objects, represents a relatively unexplored area of research. The novelty of the proposed solution lies in the reliability and accuracy of the solution for the safe navigation of a wide range of robotic structures in a predefined environment.
To demonstrate the versatility of the proposed method in this paper, robotic structures that are part of a robotic laboratory Industry 4.0 Cell [39] were used. The laboratory contains a variety of robotic structures, as shown in Figure 2, which represents a set of the most common geometric representations used for experiments in robotic research, that is, an industrial robot ABB IRB 120 [40] with six degrees of freedom, the same robot extended by a linear axis providing seven DoFs, a SCARA robot Epson LS3-B401S [41] with four DoFs, a dual-arm collaborative robot ABB IRB14000 [42] with seven DoFs on each arm, and finally, a collaborative robot Universal Robots UR3 [43] with six DoFs.
The structure of this paper is as follows. Section 2 delves into reinforcement learning methods, providing an overview of the fundamental concept of reinforcement learning. Additionally, it discusses the integration of deep learning techniques into traditional reinforcement learning methods, known as deep reinforcement learning. Section 3 is dedicated to Deep-Reinforcement-Learning-Based planning algorithms, specifically designed for tasks aimed at achieving randomly generated targets within a predefined configuration space. Finally, Section 4 summarizes the main findings and insights presented throughout this paper. It also offers reflections on the implications of the study and suggests potential avenues for future research.

2. Fundamental Concept of Reinforcement Learning

Reinforcement learning [14] is an area of machine learning in which an intelligent agent learns how to achieve specific behavior by maximizing rewards from the environment through the actions it chooses to execute, much like a human being, through the trial and error method. A higher reward encourages the agent to choose the selected action in the future, while a lower reward, also known as a penalty, has the opposite effect. The idea is that the agent will learn how to achieve its behavior within the specific environment in an effective method that converges on an optimal solution.
The problem of reinforcement learning is formally defined in terms of optimal control of a Markov Decision Process (MDP). Figure 3 illustrates its basic structure in an iteration loop. A characteristic property of MDPs is that each state is only dependent on the previous state, i.e., a memoryless property where each state contains all the information necessary to predict the next state.
A Markov Decision Process is a discrete-time stochastic control process and can be represented as the tuple (S, A, R, p), where S is the continuous multidimensional state space, and A is the continuous multidimensional action space. The state transition probabilities are defined by the function p : S × S × A [ 0 , 1 ] , which represents the probability density of the next state s S based on the current state s S and action a A .
p ( s s , a ) = P S t + 1 = s S t = s , A t = a
The reward function, defined by R : S × S × A R , represents the immediate reward that the agent receives after the transition from s S to s S using an action a A .
R ( s , a , s ) = E R t S t = s , A t = a , S t + 1 = s
The objective of the process is for the agent to learn optimal behavior, also known as a policy denoted as π = π ( a s ) , which maximizes its discounted expected return. A discount factor γ in the range ( 0 , 1 ] is usually introduced when calculating the long-term reward, resulting in the following expression for the continuous ongoing process:
G t = R t + 1 + γ R t + 2 + γ 2 R t + 3 + = k = 0 γ k R t + 1 + k ,
where γ determines the priority of long-term future rewards.
In the field of reinforcement learning, the value function is a crucial concept that guides decision-making processes. It serves as a quantitative measure of the expected cumulative reward that an agent can anticipate while occupying a specific state or following a particular action. This metric helps the agent assess the desirability of states and actions, facilitating the learning of an optimal policy.
More formally, a state value function can be defined to determine the expected return when following a policy π for a particular state s, with the value function V π ( s ) .
V π ( s ) = E π [ G t S t = s ]
The action value function, which represents the expected discounted return when starting in state s and initially taking action a but then following policy π , can be defined as follows:
Q π ( s , a ) = E π [ G t S t = s , A t = a ] .
The primary goal of the agent in reinforcement learning is to find the optimal policy π * , which is better than or equal to all other policies. This can be achieved by estimating the corresponding optimal functions for the action value function, defined as follows
Q * ( s , a ) = max π Q π ( s , a ) .
The optimal action value function is satisfied by the Bellman equation, a fundamental concept in reinforcement learning. The Bellman optimality equation explains that the value of a state is equal to the expected return when the best action a is taken in that state. The equation for Q * is defined as follows:
Q * ( s , a ) = E [ R t + 1 + γ max a Q * ( s , a ) S t = s , A t = a ] .
The Bellman optimality equation is a fundamental formula in reinforcement learning theory. After finding the optimal action value function Q * ( s , a ) , the optimal policy π * can be followed by selecting the optimal action a * in each state s, defined as
a * ( s ) = argmax a Q * ( s , a ) .
It is important to note that the optimization of the value function is often performed off-policy and can, therefore, utilize experience replay.
The well-known and straightforward algorithm for this type of problem is Q-learning, as described in [44]. The Q-learning algorithm belongs to the category of Temporal Difference (TD) learning [45]. TD learning is a form of a value-based approach in which the value function is optimized by minimizing the TD error, denoted as δ .
δ t = R t + γ max a Q π ( s , a ) Q π ( s t , a t )
The Q-learning update rule for the estimation of Q * ( s t , a t ) becomes an optimization problem described as follows
Q * ( s t , a t ) Q π ( s t , a t ) + α δ t = Q π ( s t , a t ) + α [ R t + γ max a Q π ( s , a ) Q π ( s t , a t ) ] ,
where α [ 0 , 1 ) is the learning rate.
It is important to note that the standard form of Q-learning is inefficient for large environments because it must consider every possible state–action pair to determine the optimal Q * ( s , a ) , for example, by using a tabular approach. To address this inefficiency, a general approximator based on deep neural networks can be used instead of large tables.

2.1. Deep Reinforcement Learning

Deep reinforcement learning [16] is an extension of reinforcement learning (RL) that uses deep neural networks [15] as function approximators for value functions or policies. RL, at its core, involves training agents to make sequential decisions in environments, and DRL enhances this process by employing deep neural networks to handle high-dimensional data.
DRL has significant applications in robotics, especially in addressing challenges related to path planning. In this context, several DRL algorithms, also known as actor–critic model-free RL algorithms, such as the Deep Deterministic Policy Gradient [27], the Twin Delayed Deep Deterministic Policy Gradient [28], and the Soft Actor–Critic [29], often used with an experience replay buffer [30], have proven effective. These algorithms optimize both the policy and the value functions with the overarching goal of maximizing cumulative rewards, enabling them to converge on optimal results. To enhance the learning process, an experience replay buffer is commonly employed to store transitions during interactions with the environment. Figure 4 depicts the actor-critic architecture.
The integration of Deep Reinforcement Learning into robotics and path planning demonstrates its capability to handle complex and high-dimensional data, facilitating the effective learning of various tasks [22,23,24]. In the following sections, the details of the DDPG, TD3, and SAC algorithms are briefly described.

2.1.1. Deep Deterministic Policy Gradient

The Deep Deterministic Policy Gradient (DDPG) [27] is an off-policy reinforcement learning algorithm designed for continuous action spaces that uses a deterministic policy. It utilizes two neural networks: the actor and the critic. The actor network predicts the optimal action to take in a given state, while the critic network evaluates the quality of the actor’s chosen action.
The DDPG algorithm learns the optimal policy and Q-function simultaneously. Initially, it uses the Bellman equation and off-policy memory to learn the Q-function. Subsequently, the algorithm utilizes the acquired Q-function to learn the policy. The primary objective is to determine the optimal action value, denoted as a * , for each state in a continuous control environment, similar to the Q-learning method (see Equation (7)).
The Bellman equation is utilized to estimate the optimal Q-function through a set of artificial neural networks, denoted as Q θ ( s , a ) , where θ represents the network’s parameter. The principle of the DDPG algorithm is to minimize the Mean Squared Bellman Error (MSBE) function defined for the set D of transitions (s, a, R, s , d). The equation for the MSBE function can be described as follows:
L ( θ , D ) = E D [ ( Q θ ( s , a ) ( R t + γ ( 1 d ) max a Q θ ( s , a ) ) 2 ] ,
where d indicates whether the terminal condition is satisfied or not, and the term ( R t + γ ( 1 d ) max a Q θ ( s , a ) ) is called the target.
The problem is that both Q θ and the target depend on the same parameter θ . Due to this dependency, the minimization of the MSBE function becomes unstable. Therefore, another neural network, Q θ targ , referred to as the target network, is used to compute the error function. Since the action space is infinite, it is possible to use another neural network, μ targ , known as the target policy network, to approximate the function max Q θ ( s , a ) . The target networks are then updated using the parameters of the main networks using the Polyak averaging formula [46].
Based on the above information, Equation (11) will be rewritten as follows:
L ( θ , D ) = E D [ ( Q θ ( s , a ) ( R t + γ ( 1 d ) max a Q θ targ ( s , μ targ ( s ) ) ) 2 ] .

2.1.2. Twin Delayed Deep Deterministic Policy Gradient

The Twin Delayed Deep Deterministic Policy Gradient (TD3) [28] is an off-policy reinforcement learning algorithm designed for a continuous action space. It is an extension of the DDPG algorithm that aims to overcome some of its limitations by implementing several significant improvements.
Firstly, the action is selected using so-called target policy smoothing, as follows:
a ( s ) = clip ( μ targ ( s ) + clip ( ϵ , c , c ) , a Low , a High ) ,
where ϵ is a random variable with a normal distribution and c is a hyperparameter.
Secondly, the algorithm uses clipped double Q-learning [47], which involves learning two Q-functions concurrently instead of one and selecting the smaller one to calculate the target term in the Bellman equation. This approach enables TD3 to more effectively capture the uncertainty in the environment and reduce the overestimation of value estimates that may occur in DDPG.
The TD3 algorithm includes two primary networks, denoted as Q θ 0 and Q θ 1 , and two target networks, denoted as Q θ 0 , targ and Q θ 1 , targ . The general form of the MSBE function for the TD3 algorithm is described in Equation (14).
L ( θ i , D ) = E D [ ( Q θ i ( s , a ) ( R t + γ ( 1 d ) min i 0 , 1 Q θ i , targ ( s , μ targ ( s ) ) ) 2 ]

2.1.3. Soft Actor–Critic

The Soft Actor–Critic (SAC) [29] algorithm is an off-policy reinforcement learning algorithm designed for a continuous action space. It differs from DDPG and TD3 in its approach, although it incorporates some techniques from these algorithms, such as the clipped double Q-trick. The most significant aspect of the SAC algorithm is the entropy regularization feature. This algorithm maximizes the expected return and entropy during policy training, eliminating improper convergence.
The concept of entropy, which evaluates the randomness of a variable x using its density function P, can be defined as follows:
H ( P ) = E P [ log P ( x ) ] .
Taking into account the effect of entropy, where the agent receives a bonus reward proportional to the entropy of the policy at the time step, the optimal policy can be defined as follows:
π * = argmax π E π [ t = 0 γ t ( R ( s t , a t , s t + 1 ) + α H ( π ( a t s t ) ) ) ] ,
where α > 0 is a hyperparameter called the trade-off coefficient.
In addition to the optimal policy, two Q-functions, Q θ 0 and Q θ 1 , are optimized by the SAC algorithm. It uses a clipped double Q-learning trick and updates the target networks using Polyak averaging. The MSBE function for the SAC algorithm is described in Equation (17).
L ( θ i , D ) = E D [ ( Q θ i ( s , a ) y ( r , s , d ) ) 2 ] ,
where the target term, denoted y ( r , s , d ) , is expressed as
y ( r , s , d ) = R t + γ ( 1 d ) ( min i 0 , 1 Q θ i , targ ( s , a ) α log π ( a s ) ) ,
where π is the current learned policy and a π . To optimize the policy, the SAC algorithm uses a reparameterization trick to determine the action as follows
a = f θ ( ϵ , s ) ,
where f θ is a deterministic function and ϵ is random noise with normal distribution.

3. Deep-Reinforcement-Learning-Based Motion Planning

The combination of deep neural networks and reinforcement learning, known as deep reinforcement learning, represents a relatively unexplored area of research in robotics and motion planning. The complex approach of learning sequential actions directly from raw input observations, especially in the problem of reaching a static [20,21] or random target [22,23,24,25,26] within the robot configuration space, shows potential in this area. Among the most commonly used algorithms for the presented problem, as described in the previous part, are actor–critic model-free algorithms such as DDPG, TD3, and SAC, often used with experience replay.
In consideration of the research objectives, which prioritize the implementation of a modular approach to DRL-based motion planning solutions across a variety of robotic structures, each algorithm was compared in a specific experiment. The methods highlighted in the above-mentioned literature face challenges related to accuracy, independence from the type of robotic structure, the potential occurrence of self-collision, or collision avoidance in general. The research aims to address these challenges, eliminate shortcomings, and achieve greater versatility.

3.1. Comparison of Actor–Critic Algorithms

The comparison of DRL algorithms was focused mainly on the specific robotic arm Universal Robots UR3, considering that it was part of previous research [20]. The solved problem was divided into two parts (see Figure 5), with both parts focusing on reaching the target in a pre-defined configuration space. The first part, defined by the environment E 1 , was focused on reaching the target within the configuration space without any external collision. The second part, defined by the environment E 2 , was focused on the same problem, but with the presence of a statically positioned external collision object.
In both cases, the task was to move the robotic arm from the initial position to the desired final position within the pre-defined configuration space without collisions, including self-collisions. An effective approach to avoiding collisions was to approximate the individual parts of the robot’s structure, as well as potential external collision objects, using so-called bounding boxes [48,49]. The static objects that form the base of the robot and potential external objects were approximated with Axis-Aligned Bounding Boxes (AABBs), while dynamic objects such as joints were approximated with Oriented Bounding Boxes (OBBs). The movement was executed by generating the trajectory using linear segments with parabolic blends (LSPB). The Levenberg–Marquardt method [50] was used to define the motion using a numerical inverse kinematics approach. The learning process was performed through the integration of OpenAI Gym [51] and PyBullet [52] physics-based simulator.
The observation space consists of the position of the end effector in the current iteration and the desired end effector position. The desired position, known as the target, was randomly generated in each episode to enhance the learning model. The action space consists of the end effector movement command in three-dimensional Euclidean space. The reward function, as a critical part of the learning process, was defined for the E 1 environment as follows:
R i = ( p d p i ) ,
and for the E 2 environment as
R i = ( p d p i + γ O 1 + p O p i ) .
In Equation (20), the E 1 environment was determined by the simple Euclidean distance between the current position of the end effector, denoted as p i , and the desired position of the end effector, denoted as p d . Equation (21) for the E 2 environment contains an extension of the aforementioned Equation (20) with a penalty term related to the collision object. This penalty is defined based on the position of the collision object, denoted as p O ; the current position of the end-effector, denoted as p i ; and by the threshold parameter γ O (empirically set to the value 0.01). This threshold parameter affects the significance of the penalty within the learning process. It is important to note that while the reward function for the E 1 environment adheres to conventional methodologies for the given task, the reward calculation function for the E 2 environment introduces a novel approach.
The learning process is interrupted when the robot encounters an external object or self-collision. Conditions for process interruption include the singularity check, along with evaluating the feasibility of the inverse kinematics solution. Successful completion of the learning episode is achieved when the current end-effector position of the robotic arm aligns closely with the randomly generated target, defined by the desired end-effector position.
The training process, with the parametrization shown in Appendix A, using the DDPG, SAC, and TD3 algorithms, both with and without Hindsight Experience Replay (HER), is illustrated in Figure 6 for environment E 1 and Figure 7 for environment E 2 . The comprehensive results of the evaluation process are described in Table 1 for environment E 1 and Table 2 for environment E 2 . The results underscore the importance of selecting appropriate algorithms based on the characteristics of the environment. Specifically, the TD3 algorithm proved to be effective in environments without external collisions, while the DDPG algorithm was well suited for scenarios featuring statically positioned external collision objects. This strategic approach improved the adaptability of the chosen methods for a diverse range of robotic arms in future applications.

3.2. Application of Selected Algorithms to a Wide Range of Robotic Structures

The application of suitable algorithms for a specific case, obtained from the comprehensive experiments described in the previous section, was used for a wide range of robotic arms in both the E 1 environment, as described in Figure 8, and the E 2 environment, as described in Figure 9. Specifically, the TD3 algorithm was employed in environments without external collisions, while the DDPG algorithm was utilized for scenarios featuring statically positioned external collision objects.
The results of the training process, which was evaluated for specific robot arms, namely ABB IRB 120 with and without an extended linear axis, Epson LS3-B401S, dual-arm collaborative robot ABB IRB14000, and Universal Robots UR3, are presented in Table 3 for environment E 1 and Table 4 for environment E 2 .
To underscore the universality of the proposed method, an additional prediction test was conducted for a portfolio of robotic arms. The results are presented in Table 5 for environment E 1 and Table 6 for environment E 2 . The results clearly demonstrate the high efficiency and universality of the algorithms in each environment across a diverse range of robotic structures.

4. Conclusions

In this paper, the development of a method for planning motion across a diverse range of robotic structures based on innovative algorithms was presented. The combination of deep neural networks and reinforcement learning, known as deep reinforcement learning, was represented as a relatively unexplored area of research in robotics and motion planning, especially in the problem of reaching a static or random target within the robot configuration space. The methods highlighted in the literature review faced challenges related to accuracy, independence from the type of robotic structure, potential occurrences of self-collision, or collision avoidance in general. The proposed method effectively addresses the aforementioned shortcomings and showcases the high efficiency and universality of the algorithms across a diverse range of robotic structures. To substantiate this claim, a comprehensive comparison of actor–critic model-free algorithms was conducted, including Deep Deterministic Policy Gradient, Twin Delayed Deep Deterministic Policy Gradient, and Soft Actor–Critic, both with and without Hindsight Experience Replay. The problem was divided into two parts, with both parts focusing on reaching the target in a pre-defined configuration space. The first part, defined by the environment E 1 , focused on reaching the target within the configuration space without any external collision. The second part, defined by the environment E 2 , focused on the same problem, but with the presence of a statically positioned external collision object. The movement was executed by generating the trajectory using linear segments with parabolic blends. The results underscored the importance of selecting appropriate algorithms based on the characteristics of the environment. Specifically, the TD3 algorithm proved to be effective in environments without external collisions, while the DDPG algorithm was well suited for scenarios featuring statically positioned external collision objects. This strategic approach improved the adaptability of the methods chosen for a diverse range of robotic arms, as applied to the portfolio of presented robotic arms.
It is important to note that in practical scenarios involving real robots, the execution of movements may not always be realized through the LSPB method as demonstrated in the simulation experiments. In practical scenarios, for an individualized approach to robot control, it is necessary to use special methods that enable the robot to read the trajectory profile in real-time or near real-time, instead of the simple target position. These special methods can be, for example, EGM (Externally Guided Motion) for the ABB robot and UR-RTDE (Real-Time Data Exchange) for the UR robot. Otherwise, it is necessary to rely on the trajectory generation methods defined by the manufacturer of the respective robot.

Outlook for Future Research

Future investigations into Deep-Reinforcement-Learning-Based motion planning have the potential to address more complex challenges, including the avoidance of collisions with multiple static or dynamic objects, multi-robot motion planning, human–machine collaboration, planning with energy consumption or path efficiency optimization, intelligent grasping of diverse objects, and in general multi-objective environments for both simulation and real-world applications. One avenue for tackling these challenges involves enhancing DRL algorithms through the integration of multi-agent structures, such as the Multi-Agent Deep Deterministic Policy Gradient [53] or Multi-Agent TD3 [54]. These frameworks offer the potential to optimize collaborative decision-making among multiple agents, thereby improving the efficiency and robustness of motion planning tasks. Another potential research objective is to use a more sophisticated physics-based simulation tool, such as Unity3D or NVIDIA Isaac Sim, instead of the PyBullet tool that was utilized.

Author Contributions

Conceptualization, R.P., J.K. and R.M.; methodology, R.P. and J.K.; investigation, R.P. and J.K.; resources, R.P. and J.K.; writing—original draft preparation, R.P., J.K., R.M. and M.J.; writing—review and editing, R.P., J.K., R.M. and M.J.; software, R.P. and M.J; visualization, R.P. and M.J.; supervision, R.M.; project administration, R.P. and J.K.; funding acquisition, J.K. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the project IGA BUT No. FSI-S-23-8394 “Artificial intelligence methods in engineering tasks”.

Data Availability Statement

The code used in this work is available on the GitHub repository at the following URL: https://github.com/rparak/PyBullet_Industrial_Robotics_Gym (accessed on 25 March 2024).

Conflicts of Interest

The authors declare no conflicts of interest.

Appendix A. Hyperparameters

The appendix presents the hyperparameter structure that was used for the experiments in both the E 1 and E 2 environments. The selection of these hyperparameters was inspired by a comprehensive review detailed in [22].
Table A1. Hyperparameter structure used for experiments in both types of environments.
Table A1. Hyperparameter structure used for experiments in both types of environments.
HyperparametersDescription
Network typeMulti-layer Perceptron (MLP)
Network size3 layers with 256 units each and ReLU non-linearities
OptimizerAdam optimizer [55] with 1 · 10 3 to train both actor and critic
Learning rate0.001
Polyak-averaging coefficient [46]0.95
Action L2 norm coefficient1.0
Observation clipping [ 1 , 1 ]
Action clipping [ 1 , 1 ]
Probability of random actions0.3
Scale of additive Gaussian noise0.2
Replay Buffer size 10 6 transitions
Batch size256
Episode length100
Total timesteps 10 5

References

  1. Uygun, Y. The Fourth Industrial Revolution-Industry 4.0. 2021. Available online: https://ssrn.com/abstract=3909340 (accessed on 5 January 2024).
  2. Erboz, G. How to define industry 4.0: Main pillars of industry 4.0. Manag. Trends Dev. Enterp. Glob. Era 2017, 761, 761–767. [Google Scholar]
  3. Palka, D.; Ciukaj, J. Prospects for development movement in the industry concept 4.0. Multidiscip. Asp. Prod. Eng. 2019, 2, 315–326. [Google Scholar] [CrossRef]
  4. Siciliano, B.; Khatib, O. Springer Handbook of Robotics; Springer: Berlin/Heidelberg, Germany, 2016; pp. 11–33. [Google Scholar]
  5. Siciliano, B.; Sciavicco, L.; Villani, L.; Oriolo, G. Robotics: Modelling, Planning and Control, 1st ed.; Springer Publishing Company, Incorporated: Berlin/Heidelberg, Germany, 2008. [Google Scholar]
  6. Liu, S.; Liu, P. Benchmarking and optimization of robot motion planning with motion planning pipeline. Int. J. Adv. Manuf. Technol. 2022, 118, 949–961. [Google Scholar] [CrossRef]
  7. Xanthidis, M.P.; Esposito, J.M.; Rekleitis, I.; O’Kane, J.M. Analysis of motion planning by sampling in subspaces of progressively increasing dimension. arXiv 2018, arXiv:1802.00328. [Google Scholar]
  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. Tanha, S.D.N.; Dehkordi, S.F.; Korayem, A.H. Control a mobile robot in Social environments by considering human as a moving obstacle. In Proceedings of the 2018 6th RSI International Conference on Robotics and Mechatronics (IcRoM), Tehran, Iran, 23–25 October 2018; pp. 256–260. [Google Scholar] [CrossRef]
  10. Juříček, M.; Parák, R.; Kůdela, J. Evolutionary Computation Techniques for Path Planning Problems in Industrial Robotics: A State-of-the-Art Review. Computation 2023, 11, 245. [Google Scholar] [CrossRef]
  11. Kudela, J.; Juříček, M.; Parák, R. A collection of robotics problems for benchmarking evolutionary computation methods. In Applications of Evolutionary Computation, Proceedings of the International Conference on the Applications of Evolutionary Computation (Part of EvoStar), Brno, Czech Republic, 12–14 April 2023; Springer: Berlin/Heidelberg, Germany, 2023; pp. 364–379. [Google Scholar]
  12. Kudela, J. A critical problem in benchmarking and analysis of evolutionary computation methods. Nat. Mach. Intell. 2022, 4, 1238–1245. [Google Scholar] [CrossRef]
  13. Stripinis, L.; Kudela, J.; Paulavicius, R. Benchmarking Derivative-Free Global Optimization Algorithms Under Limited Dimensions and Large Evaluation Budgets. IEEE Trans. Evol. Comput. 2024. early access. [Google Scholar] [CrossRef]
  14. Sutton, R.S.; Barto, A.G. Reinforcement Learning: An Introduction; MIT Press: Cambridge, MA, USA, 2018. [Google Scholar]
  15. Goodfellow, I.; Bengio, Y.; Courville, A. Deep Learning; MIT Press: Cambridge, MA, USA, 2016. [Google Scholar]
  16. François-Lavet, V.; Henderson, P.; Islam, R.; Bellemare, M.G.; Pineau, J. An introduction to deep reinforcement learning. Found. Trends® Mach. Learn. 2018, 11, 219–354. [Google Scholar] [CrossRef]
  17. Liu, R.; Nageotte, F.; Zanne, P.; de Mathelin, M.; Dresp-Langley, B. Deep reinforcement learning for the control of robotic manipulation: A focussed mini-review. Robotics 2021, 10, 22. [Google Scholar] [CrossRef]
  18. Han, D.; Mulyana, B.; Stankovic, V.; Cheng, S. A survey on deep reinforcement learning algorithms for robotic manipulation. Sensors 2023, 23, 3762. [Google Scholar] [CrossRef]
  19. Elguea-Aguinaco, Í.; Serrano-Muñoz, A.; Chrysostomou, D.; Inziarte-Hidalgo, I.; Bøgh, S.; Arana-Arexolaleiba, N. A review on reinforcement learning for contact-rich robotic manipulation tasks. Robot.-Comput.-Integr. Manuf. 2023, 81, 102517. [Google Scholar] [CrossRef]
  20. Parák, R.; Matoušek, R. Comparison of Multiple Reinforcement Learning and Deep Reinforcement Learning Methods for the Task Aimed at Achieving the Goal. Mendel J. Ser. 2021, 27, 1–8. [Google Scholar] [CrossRef]
  21. Kristensen, C.B.; Sørensen, F.A.; Nielsen, H.B.; Andersen, M.S.; Bendtsen, S.P.; Bøgh, S. Towards a robot simulation framework for e-waste disassembly using reinforcement learning. Procedia Manuf. 2019, 38, 225–232. [Google Scholar] [CrossRef]
  22. Plappert, M.; Andrychowicz, M.; Ray, A.; McGrew, B.; Baker, B.; Powell, G.; Schneider, J.; Tobin, J.; Chociej, M.; Welinder, P.; et al. Multi-goal reinforcement learning: Challenging robotics environments and request for research. arXiv 2018, arXiv:1802.09464. [Google Scholar]
  23. Gallouédec, Q.; Cazin, N.; Dellandréa, E.; Chen, L. panda-gym: Open-source goal-conditioned environments for robotic learning. arXiv 2021, arXiv:2106.13687. [Google Scholar]
  24. Rzayev, A.; Aghaei, V.T. Off-Policy Deep Reinforcement Learning Algorithms for Handling Various Robotic Manipulator Tasks. arXiv 2022, arXiv:2212.05572. [Google Scholar]
  25. Mahmood, A.R.; Korenkevych, D.; Komer, B.J.; Bergstra, J. Setting up a reinforcement learning task with a real-world robot. In Proceedings of the 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 1–5 October 2018; pp. 4635–4640. [Google Scholar]
  26. Franceschetti, A.; Tosello, E.; Castaman, N.; Ghidoni, S. Robotic arm control and task training through deep reinforcement learning. In Intelligent Autonomous Systems 16, Proceedings of the International Conference on Intelligent Autonomous Systems, Singapore, 22–25 June 2021; Springer: Berlin/Heidelberg, Germany, 2021; pp. 532–550. [Google Scholar]
  27. Lillicrap, T.P.; Hunt, J.J.; Pritzel, A.; Heess, N.; Erez, T.; Tassa, Y.; Silver, D.; Wierstra, D. Continuous control with deep reinforcement learning. arXiv 2015, arXiv:1509.02971. [Google Scholar]
  28. Fujimoto, S.; Hoof, H.; Meger, D. Addressing function approximation error in actor–critic methods. In Proceedings of the International Conference on Machine Learning, Stockholm, Sweden, 10–15 July 2018; PMLR: London, UK, 2018; pp. 1587–1596. [Google Scholar]
  29. Haarnoja, T.; Zhou, A.; Abbeel, P.; Levine, S. Soft Actor–Critic: Off-policy maximum entropy deep reinforcement learning with a stochastic actor. In Proceedings of the International Conference on Machine Learning, Stockholm, Sweden, 10–15 July 2018; PMLR: London, UK, 2018; pp. 1861–1870. [Google Scholar]
  30. Andrychowicz, M.; Wolski, F.; Ray, A.; Schneider, J.; Fong, R.; Welinder, P.; McGrew, B.; Tobin, J.; Pieter Abbeel, O.; Zaremba, W. Hindsight experience replay. In Proceedings of the Advances in Neural Information Processing Systems, Long Beach, CA, USA, 4–9 December 2017; Volume 30. [Google Scholar]
  31. Honerkamp, D.; Welschehold, T.; Valada, A. Learning kinematic feasibility for mobile manipulation through deep reinforcement learning. IEEE Robot. Autom. Lett. 2021, 6, 6289–6296. [Google Scholar] [CrossRef]
  32. Malik, A.; Lischuk, Y.; Henderson, T.; Prazenica, R. A deep reinforcement-learning approach for inverse kinematics solution of a high degree of freedom robotic manipulator. Robotics 2022, 11, 44. [Google Scholar] [CrossRef]
  33. Li, X.; Liu, H.; Dong, M. A general framework of motion planning for redundant robot manipulator based on deep reinforcement learning. IEEE Trans. Ind. Inform. 2021, 18, 5253–5263. [Google Scholar] [CrossRef]
  34. Thumm, J.; Althoff, M. Provably safe deep reinforcement learning for robotic manipulation in human environments. In Proceedings of the 2022 International Conference on Robotics and Automation (ICRA), Philadelphia, PA, USA, 23–27 May 2022; pp. 6344–6350. [Google Scholar]
  35. Shahid, A.A.; Piga, D.; Braghin, F.; Roveda, L. Continuous control actions learning and adaptation for robotic manipulation through reinforcement learning. Auton. Robot. 2022, 46, 483–498. [Google Scholar] [CrossRef]
  36. Kilinc, O.; Montana, G. Reinforcement learning for robotic manipulation using simulated locomotion demonstrations. Mach. Learn. 2022, 111, 465–486. [Google Scholar] [CrossRef]
  37. Bing, Z.; Zhou, H.; Li, R.; Su, X.; Morin, F.O.; Huang, K.; Knoll, A. Solving robotic manipulation with sparse reward reinforcement learning via graph-based diversity and proximity. IEEE Trans. Ind. Electron. 2022, 70, 2759–2769. [Google Scholar] [CrossRef]
  38. Centurelli, A.; Arleo, L.; Rizzo, A.; Tolu, S.; Laschi, C.; Falotico, E. Closed-loop dynamic control of a soft manipulator using deep reinforcement learning. IEEE Robot. Autom. Lett. 2022, 7, 4741–4748. [Google Scholar] [CrossRef]
  39. Parák, R.; Matoušek, R.; Lacko, B. I4C—Robotic cell according to the Industry 4.0 concept. Automa 2021, 27, 10–12. [Google Scholar]
  40. ABB Ltd. ABB IRB 120 Product Manual; ABB Ltd.: Zurich, Switzerland, 2022. [Google Scholar]
  41. Seiko Epson Corporation. Industrial Robot: SCARA ROBOT LS-B Series MANUAL; Seiko Epson Corporation: Suwa, Japan, 2024. [Google Scholar]
  42. ABB Ltd. ABB IRB 14000 Product Manual; ABB Ltd.: Zurich, Switzerland, 2022. [Google Scholar]
  43. Universal Robots A/S. User Manual UR3e; Universal Robots A/S: Odense, Denmark, 2024. [Google Scholar]
  44. Dayan, P.; Watkins, C. Q-learning. Mach. Learn. 1992, 8, 279–292. [Google Scholar] [CrossRef]
  45. Tesauro, G. Temporal difference learning and TD-Gammon. Commun. ACM 1995, 38, 58–68. [Google Scholar] [CrossRef]
  46. Polyak, B.T.; Juditsky, A.B. Acceleration of stochastic approximation by averaging. SIAM J. Control. Optim. 1992, 30, 838–855. [Google Scholar] [CrossRef]
  47. Van Hasselt, H.; Guez, A.; Silver, D. Deep reinforcement learning with double q-learning. In Proceedings of the AAAI Conference on Artificial Intelligence, Phoenix, AZ, USA, 12–17 February 2016; Volume 30. [Google Scholar]
  48. Ericson, C. Real-Time Collision Detection; CRC Press: Boca Raton, FL, USA, 2004. [Google Scholar]
  49. Van Den Bergen, G. Collision Detection in Interactive 3D Environments; CRC Press: Boca Raton, FL, USA, 2003. [Google Scholar]
  50. Sugihara, T. Solvability-unconcerned inverse kinematics by the Levenberg–Marquardt method. IEEE Trans. Robot. 2011, 27, 984–991. [Google Scholar] [CrossRef]
  51. Brockman, G.; Cheung, V.; Pettersson, L.; Schneider, J.; Schulman, J.; Tang, J.; Zaremba, W. Openai gym. arXiv 2016, arXiv:1606.01540. [Google Scholar]
  52. Coumans, E.; Bai, Y.P.; PyBullet, A. PyBullet, a Python Module for Physics Simulation for Games, Robotics and Machine Learning. 2016. Available online: https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA (accessed on 5 January 2024).
  53. Li, S.; Wu, Y.; Cui, X.; Dong, H.; Fang, F.; Russell, S. Robust multi-agent reinforcement learning via minimax deep deterministic policy gradient. In Proceedings of the AAAI Conference on Artificial Intelligence, Honolulu, HI, USA, 27 January–1 February 2019; Volume 33, pp. 4213–4220. [Google Scholar]
  54. Zhang, F.; Li, J.; Li, Z. A TD3-based multi-agent deep reinforcement learning method in mixed cooperation-competition environment. Neurocomputing 2020, 411, 206–215. [Google Scholar] [CrossRef]
  55. Kingma, D.P.; Ba, J. Adam: A method for stochastic optimization. In Proceedings of the International Conference on Learning Representations (ICLR)HER, San Diego, CA, USA, 7–9 May 2015; Volume 5, p. 6. [Google Scholar]
Figure 1. A schematic representation of a motion planning problem in two-dimensional space, illustrating an n-link robotic manipulator R within a collision-free configuration space C free with obstacles denoted as O .
Figure 1. A schematic representation of a motion planning problem in two-dimensional space, illustrating an n-link robotic manipulator R within a collision-free configuration space C free with obstacles denoted as O .
Computation 12 00116 g001
Figure 2. An illustration of the robotic structures that are part of the Industry 4.0 Cell (I4C).
Figure 2. An illustration of the robotic structures that are part of the Industry 4.0 Cell (I4C).
Computation 12 00116 g002
Figure 3. The interaction between an agent and the environment in a Markov Decision Process (MDP), adapted from [14].
Figure 3. The interaction between an agent and the environment in a Markov Decision Process (MDP), adapted from [14].
Computation 12 00116 g003
Figure 4. An overview of the actor–critic architecture. The Temporal Difference (TD) error δ t is utilized to adjust both the critic’s action value function Q ( s , a ) and the actor’s policy π ( a s , θ ) , which is parameterized by θ [14,16].
Figure 4. An overview of the actor–critic architecture. The Temporal Difference (TD) error δ t is utilized to adjust both the critic’s action value function Q ( s , a ) and the actor’s policy π ( a s , θ ) , which is parameterized by θ [14,16].
Computation 12 00116 g004
Figure 5. An illustration of both types of environments, E 1 (left) and E 2 (right), that were used in an experiment focused on reaching the target in a pre-defined configuration space C free . The yellow wireframe determines a pre-defined configuration space C free , while the green wireframe delineates the area where the target was randomly generated. The red sphere within the environment E 2 represents an obstacle approximated with Axis-Aligned Bounding Box (AABB), denoted as O A A B B .
Figure 5. An illustration of both types of environments, E 1 (left) and E 2 (right), that were used in an experiment focused on reaching the target in a pre-defined configuration space C free . The yellow wireframe determines a pre-defined configuration space C free , while the green wireframe delineates the area where the target was randomly generated. The red sphere within the environment E 2 represents an obstacle approximated with Axis-Aligned Bounding Box (AABB), denoted as O A A B B .
Computation 12 00116 g005
Figure 6. The training process shows success rates within the environment type E 1 for the DDPG, SAC, and TD3 algorithms (left) and an extension with HER (right).
Figure 6. The training process shows success rates within the environment type E 1 for the DDPG, SAC, and TD3 algorithms (left) and an extension with HER (right).
Computation 12 00116 g006
Figure 7. The training process shows success rates within the environment type E 2 for the DDPG, SAC, and TD3 algorithms (left) and an extension with HER (right).
Figure 7. The training process shows success rates within the environment type E 2 for the DDPG, SAC, and TD3 algorithms (left) and an extension with HER (right).
Computation 12 00116 g007
Figure 8. An illustration of a wide range of robotic structures within the E 1 environment, simulated using a PyBullet physics-based simulator. These structures were used in an experiment that focused on reaching the target in a pre-defined configuration space.
Figure 8. An illustration of a wide range of robotic structures within the E 1 environment, simulated using a PyBullet physics-based simulator. These structures were used in an experiment that focused on reaching the target in a pre-defined configuration space.
Computation 12 00116 g008aComputation 12 00116 g008b
Figure 9. An illustration of a wide range of robotic structures within the E 2 environment, simulated using PyBullet physics-based simulator. These structures were used in an experiment that focused on reaching the target in a pre-defined configuration space.
Figure 9. An illustration of a wide range of robotic structures within the E 2 environment, simulated using PyBullet physics-based simulator. These structures were used in an experiment that focused on reaching the target in a pre-defined configuration space.
Computation 12 00116 g009
Table 1. The table presents experimental results comparing various DRL algorithms within the E 1 environment. The required minimum success rate to meet the specified criteria was set at 0.98.
Table 1. The table presents experimental results comparing various DRL algorithms within the E 1 environment. The required minimum success rate to meet the specified criteria was set at 0.98.
AlgorithmSuccess RatePercentage of Successful TargetsMean Reward per EpisodeMean Episode Length
DDPG0.98–1.095.86%−0.3885.299
DDPG + HER0.98–1.089.83%−0.3875.431
SAC0.98–1.096.52%−0.4085.682
SAC + HER0.98–1.094.85%−0.4075.701
TD30.98–1.096.61%−0.3865.298
TD3 + HER0.98–1.078.73%−0.3955.720
Table 2. The experimental results comparing various DRL algorithms within the E 2 environment. The required minimum success rate to meet the specified criteria was set at 0.8.
Table 2. The experimental results comparing various DRL algorithms within the E 2 environment. The required minimum success rate to meet the specified criteria was set at 0.8.
AlgorithmSuccess RatePercentage of Successful TargetsMean Reward per EpisodeMean Episode Length
DDPG0.8–0.9795.01%−0.7105.866
DDPG + HER0.8–0.9686.72%−0.7115.944
SAC0.8–0.855.048%−0.7095.684
SAC + HER0.8–0.8819.07%−0.7135.844
TD30.8–0.9689.59%−0.7115.901
TD3 + HER0.8–0.9481.99%−0.7186.146
Table 3. The table presents experimental results comparing a wide range of robotic structures using the TD3 algorithm within the E 1 environment. The minimum success rate required to meet the specifications was set at 0.98.
Table 3. The table presents experimental results comparing a wide range of robotic structures using the TD3 algorithm within the E 1 environment. The minimum success rate required to meet the specifications was set at 0.98.
Robot TypeSuccess RatePercentage of Successful TargetsMean Reward per EpisodeMean Episode Length
Universal Robots UR30.98–1.096.61%−0.3865.298
ABB IRB 1200.98–1.084.32%−0.6026.073
ABB IRB 120 Ext.0.98–1.087.65%−0.6376.647
ABB IRB 14000 (L)0.98–1.094.51%−0.2564.593
ABB IRB 14000 (R)0.98–1.091.69%−0.2564.608
Epson LS3-B401S0.98–1.094.39%−0.0642.474
Table 4. The table presents experimental results comparing a wide range of robotic structures using the DDPG algorithm within the E 2 environment. The minimum success rate required to meet the specifications was set at 0.8.
Table 4. The table presents experimental results comparing a wide range of robotic structures using the DDPG algorithm within the E 2 environment. The minimum success rate required to meet the specifications was set at 0.8.
Robot TypeSuccess RatePercentage of Successful TargetsMean Reward per EpisodeMean Episode Length
Universal Robots UR30.8–0.9795.01%−0.7105.866
ABB IRB 1200.8–0.9895.26%−0.8746.609
ABB IRB 120 Ext.0.8–0.9896.83%−1.0318.041
ABB IRB 14,000 (L)0.8–0.9794.85%−0.5035.356
ABB IRB 14,000 (R)0.8–0.9692.14%−0.4995.227
Epson LS3-B401S0.8–0.9998.19%−0.3965.040
Table 5. The table presents experimental results comparing a wide range of robotic structures using the TD3 algorithm within the E 1 environment for one hundred randomly generated targets. The position error is given in meters.
Table 5. The table presents experimental results comparing a wide range of robotic structures using the TD3 algorithm within the E 1 environment for one hundred randomly generated targets. The position error is given in meters.
Robot TypeSuccess RateMean Reward per EpisodeMean Episode LengthMean Absolute Position Error
Universal Robots UR31.0−0.3654.940.0024
ABB IRB 1201.0−0.5015.260.0055
ABB IRB 120 Ext.1.0−0.5025.160.0061
ABB IRB 14,000 (L)1.0−0.2334.210.0024
ABB IRB 14,000 (R)1.0−0.2284.130.0028
Epson LS3-B401S1.0−0.0592.320.0030
Table 6. The table presents experimental results comparing a wide range of robotic structures using the DDPG algorithm within the E 2 environment for one hundred randomly generated targets. The position error is given in meters.
Table 6. The table presents experimental results comparing a wide range of robotic structures using the DDPG algorithm within the E 2 environment for one hundred randomly generated targets. The position error is given in meters.
Robot TypeSuccess RateMean Reward per EpisodeMean Episode LengthMean Absolute Position Error
Universal Robots UR31.0−0.7116.040.0058
ABB IRB 1201.0−0.8596.450.0023
ABB IRB 120 Ext.1.0−0.9456.980.0065
ABB IRB 14,000 (L)1.0−0.4715.150.0040
ABB IRB 14,000 (R)1.0−0.4705.120.0032
Epson LS3-B401S1.0−0.3744.790.0027
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

Parák, R.; Kůdela, J.; Matoušek, R.; Juříček, M. Deep-Reinforcement-Learning-Based Motion Planning for a Wide Range of Robotic Structures. Computation 2024, 12, 116. https://doi.org/10.3390/computation12060116

AMA Style

Parák R, Kůdela J, Matoušek R, Juříček M. Deep-Reinforcement-Learning-Based Motion Planning for a Wide Range of Robotic Structures. Computation. 2024; 12(6):116. https://doi.org/10.3390/computation12060116

Chicago/Turabian Style

Parák, Roman, Jakub Kůdela, Radomil Matoušek, and Martin Juříček. 2024. "Deep-Reinforcement-Learning-Based Motion Planning for a Wide Range of Robotic Structures" Computation 12, no. 6: 116. https://doi.org/10.3390/computation12060116

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