Next Article in Journal
Research on Spatial Developable Mechanism Considering Revolute Clearance Joints with Irregular Rough Surfaces
Previous Article in Journal
Design and Self-Calibration Method of a Rope-Driven Cleaning Robot for Complex Glass Curtain Walls
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

An Efficient Quadratic Programming Method for Kinematic Control of Redundant Manipulators under Joint Velocity Constraints

1
School of Health Science and Engineering, University of Shanghai for Science and Technology, Shanghai 200093, China
2
Shanghai University of Medicine and Health Sciences, Shanghai 200120, China
3
Center for Medicine Intelligent and Development, China Hospital Development Institute, Shanghai Jiaotong University, Shanghai 200025, China
4
Institute of Machine Intelligence, University of Shanghai for Science and Technology, Shanghai 200093, China
*
Authors to whom correspondence should be addressed.
Actuators 2024, 13(7), 273; https://doi.org/10.3390/act13070273
Submission received: 19 June 2024 / Revised: 13 July 2024 / Accepted: 16 July 2024 / Published: 20 July 2024
(This article belongs to the Section Actuators for Robotics)

Abstract

:
This paper presents an efficient inverse kinematics solution for redundant robotic arms. The proposed method combines the principles of continuation methods, improves the instability of the computation time by increasing the convergence of the kinematics function, and improves the efficiency of traditional numerical methods. The effectiveness and efficient performance of the method are demonstrated through comparative experiments. The computational speed of the method is twice as fast as the Newton–Raphson method under joint limit constraints and equal solution accuracy.

1. Introduction

Inverse kinematics (IK) is a fundamental issue in the field of robotic motion control, constituting one of its more computationally intensive aspects. It enables the determination of joint configurations corresponding to a specified task of the end-effector in the Cartesian space. Resolving this problem typically requires a sophisticated approach, given the intricacies of the manipulator’s geometry and the nonlinear trigonometric equations that govern the transformation from the Cartesian space to the joint space. The issue intensifies with kinematically redundant robots, where the number of degrees of freedom surpasses the six coordinates required for reaching any point in the three-dimensional workspace [1]. The classic numerical algorithm for solving IK problems is the Newton–Raphson (NR) method [2,3]. The basic kinematic theory of the coordinated motion of rigid bodies is also formulated as the first-order differential kinematics, which is the relationship between the velocity of the robot’s joints and the end-effector velocity [4,5]. It necessitates the computation of the fundamental Jacobian matrix, where efficient methods for its computation are already accessible [6,7,8]. However, the Newton method does not handle kinematic singularities well: when a robot nears a kinematic singularity, the Newton method struggles to manage it effectively. This proximity leads to ill-conditioned inverse differential kinematics solutions, resulting in excessively high joint velocities and significant control deviations [9]. Consequently, the inverse kinematics solution employing the damped least squares (DLS) approach, known as the Levenberg–Marquardt (LM) algorithm, has been put forward in [10] to circumvent singularities. This method seeks a feasible solution by incorporating a damping factor, albeit at the cost of some precision [11]. In subsequent research, the DLS method has also been proven to be more suitable for solving the inverse kinematics of redundant robots and hyper-redundant robots [12], and compared to heuristic algorithms for solving inverse kinematics, it still holds an advantage when evaluated based on the computational accuracy and average time [13,14]. Owing to the inherent hardware constraints, including the limitations on the joint ranges and the angular velocities of the motors, the quadratic programming (QP) method has been developed to address the kinematic redundancy issue and the intractable problem of singularities [15]. Given the method’s exceptional merits, the QP-based IK methods with NR formulation have been the subject of extensive research endeavors [16,17,18,19,20] during the past decade. In addition to numerical methodologies, data-driven approaches for solving inverse kinematics have garnered extensive research attention. In the articles [21,22], the IK solver can be supplanted by neural networks (NNs), thereby achieving results with millimeter-level precision. Furthermore, the deep reinforcement-learning (DRL) methodology has been successfully employed for addressing inverse kinematics problems in redundant manipulators [23]. However, data-based IK depends on the training and the amount of data available, on which the learning time depends, and avoids falling into overfitting [13]. In comparison with iterative approaches, the outcomes derived from learning-based methods exhibit the results with a degree of error [24].
In terms of the development of methods for the IK problem, from NR- to QP-based IK, numerical iterative methods have been the mainstream approach for solving the problem. They offer advantages such as fast convergence and high accuracy [25], and especially the QP method has been widely applied in practice. Although QP-based inverse kinematics are highly effective at handling multiple constraints simultaneously, such as joint limits, they generally have higher computational costs and longer computation times compared to unconstrained methods. Additionally, because the formulation of the QP problem is still based on the Jacobian matrix, it retains the drawbacks of the NR method.
The objective of this study is to introduce the continuation method (CM)—a type of perturbation and homotopy technique that ensures the existence of a solution along a specific path, provided the auxiliary homotopy function is appropriately selected [26,27] to construct a constrained differential IK problem. This method tackles two critical challenges associated with Jacobian-based methods: the difficulty of selecting suitable initial estimates and the rate at which the method achieves convergence [28]. Consequently, it enhances both the computational efficiency and the stability of the solution process, making it well suited for real-time robotic systems.
The primary contributions of this study are succinctly outlined below:
-
The proposal to integrate differential kinematics with the continuation method into a numerical iterative approach and to construct it as a constrained QP problem to ensure its practicality. Additionally, the design of the corresponding homotopy auxiliary functions enhances its convergence, thereby improving the computational efficiency and accelerating the computation speed to the level of unconstrained solutions.
-
Experimental validation on a variety of classical redundant robot kinematic chains. The proposed method has been tested and validated across various robotic kinematic chains, comparing it with classic IK methods. The experiments indicate that, compared to the classic unconstrained and constrained IK methods, the proposed method significantly optimizes several metrics, including the number of iterations, average computation time, accuracy, and precision.

2. Problem Statement

2.1. Unconstrained Jacobian-Based Inverse Kinematics

In an m-dimensional task space x, for an n-degree-of-freedom serial-link manipulator where mn, to accomplish a specific task, the following equations must vary continuously with the time t [29]:
x t = Φ q t
where x     R m is the pose vector in the Cartesian space, q     R n is the joint configuration vector, and Φ is the forward kinematics function of the serial manipulators, which is also written as a homogeneous transformation matrix. For the i-th frame of the manipulators to the base frame, the transformation is composed of a rotation matrix R i   R 3 × 3 and a translation vector p i   R 3 as:
Φ i = R i P i 0 1 × 3 1
According to work [6], differentiating the equation with respect to the variable t gives:
x ˙ = J q ˙
where J q = Φ q q R m × n is the analytical Jacobian. Hence, the relationship in the IK problem between the joint configuration velocities q ˙ R n and the velocity error of the end-effector x ˙ e R m can be expressed as:
x ˙ e = v e w e = J q q ˙  
where v e corresponds to the linear velocity vector required to move from p to p d in unit time δ t , and ω e corresponds to the angular velocity vector required to rotate from R to R d in unit time δ t [7]. To solve Equation (4) concerning q ˙ , the straightforward solution by the NR method is written as:
q ˙ = J 1 x ˙ e
Due to the redundancy with m < n, direct matrix inversion is inapplicable for solving q ˙ . However, a frequently utilized Moore–Penrose pseudoinverse J† [1] is:
J = JT(JJT)−1
The classic IK problem aims to gradually reduce x ˙ e to zero through iteration. The solution is achieved iteratively from an initial guess q 0 according to an updated law with the updated δ q obtained by multiplying q ˙ and δ t in the joint space:
q k + 1 = q k + δ q
Based on the Levenberg–Marquardt method [10], a damping factor k is introduced to modify the Jacobian matrix in Equation (3) as follows:
J * = J T 1 J T J + k 2 I
Aside from the construction of the Jacobian matrix, the damped Newton method still utilizes the iterative approach of the Newton method to compute the joint angles.

2.2. QP-Based Inverse Kinematics

According to Equation (4) with optimization formalism, the goal function to be minimized can be formulated as [30]:
  min q ˙ ˙ J q ˙ x ˙ e + λ q ˙
Bringing together the previously derived equations, the IK problem can be formulated as a QP problem with constraints on the joint velocities:
min ξ 1 2 ξ T W ξ + h T
s . t . A ξ B
In the general formulation, ξ = J q ˙ x ˙ e . Hence, the matrices W and h can be expressed, respectively, as:
W = J T J + λ
h = x ˙ e T J
The matrix of the inequality constraints can be set as:
A = I n I n 2 n × n
B = q ˙ r u 1 q ˙ r u n q ˙ r l 1 q ˙ r l n 2 n × 1
where the matrix B is the constraints combined with q ˙ r l i and q ˙ r u i , which are expressed, respectively, as:
q ˙ r l i = max q ˙ l i , q l i q i Δ t
q r u i ˙ = min q ˙ u i , q u i q i Δ t
where the q l i and q u i represent the lower limit and the upper limit of the allowable joint ranges, respectively, and q ˙ l i and q ˙ u i represent the same constraints at the velocity level. The new joint velocity vectors can be obtained by iterative computation with constraints.

3. Methodology

As stated above, the continuation method can overcome some of the significant drawbacks of Newton’s iteration. By enhancing the rate of convergence, it is possible to optimize the efficiency and speed of the iteration. In the proposed method, the first step is to write an adjustable auxiliary homotopy function. The function must be known and straightforward to solve. The function must be chosen such that the Jacobian matrix remains invertible during the entire incremental process, ensuring a path to a specific solution set [31]. The auxiliary continuation function defined here can be expressed as follows:
F q ˙ = J q ˙ x e ˙
E q 0 = x d Φ q 0
G q ˙ = F q ˙ E q 0
where F q ˙ is the goal function represented as the classic expression of the differential IK problem. In Equation (18), x d is the target pose of the end-effector and E q 0 represents the pose error between the initial pose and x d . Equations (17) and (18) elucidate the error for the mapping from the joint space to the task space, albeit in distinct dimensions: one in terms of velocity and the other in terms of position. The derivatives with respect to the time of E q 0 exhibit a linear correlation with F q ˙ . Using this relationship with the goal function enables the formulation of a novel auxiliary function G q ˙ , as expressed in Equation (19).
Finally, the function using the continuation method [26] can be written as follows:
H q ˙ , s s F q ˙ + 1 s G q ˙ = 0
In general, s is an arbitrary homotopy parameter and varies from 0 to 1, i.e., s ∈ [0, 1]. In Equation (20), the conventional continuation formulation is the continuous linear transformation for the function H. To enhance the performance of the homotopy auxiliary function, we varied the homotopic parameter slightly and reformulated it to be nonlinear. The new formulation chosen has been proposed as a hyperbolic function, which ensures that the continuation path is smooth and differentiable. It is written as:
s t = tanh t
where t is an arbitrary parameter and varies from 0 to positive infinity, i.e., t ∈ [0, +∞]. Another benefit of the function is that we can increase t without the risk of s exceeding 1. According to Equation (20), the following two boundary conditions have been formulated:
H q ˙ , 0 = G q ˙
H q ˙ , 1 = F q ˙
The formulation for the continuation of the unconstrained inverse kinematics problem is now fully established. By progressively augmenting the parameter s, the solution to the IK problem can be effectively determined. In the proposed method, it can also be used to construct the cost function of the constraint’s optimization problem. The cost function can be directly defined as:
min q ˙ ˙ H q ˙ , s
If we define the following equation as the function of the homotopy parameter s:
g 0 s = 1 s G q ˙ 0
With Equations (20), (24) and (25), the complete QP-based IK problem can be developed as:
min q ˙ 1 2 q ˙ T J T J q ˙ x ˙ T + g 0 s T J q ˙
s . t . q ˙ r l q ˙ q ˙ r u
In this way, the QP problem can be reformulated and referred to as the CM in next section. Furthermore, the Jacobian matrix can be adjusted to incorporate damping effects, as indicated in Equation (8). Therefore, the goal function in Equation (17) can be redefined using the LM method. This approach can introduce unconstrained optimization into the proposed method. This method can integrate the benefits of unconstrained optimization into IK problems that lack joint constraints, effectively applied when directly solving the homotopy function. This change will also be incorporated into the comparisons in the subsequent experiments, and it is temporarily referred to as the CM-LM method. In robotics, kinematic redundancy is frequently utilized to enhance the performance of additional tasks or to optimize the inverse kinematics solution within the manipulator’s null space. Techniques such as task augmentation [32] or null-space projection [33], which can be implemented using the Jacobian-based method, are capable of achieving these goals. However, the exploration of these methods extends beyond the current work’s focus.

4. Results and Analysis

In this section, we will detail the algorithm of the CM using pseudo-code and its applied robot models, and then compare this new QP-based IK method with the existing Jacobian-based most commonly used IK solvers (NR method and LM method) to measure their practical performance. The NR methods with a Hessian matrix, which requires second-order derivative information, are not involved in the comparison because of their larger computational volume, higher computational complexity, and longer computation time.

4.1. Benchmark Setup

Benchmarks are performed with a standard laptop equipped with a relatively new CPU (Intel(R) Core i9-12900H-12th Generation 2.50 GHz processor, Intel Corporation, Santa Clara, CA, United States). The operating system is Ubuntu 22.04 LTS. The Jacobian matrix is uniformly obtained through function calls from the Pinocchio [34] Python interface in the testing codes. The uniform QP solver used is ProxQP [35]. Furthermore, all the computations are performed with double-precision arithmetic, providing 52-bit accuracy.

4.2. Manipulator Models

In order to verify the generality of the method, we choose a few classic 7-DOF robots as the test models. The manipulators used in the experiments are, respectively, Diana7(Agile robot, Beijing, Munich, China, Germany), Iiwa14(Kuka, Augsburg, Germany), Kinova Gen3 (Kinova, Boisbriand, Canada), Franka Emika panda(Franka Emika, Munich, Germany), as well as the 7-DOF arm of the humanoid robots developed by our team, X02. For these classical robot arms, this paper does not delve into extensive discussions. However, the kinematic parameters of the X02 and Diana7 models are presented in Appendix A.

4.3. Algorithms and Evaluations

To validate the effectiveness and advantages of the proposed algorithm, the experiments have been based on six indicators: valid range, success rate, computation time, number of iterations, convergence efficiency, and computational accuracy. In general, solving the differential kinematics problem requires a small positional error and a very short time interval to align with the mapping from the joint space to the task space, as represented by the Jacobian matrix. To test the capabilities of the methods to their limits in experiments, we introduce a metric vector, denoted as q η R n , which quantifies the difference between the input and output joint postures of the n-DOF robot. The q η can be written as:
q η = q target q init
The target and initial joint configurations are represented by q target and q init , respectively. By inserting q target into Equation (1), we determine the end-effector’s position and orientation for the input of the IK solver, and q init serves as the initial guess. In subsequent experiments, each term in q η will be generated as a random value based on the parameter η, which is designated to represent the maximum allowable joint variation. When generating the random error, each error between the initial joint and the target joint does not exceed η. Hence, the expression of the i-th joint random error can be written as:
q η i = r η
where r is a random value in the range of −1 to 1. In this way, the randomization of the target joints is feasible, and an increase in the value of η facilitates the generation of a diverse array of joint targets with greater variations from the initial joint values.
The algorithms run until convergence is achieved, as determined by the condition:
ε | x e |
where ε is the desired precision. It is initially set as ε = 1 × 10 4 , and its value can be reduced as needed in later tests. The algorithms can be stopped when the above condition is satisfied or the iteration limit is reached (Algorithm 1).
Algorithm 1: QP problem with continuation method
 Input: Initial guess q, Target pd, Rd
Initialization:
  Equation (1): pinit, Rinit = ForwardKinematics(q)
  Equation (4): err = computeError(pd, Rd, pinit, Rinit)
  Init parameters: t = 0, i = 0, dt, gt
  Equation (17): Init G(q)
while not (stopping criterion = Equation (28)) do
    s = tanh(t)
    Equation (25): g0 = computeg0(G, s)
    err = err + g0
    J = computeJacobian(q)
     q ˙ = ProxQP(J, err, q)
    q = q + q ˙
    pinit, Rinit = ForwardKinematics(q)
    err = computeError(pd, Rd, pinit, Rinit)
    t = t + dts
    i = i + 1
    if i mod gt == 0 then
     Init G(q)
  end
 end
 Output: q

4.4. Computation Range

In this section, the comparisons highlight the distinct valid computational ranges for the NR, LM, and CM methods. In the tests, we compare 10 sets of random target configurations generated by η with values varying from 0.2 to 2.0 in radians. A total of 250,000 tests were conducted on both constrained and unconstrained IK problems with different η values. In these tests, the initial guess as to the joint configurations was randomly generated, the effective precision ε of the IK solution was 1 × 10 4 , the maximum number of iterations was set to 300. The comparisons of the average performance per 50,000 computations for different kinematics chains are shown in the following figures.
From Figure 1, Figure 2, Figure 3, Figure 4 and Figure 5, we first compare the unconstrained iterative methods by applying the improved strategy based on the continuation to the NR method and the LM method, respectively, and then we compare them with their original forms. Considering the failure times, the four methods prove to be extremely reliable when the η value is comparatively low, indicating that the target pose is near the current pose. This result aligns well with the Jacobian matrix mapping significance. The computation time indicates that the LM method, as an unconstrained optimization technique, is significantly faster than the NR method. However, the proposed methods are outperformed by the traditional method in terms of both the failure times and the computational time for five robot arms. Furthermore, it is easy to see that the computational time optimization effect from the Jacobian with damping factor is considerably diminished in the continuation formulation. This demonstrates that the CM requires only the essential Jacobian matrices. Thus, the CM-LM method is removed in subsequent experiments.
In the QP formulation, the valid range and computation time are significantly worse due to the inclusion of joint angle constraints in the solving process. The figures for the different robots illustrate that when η exceeds 1.2, the accuracy of these methods falls below 90%, and when η ranges from 0 to 0.8, the accuracy is stable and acceptable. It can be seen that the presented method surpasses traditional methods in terms of the solving accuracy, yet its valid range still depends on the properties of the original function. Nevertheless, it indicates that the computational speed of the CM method has still nearly doubled.

4.5. Analysis of Iterations and Applications

To further explore the capability boundaries of the methods, in this section, we select η = 0.6 as the benchmark input to evaluate the precision of the solution’s accuracy. During this phase of the comparative trials, we have limited the maximum number of iterations to 300 to assess the highest level of precision attainable by these methods within such constraints, as well as the number of iterations needed to attain this level of precision.
In Table 1, the precision is categorized into two grades: 1 × 10−4 and 1 × 10−14. Under the first grade, all three methods achieve good accuracy rates and the proposed method is higher than other methods in terms of accuracy. At the higher level of precision, the proposed method substantially surpasses the other approaches. It is clear that, under the 300-iteration constraint, the NR method and the LM method are incapable of achieving this degree of accuracy. We also observe that the computational time for all the methods increases as the accuracy improves. However, the method introduced consistently remains under 2 milliseconds in execution time and sustains a correctness rate exceeding 99.4%. Another phenomenon is that the Jacobian with damping factor does not offer benefits compared to the classic Jacobian in the computation; instead, it makes the computation time longer.
To better observe the number of iterations and convergence of these methods, in Figure 6, we deliberately chose a set of joint configurations characterized by a substantial initial error in the group of η = 0.6 and meticulously record the error progression at each iteration for the NR method and the CM method for four robots. The vertical axis is represented as the error precision, which we describe in a logarithmic scale for visualization purposes. The error curve of the NR method exhibits a slow and steady decline. In comparison, the error curve of the CM method demonstrates a regular decrease coinciding with the updates of the auxiliary function, showing a very pronounced downward trend. The accuracy has been enhanced to a level of 1 × 10−15, and it has been confirmed that the proposed method consistently attains this precision within 120 iterations. Furthermore, after several manual adjustments to the continuation parameters, we can conveniently reduce the number of iterations to below 60. It is imperative to note that in the discrete-space continuation method, the parameter s is incremented in steps. If the step size Δs is too large, the method may rapidly iterate to a position near the objective but may not achieve full convergence. Conversely, if Δs is too small, the function may exhibit oscillations, which can reduce the efficiency of the convergence process.
In order to test the application of the method to a physical robot, we chose to apply the method to the teleoperation task of the humanoid robot X02. A video of the real system demonstrating it has been submitted OneDrive to process and is available at https://1drv.ms/v/c/e156dbff9bfce842/EUjcsDurifdDhVuajkN-o00BDdli1BDf-v1L4Kof4vbrNg (accessed on 6 July 2024). In this video, the X02 robot communicates with a VR teleoperation device known as PICO at a frequency close to 1000 Hz to accomplish the task of pouring water. Throughout the task, we have addressed the robot’s motion control in real time using the CM method. It is important to note that in this system, there is no low-level controller responsible for interpolating the underlying joint positions.

4.6. Discussion

After the experimental comparisons, it is evident that the proposed method significantly outperforms the traditional Newton’s method in terms of the computation time, number of iterations, and correctness rate when dealing with QP problems. With the notable increase in the computational power of embedded hardware in recent years, our method demonstrates practical application value. However, experiments also show that, similar to traditional QP methods, the computational error rate of our method increases dramatically when the initial value differs significantly from the expected value. The effect of the initial state is still not negligible. Secondly, the choice of auxiliary function significantly influences the computational efficiency. An inappropriate auxiliary function can not only increase the computational load but also fail to achieve the desired optimization outcome. This aspect may require further research, potentially from a topological perspective. Finally, although it optimizes the computational efficiency of the QP problem, it does not add a secondary task to the problem, and we will try to integrate the two in our future research.

5. Conclusions

This paper presents a continuation method-based inverse kinematics technique for redundant manipulators. This technique enables high-speed inverse kinematics computation while considering the robot’s physical kinematic limitations. It leverages the advantages of homotopy, starting from a function path to circumvent issues such as poor convergence, the tendency to fall into local minima, dependence on the initial guess point, and singularities in the kinematic function. Enhancing the iteration’s convergence efficiency improves the computational speed and accuracy, making it more suitable for real-time robotic systems. In future work, we will consider applying the method to QP problems with a second task and verify that the method still possesses superior performance to Jacobian-based methods.

Author Contributions

Conceptualization, T.W. and Q.L.; Methodology, Z.L.; Software, Z.L.; Validation, Z.L.; Formal analysis, Z.L. and P.W.; Resources, Z.L.; Data curation, P.W.; Writing—original draft, Z.L.; Writing—review & editing, Z.L. and Q.L.; Visualization, P.W.; Supervision, W.Z., T.W. and Q.L.; Project administration, T.W.; Funding acquisition, T.W. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the National Natural Science Foundation of China (Grant No. 92048205).

Data Availability Statement

The data generated for this study are available on request to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

Appendix A

Appendix A.1

The agile robot Diana7 is a 7-DOF robotic arm with revolute joints.
Figure A1. Agile robot Diana7 with the home configuration (in millimeters).
Figure A1. Agile robot Diana7 with the home configuration (in millimeters).
Actuators 13 00273 g0a1
Table A1. DH parameters of the Diana7 robot.
Table A1. DH parameters of the Diana7 robot.
Joint iqi/raddi/mmai/mmαi/rad
1q1−285.60π
2q200π/2
3q3−458.60π/2
4q4065π/2
5q5−455.4−52.8π/2
6q6 + π0−12.2π/2
7q7−116.987π/2

Appendix A.2

Figure A2. X02 robot and its 7-DOF arms.
Figure A2. X02 robot and its 7-DOF arms.
Actuators 13 00273 g0a2
Table A2. DH parameters of the X02 robot’s arm.
Table A2. DH parameters of the X02 robot’s arm.
Joint iqi/raddi/mmai/mmαi/rad
1 q 1 + π / 2 00 7 π / 12
2 q 2 7 π / 12 00 π / 2
3 q 3 π / 2 −2850 π / 2
4 q 4 010 π / 2
5 q 5 −205−10 π / 2
6 q 6 + π 00 π / 2
7 q 7 π / 2 85.850 π / 2
The forward kinematics can be formulated as follows:
Φ q = e φ 1 q 1 e φ 2 q 2 e φ 3 q 3 e φ 4 q 4 e φ 5 q 5 e φ 6 q 6 e φ 7 q 7 M
where the screw vector φ is associated with each joint, combining rotational and translational information, which can describe the motion of the joint. The e φ q is the form of an exponential map, which maps the screw vector to a transformation matrix. This mapping can convert the local motion of the joint into motion in the global coordinate system. The product in the expression e φ 1 q 1 e φ 2 q 2 e φ 7 q 7 represents the cumulative effect of the relative motion of each joint of the robot. The motion of each joint is relative to the previous one. The matrix M can be obtained by the DH parameters with the home posture of the robot.
The matrix M of Diana7 is written as follows:
M = 1 0 0 0.87 0 1 0 0.0 0 0 1 13.165 0 0 0 1
The matrix M of X02 is written as follows:
M = 1 0 0 0.0 0 1 0   0.194 0 0 1 0.2522 0 0 0 1

References

  1. Benati, M.; Morasso, P.; Tagliasco, V. The inverse kinematic problem for anthropomorphic manipulator arms. Trans. ASME J. Dyn. Syst. Meas. Control 1982, 104, 110–113. [Google Scholar] [CrossRef]
  2. Ortega, J.M.; Rheinboldt, W.C. Iterative Solution of Nonlinear Equations in Several Variables; SIAM: Philadelphia, PA, USA, 2000. [Google Scholar]
  3. Goldenberg, A.; Benhabib, B.; Fenton, R. A complete generalized solution to the inverse kinematics of robots. IEEE J. Robot. Autom. 1985, 1, 14–20. [Google Scholar] [CrossRef]
  4. Whitney, D.E. The Mathematics of Coordinated Control of Prosthetic Arms and Manipulators. J. Dyn. Syst. Meas. Control 1972, 94, 303–309. [Google Scholar] [CrossRef]
  5. Haviland, J.; Corke, P. Manipulator differential kinematics: Part I: Kinematics, velocity, and applications. IEEE Robot. Autom. Mag. 2023, 2–11. [Google Scholar] [CrossRef]
  6. Orin, D.E.; Schrader, W.W. Efficient computation of the Jacobian for robot manipulators. Int. J. Robot. Res. 1984, 3, 66–75. [Google Scholar] [CrossRef]
  7. Gonzalez-Palacios, M.A.; Angeles, J.; Ranjbaran, F. The kinematic synthesis of serial manipulators with a prescribed Jacobian. In Proceedings of the IEEE International Conference on Robotics and Automation, Atlanta, GA, USA, 2–6 May 1993; IEEE: New York, NY, USA, 1993; pp. 450–455. [Google Scholar]
  8. Gosselin, C.M.; Guillot, M. The synthesis of manipulators with prescribed workspace. J. Mech. Des. 1991, 113, 451–455. [Google Scholar] [CrossRef]
  9. Chiaverini, S.; Siciliano, B.; Egeland, O. Review of the damped least-squares inverse kinematics with experiments on an industrial robot manipulator. IEEE Trans. Control Syst. Technol. 1994, 2, 123–134. [Google Scholar] [CrossRef]
  10. Nakamura, Y.; Hanafusa, H. Inverse Kinematic Solutions With Singularity Robustness for Robot Manipulator Control. J. Dyn. Syst. Meas. Control 1986, 108, 163–171. [Google Scholar] [CrossRef]
  11. Zhao, J.; Xu, T.; Fang, Q.; Xie, Y.; Zhu, Y. A synthetic inverse kinematic algorithm for 7-DOF redundant manipulator. In Proceedings of the 2018 IEEE International Conference on Real-time Computing and Robotics (RCAR), Kandima, Maldives, 1–5 August 2018; IEEE: New York, NY, USA, 2018; pp. 112–117. [Google Scholar]
  12. Phuoc, L.M.; Martinet, P.; Lee, S.; Kim, H. Damped least square based genetic algorithm with Gaussian distribution of damping factor for singularity-robust inverse kinematics. J. Mech. Sci. Technol. 2008, 22, 1330–1338. [Google Scholar] [CrossRef]
  13. Moreno, L.A.O.; Ramírez, D.V.; Sánchez, M.P.; Rodríguez, L.R. Comparative Study of Iterative Methods for Inverse Kinematics of Redundant Serial Robots with Increasing Degrees of Freedom. In Proceedings of the 2023 IEEE International Autumn Meeting on Power, Electronics and Computing (ROPEC), Ixtapa, Mexico, 18–20 October 2023; IEEE: New York, NY, USA, 2023; Volume 7, pp. 1–6. [Google Scholar]
  14. Wang, L.-C.T.; Chen, C.-C. A combined optimization method for solving the inverse kinematics problems of mechanical manipulators. IEEE Trans. Robot. Autom. 1991, 7, 489–499. [Google Scholar] [CrossRef]
  15. Cheng, F.-T.; Chen, T.-H.; Sun, Y.-Y. Efficient algorithm for resolving manipulator redundancy—The compact QP method. In Proceedings of the 1992 IEEE International Conference on Robotics and Automation, Nice, France, 12–14 May 1992; IEEE Computer Society: Los Alamitos, CA, USA, 1992; pp. 508–509. [Google Scholar]
  16. Zhang, Z.; Zhang, Y. Variable joint-velocity limits of redundant robot manipulators handled by quadratic programming. IEEE/ASME Trans. Mechatron. 2012, 18, 674–686. [Google Scholar] [CrossRef]
  17. Kanoun, O.; Lamiraux, F.; Wieber, P.-B. Kinematic control of redundant manipulators: Generalizing the task-priority framework to inequality task. IEEE Trans. Robot. 2011, 27, 785–792. [Google Scholar] [CrossRef]
  18. Marić, F.; Giamou, M.; Khoubyarian, S.; Petrović, I.; Kelly, J. Inverse kinematics for serial kinematic chains via sum of squares optimization. In Proceedings of the 2020 IEEE International Conference on Robotics and Automation (ICRA), Paris, France, 31 May–31 August 2020; IEEE: New York, NY, USA, 2020; pp. 7101–7107. [Google Scholar]
  19. Woliński, Ł.; Wojtyra, M. A novel QP-based kinematic redundancy resolution method with joint constraints satisfaction. IEEE Access 2022, 10, 41023–41037. [Google Scholar] [CrossRef]
  20. Khudher, D.; Powell, R. Quadratic programming for inverse kinematics control of a hexapod robot with inequality constraints. In Proceedings of the 2016 International Conference on Robotics: Current Trends and Future Challenges (RCTFC), Thanjavur, India, 19–20 December 2016; IEEE: New York, NY, USA, 2016; pp. 1–5. [Google Scholar]
  21. Bensadoun, R.; Gur, S.; Blau, N.; Wolf, L. Neural inverse kinematic. In Proceedings of the International Conference on Machine Learning (ICML), Baltimore, MD, USA, 17–23 July 2022; PMLR: New York, NY, USA, 2022; pp. 1787–1797. [Google Scholar]
  22. Aggogeri, F.; Pellegrini, N.; Taesi, C.; Tagliani, F.L. Inverse kinematic solver based on machine learning sequential procedure for robotic applications. J. Phys. Conf. Ser. 2022, 2234, 012007. [Google Scholar] [CrossRef]
  23. 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]
  24. Guo, Z.; Huang, J.; Ren, W.; Wang, C. A reinforcement learning approach for inverse kinematics of arm robot. In Proceedings of the 2019 4th International Conference on Robotics, Control and Automation (ICRCA), Guangzhou, China, 26–28 July 2019; pp. 95–99. [Google Scholar]
  25. Ben-Israel, A. A Newton-Raphson method for the solution of systems of equations. J. Math. Anal. Appl. 1966, 15, 243–252. [Google Scholar] [CrossRef]
  26. Wu, T.-M. The inverse kinematics problem of spatial 4P3R robot manipulator by the Homotopy Continuation Method with an adjustable auxiliary Homotopy function. Nonlinear Anal. Theory Methods Appl. 2006, 64, 2373–2380. [Google Scholar] [CrossRef]
  27. Wu, T.-M. A study of convergence on the Newton-homotopy continuation method. Appl. Math. Comput. 2005, 168, 1169–1174. [Google Scholar] [CrossRef]
  28. Morgan, A.P. A method for computing all solutions to systems of polynomials equations. ACM Trans. Math. Softw. 1983, 9, 1–17. [Google Scholar] [CrossRef]
  29. Moe, S.; Antonelli, G.; Teel, A.R.; Pettersen, K.Y.; Schrimpf, J. Set-based tasks within the singularity-robust multiple task-priority inverse kinematics framework: General formulation, stability analysis, and experimental results. Front. Robot. AI 2016, 3, 16. [Google Scholar] [CrossRef]
  30. Lloyd, S.; Irani, R.A.; Ahmadi, M. Fast and robust inverse kinematics of serial robots using Halley’s method. IEEE Trans. Robot. 2022, 38, 2768–2780. [Google Scholar] [CrossRef]
  31. Wu, T.-M. Solving the nonlinear equations by the Newton-homotopy continuation method with adjustable auxiliary homotopy function. Appl. Math. Comput. 2006, 173, 383–388. [Google Scholar] [CrossRef]
  32. Egeland, O. Task-space tracking with redundant manipulators. IEEE J. Robot. Autom. 1987, 3, 471–475. [Google Scholar] [CrossRef]
  33. Chan, T.F.; Dubey, R.V. A weighted least-norm solution based scheme for avoiding joint limits for redundant joint manipulators. IEEE Trans. Robot. Autom. 1995, 11, 286–292. [Google Scholar] [CrossRef]
  34. Carpentier, J.; Saurel, G.; Buondonno, G.; Mirabel, J.; Lamiraux, F.; Stasse, O.; Mansard, N. The Pinocchio C++ library: A fast and flexible implementation of rigid body dynamics algorithms and their analytical derivatives. In Proceedings of the 2019 IEEE/SICE International Symposium on System Integration (SII), Paris, France, 14–16 January 2019; IEEE: New York, NY, USA, 2019; pp. 614–619. [Google Scholar]
  35. Bambade, A.; El-Kazdadi, S.; Taylor, A.; Carpentier, J. Prox-qp: Yet another quadratic programming solver for robotics and beyond. In Proceedings of the RSS 2022-Robotics: Science and Systems, New York, NY, USA, 27 June–1 July 2022. [Google Scholar]
Figure 1. Comparisons of IK problems using Diana7.
Figure 1. Comparisons of IK problems using Diana7.
Actuators 13 00273 g001
Figure 2. Comparisons of IK problems using Kinova Gen3.
Figure 2. Comparisons of IK problems using Kinova Gen3.
Actuators 13 00273 g002
Figure 3. Comparisons of IK problems using X02.
Figure 3. Comparisons of IK problems using X02.
Actuators 13 00273 g003
Figure 4. Comparisons of IK problems using Kuka iiwa14.
Figure 4. Comparisons of IK problems using Kuka iiwa14.
Actuators 13 00273 g004
Figure 5. Comparisons of IK problems using Franka Emika Panda.
Figure 5. Comparisons of IK problems using Franka Emika Panda.
Actuators 13 00273 g005
Figure 6. Error convergence in iterations. CM1 and CM2 represent, respectively, the proposed method with different increments of the homotopy parameter Δ s .
Figure 6. Error convergence in iterations. CM1 and CM2 represent, respectively, the proposed method with different increments of the homotopy parameter Δ s .
Actuators 13 00273 g006
Table 1. Comparisons of different IK methods in the QP formulation with different precision and a maximum iteration of 300.
Table 1. Comparisons of different IK methods in the QP formulation with different precision and a maximum iteration of 300.
RobotPrecisionMethodAccuracyTimes (ms)Max IterationsMax IterationsMin Iterations
Diana71 × 10−4NR99.15%1.8985.125260
LM99.15%4.5385.125260
CM99.79%0.4918.223814
1 × 10−14NR19.82%6.39297.6300277
LM19.82%15.71297.6300277
CM99.46%1.9783.026768
Iiwa141 × 10−4NR99.64%1.7485.117464
LM99.64%4.0885.123664
CM99.92%0.4418.024814
1 × 10−14NR19.15%5.82297.7300281
LM19.12%13.96297.7300282
CM97.86%1.7782.826470
Kinova Gen31 × 10−4NR98.27%1.7184.325657
LM98.27%4.2584.329057
CM99.49%0.4718.323714
1 × 10−14NR23.32%5.72297.4300281
LM23.31%13.76297.4300281
CM96.73%1.7984.926771
Panda1 × 10−4NR99.06%1.8784.927057
LM99.06%4.2984.927057
CM99.71%0.4818.118814
1 × 10−14NR20.97%6.16297.5300280
LM20.95%14.23297.5300280
CM99.49%1.8882.926670
X021 × 10−4NR98.52%2.5084.422159
LM98.52%5.1084.422359
CM99.51%0.6918.018314
1 × 10−14NR24.66%8.83297.2300275
LM24.65%17.63297.2300275
CM98.56%2.7283.226569
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

Li, Z.; Wang, P.; Zhao, W.; Wu, T.; Li, Q. An Efficient Quadratic Programming Method for Kinematic Control of Redundant Manipulators under Joint Velocity Constraints. Actuators 2024, 13, 273. https://doi.org/10.3390/act13070273

AMA Style

Li Z, Wang P, Zhao W, Wu T, Li Q. An Efficient Quadratic Programming Method for Kinematic Control of Redundant Manipulators under Joint Velocity Constraints. Actuators. 2024; 13(7):273. https://doi.org/10.3390/act13070273

Chicago/Turabian Style

Li, Zongdao, Pengfei Wang, Wenlong Zhao, Tao Wu, and Qingdu Li. 2024. "An Efficient Quadratic Programming Method for Kinematic Control of Redundant Manipulators under Joint Velocity Constraints" Actuators 13, no. 7: 273. https://doi.org/10.3390/act13070273

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