1. Introduction
Engineering problems are, in general, multi-objective ones, where solutions are based on trade-offs of functionality, ergonomic constraints, financial limitations, and technical awareness. The decision-making process in engineering may be very challenging essentially because of the compromises which should be made between possibilities and constraints. There are two main approaches to handle such problems; the first consists of addressing them as a mono-objective problem made by merging the several controversial sub-objectives into a single one using an old mechanism called the weighted sum. The weighted sum aggregates the different objectives of a problem into a single one [
1,
2,
3]. The weighted sum consists of aggregating several mono-objective functions using a moderation coefficient, the weight, which is defined according to the relevance of an objective toward others. The main issue with such a strategy is how to manage those coefficients and how to define the needed aggregation rules. In reality, this approach includes a heuristic aspect, since in reality there are no rules fixing clearly how the coefficients, weights, are attributed. When all objectives obtain the same impact on optimality, we may think about equivalent equal weights, while this is very rare in reality [
3], and arguing the choices of a weighting is far from being a simple issue.
Multi-objective optimization tends to find a trade-off of several controversial mono-objectives satisfying a global optimality for a specific need. In Pareto-based multi-objective optimization, MO, a set of mono-objective solutions are generated, then a selection strategy using the Pareto front is used to merge the objectives and to find the solution satisfying several objectives [
4].
Alternatively, and using the fuzzy or the rough representations of the controversial objectives, a rough or a fuzzy solution representing a possible trade-off may be defined using rough sets and fuzzy sets, which may be also used for the assessment of global optimality based on mono-objectives results [
5].
Pareto multi-objective strategies have been investigated for mechanical system design by Deb et al. since 2005, where authors applied an evolutionary multi-objective optimization to design a leg mechanism based on three objective functions [
6]. In a more generic manner, a multi-objective bees algorithm (MOBA) was investigated to solve three different multi-objective engineering problems: a satellite heat pipe design problem, a space truss design, and the pressure vessel design problem. Results showed evidently that the Pareto-based approach is better than the weighted sum method, essentially for the test bed of mechanical engineering problems [
7].
In industrial robotics, robotized arms are used in a large panel of applications, essentially in mass production and assembly lines, such as car assembly lines [
8]. Robotics arms are also used in food manufacturing, handling operations, and smart logistics chains [
9,
10]. Robotics arms may be considered as a generic tool of any industrial process; at the only condition that a specific end-effector is available or specially added to the arm, such tools may be used for painting or welding operations [
11]. Whatever the industrial application of a robotic arm, a path design is needed. The path design plans the robot motions needed to perform a task [
12]. To perform a task, a robot arm needs to achieve a position with respect to a suitable orientation. Such a criterion is mandatory for handling processes where a specific orientation is needed for the end-effector position to be able to grasp objects. In welding processes, the welding tool should achieve a target point with a specific orientation, making the inverse kinematics problem a real multi-objective one [
11]. In robotics, inverse problems may also be addressed as multi-objective; among them, inverse dynamics and inverse kinematics, IK. IK is a typical multi-objective problem at any time the focus is not limited to the end-effector position.
For inverse kinematics of robotic arms, the weighted sum is commonly used to merge position and orientation objectives of the end-effectors, and even if the proposals are presented as multi-objective, this approach is definitively closer to mono-objective rather than multi-objective. The authors in [
13] proposed a knowledge-based artificial bee, k-ABC, which is an ABC with a compromise between the exploration and exploitation. The k-ABC was applied to solve the inverse kinematics of a 5-degree of freedom, 5-DOF, robotic arm, by merging the error fitness and the orientation into a single mono-objective formulation with application which minimizes the position and the orientation Euclidean distance toward a couple of target values. The proposal showed its effectiveness in drawing a circular path. In [
14], a particle swarm optimization inverse kinematics solver, Ik-PSO, is investigated for the 6-DOF industrial KUKA KR 6 r900, with position and orientation objectives, and where the multi-objective strategy was based on a weighted sum of position and orientation errors. A similar approach was proposed with application to a 5-DOF industrial robot, the Kuka Youbot manipulator [
15], where authors used the inertia weight PSO with an exponentially decreasing inertia weight, cognitive, and social coefficients. A swarm approach with behavior moderation based on Gaussian-like distributions was also proposed in [
16], where a beta function was introduced to distinguish two types of swarm behaviors: one for search phase and one for exploitation phase with application to inverse kinematics. The beta salp swarm algorithm, beta SSA, was proposed in [
16] for general optimization and inverse kinematics. The beta SSA is an SSA where search and explore phases are managed using beta profiles.
Multi-objective approaches of articulated systems and robotic arms are not popular, while they are more effective and more suitable to handle the difference in dimensions between position and orientation. Pena et al. (2016) developed an MO strategy for inverse kinematics for a 6-DOF robotic arm based on The Fast and Elitists Non-Dominated Sorting Genetic Algorithm and the Bacterial Chemotaxis Multi-Objective Algorithm [
17]. The multi-objective inverse kinematics, MO-IK, solver was used to optimize a couple of objective functions for position and orientation of the end-effector. A multi-objective PSO (MO-PSO)-based method for inverse kinematics was proposed in [
18], where authors used MO-PSO to minimize the error position as well as the angular elongation between initial and final poses. An evolutionary multi-objective approach for inverse kinematics was proposed in [
19] for the grasping problem of the humanoid robots; the proposal showed that such an approach can find accurate solutions in real time when compared to classical IK solvers.
In this paper, a new modified behavior PSO variant is proposed, m-PSO, which stands for a fitness-oriented PSO where the swarm particles evolve differently according to their fitness. A multi-objective optimization approach is then proposed based on m-PSO, the MO-M-PSO, which is applied to solve the inverse kinematics of a 5-DOF robotic arm, which is a 3D-printed educational robot. The arm inverse kinematics problem is formulated as a multi-objective problem assessing end-effector position and orientation as two separate objectives. A Pareto front strategy is then used to find out the best compromise between those objectives.
The remainder of this paper is organized as follows:
Section 2, presents the multi-objective optimization concepts and challenges, then in
Section 3, a multi-objective modified PSO, MO-m-PSO, is presented and detailed.
Section 4 is dedicated to experimental investigations, which include a single-point IK solution as well as circular path planning for the 5-DOF robotic arm. The proposed method is compared to recent state-of-the-art contributions in
Section 5. Finally, conclusion and perspectives are developed in
Section 6.
3. Multi-Objective Inverse Kinematics Problem Statement
The inverse kinematics, IK, problem consists of computing a set of joint’s motions that enable the end-effector of a robot manipulator to reach a specific target point. However, some industrial operations, such as welding, may need also a specific orientation of the end-effector besides its position. For example, the welding operation demands a functional tilt of the welding tools toward the welded surface. Such a constraint needs to be handled by a multi-objective strategy.
Classically, a problem may be solved by retrieving the inverse kinematics model by inverting the forward model, which is simple to build. However, it is not as simple as that, because the inverse model may not be existing at some specific singular points where the forward model is not invertible.
Therefore, the proposed method transforms the IK problem into an optimization consisting of minimizing the end-effector position and orientation based on the forward kinematics model of the systems, which is built using the Denavit–Hartenberg approach. Such an approach allows to avoid classical inverse kinematics solvers challenges including singularities, which may harm the existence of an inverse expression.
The proposal consists of addressing the constraints and needs with mono-objective functions, one for each, and then applying a metaheuristic solver with a Pareto strategy to obtain the best trade-off among them. For example, when the need is about position and orientation, such as in welding or painting, two main functions are addressed:
3.1. The Forward Modeling of the 5-DOF-Robotic Arm
A 3D-printed robotic arm with 5-DOF excluding the gripper joint, as in
Figure 2a, and the detailed kinematic representations and frames decomposition are illustrated in
Figure 2b. The first three rotational joints starting from the base are actuated using an MG996R servo-motor, while the two joints of wrist roll and wrist pitch are actuated with a smaller micro-servo, the SG90. The gripper grasping is also controlled by a SG90 servo; however, it is not included in the model. The system is controlled using an Arduino board and a set of H-bridges to avoid any overload when controlling servos. Such a robotic arm has a low cost and can be used for a variety of educational applications. It allows us to understand the main issues of robotics arms’ motions pacification, which are similar in industrial arms applications.
Figure 2 represents a 3D rendering of the used 5-DOF arm (
Figure 2a) as well as its kinematics scheme (
Figure 2b). The Denavit–Hartenberg (DH) convention is used to obtain the forward kinematics expression of the 5-DOF robot manipulator; the DH parameters of the arm are reported in
Table 1 and the relative frames displacements and rotations are indicated in
Figure 2b.
3.2. Denavit–Hartenberg Forward Kinematics Model of the Robotic Arm
The Denavit–Hartenberg, DH, convention provides a systematic methodology to express the forward kinematics model of a serial robot, using a generic transformation matrix modeling the position and the orientation between two sequential frames
and
,
[
29,
30].
Table 1 reports the DH parameters of the system, where i indicates the joint sequence, and
is the distance between
and
along
.
is the angle between
and
around
.
is the distance from
towards
along
.
is the angle of joint i which is the angle between
and
around
.
The position and orientation of the end-effector of the 5-DOF robotic arm are expressed as a 4 × 4 homogeneous matrix
, which is the result of the multiplication of the above matrices, as in Equation (
9).
Note that
stands for the homogeneous transformation matrix describing transformations of frame
toward frame
[
30,
31].
The terms
, and
are the elements that describe the orientation of the end-effector, while
are the coordinates of the end-effector with respect to the base frame, whose final expression is in Equation (
10).
stands for
and
represnts
. The terms
and
are the Denavit–Hartenberg, DH, parameters indicated in
Table 1.
This Denavit–Hartenberg kinematic modeling approach allows to retrieve the position of the end-effector as well as the orientations. Orientations needs to be converted to Euler angles which are commonly used in orientation control for robotics. This transformation is detailed in the next paragraph.
3.3. Managing the Orientation of the End-Effector
Euler angles convention (
) is a classical standard used in robotics, essentially to specify orientations. The Euler convention, as illustrated in
Figure 3, represents orientations as follows:
Frame 1 rotates first by an angle around , of frame 0;
Then Frame 2 rotates of around ;
Lastly, Frame 3 rotates around by an angle .
The end-effector orientation by be represented by Euler angular convention, which allows a more generic and interpretable representation of the orientation. Euler’s rotations toward the
base frame are, respectively,
. They may be computed on Equations (
11)–(
13), terms which are retrieved from the homogeneous transformation matrix detailed in Equation (
9).
where the
terms are those appearing in the homogenous transformation matrix of the arm detailed in Equation (
9).
Mono-objective optimization of the orientation aims to minimize the Euclidean distance of the generated solution toward a target orientation, as in Equation (
14).
3.4. Inverse Kinematics as a Multi-Objective Problem
Assuming that the joints coordinate is
, which may be rotations or translations but also angular or linear velocities; that the target position is
; and that the forward kinematics model of the system is in Equation (
9), the inverse multi-objective inverse kinematics model considering orientation may be formulated as in Equation (
15).
where
stands for the Euclidean distance of the end-effector position to the target position, which is subject to minimization.
is the Euclidean distance of the end-effector orientation to the target orientation which is also subject to minimization. (
) are the coordinates of the target position
.
is the end-effector position for a given joints position
. The target orientation (
) represents the desired orientation of the end-effector.
The first objective is related to and aims to minimize the distance between the target position and the end-effectors’ position. The second objective is related to the function , and tends to satisfy a given orientation constraint of the effector. Orientation optimization attempts to minimize the mean of the total angular errors to obtain the closest orientation possible to what is desired.
The multi-objective inverse kinematics solving may be resumed within the key steps presented in Algorithm 2
Algorithm 2 Simplified pseudocode of Mo-m-PSO for inverse kinematics. |
Begin Fix target position Fix orientation target Initialize a MO-m-PSO Swarm Q() ← random(Q1, Q2, ..., Qn) ← (forward kinematics model) while (not stop) for each particle Compute = ▹ System forward kinematics Compute = ▹ Euler angles transformation Execute / subject to as a mono-objective Execute / subject to as a mono-objective find Pareto Utopia point of Select / satisfying end for end while Return ( ) end |
Note that both mono-objectives PSO processes are set to the same number of particles, similar m-PSO parameters, and the same maximum iterations number. The stop condition could either be set to the maximum achieved iterations or a fixed error value.
4. Simulation and Results
The modified PSO, m-PSO, and its multi-objective version MO-m-PSO for inverse kinematics were applied to solve the inverse kinematics of an educational robotic arm using four scenarios:
The first test stands for the mono-objective version evaluations; it includes the single target point performances analysis and comparison with related methods.
The second scenario is the classical one-target test, where one target and one orientation is given and MO-m-PSO aims to determine the appropriate angles that assure achieving that orientation and position with as minor an error as possible.
The third scenario consists of generating 100 different random points covering the majority of the workspace space of the robot, then for each point an inverse kinematics solution is returned by MO-m-PSO. To assess the solver quality, the mean and standard deviations of the results are analyzed.
The path tracking test is where a circular trajectory is generated in the workspace of the 5-DOF robot. The circular path is made of 50 points. The role of the inverse kinematics solvers based on MO-m-PSO is to find the best possible solution for each point taking into consideration the desired orientation. Such a scenario may be used in soldering or in the industrial robotized components placement process.
4.1. Mono-Objective, m-PSO, Single Target Point Evaluation
A feasible target point is fixed at the location ( cm, cm, cm), which corresponds to an random joints position . Then, the m-PSO mono-objective solver is asked to achieve this position. The test is operated with a swarm of 50 particles, and for the search behavior of the m-PSO, and and for the exploitation behavior.
This test was repeated 30 times, and for all tests, the proposal achieved a feasible solution of the problem with position errors ranging from
to
The average error is about
. A 3D representation of a solution is shown in
Figure 4a; its corresponding fitness of up to 500 iterations appears in
Figure 4b.
It is important to note here that the obtained solutions through the computation, m-PSO, by about iteration 300, are precise enough for the real robotic arm used for a real practice test, since the printed robot resolution has about a
cm range, which means a quadratic position error of about
. The 3D representation of the robotic arm is performed using the Corke robotics toolbox [
31].
4.2. MO-m-PSO with Position and Orientation Objectives
This test is equivalent to the first one but with an additional orientation constrain. The test concerns the multi-objective variant of m-PSO, MO-m-PSO. The target point (
cm,
cm,
cm) was chosen arbitrary by applying the forward kinematics of a particular configuration
. The desired orientation used in this test was formulated by [
]. Its forward kinematics homogeneous transformation matrix is as in Equation (
16):
According to Equation (
16), the resulted orientation is defined by (
).
Figure 5a shows the Pareto font for position/orientation objectives which allows to select the optimal solution corresponding to
, for which the corresponding 3D representation appears in
Figure 5b.
The test was repeated over 100 epochs, which allowed us to compute the mean position and orientation errors as well as the standard deviations. Results are presented in
Table 2, which shows that the best position error is about
; this is not technically achievable with the current 5-DOF robotic arm. The best orientation error was about
which is extremely precise for an educational robotic arm. The means and standard deviations of these errors are also presented in
Table 2. The mean of position error is about
, while the mean of orientation error is about
.
4.3. Multiple Target Points for Statistical Analyses
The test consists of evaluating the capacity of MO-m-PSO to correctly solve a set of 100 random points generated in the workspace of the 5-DOF robotic arm; each point is associated with a random orientation. This test serves for a statistical analysis of the MO-m-PSO in solving the IK problem. The test conditions are the following: 100 search agents and 500 iterations for each target point.
Table 3 shows the best, worst, mean, and standard deviation of the obtained solutions.
It is clear that when an orientation constraint is added to the inverse kinematics, the position errors obtained are more important than when the system operates without the orientation constrain, while in real industrial applications, the orientation respect may make a great difference between acceptable and non-acceptable solutions.
Figure 6 shows both the position errors and the orientation errors for the 100 random test points, taking into consideration both the position and the orientation errors. The plots confirmed the results and showed that the orientation objective was achieved with a relative degradation of the position error, as in mono-objective m-PSO.
4.4. Multi-Objective m-PSO for Path Tracking with Fixed Orientation Simulation
The path tracking test consists of assessing the robot to track a circular path in a 3D workspace. The path is composed of a set of target points
belonging to a planar circular path (see
Figure 7c) and satisfying Equation (
17):
where
stands for the angular step, which depends on the number of points (steps) chosen in the trajectory, and the center of the circle position is at
. If the circle is sampled into
points, then the angular step
can be computed using Equation (
18).
For this test, the circular path is designed as follows:
The workspace distances are specified in centimeter, cm.
The circle center position is .
The circle radius is .
The end-effector orientation is fixed so that it is maintained perpendicular to the plan of the circular trajectory, which leads to the following orientation constraints: , is free.
Simulations showed that the circular path tracking was conducted in a very efficient manner. The mean error obtained over the 100 points was about
cm, where the target path is in red while the obtained path is in black. The orientations were respected with high precision since the mean error is about
. The mean and standard deviation of position error and orientation are reported in
Table 4, while
Figure 7 shows the relative error obtained at each point.
Desired and obtained path are visible in
Figure 7a, while
Figure 7b shows the joints’ angular positions returned by MO-m-PSO for a circular path made of 50 points. A 3D representation of the arm at point 25 is presented in
Figure 7c.
6. Experimental Validation on a 3D-Printed ARM
The experimental investigation consists of printing, assembling, and controlling a 3D-printed arm using inverse solutions generated by the m-PSO and M0-m-PSO. The 3D-printed arm is for educational use only and serves as an integration prototype. The experimental setup is shown in
Figure 9. It includes the following:
Matlab software;
An Arduino Uno board;
The 3D-printed arm.
The inverse kinematics solver runs on Matlab software with a PC powered by i7 Intel processor and a RAM of 12 GB.
This test is conducted using the following steps:
A target point is fixed by the user, it mimics the simulated random point test, then the proposed metaheuristic solver generates an online inverse solution and generates the joints control using the Arduino pulse wave modulation outputs, PWM.
The test is video reported, and the Kinovea video analysis software is used to gather the practical joints motions as well as the real target point, as in
Figure 9.
This test is repeated 20 times and the position errors are reported to evaluate the repeatability precision.
Figure 9 shows the target point, which is
, in centimeters, and the obtained solution with Kinovea annotations for analysis.
Table 7 presents the mean, minimum, maximum, and standard deviation errors towards the base frame
.
Results showed that the computational results of the proposed method are very precise in regards to the experimental results. The limitations of the 3D-printed robotic arm are clear, essentially when based on maximum and minimum real positions. The real target points position errors were of toward X, it ranges among toward Y, and among toward Z. Standard deviations were around 0.3. The precision limitations are essentially due to the limited quality of the 3D-printing mechanical frame, making it very limited for industrial use while being acceptable for educational use, and may help in explaining the gaps that may occur between the computational models and the mechanical system limitations.
7. Conclusions and Future Works
This paper addresses the inverse kinematics problems of a 3D-printed 5-DOF robotics arm for educational use. The paper proposed a behavior-modified PSO, m-PSO, and its multi-objective version (MO-m-PSO) to solve the inverse kinematics problem of a 3D-printed 5-DOF robotic arm, with a focus on the multi-objective approach. The proposed approach adapts the particles’ behavior rather than the PSO parameters, and particles evolve differently considering their level of optimality. Mo-m-PSO for inverse kinematics was tested using test scenarios which mimic the industrial needs of robotics arms:
The simple target point test, which assesses the precision capacities of the inverse kinematics solver as well as its convergence.
The random target point test, which allows to prove the robustness of the proposal and its capacity to correctly address any inverse solution within its work space.
The path planning task, which allows to confirm that the proposed method can be used to plan specific inverse solutions belonging to a specific geometric shape; here, a circle.
Results demonstrated that the mono-objective m-PSO as well as the MO-m-PSO are good potential solvers for inverse kinematics; however, the multi-objective Pareto strategy reduced the position precision while satisfying the needed orientation.
Acceptable trade-offs were correctly returned with solutions which are mechanically up to the precision and resolution of the system. Errors were on the order of millimeters for a system acting within the centimeter range.
Nonparametric statistical comparatives demonstrate that the proposed methods are very competitive toward existing state-of-the-art methods.
Future investigations may concern the impact of the heuristic parameters on the level of performances such as in [
39]. A focus on multi-objective optimization to cope with dynamical aspects of the robotic arm modeling, which may include torque and global energy reductions of the systems while executing a path, is also to be conducted.