1024
IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 51, NO. 6, JUNE 2006
Adaptive Jacobian Tracking Control of Robots With Uncertainties in Kinematic, Dynamic and Actuator Models C. C. Cheah, C. Liu, and J. J. E. Slotine
Abstract—Most research so far on robot trajectory control has assumed that the kinematics of the robot is known exactly. However, when a robot picks up tools of uncertain lengths, orientations, or gripping points, the overall kinematics becomes uncertain and changes according to different tasks. Recently, we derived a new adaptive Jacobian tracking controller for robots with uncertain kinematics and dynamics. This note extends the results to include redundant robots and adaptation to actuator parameters. Experimental results are presented to illustrate the performance of the proposed controller. Index Terms—Actuator model, adaptive control, dynamics, robot kinematics, tracking control, uncertainty.
I. INTRODUCTION Robot manipulators are required to handle various tools and, hence, the dynamic parameters of the robots vary during operation and are difficult to be predicted in advance. By exploring physical properties of the robot system, Takegaki and Arimoto [1] and Arimoto [2] showed using Lyapunov’s method that simple controllers such as the proportional-derivative (PD) and proportional–integral-derivative (PID) feedback are effective for setpoint control despite the nonlinearity and uncertainty of the robot dynamics. To deal with trajectory tracking control, several adaptive robot control laws have been proposed and much progress has been obtained in respect to understanding how the robot can track a desired trajectory in the presence of uncertain dynamic parameters [3]–[17]. However, most research on robot control has assumed that the exact kinematics and Jacobian matrix of the manipulator from joint space to Cartesian space are known. This assumption leads us to several open problems in the development of robot control laws today. In free motion [18], this implies that the exact lengths of the links, joint offsets and the object which the robot is holding, must be known. Unfortunately, no physical parameters can be derived exactly. Moreover, when the robot picks up objects or tools of different lengths, unknown orientations and gripping points, the overall kinematics are changing and, therefore, difficult to derive exactly. Therefore, the robot is not able to manipulate the tool to a desired position if the length or gripping point of the tool is uncertain. When the control problem is extended to the control of multifingered robot hands [19], such assumption also limits its potential applications because the kinematics is uncertain in many applications of robot hands. For example, the contact points of the robot fingers are uncertain and changing during manipulation. Similarly, in hybrid position force control [20], the assumption of exact kinematics also leads us to an open problem on how to control the robot if the kinematics and constraint are uncertain. To overcome the problem of uncertain kinematics, several approximate Jacobian setpoint controllers [21]–[23] were proposed recently.
Manuscript received October 21, 2004; revised July 5, 2005 and November 30, 2005. Recommended by Associate Editor F. Bullo. C. C. Cheah and C. Liu are with School of Electrical and Electronic Engineering, Nanyang Technological University, Singapore 639798, Republic of Singapore (e-mail:
[email protected]). J. J. E. Slotine is with Nonlinear Systems Laboratory, Massachusetts Institute of Technology, Cambridge, MA 02139 USA (e-mail:
[email protected]).
The proposed controllers do not require the exact knowledge of kinematics and Jacobian matrix that is assumed in the literature of robot control. Using the approximate Jacobian control approach, other open problems such as force control with uncertainties [24] and control of robot fingers with uncertain contact points [25] can be resolved in a unified formulation. However, the results in [21]–[23] are focusing on setpoint control of robot. In some applications, it is necessary to specify the motion in much more details than simply stating the desired final position. Thus, a desired trajectory should be specified. Recently, an adaptive Jacobian controller was proposed for trajectory tracking control of robot manipulators [26], [27]. The controller does not require the exact knowledge of kinematics and Jacobian matrix that is assumed in the literature of tracking control. However, it is assumed in [26] and [27] that the actuator model is known exactly. Since the actuator model may be uncertain in practice, calibration is necessary to identify the exact parameters of the actuator in implementing the robot controllers. In addition, the actuator parameters could change as temperature varies due to overheating of motor or changes in ambient temperature. Hence, in the presence of the modeling uncertainty or calibration error, the convergence of the tracking error may not be guaranteed. This note extends the algorithm of [26] to include redundant robots and adaptation to actuator parameters. A new adaptive Jacobian controller is proposed for trajectory tracking of robot with uncertain kinematics, dynamics and actuator model. Experimental results are presented to illustrate the performance of the proposed controller. II. ROBOT DYNAMICS AND KINEMATICS If a direct current (dc) motor driven by an amplifier is used as actuator at each joint of the robot, the dynamics of the robot with n degree of degrees of freedom can be expressed as [2], [28]
M (q ) q+ B+
1 _ M (q ) + S (q; q_)
2
q_ + g (q ) = Ku
(1)
where M (q ) 2 Rn2n is the inertia matrix, B 2 Rn2n is a matrix of damping coefficients, u 2 Rn is either a voltage or current inputs to the amplifiers, K 2 Rn2n is a diagonal transmission matrix that relates the actuator input u to the control torque
S (q; q_)q_ =
1 _ M (q )q_ 2
0 21
@ T q_ M (q )q_ @q
T
and g (q ) 2 Rn is the gravitational force. Several important properties of the dynamic equation described by (1) are given as follows [2], [4], [28], [29]. Property 1: The inertia matrix M (q ) is symmetric and uniformly positive–definite for all q 2 Rn . Property 2: The matrix S (q; q_) is skew-symmetric so that T S (q; q_ ) = 0 for all 2 Rn . Property 3: The dynamic model as described by (1) is linear in a set of physical parameters d = (d1 ; 1 1 1 ; dp )T as M (q ) q+
B+
1 _ M (q ) + S (q; q_ )
2
q_ + g (q ) = Yd (q; q; _ q; _ q)d
where Yd (1) 2 Rn2p is called the dynamic regressor matrix. } In most applications of robot manipulators, a desired path for the end-effector is specified in task space or operation space such as Carte-
0018-9286/$20.00 © 2006 IEEE
IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 51, NO. 6, JUNE 2006
sian space or visual space [2], [21], [30]. Let x vector defined by
2 Rm be a task space
x = h(q) where m n, h(1) 2 Rm is a transformation describing the relation between the joint space and task space. The task-space velocity x_ is related to joint-space velocity q_ as
x_ = J (q)q_
(2)
where J (q ) 2 Rm2n is the Jacobian matrix from joint space to task space. If cameras are used to monitor the position of the end-effector, the task space is defined as image space in pixels. Let r represent the position of the end-effector in Cartesian coordinates and x represent the vector of image feature parameters [32]. The image velocity vector x_ is related to the joint velocity vector q_ as [32]
x_ = JI (r)Je (q)q_
x_ = J (q)q_ = Yk (q; q_)k
(3)
where Yk (q; q_) 2 Rm2q is called the kinematic regressor matrix. } Remark 1: In the presence of kinematic uncertainty, inverse kinematics cannot be used to derive the desired trajectory in joint space. In addition, when the dynamics equation is expressed in task space by using (2) and its derivative, we have
0M (q)J 01 (q)J_(q)+B + 21 M_ (q)+S (q; q_) 2J 01 (q)x_ + g(q) = Ku:
The aforementioned equation cannot be expressed in a form as in Property 3 because J 01 (q ) is not linear in the unknown kinematic parameters. In addition, the mapping between force and torque using Jacobian transpose is also uncertain due to the unknown kinematic parameters. For example, for a two link nonredundant robot holding an object, the Jacobian matrix J (q ) from joint space to Cartesian space can be derived as
J (q ) =
0(l1s1 + l2 s12 + lo s12o) 0(l2 s12 + lo s12o ) l1 c1 + l2 c12 + lo c12o
where l1 and l2 are the link lengths, l0 and q0 are the length and grasping angle of the object, respectively, s1 = sin(q1 ), s12 = sin(q1 + q2 ), s12o = sin(q1 + q2 + qo ), c1 = cos(q1 ), c12 = cos(q1 + q2 ), and c12o = cos(q1 + q2 + qo ). In presence of kinematic uncertainty, the parameters l1 , l2 , lo , and q0 are unknown. The inverse Jacobian matrix J 01 (q ) can be obtained as
J 01 (q) =
1
l1 l2 s2 + l1 lo s2o 2 0(l1 cl12 c+12l2+c12lo c+12loo c12o )
l2 s12 + lo s12o
0(l1 s1 + l2 s12 + lo s12o )
which is nonlinear in the unknown parameters l1 , l2 , lo , and q0 . Therefore, the standard adaptive controller by Slotine and Li [4] cannot be applied directly to overcome the uncertainty in both kinematics and dynamics. Hence, in the presence of kinematic uncertainty, the adaptive method [4] results in tracking error or even unstable response in the end-effector’s motion. The nonlinearity and uncertainty of the robot kinematics pose a difficult and challenging adaptive tracking control problem which remains unsolved for almost two decades. III. ADAPTIVE JACOBIAN TRACKING CONTROL
where JI (r) is the image Jacobian matrix [32] and Je (q ) is the manipulator Jacobian matrix of the mapping from joint space to Cartesian space. In the presence of uncertainties in the camera parameters, the exact image Jacobian matrix and the manipulator Jacobian matrix cannot be obtained. If a position sensor is used to monitor the position of the end-effector, the task space is defined as Cartesian space and, hence, J (q ) = Je (q ) where Je (q ) is the manipulator Jacobian. A property of the kinematic equation described by (2) is stated as follows [26]. Property 4: The right hand side of (2) is linear in a set of kinematic parameters k = (k1 ; 1 1 1 ; kq )T , such as link lengths and joint offsets. Hence, (2) can be expressed as
M (q)J 01 (q)x +
1025
l2 c12 + lo c12o
In this section, we present an adaptive Jacobian tracking controller for robot with uncertain kinematics, dynamics, and actuator model. The main idea of the derivation is to introduce an adaptive sliding vector based on estimated task-space velocity, so that kinematic, dynamic, and actuator adaptation can be performed concurrently. In the presence of kinematic uncertainty, the parameters of the Jacobian matrix is uncertain and, hence, (3) can be expressed as
x^_ = J^(q; ^k )q_ = Yk (q; q_)^k
(4)
^_ 2 Rm denotes an estimated task-space velocity, J^(q; ^k ) 2 where x m2n R is an approximate Jacobian matrix, and ^k 2 Rq denotes a set of estimated kinematic parameters. Let us define a vector x_ r 2 Rm as
x_ r = x_ d 0 (x 0 xd )
(5)
where xd 2 Rm is a desired trajectory, x_ d = dxd =dt 2 Rm is the desired velocity specified in task space, and is a positive constant. Differentiating (5) with respect to time, we have
xr = xd 0 (x_ 0 x_ d )
(6)
m where x d = dx_ d =dt 2 R is the desired acceleration in task space. Next, define an adaptive task-space sliding vector using (4) as
s^x = x^_ 0 x_ r = J^(q; ^k )q_ 0 x_ r
(7)
where J^(q; ^k )q_ = Yk (q; q_ )^k as indicated in (4). The above vector is adaptive in the sense that the parameters of the approximate Jacobian matrix is updated by a parameter update law (18). Differentiating (7) with respect to time, we have
s^_ x = x^ 0 xr = J^(q; ^k )q + J_^(q; ^k )q_ 0 xr
(8)
1026
IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 51, NO. 6, JUNE 2006
^
^_
where x denotes the derivative of x. In the redundant case, the null space of the approximate Jacobian matrix can be used to minimize a performance index [13], [31]. Next, let
q_r = J^+ (q; ^k )_xr + In 0 J^+ (q; ^k )J^(q; ^k )
where x x 0 xd , x x 0 xd , and Kv 2 Rm2m and Kp 2 m 2 m R are symmetric positive–definite gain matrices, ii) a dynamic adaptation law
1 =
1_ = _ _
^_ d = 0Ld YdT (q; q;_ q_r ; qr )s
(9)
^ ( ^ ) = ^ ( ^ )( ^( ^ ) ^ ( ^ ))
where J + q; k J T q; k J q; k J T q; k 01 is the generalized inverse of the approximate Jacobian matrix, and 2 Rn is minus the gradient of the convex function to be optimized. In this note, we assume that the robot is operating in a finite task space such that the approximate Jacobian matrix is of full rank. From (9), we have
(17)
iii) a kinematic adaptation law
^_ k = Lk YkT (q; q_)(Kv 1_x + Kp 1x)
(18)
and iv) an actuator adaptation law
qr = J^+ (q; ^k )xr + J_^ (q; ^k )_xr + In 0 J^+ (q; ^k )J^(q; ^k ) +
+ 0J_^ (q; ^k )J^(q; ^k ) 0 J^+ (q; ^k )J_^(q; ^k )
:
_ (10)
...
(11)
o = J^T (q; ^k )(Kv 1_x + Kp 1x) 0 Yd (q; q;_ q_r ; qr )^d :
and
(20)
^
s_ = q 0 qr :
(12)
From (9) and (11), we note that
J^(q; ^k )s = (x^_ 0 x_ d ) + (x 0 xd ) = s^x :
(13)
Substituting (11) and (12) into (1), the equations of motion can be expressed as
M (q)_s + B + 1 M_ (q) + S (q; q_) s + M (q)qr +
2
(19)
where Lk 2 Rq2q and Ld 2 Rp2p are symmetric positive–definite matrices, La 2 Rn2n is a positive–definite and diagonal matrix, Ya o diag f0o1 ; 0o2 ; ; 0on g, and oi denotes the ith element of the vector o which is defined as
( )=
Hence, we have an adaptive sliding vector in joint space as
s = q_ 0 q_r
^_a = 0La Ya (o )s
B + 1 M_ (q) + S (q; q_) q_r + g(q) = Ku:
2
(14)
From Property 3, the last five terms of (14) are linear in a set of dynamics parameters d and, hence, can be expressed as
M (q)qr + B + 1 M_ (q)+ S (q; q_) q_r + g(q)= Yd (q; q;_ q_r ; qr )d
2
so the dynamic (14) can be written as
M (q)_s + B + 1 M_ (q) + S (q; q_) s + Yd (q; q;_ q_r ; qr )d = Ku:
2
(15) The algorithm we will now derive is composed of i) a control law based on an approximate transmission matrix K 2 Rn2n as
^
u = 0K^ 01 J^T (q; ^k )(Kv 1x_ + Kp 1x) +K^ 01 Yd (q; q;_ q_r ; qr )^d + K^ 01 Ya (o )^a
(16)
In the adaptive control law (16), a constant K 01 is used to transform the control torque to an approximate actuator input. The first term is an approximate Jacobian transpose feedback law of the task-space velocity and position errors; the second term is an estimated dynamic compensation term; and the last term is used to compensate for the uncertainty introduced by the constant estimated transmission matrix K . The estimated dynamic parameters d is updated using (17), and the estimated kinematic parameters k of the approximate Jacobian matrix J q; k is updated using (18). The linear parameterization of the kinematic parameters is obtained from (3). The key novelties are that the algorithm is now augmented by a kinematic adaptation law (18) and an actuator adaptation law (19) and that a specific choice of qr is exploited throughout. In the proposed controller, x is measured from a position sensor. Many commercial sensors are available for measurement of x, such as vision systems, electromagnetic measurement systems, position sensitive detectors, or laser trackers. The closed-loop dynamics is obtained by substituting (16) into (15) to give
^
^( ^ )
^
^
_
M (q)_s + B + 1 M_ (q) + S (q; q_) s + Yd (q; q;_ q_r ; qr )1d 2 + J^T (q; ^k )(Kv 1_x + Kp 1x) + (K K^ 01 0 I )o (21) 0 K K^ 01Ya (o )^a = 0
1 = ^
^
where o is defined in (20) and d d 0 d . The estimated kinematic parameters k of the approximate Jacobian matrix J q; k is updated by the parameter update (18) and then used in the inverse approximate Jacobian matrix J + q; k , qr , and qr in the dynamic regressor matrix. Note that k (like q and q ) is just part of the states of the adaptive control system and, hence, can be used in the control variables even if it is nonlinear in the variables (provided that a linear parameterization can be found elsewhere in the system model i.e., (3)). Since J q; k and its inverse J + q; k are updated by q + and k , J q; k and J q; k are functions of q , q , k , x, and x because k is described by (18).
^( ^ )
^ _^( ^ ) ^_
^
^( ^ ) _^ ( ^ )
^ ( ^) _ _
^ ( ^) _^ 1
1_
IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 51, NO. 6, JUNE 2006
^
( )
Since K , K , and Ya o are diagonal matrices, the last two terms of (21) can be expressed as
(K K^ 01 0 I )o 0 K K^ 01 Ya (o )^a = Ya (o)(a 0 K K^ 01^a ) (22) =1 ( ^) ^
^
0 ki =ki and ki and ki are the ith diagonal elements where ai of K and K , respectively. Substituting (22) into (21), we have M (q)_s + B + 1 M_ (q) + S (q; q_) s + Yd (q; q;_ q_r ; qr )1d +
2 ^J T (q; ^k )(Kv 1x_ + Kp 1x) + Ya (o)1a = 0
1 =
^ ^_
1 _ =
^ ^
(23)
where a a 0 K K 01 a and, hence, a 0K K 01 a . Let us define a Lyapunov-like function candidate as
V
= 12 sT M (q)s + 12 1dT Ld011d + 21 1kT Lk011k ^ 01 1a + 1 1xT (Kp + Kv )1x + 21 1aT La01KK 2 1 =
= sT M (q)_s + 21 sT M_ (q)s 0 1dT Ld01^_ d 0 1kT Lk01^_ k 01aT La01^_ a + 1xT (Kp + Kv )1_x: ^_
^_
= 02sT Bs_ 0 21x_ T Kv 1x 0 21xT Kp 1x:_ This shows that V is bounded since 1x, 1x_ , and 1 x are all bounded. Hence, V_ is uniformly continuous. Using Barbalat’s lemma, we have 1x = x 0 xd ! 0, 1x_ = x_ 0 x_ d ! 0, and s ! 0 as t ! 1.444 Remark 2: If the kinematic parameter update (18) is modified as
^_ k = 0P YkT (q; q_)P (x^_ 0 x_ ) + Lk YkT (q; q_)(Kv 1_x + Kp 1x)
^_
= 0sT Bs 0 s^xT (Kv 1x_ + Kp 1x) + 1xT (Kp + Kv )1x_ 01kT YkT (q; q_)(Kv 1_x + Kp 1x):
_
V
Substituting M q s from (23), k from (18), d from (17), and a from (19) into the aforementioned, using Property 2 and (13), yields
V_
0
(24)
^
( )_
() _ 1 1 1 1 1 1 1 1 ^ ^ ^ ^ = ^( ^ ) 1 _ _ _ _ _ 1__ ^ 1 1_ _ () _ _ ^_
Proof: Since M q is uniformally positive–definite, V in (24) is positive–definite in s, x, k , d , and a . Since V , V is also bounded, and, therefore, s, x, k , d , and a are bounded vectors. This implies that k , d , and a are bounded, x is bounded if xd is bounded, and sx J q; k s is bounded. Since x is bounded, xr in (5) is also bounded if xd is bounded. Therefore, qr in (9) is also bounded if the approximate Jacobian matrix is of full rank. From (11), q is bounded and the boundedness of q means that x is bounded since the Jacobian matrix is bounded. Hence, x is bounded and xr in (6) is also bounded if xd is bounded. From (18), k is, therefore, bounded since x, x, and q are bounded and Yk 1 is a trigonometric function of q . Therefore, qr in (10) is bounded. From the closed-loop (23), we can conclude that s is bounded. The boundedness of s imply the boundedness of q as seen from (12). From (8), sx is, therefore, bounded. Finally, differentiating (26) with respect to time and rearranging yields
1x + 1x_ = s^_ x + Y_k (q; q;_ q)1k 0 Yk (q; q_)^_ k which means that 1 x = x 0 xd is also bounded. To apply Barbalat’s lemma, let us check the uniform continuity of V_ . Differentiating (28) with respect to time gives
where k k 0 k . Differentiating with respect to time and using Property 1, we have
V_
1027
(25)
_
where P is a symmetric positive–definite matrix, this adds to V minus the P square norm of Yk q; q k . Hence, Yk q; q k also converges to zero. In addition, if the persistent excitation condition is satisfied, the convergence of k to k can be achieved. Remark 3: From (26), the adaptive sliding vector can be expressed as
( _)1 ^
( _)1
From (7), (3), and (5), we have
s^x = 1x_ + 1x 0 Yk (q; q_)1k where
^_ Yk (q; q_)1k = J (q)_q 0 J^(q; ^k )q_ = x_ 0 x:
(27)
= 0sT Bs 0 1x_ T Kv 1x_ 0 1xT Kp 1x 0:
(28)
We are now in a position to state the following theorem. Theorem: The adaptive Jacobian tracking control law (16) and the parameter update laws(17)–(19) guarantee the stability and result in the convergence of position and velocity tracking errors of the adaptive control system, that is x 0 xd ! and x 0 xd ! as t ! 1.
0
_ _
0
(29)
Hence, the signs of the parameter update laws in (18) and (17) are different because the last term in (16) is positive, while the last term in the aforementioned is negative. Remark 4: As seen from (11) and (29), if Yk q; q k also converges to zero, the convergence of x and x to zero implies that q converges to qr (even if B ). Remark 5: In this note, we assume that the robot is operating in a finite task space such that the approximate Jacobian matrix is of full rank. Note from (9) that J + q; k is used only in the definition of control variable qr . Therefore, we should be able to control this by bounding the variable or using a singularity-robust inverse of the approximate Jacobian matrix [31]. A projection algorithm can be used to ensure that k remains bounded in an appropriate region [23]. Hence, singularities only depend on q , not k . It may also be possible to avoid boundary singularities by originally overestimating the size of the robot.
_
Substituting (26) into (25) yields
V_
s^x = 1x_ + 1x + Yk (q; q_)^k 0 Yk (q; q_)k :
(26)
_
^
=0
^ ( ^) ^
1
1_
( _)1
_
1028
IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 51, NO. 6, JUNE 2006
Fig. 1. Path and position errors of first experiment.
Fig. 2. Path and position errors of second experiment.
Remark 6: Following [13], a simplification of the computation of (10) can be written as qr = J^+ (q; ^k ) x r
0 J_^(q; ^k )q_r 2
+ (In
0 J^+ (q; ^k )J^(q; ^k )
T _ + J_^ (q; ^k )J^+T (q; ^k )(q_r
0
)
where the derivative of the generalized inverse is not required.
effector. The task-space velocities are obtained from differentiation of the measured position. The robot is required to hold an object with uncertain length and grasping angle and follow a circular trajectory specified in Cartesian space as
Xd = 0:33 + 0:1 sin(0:54 + 3t); Yd = 0:41 + 0:1 cos(0:54 + 3t):
The relationship between the velocities in task space and the velocities of the joints is given by
IV. EXPERIMENTAL RESULTS To illustrate the performance of the adaptive Jacobian tracking controller, we implemented the proposed controller on a two-link direct drive robot [26], using a personal computer (PC) with Pentium II processor. The controller is running in Microsoft Windows NT together with VenturCom’s RTX, a hard real-time extension. The sampling period is set as 3 ms. A position sensitive detector (PSD) camera manufactured by Hamamatsu is used to measure the position of the robot end
x_ = J (q )q_ s1 q_1 s12 (q_1 + q_2 ) = c1 q_1 c12 (q_1 + q_2 ) l1 l2 + lo co lo s o
0
2
0
0c12 (q_1 + q_2 ) 0s12 (q_1 + q_2 ) (30)
IEEE TRANSACTIONS ON AUTOMATIC CONTROL, VOL. 51, NO. 6, JUNE 2006
where l1 and l2 are the link lengths, l0 and q0 are the length and grasping angle of the object, respectively, c1 = cos q1 , s1 = sin q1 , c12 = cos(q1 + q2 ), s12 = sin(q1 + q2 ), c12o = cos(q1 + q2 + qo ), s12o = sin(q1 + q2 + qo ), co = cos qo , and so = sin qo ,. The proposed controller in the Theorem was implemented on the robot holding an object with uncertain length and grasping angle. The length of the object was approximately set as 0.06 m and the grasping angle was approximately set as 45 . The object length and grasping angle were estimated as ^ lo (0) = 0:12 m and q^o (0) = 20 , respectively, and the link lengths were set as ^ l1 (0) = 0:25 m and ^l2 (0) = 0:27 m. The initial position of the robot end effector was specified as (X (0); Y (0)) = (0:28; 0:52). ^ = [2:45; 0:95]. Experimental The actuator model is estimated as K results with La = diagf0:15; 0:10g, Lk = diagf0:13; 0:15; 0:015g, Ld = diagf0:01; 0:002; 0:002; 0:002; 0:015; 0:01; 0:01g, Kv = diagf2; 2g, Kp = diagf420; 380g, and = 1:2 are presented in Fig. 1. As seen from the results, the tracking errors converge with updating of the estimated actuator, kinematic, and dynamic parameters. In the second experiment, we varied the actual length and grasping angle of the object. The length of the object was approximately set as 0.1 m and the grasping angle was approximately set as 60 . The experiment results are shown in Fig. 2. V. CONCLUSION We have proposed an adaptive Jacobian controller for the tracking control of robot with uncertain kinematics, dynamics, and actuator model. Novel parameter update laws are proposed to update uncertain kinematics, dynamics, and actuator parameters. We have shown that the robot end effector is able to track a desired trajectory with the uncertain parameters being updated online by the proposed parameter update laws. Experimental results illustrate the performance of the proposed controller.
REFERENCES [1] M. Takegaki and S. Arimoto, “A new feedback method for dynamic control of manipulators,” ASME J. Dynam. Syst., Meas. Control, vol. 102, pp. 119–125, 1981. [2] S. Arimoto, Control Theory of Nonlinear Mechanical Systems—A Passivity-Based and Circuit-Theoretic Approach. Oxford, U.K.: Clarendon Press, 1996. [3] J. J. Craig, P. Hsu, and S. S. Sastry, “Adaptive control of mechanical manipulators,” Int. J. Robot. Res., vol. 6, no. 2, pp. 16–28, 1987. [4] J. J. E. Slotine and W. Li, “On the adaptive control of robot manipulators,” Int. J. Robot. Res., no. 6, pp. 49–59, 1987. [5] ——, “Adaptive manipulator control: a case study,” IEEE Trans. Autom. Control, vol. 33, no. 11, pp. 995–1003, Nov. 1988. [6] R. H. Middleton and G. C. Goodwin, “Adaptive computed torque control for rigid link manipulators,” Syst. Control Lett., vol. 10, pp. 9–16, 1988. [7] D. E. Koditschek, “Adaptive techniques for mechanical systems,” in Proc. 5th Yale Workshop Applications of Adaptive Systems Theory, New Haven, CT, 1987, pp. 259–265. [8] J. T. Wen and D. Bayard, “New class of control laws for robotic manipulators—Part 2. Adaptive case,” Int. J. Control, vol. 47, no. 5, pp. 1387–1406, 1988. [9] B. Paden and R. Panja, “A globally asymptotically stable ‘PD+’ controller for robot manipulator,” Int. J. Control, vol. 47, no. 6, pp. 1697–1712, 1988. [10] R. Kelly, R. Carelli, and R. Ortega, “Adaptive motion control design of robot manipulators. An input-output approach,” Int. J. Control, vol. 50, no. 6, pp. 2563–2581, 1989. [11] R. Ortega and M. W. Spong, “Adaptive motion control of rigid robots: a tutorial,” Automatica, vol. 25, no. 6, pp. 877–888, 1989. [12] N. Sadegh and R. Horowitz, “Stability and robustness analysis of a class of adaptive controllers for robotic manipulators,” Int. J. Robot. Res., vol. 9, no. 3, pp. 74–92, 1990. [13] G. Niemeyer and J. J. E. Slotine, “Performance in adaptive manipulator control,” Int. J. Robot. Res., vol. 10, no. 2, pp. 149–161, 1991.
1029
[14] H. Berghuis, R. Ortega, and H. Nijmeijer, “A robust adaptive robot controller,” IEEE Trans. Robot. Autom., vol. 9, no. 6, pp. 825–830, Dec. 1993. [15] L. L. Whitcomb, A. Rizzi, and D. E. Koditschek, “Comparative experiments with a new adaptive controller for robot arms,” IEEE Trans. Robot. Autom., vol. 9, no. 1, pp. 59–70, Feb. 1993. [16] K. W. Lee and H. Khalil, “Adaptive output feedback control of robot manipulators using high gain observer,” Int. J. Control, vol. 67, no. 6, pp. 859–868, 1997. [17] P. Tomei, “Robust adaptive friction compensation for tracking control of robot manipulators,” IEEE Trans. Autom. Control, vol. 45, no. 11, pp. 2164–2169, Nov. 2000. [18] S. Arimoto, “Robotics research toward explication of everyday physics,” Int. J. Robot. Res., vol. 18, no. 11, pp. 1056–1063, 1999. [19] A. Bicchi, “Hands for dexterous manipulation and robust grasping: a difficult road toward simplicity,” IEEE Trans. Robot. Autom., vol. 16, no. 6, pp. 652–662, Dec. 2000. [20] T. Yoshikawa, “Force control of robot manipulators,” in Proc. IEEE Conf. Robotics and Automation, San Francisco, CA, 2000, pp. 220–226, Invited session on robot control. [21] C. C. Cheah, S. Kawamura, and S. Arimoto, “Feedback control for robotic manipulators with an uncertain Jacobian matrix,” J. Robot. Syst., vol. 12, no. 2, pp. 119–134, 1999. [22] C. C. Cheah, M. Hirano, S. Kawamura, and S. Arimoto, “Approximate Jacobian control for robots with uncertain kinematics and dynamics,” IEEE Trans. Robot. Autom., vol. 19, no. 4, pp. 692–702, Aug. 2003. [23] W. E. Dixon, “Adaptive regulation of amplitude limited robot manipulators with uncertain kinematics and dynamics,” in Proc. Amer. Control Conf., Boston, MA, 2004, pp. 3844–3939. [24] C. C. Cheah, S. Kawamura, and S. Arimoto, “Stability of hybrid position and force control for robotic manipulator with uncertain kinematics and dynamics,” Automatica, vol. 39, no. 5, pp. 847–855, 2003. [25] C. C. Cheah, H. Han, S. Kawamura, and S. Arimoto, “Grasping and position control of multi-fingered robot hands with uncertain jacobian matrices,” in Proc. IEEE Int. Conf. Robotics Automation, Leuven, Belgium, 1998, pp. 2403–2408. [26] C. C. Cheah, C. Liu, and J. J. E. Slotine, “Approximate jacobian adaptive control for robot manipulators,” in Proc. IEEE Int. Conf. Robotics Automation, New Orleans, LA, 2004, pp. 3075–3080. [27] ——, “Adaptive Jacobian tracking control of robots based on visual task-space information,” in Proc. IEEE Int. Conf. Robotics Automation, 2005, pp. 3509–3514. [28] F. L. Lewis, C. T. Abdallah, and D. M. Dawson, Control of Robot Manipulators. New York: Macmillan, 1993. [29] J. J. E. Slotine and W. Li, Applied Nonlinear Control. Englewood Cliffs, NJ: Prentice-Hall, 1991. [30] O. Khatib, “A unified approach for motion and force control of robot manipulators: the operation space formulation,” IEEE Trans. Robot. Autom., vol. 3, no. 1, pp. 43–53, Feb. 1987. [31] Y. Nakamura, Advanced Robotics. Reading, MA: Addison-Wesleyn, 1985. [32] G. H. S. Hutchinson and P. Corke, “A tutorial on visual servo control,” IEEE Trans. Robot. Autom., vol. 12, no. 5, pp. 651–670, Oct. 1996.