Download as pdf or txt
Download as pdf or txt
You are on page 1of 7

2013 21st Mediterranean Conference on Control & Automation (MED)

Platanias-Chania, Crete, Greece, June 25-28, 2013

Kinematic Control of Robot Manipulators Using Filtered Inverse


Lucas V. Vargas1 , Antonio C. Leite1 , Ramon R. Costa1

Abstract— This paper presents a kinematic control scheme interesting property of the algorithm is its ability to deal
for robot manipulators based on an algorithm that dynamically with the problem of kinematic singularities. Compared to
estimates an inverse of the Jacobian matrix. An interesting other methods described in the literature, the tuning of the
property of this algorithm is its ability to deal with the
problem of kinematic singularities. The output of the algorithm proposed algorithm depends only on a single gain parameter.
can be interpreted as the filtered inverse of the Jacobian A case study is presented for the problem of trajectory
matrix. A case study of a 3-DoF non-redundant manipulator is tracking of a non-redundant manipulator. Simulation results
presented. Some simulation results illustrate the performance illustrate the performance and feasibility of the proposed
of the proposed methodology. methodology.
Index Terms— Inverse kinematics, manipulators, robot kine-
matics, singularities. II. M ANIPULATORS KINEMATICS
Consider the kinematic modeling of a robot manipulator.
I. I NTRODUCTION The position of the end-effector p ∈ Rm is given by the direct
In recent years considerable research effort has been done kinematic mapping
to find a generic and robust solution to the problem of p = h(q) , (1)
inverse kinematics of robotic manipulators [1], [2]. The
where q ∈ Rn is the vector of the manipulator joint variables
difficulty dwells in the singularities, that is, in the kinematic
and h(·) : Rn 7→ Rm is a mapping, in general nonlinear,
configurations where the Jacobian matrix has incomplete
which describes the relationship between joints space Q and
rank. At a singularity, the mobility is reduced and infinitely
operational space O.
many solutions to the problem can exist [3].
The kinematic differential equation can be obtained as
An approach to avoid some types of singularities in
redundant manipulators is to use the extra degrees of mobility ṗ = J(q) q̇ , (2)
of the kinematic structure [4], [5]. The methods using the Ja-
cobian pseudoinverse may fail to find an acceptable solution where J(q) = ∂h(q)
∂q ∈ R
m×n
is the analytical Jacobian. The
in the neighborhood of a singularity since they can generate kinematic model (2) has the following property, useful in the
large steady-state error and/or high joint velocities. Also, the stability analysis of robot manipulators with revolute joints:
methods based on the transposed Jacobian matrix, although Property 1 [12]: J(q) is bounded for all possible values
numerically efficient in the presence of singularities, do not of q(t), i.e., it depends on q(t) as the argument of limited
guarantee asymptotic stability of the tracking error [3]. trigonometric functions and
Other methods for solving the inverse kinematics prob-
lem use optimization techniques such as, for example, the ||J(q)||∞ ≤ c1 ,
cyclic coordinate descent method (CCD), which is based on
where c1 is a known positive constant.
nonlinear programming [6]. The damped least square (DLS)
algorithm finds the inverse kinematics based on the Jacobian A. Kinematic control
pseudoinverse [7]–[9]. A damping factor introduced to avoid
Consider the kinematic control problem for a n-DoF robot
singularities establishes a compromise between accuracy and
manipulator. In this framework, the robot motion can be
feasibility of the solution. The feedback inverse kinematics
simply described by:
(FIK) method does not require a damping factor and employs
a feedback loop to minimize the difference between the q̇i = ui , (i = 1, · · · , n) , (3)
actual and desired velocities in the operational space [10],
[11]. where qi is the angular position of the i-th joint, q̇i is the
This paper presents a kinematic control scheme for ma- angular velocity of the i-th joint and ui is the velocity control
nipulators based on an algorithm that dynamically estimates signal applied to the i-th joint motor drive. Then, from (1)
the inverse of the Jacobian matrix. In the particular case and considering the kinematic control (3), we obtain the
where the matrix to be inverted is constant, the output following system
from the algorithm can be viewed as its filtered inverse. An ṗ = J(q) u . (4)

* This work was supported by CAPES, CNPq and FAPERJ. In the case where the Jacobian matrix is square (m = n)
1 Department of Electrical Engineering, COPPE/UFRJ, Rio de Janeiro, and non-singular, the velocity control signal is given by
RJ 21941-972, Brazil. e–mail: lucasvar@coep.ufrj.br,
toni@coep.ufrj.br, ramon@coep.ufrj.br. u = J −1 (q) v , (5)

978-1-4799-0995-7/13/$31.00 ©2013 IEEE 27


where v(t) is a Cartesian control signal. For the case where B. The DLS method
m < n, the control signal can be obtained by The solution (6) can be computed only when the Jacobian
† matrix has full rank. Otherwise, when the manipulator is at
u = J (q) v , (6)
a singular configuration, the control system (4) has linearly
where J † = J T (J J T )−1 is the right pseudoinverse of J. The dependent equations. It is important to note that the inversion
control signal (6) locally minimizes the norm of the velocities of the Jacobian matrix may represent a problem also in
of the joints, provided that (A1) the robot kinematics is the vicinity of a singularity, where the matrix becomes ill-
known and (A2) v(t) does not lead the robot to singular conditioned.
configurations. The failure of this last condition is still an One well known solution to the kinematic control in
important research topic in robotics, and will be discussed the vicinity of a singularity is given by the DLS method,
below. proposed in [7]. In this method, the inverse of the Jacobian
In this work, for simplicity, the orientation control is not is approximated by
considered. The control goal is to track a reference trajectory
J ∗ = J T (JJ T + α I)−1 , (10)
pd (t) from the current end-effector position p, that is:
where α > 0 is a damping factor introduced to improve the
p → pd (t) , e p = pd − p → 0 , (7) numerical conditioning, and is given by

where ep ∈ Rm is the position error of the end-effector. 0 , if w ≥ w0 ,
Combining (4) and (5), we have that ṗ = v, and thus, the α=  2 (11)
 α0 1 − w
position error dynamics is given by ėp = ṗd − v. Then, using w0 , if w < w0 ,
a proportional plus feedforward control law p
where w = det J(q)J T (q) is the manipulability measure,
v = ṗd + Λ ep , (8) α0 is a scaling factor, and w0 is a parameter that defines a
boundary for the singularity neighborhood. The main idea
where Λ = λ I is the proportional gain matrix, the position behind the method is to attenuate the non-feasible joint
error is governed by ėp + Λ ep = 0. Therefore, with an velocities in the neighborhood of a singular configuration,
appropriate choice of λ > 0, the closed-loop system is allowing the end-effector to deviate from the desired refer-
exponentially stable and hence limt→∞ ep (t) = 0. ence trajectory [3].
Figure 1 shows the block diagram of the kinematic control
algorithm given by equations (1) to (8). However, when III. P ROPOSED ALGORITHM
the manipulator is redundant (m < n) the Jacobian matrix For simplicity, consider initially a scalar problem. Given a
has more columns than rows and therefore (4) has infinite signal k(t), denote by θ(t) a signal such that kθ → 1. In other
solutions. In this case, an interesting approach is to formulate words, the “inverse” θ(t) is not computed instantaneously
the kinematic control as a linear optimization problem with as 1/k(t) but is dynamically updated. To derive a suitable
constraints [3]. dynamics for θ(t), we introduce the error

p h(·) S = kθ − 1 . (12)

+

ep
Now consider the positive function
v u R q
pd Σ Λ Σ J † (·)
+ 2V (S) = S 2 . (13)
+

ṗd
After deriving with respect to time, it gives
 
V̇ (S) = S Ṡ = S k̇θ + k θ̇ . (14)
Fig. 1. Block diagram of the kinematic control algorithm.
In view of the above equation, we select the update law
Due to the presence of n − m redundant degrees of
freedom, the solution (6) can be modified by introducing θ̇ = −βSk , (15)
a term belonging to the null space of J, i.e. where β > 0 is the update gain. As a result, we get

u = J † v + I − J † J q̇0 , (9) V̇ (S) = S k̇θ − βS 2 k 2 . (16)
where q̇0 is a vector of arbitrary joints velocities that can Notice that the update law (15) assures that the second term
be specified to satisfy an additional constraint with a sec- in (16) is non positive. The first term, however, remains
ondary priority (e.g., avoiding singularities or obstacles). The with undefined sign and depends on the k̇. Here, we begin
solution obtained locally minimizes the norm of the joints analyzing the simplest case where k̇ ≡ 0. In this case,
velocities and allows the generation of internal movements V̇ (S) ≤ 0. The equation (15) can be rewritten as
to reconfigure the manipulator structure without changing the
pose of the end-effector [3]. θ̇ = −β(kθ − 1)k = −βk 2 θ + βk . (17)

28
Using the differential operator s, we can explicit θ as Now, from (16) and the fact that S 6= 0, it follows that
βk 1   V̇ = S k̇θ − βS 2 k 2 = 0.5f˙ , (21)
θ= 2
= 1/k , (18)
s + βk τs + 1
from where we can explicit k̇ as
where τ = 1/βk 2 . Thus, θ can be interpreted as the output
0.5f˙ + βf k 2
of a linear filter where the input is the true inverse 1/k , that k̇ = . (22)
is, θ converges exponencially to 1/k. Sθ
Observe that the smaller is k, the larger is τ and con- Upon substituting (20) into (22), we find
sequently the slower is the filter. The same is observed for 0.5f˙ + βf k 2
the gain β: the smaller is the update gain, the larger is the k̇ = √ k. (23)
f− f
time constant of the filter. Motivated by (18) we will call the
signal θ the filtered inverse of k. For a constant function f (t) ≡ c, 0 < c < 1, k̇ reduces to

A. Properties of the filtered inverse k̇ = −ak 3 , (24)


√ √
An important property of the algorithm (15) is that for where a = β c/(1 − c). The solution of (24) is given by
s
k ≡ 0 it gives θ̇ ≡ 0 and, as a consequence, θ(t) ≡ θ(0).
1
Figure 2 shows the θ × k plane with the locus of S = 0 k(t) = k(0) . (25)
2at k(0)2 + 1
and some trajectories for different initial conditions θ(0). In
view of this figure, we can state that for any constant k the This example shows that, in fact, the filtered inverse θ
output θ(t) is bounded. can eventually grow unbounded, however, the signal k(t)
should be converging to zero slower than any exponential.
θ Consequently, the rate of increase of θ should also be slower
S=0 than any exponential.
The main properties of the algorithm (15) can be summa-
S<0 S>0 rized as follows:
k<0 k>0
θ̇ < 0 θ̇ < 0
(P1) k ≡ 0 ⇒ θ(t) = θ(0).
(P2) k constant ⇒ θ ∈ L∞ .
S = −1 (P3) k ∈ L∞ ⇒ θ̇ ∈ L∞ .
S<0 (P4) θ(t) has no finite escape time.
k B. Filtered inverse of matrices
The algorithm (15) can be easily generalized to deal with
matrices. Denote by K(t) a given matrix and by Θ its
S>0 S<0
k<0 k>0 estimated inverse. Again, it is assumed that the inverse is
θ̇ > 0 θ̇ > 0 not computed as K −1 (t), but is dynamically updated. Then,
to establish a suitable dynamics for Θ(t) we introduce an
error signal based on the right inverse
Sr = KΘ − Im , (26)
Fig. 2. Trajectories for different initial conditions in θ × k plane.
and an error signal based on the left inverse
Consider now the case of a time-varying k(t). It is clear Sℓ = ΘK − In , (27)
from Figure 2 that the only possibility of θ(t) to grow
without bound is in the region delimited by −1 < S < 0 where Sr ∈ Rm×m and Sℓ ∈ Rn×n . Consider initially the
(see the hatched region in the first quadrant). The closer k error (26) and the positive function 2 Vr = tr(SrT Sr ), where
is to zero, the larger may be θ. However, it can be easily tr(·) is the trace function. The time derivative of Vr is given
verified that in this region 0 < |k| < 1 and 0 < |θ̇| < β. by
This means that θ cannot escape in finite time. 2 V̇r = tr(ṠrT Sr + SrT Ṡr )
An example where k → 0 and θ → ∞ can be constructed
as follows. Consider a trajectory inside the hatched region. = 2tr(SrT K̇ Θ) + 2tr(SrT K Θ̇) . (28)
Such trajectory must satisfy In view of (28), we choose the following update law
2V = S 2 = f (t) , (19) Θ̇ = −ΓK T Sr , (29)
T
where f (t) is a continuous function such that 0 < f (t) < 1, where Γ = Γ > 0 is the update gain matrix. As a result,
∀t. Since −1 < S < 0 and k > 0, it follows from (19) that we have that

p 1− f V̇r = tr(SrT K̇ Θ) −tr(SrT K Γ K T Sr ) . (30)
S = kθ − 1 = − f ⇒ θ = . (20) | {z }
k ≤0

29
Similarly, for the error (27) we consider the positive This way, the similarity between scalar case and the
function 2 Vℓ = tr(SℓT Sℓ ), which has time derivative along multivariable case can verified by analyzing the diagonal
the trajectories of the system given by and the off-diagonal elements of Ψ = V T ΘU . Consider the
simplest case where K̇ ≡ 0. The dynamics of Ψ is given by
2 V̇ℓ = tr(ṠℓT Sℓ + SℓT Ṡℓ )
= 2tr(SℓT Θ K̇) + 2tr(SℓT Θ̇ K) . (31) Ψ̇ = V T Θ̇U . (37)

Now, the update law is selected as Using the composite update law proposed in (34) and
considering a scalar gain Γ > 0 we obtain
Θ̇ = −ΓSℓ K T , (32)
Ψ̇ = −ΓV T (Sℓ K T + K T Sr )U
T
where Γ = Γ > 0. As as result, we have = −ΓV T (ΘK − In )V ΣT − ΓΣT U T (KΘ − Im )U
V̇ℓ = tr(SℓT Θ K̇) −tr(K SℓT Γ Sℓ K T ) . (33) = −Γ(V T ΘU Σ − In )ΣT − ΓΣT (ΣV T ΘU − Im )
| {z }
≤0 = −Γ(ΨΣ − In )ΣT − ΓΣT (ΣΨ − Im ) . (38)
For the case of non-redundant manipulators (m = n) both The matrix Ψ can be decomposed as
update laws (29) and (32) can be used to solve the problem of
inverse kinematics, since the left and right inverse matrices Ψ = DΘ + R Θ , (39)
are equal. However, in the case of redundant manipulators where DΘ ∈ Rn×m has the diagonal elements of Ψ and
(m < n), the error matrices Sr and Sℓ have different di- RΘ ∈ Rn×m has the off-diagonal elements of Ψ (residual
mensions. For a Jacobian matrix with full rank by rows, i.e., elements), with zeros on the diagonal. Thus, Ψ̇ = ḊΘ + ṘΘ
rank(J) = m, there are infinitely many solutions X such that and, therefore,
JX = I, while there is no solution Y such that Y J = I. An
interpretation of this fact, in terms of the kinematic control ḊΘ + ṘΘ = − Γ(DΘ Σ + RΘ Σ − In )ΣT
of the manipulator, is that the right inverse obtained from − ΓΣT (ΣDΘ + ΣRΘ − Im ) . (40)
(29) (derived from the error matrix Sr ) allows the trajectory
tracking in the operational space but, because of the plethora Note that the products of diagonal matrices and residual
of solutions, the control variable u has components in the null matrices are also residual, presenting zeros on the diagonal.
space of J. These joint velocities components do not alter Thus, it is possible to separate the dynamics of DΘ and RΘ .
the end-effector velocities in Cartesian space. By the other For the diagonal of Ψ, we have
hand, it can be shown that the left inverse (32) (derived from
ḊΘ = −Γ(DΘ Σ − I)ΣT − ΓΣT (ΣDΘ − I) . (41)
the error matrix Sℓ ) minimizes the projection of u in the null
space of J, resulting in an optimal control variable. The dynamics of the diagonal element di is given by
Thus, in view of the above remarks, we propose an update
law based on both error matrices, Sr and Sℓ , simultaneously: d˙i = −Γ(di σi − 1)σi − Γσi (σi di − 1)
= −2ΓSi σi , (42)
Θ̇ = −Γ(Sℓ K T + K T Sr ) , (34)
which has a form similar to the scalar case analyzed previ-
where Γ = ΓT > 0 is the update gain matrix. This composite ously (notice that σi ∈ R+ ). Notice also that
update law (34) is easily obtained from the positive function
Vc = Vr + Vℓ . d˙i = −2Γσi2 di + 2Γσi , (43)
Note that the only assumption required to employ this
method in the inverse kinematic problem is that the desired which means that the diagonal elements di are converging
trajectory of the end-effector is not converging (slower than exponentially to 1/σi . For the off diagonal elements we have
exponentially) to a singularity. that
ṘΘ = − ΓRΘ ΣΣT − ΓΣT ΣRΘ . (44)
| {z } | {z }
C. Convergence property I II
Consider the singular value decomposition (SVD) of the The matrices ΣΣT and ΣT Σ are diagonal square matrices
gain matrix K(t) ∈ Rm×n whose elements are the squares of the singular values of
K = U Σ V T, (35) K. If m 6= n, one of these matrices also has zeros in the
diagonal. An important remark is the effect of these zeros
where U ∈ Rm×m , Σ ∈ Rm×n and V ∈ Rn×n . The on the matrix RΘ . In term I, obtained when considered the
matrices U and V are orthogonal matrices whose columns use of Sℓ , the zeros multiply the columns of RΘ . On the
are eigenvectors of KK T and K T K, respectively, and the other hand, in the term II, obtained when Sr is considered,
matrix Σ has r singular values of K in its diagonal. Thus, the zeros are applied to the rows of RΘ . Thus, the dynamics
Θ may be expressed conveniently as of the residual elements may be written as
Θ = V Ψ UT . (36) ṙij + Γ(σi∗2 + σj∗2 )rij = 0 , (45)

30
θ2 k
where σk∗ = σk if k ≤ min(m, n) and σk∗ = 0 otherwise S(S + 2) = 0
(rectangular matrices). The use of the two error matrices Sℓ
and Sr makes the residue convergence dependent of two
distinct single values, related to the row and column. For
instance, consider the case where m = n and σm = 0.
The use of an update law based only on Sr (with zeros
multiplying the rows) would result in ṙmj = 0, ∀j. The k
residual elements of the entire m-th row cannot change
and therefore cannot become null. The composite algorithm
which also uses Sℓ (with zeros multiplying the columns)
ensures the convergence of these residues to 0 since σj 6= 0.
S(S + 2) = 0
For the m < n case, with full rank, the residual elements
rij for i > m are related with vectors in the null space of
K. The use of Sℓ ensures that these elements converge to Fig. 4. Typical curve in θ 2 k × k plane.
zero. For the case where m > n, the residuals rij for j > n
are associated with vectors in null space of K T and only the
use of Sr ensures convergence of these residual terms to 0. trajectories of the system is given by V̇e = eTp Λ(ṗd − K u).
Then, for u = uM = Θ ΘT K T v , the following equation is
IV. M ODIFIED CONTROL LAW obtained
Consider the scalar gain k and its inverse function k −1 .
The inverse has the same sign of k. The same is not verified V̇e = eTp Λ(I − P P T ) ṗd − eTp Λ P P T Λ ep , (48)
| {z }
for the function k and its filtered inverse θ. Figure 3 below Φ
illustrates a typical curve in θ ×k plane for a gain k evolving
where P = K Θ. Notice that the term Φ corresponds to a
from the positive to the negative half-plan.
negative semi-definite term, regardless of the quality of the
θ estimate given by the filtered inverse algorithm (34). In the
S=0 case where K has reduced rank, the use of uM (v) = ΘM v
cancels the components of v in the null space of K T . That
is, for v = vc +vn , where vc ∈ Col(K) and vn ∈ N ul(K T ),
we have that uM (v) = uM (vc ).

V. S IMULATION RESULTS
k
In this section, we present simulation results obtained for
a 3-DoF non-redundant manipulator with 3 revolute joints
(Figure 5). The performance of the proposed inverse kine-
matics algorithm is analyzed for some desired trajectories
S=0 and compared with the DLS algorithm [7].

Fig. 3. Typical curve in θ × k plane.

In order to recover the equality of sign, we propose a


modification in the way θ is applied in the control law u.
Thus, our proposal is
θM = θ 2 k , (46)
so that sign(θM ) = sign(k). Figure 4 illustrates the behavior
of θM for the same temporal evolution of k considered in
the Figure 3.
For the multivariable case a similar modification is pro-
posed. The matrix ΘM is given by
ΘM = ΘΘT K T . (47)
Notice that ΘΘT is symmetric positive semi-definite. Con-
sider the kinematic control problem given by the equation
ėp = ṗd − Ku (K here is the Jacobian matrix) and the Lya-
punov function 2Ve = eTp Λep . Its time derivative along the Fig. 5. Zebra-ZERO manipulator and desired trajectories.

31
The length of the manipulator links are l1 = 27.94 cm and for t ∈ [0 30]. The methods present satisfactory performance
l2 = 39.36 cm. Consider λ = 5, α0 = 300 and ω0 = 103 . in tracking the desired trajectory but it can be observed that
The update gain Γ = 15 I is used for all case studies. The the DLS algorithm, for the specific gains used, resulted in
initial conditions are Θ0 = 03×3 and q(0) = [0 π2 −π]T rad. a trajectory that moves away from these singular configura-
The direct kinematic mapping of the manipulator is given by tions, as seen in Figure 7.
 
c1 (ℓ1 c2 − ℓ2 s23 )
h(q) =  s1 (ℓ1 c2 − ℓ2 s23 )  , (49) 10
ℓ1 s2 + ℓ2 c23 Filtered Inverse
DLS
where c1 = cos(q1 ), s1 = sin(q1 ), c2 = cos(q2 ), s2 = sin(q2 ), 5

||e||
c23 = cos(q2+q3 ), s23 = sin(q2 +q3 ), and the Jacobian matrix
is obtained from J(q) = ∂h(q)
∂q .
0

A. Case Study I
−5
0 5 10 15 20 25 30
Initially, we consider the problem of tracking a singularity time [s]
free trajectory, given by: 4
x 10
4
  Filtered Inverse
37.86 − 15 cos(0.3 t) 3 DLS
pId (t) =  10 sin(0.3 t) . (50)
11.44 2

ω
1
As expected, both methods allowed the tracking of the
0
desired trajectory with practically no error. The norms of
the errors and manipulability measures are shown in Figure 0 5 10 15 20 25 30
time [s]
6. The trajectory considered is far from singularities, then
α = 0 during all times.
Fig. 7. Case Study II - Tracking error norm and manipulability.

30
Filtered Inverse C. Case Study III
DLS
20 In this case, we analyze the performance of the methods
for an extreme case, in which part of the desired trajectory
||e||

10
is outside the workspace of the manipulator, so that the error
0
cannot be cancelled. The trajectory III is given by
 
0 5 10 15 20 25 30 62.86 − 15 cos(0.3 t)
time [s] pIII
d (t) =
 10 sin(0.3 t) , (52)
4
6
x 10 11.44
Filtered Inverse
5 DLS which is similar to trajectory I but shifted in the positive x-
4
axis. The norms of the errors and manipulability measures
are presented in Figure 8. Both algorithms allow the tracking
ω

3
of the viable part of the trajectory. But at some point, the
2 desired trajectory becomes unreachable and both methods
1 lead the manipulator to configurations near singularities
0 5 10 15 20 25 30
time [s] (ω ≈ 0). Once the desired trajectory is feasible again, both
methods ensure that the tracking errors become small. It
Fig. 6. Case Study I - Tracking error norm and manipulability.
can be observed that, for the gains used in the simulations,
the DLS algorithm has a degraded performance near the
singularity and, once the trajectory becomes feasible again,
B. Case Study II a considerable deviation is observed.
In this case, a trajectory that passes through singular
VI. C ONCLUSION
configurations (shoulder singularities) is considered. In these
configurations there are infinitely many solutions to the This work presents an alternative algorithm for calculating
inverse kinematics problem. The desired trajectory is given the inverse kinematics of robot manipulators, which can be
by   interpreted as a filtered inverse. Several simulation results
0 illustrate the good performance of the proposed algorithm.
pII
d (t) = 5 sin(0.4 t)
  (51) Although in this study only the position control problem
25 − 0.3t has been addressed, the application of the method can be

32
computation of manipulability measures.
25
Filtered Inverse Future research topics considering the ideas discussed here
20 DLS are to relax the assumption of complete knowledge of the
15
robot kinematics and include the nonlinear robot dynamics
||e||

10
in the control design.
5
0 R EFERENCES
−5 [1] K. Tchon and J. Jakubiak, “Extended Jacobian inverse kinematics
0 5 10 15 20 25 30
time [s] algorithm for nonholonomic mobile robots,” International Journal of
4 Control, vol. 79, no. 8, pp. 895–909, 2006.
x 10
[2] S. Chiaverini, G. Oriolo, and I. D. Walker, “Kinematically redundant
8 Filtered Inverse manipulators,” in Springer Handbook of Robotics, 1st ed., B. Siciliano
DLS and O. Khatib, Eds. Springer-Verlag Ltd., 2008, pp. 245–268.
6
[3] B. Siciliano, L. Sciavicco, L. Villani, and G. Oriolo, Robotics: Mod-
elling, Planning and Control. Springer Publishing Company, Inc.,
ω

4
2009.
2 [4] K. Tchon and A. Matuszok, “On avoiding singularities in redundant
0 robot kinematics,” Robotica, vol. 13, pp. 599–606, 1995.
[5] S. Chiaverini, “Singularity-robust task-priority redundancy resolution
0 5 10 15 20 25 30 for real-time kinematic control of robot manipulators,” IEEE Transac-
time [s]
tions on Robotics and Automation, vol. 13, no. 3, pp. 398–410, 1997.
[6] L.-C. T. Wang and C. C. Chen, “A combined optimization method for
solving the inverse kinematics problem of mechanical manipulators,”
Fig. 8. Case Study III - Tracking error norm and manipulability.
IEEE Transactions on Robotics and Automation, vol. 7, no. 4, pp.
489–499, 1991.
[7] Y. Nakamura and H. Hanafusa, “Inverse kinematic solution with
singularity robustness for robot manipulator control,” ASME Journal
extended to the orientation control problem as well. Pre- of Dynamic Systems, Measurement and Control, vol. 108, no. 3, pp.
liminary simulations have shown that the performance for 163–171, 1986.
[8] C. W. Wampler, “Manipulator inverse kinematic solutions based on
both cases are similar. Interesting results were obtained for vector formulations and damped least-squares methods,” IEEE Trans-
the case where the reference position and orientation can actions on System, Man and Cybernetics., vol. 16, no. 1, pp. 93–101,
not be achieved simultaneously. In this case, the use of the 1986.
[9] S. Chiaverini, B. Siciliano, and O. Egeland, “Review of the damped
proposed algorithm and the adjustment of the gains allows least-squares inverse kinematics with experiments on an industrial
prioritization of the control objectives. This is a research robot manipulator,” IEEE Transactions on Control Systems Technol-
topic currently under development. ogy, vol. 2, no. 2, pp. 123–134, 1994.
[10] A. N. Pechev, “Inverse kinematics without matrix inversion,” in IEEE
Compared with other algorithms described in the litera- International Conference on Robotics & Automation, Pasadena, CA,
ture, one advantage of the proposed algorithm is that it has USA, 2008, pp. 2005–2012.
[11] S. M. Ahmed and A. N. Pechev, “Performance analysis of FIK and
only one design parameter: the update gain, directly related DLS inverse kinematics using six degree of freedom manipulator,” in
to the performance of the algorithm. From the computational IEEE International Conference on Robotics and Biomimetics, Guilin,
point of view, the proposed method provides computational China, 2009, pp. 1405–1410.
[12] W. E. Dixon, “Adaptive regulation of amplitude limited robot manip-
efficiency since it does not require matrix manipulations ulators with uncertain kinematics and dynamics,” IEEE Transactions
such as matrix inversion, singular value decomposition and on Automatic Control, vol. 52, no. 3, pp. 488–493, 2007.

33

You might also like