6
HAVE 2008 - IEEE International Workshop on Haptic Audio Visual Environments and their Applications Ottawa, Canada, October 18–19, 2008 Linear Velocity and Acceleration Estimation of 3 DOF Haptic Interfaces Jilin Zhou, Xiaojun Shen, Emil M. Petriu, and Nicolas D. Georganas Distributed and Collaborative Virtual Environments Research Laboratory (DISCOVER) School of Information and Technology University of Ottawa Ottawa, Ontario K1N 6N5 Email: jzhou/shen/petriu/[email protected] Abstract – Velocity and acceleration of the end effector of a haptic interface are required for haptic rendering in many aspects such as software damping, friction force rendering, and position control, etc. However, due to limited sensor resolution, non-linearity of forward kinematics, high maneuverability of human arm/hand, and high sam- pling rate requirement, getting a precise and robust velocity and ac- celeration estimation is very challenging. In this paper, an adaptive 4-state Kalman filter to estimate the velocity and the acceleration of the end effector is proposed considering that the human arm/hand trajectory has at least 5 non-zero derivatives and the skilled move- ments follows the constrained minimum jerk trajectory planning. The preliminary simulation results show the effectiveness of the proposed method. Keywords – Haptic interface, velocity, acceleration, minimum-jerk, Kalman filter. I. INTRODUCTION A haptic interface is a kind of human computer interface which allows the manual interactions with the virtual environ- ments. Currently, there are mainly two types of haptic inter- faces which are designed to provide kinesthetic and cutaneous feedback respectively. The kinesthetic feedback haptic inter- face usually consists of a set of rigid links connected together by a set of joints. A tool, usually a pen-like end effector, is attached to the end of the interface to interact with the vir- tual environments. Motors are attached to the joints so that the feedback force from the virtual environments can be displayed to the users. In haptic applications, an accurate velocity and acceleration estimation is important in many aspects. Some of them are as follows: The mechanical system of the impedance control haptic interface is designed to have very small physical damp- ing. It is important to have active software damping with velocity feedback to improve the stability of the system [1]. The velocity and acceleration information is important to many control algorithms for tele-operations [2]. For rendering of complex and detailed virtual objects, the computation intensive collision detection module is de- coupled from the timing critical haptic servo loop [3]. The velocity and acceleration information is required to predict the local contact model. The velocity and the acceleration give the momentum in- formation during contact transition [4]. For example, we feel more pain when we hit a wall at a high speed than at a slow speed. The velocity information is often needed to simulate the friction force and the surface texture [5]. The movement of a haptic interface is usually sensed by means of optical encoders attached to the motor shafts. Since most of the currently available haptic interfaces are equipped with neither tachometers nor accelerometers, the velocity and the acceleration information have to be derived from the position measurements. Here we are only interested in the linear ve- locity and acceleration of the end effector which are needed in the simulations, but not the joint velocity of the device. Generally, to get the velocity of a point on the end effector, the joint velocity is first estimated from the joint angle’s mea- surements and then converted into the linear velocity using the device’s current Jacobian matrix. Let’s consider a sin- gle joint encoder with a resolution of Δ=0.003 rad. N is the number of increments measured during a sampling interval T =0.001s. The joint velocity estimated with the first-order difference method is N Δ/T , which gives a velocity resolution of Δ/T =3rad/s. For a lever with a length L = 100 mm connected to the joint, the linear velocity resolution at the lever end is then ΔL/T = 300mm/s. The higher the sam- pling rate, the worse the velocity resolution will be. The ac- celeration estimate is even worse, which gives a resolution of ΔL/T 2 = 300m/s 2 . Apparently, the first-order difference method fails because the high frequency noise components are correspondingly amplified. On the other hand, sophisticated filters often suffer from the drawback that their performance degrades significantly when the actual motion departs from the assumed model. In addition, this conversion from the joint space into the Cartesian space does not reflect the causality of the real situation. It is that the user manipulates the end effector in Cartesian space which induces the joints’ motions in the joint space, but not vice versa. Therefore, due to the limited shaft encoder resolution, the non-linearity of forward kinematics, the high maneuverability of human arm/hand, and 978-1-4244-2669-0/08/$25.00 ©2008 IEEE

[IEEE 2008 IEEE International Workshop on Haptic Audio visual Environments and Games (HAVE 2008) - Ottawa, ON, Canada (2008.10.18-2008.10.19)] 2008 IEEE International Workshop on Haptic

Embed Size (px)

Citation preview

Page 1: [IEEE 2008 IEEE International Workshop on Haptic Audio visual Environments and Games (HAVE 2008) - Ottawa, ON, Canada (2008.10.18-2008.10.19)] 2008 IEEE International Workshop on Haptic

HAVE 2008 - IEEE International Workshop on

Haptic Audio Visual Environments and their Applications

Ottawa, Canada, October 18–19, 2008

Linear Velocity and Acceleration Estimation of 3 DOF Haptic Interfaces

Jilin Zhou, Xiaojun Shen, Emil M. Petriu, and Nicolas D. Georganas

Distributed and Collaborative Virtual Environments Research Laboratory (DISCOVER)

School of Information and Technology

University of Ottawa

Ottawa, Ontario K1N 6N5

Email: jzhou/shen/petriu/[email protected]

Abstract – Velocity and acceleration of the end effector of a haptic

interface are required for haptic rendering in many aspects such as

software damping, friction force rendering, and position control, etc.

However, due to limited sensor resolution, non-linearity of forward

kinematics, high maneuverability of human arm/hand, and high sam-

pling rate requirement, getting a precise and robust velocity and ac-

celeration estimation is very challenging. In this paper, an adaptive

4-state Kalman filter to estimate the velocity and the acceleration of

the end effector is proposed considering that the human arm/hand

trajectory has at least 5 non-zero derivatives and the skilled move-

ments follows the constrained minimum jerk trajectory planning. The

preliminary simulation results show the effectiveness of the proposed

method.

Keywords – Haptic interface, velocity, acceleration, minimum-jerk,

Kalman filter.

I. INTRODUCTION

A haptic interface is a kind of human computer interface

which allows the manual interactions with the virtual environ-

ments. Currently, there are mainly two types of haptic inter-

faces which are designed to provide kinesthetic and cutaneous

feedback respectively. The kinesthetic feedback haptic inter-

face usually consists of a set of rigid links connected together

by a set of joints. A tool, usually a pen-like end effector, is

attached to the end of the interface to interact with the vir-

tual environments. Motors are attached to the joints so that the

feedback force from the virtual environments can be displayed

to the users. In haptic applications, an accurate velocity and

acceleration estimation is important in many aspects. Some of

them are as follows:

• The mechanical system of the impedance control haptic

interface is designed to have very small physical damp-

ing. It is important to have active software damping with

velocity feedback to improve the stability of the system

[1].

• The velocity and acceleration information is important to

many control algorithms for tele-operations [2].

• For rendering of complex and detailed virtual objects, the

computation intensive collision detection module is de-

coupled from the timing critical haptic servo loop [3].

The velocity and acceleration information is required to

predict the local contact model.

• The velocity and the acceleration give the momentum in-

formation during contact transition [4]. For example, we

feel more pain when we hit a wall at a high speed than at

a slow speed.

• The velocity information is often needed to simulate the

friction force and the surface texture [5].

The movement of a haptic interface is usually sensed by means

of optical encoders attached to the motor shafts. Since most

of the currently available haptic interfaces are equipped with

neither tachometers nor accelerometers, the velocity and the

acceleration information have to be derived from the position

measurements. Here we are only interested in the linear ve-

locity and acceleration of the end effector which are needed

in the simulations, but not the joint velocity of the device.

Generally, to get the velocity of a point on the end effector,

the joint velocity is first estimated from the joint angle’s mea-

surements and then converted into the linear velocity using

the device’s current Jacobian matrix. Let’s consider a sin-

gle joint encoder with a resolution of ∆ = 0.003 rad. N is

the number of increments measured during a sampling interval

T = 0.001s. The joint velocity estimated with the first-order

difference method is N∆/T , which gives a velocity resolution

of ∆/T = 3rad/s. For a lever with a length L = 100 mmconnected to the joint, the linear velocity resolution at the

lever end is then ∆L/T = 300mm/s. The higher the sam-

pling rate, the worse the velocity resolution will be. The ac-

celeration estimate is even worse, which gives a resolution of

∆L/T 2 = 300m/s2. Apparently, the first-order difference

method fails because the high frequency noise components are

correspondingly amplified. On the other hand, sophisticated

filters often suffer from the drawback that their performance

degrades significantly when the actual motion departs from the

assumed model. In addition, this conversion from the joint

space into the Cartesian space does not reflect the causality

of the real situation. It is that the user manipulates the end

effector in Cartesian space which induces the joints’ motions

in the joint space, but not vice versa. Therefore, due to the

limited shaft encoder resolution, the non-linearity of forward

kinematics, the high maneuverability of human arm/hand, and

978-1-4244-2669-0/08/$25.00 ©2008 IEEE

Page 2: [IEEE 2008 IEEE International Workshop on Haptic Audio visual Environments and Games (HAVE 2008) - Ottawa, ON, Canada (2008.10.18-2008.10.19)] 2008 IEEE International Workshop on Haptic

the high sampling requirement of haptic simulations, getting a

precise and robust velocity and acceleration estimation is very

challenging.

In this paper, an adaptive 4-state Kalman filter to estimate

the velocity and the acceleration of the end effector is pro-

posed considering that the human arm/hand trajectory has at

least 5 non-zero derivatives and the skilled movements follows

the constrained minimum jerk trajectory planning. The rest of

the paper is organized as follows: previous methods in the liter-

ature are discussed in Sec. 2, Sec. 3 presents the minimum-jerk

movement characteristic, Sec. 4 presents the proposed method,

the preliminary simulation results are given in Sec. 5, and Sec.

6 concludes the paper and lists some future work.

II. RELATED WORK AND DISCUSSIONS

In [6], Friedland uses a Kalman filtering technique to an-

alyze the achievable position and velocity accuracy in a sys-

tem which measures position at a uniform sampling interval

of T . With the assumption of a zero mean, uncorrelated, and

piecewise-constant acceleration, the author shows that it is pos-

sible to estimate the position with a greater accuracy than the

inherent sensor resolution by use of a sufficiently high sam-

pling rate which satisfies

T < 0.49

σa

, (1)

where ∆ is the inherent sensor resolution, and σa is the rms

of the acceleration. But for the velocity estimation, it is al-

ways greater than the unity. The higher the product of σaT ,

the worse the estimated velocity resolution.

In [7] and [8], Belanger et al. studies the asymptotic be-

havior of the Kalman filtering for the robotic joint velocity and

acceleration estimation as T tends to zero. The angle signal

is assumed to be generated by passing a white noise through

a linear and all-pole filter. As T goes to zero, this all-pole

filter can be simplified to a multi-integrator system. If both ve-

locity and acceleration estimates are desired, at least a triple-

integrator model is needed. Otherwise, a double-integrator is

used for only velocity estimates. In [7], a single robot joint un-

der PD control is used to compare different estimation meth-

ods. The simulation results are consistent with Eq. 1. Com-

pared with the first-order finite difference method, the triple-

integrator model is 2∼4 times better in terms of the standard

deviation (SD) of the velocity estimation, and there is an or-

der of magnitude improvement in the acceleration estimation.

For a 10 ms sampling interval, the first-order finite difference

method does give an acceptable velocity estimation, but the

acceleration estimation is totally unacceptable. Compared with

double-integrator, the triple-integrator model gives a slight bet-

ter results for the velocity estimation. However, this does not

imply that the higher the filter’s order, the better the estimation

results. It really depends on the dynamics of the motion itself.

The process noise q is considered as a tuning parameter. For

different q, there is a trade-off between the resulted mean er-

ror and the standard deviation. A smaller q gives a smoother

profile but a larger mean error, and vice versa. It implies that qshould be adjusted in real-time when the range of the acceler-

ation’s variance is large. The simulation results show that the

double integrator model is less sensitive to the choice of q.

Back in 1970, Singer derives a well-known optimal Kalman

filter to estimate the states of some maneuvering targets, such

as aircrafts, ships, and submarines, where the data sample are

received by radars[9]. In fact, the haptic interface is also a

man maneuvering target. The dynamic equation of target mo-

tion is constructed with the assumption that the target moves at

constant velocity at norm and all the maneuvering actions are

viewed as perturbations upon the constant velocity trajectory.

The maneuver capability is specified by two quantities: the

variance of the acceleration σ2m and the duration of the maneu-

vering Tm. Singer exploits an important fact that if a target is

accelerating at time t, it is likely to be accelerating also at time

t + τ for a sufficiently small τ . With the standard discretiza-

tion procedure, the discrete time target equations of motion has

a form

x(k + 1) = Φ(T, α)x(k) + u(k), (2)

where T is the sampling interval, α is the reciprocal of Tm, and

Φ(T, α) is the state transition matrix given by

Φ(T, α) =

1 T 1α2 (−1 + αT + e−αT )

0 1 1α(1 − e−αT )

0 0 e−αT

. (3)

When αT is small, Φ(T, α) and the process covariance matrix

Q(k) = E{u(k)u(k)T } reduce to

Φ =

1 T T 2/20 1 T0 0 1

, Q(k) = q

T 5

20T 4

8T 3

6T 4

8T 3

3T 2

2T 3

6T 2

2 T

, (4)

where q = 2ασ2m. They are the same as the triple-integrator

Belanger model. However, the conditions to get these re-

duced forms are different: T → 0, and αT → 0 respectively.

The process noise variance q currently has an explicit physical

meaning and it can be determined intelligently instead of using

trial-and-error. It is obvious that the Belanger triple-integrator

model takes the special form of the Singer’s model. For hap-

tic simulations where T is around 1ms for a continuous force

feedback, these reduced matrices are computationally attrac-

tive but should be used with caution. A small T does not imply

small αT . For the skillful human hand movements, α is usu-

ally large.

In [10], Janabi-Sharifi et al. proposes a first-order adaptive

windowing method which minimizes the velocity estimates’

error variance with the assumption that the position trajectory

has a piecewise continuous and bounded derivative and a uni-

formly distributed (‖ ek ‖∞= d) measurement noise. The

method is to find a maximum window size M ∈ {2, 3, · · · }

Page 3: [IEEE 2008 IEEE International Workshop on Haptic Audio visual Environments and Games (HAVE 2008) - Ottawa, ON, Canada (2008.10.18-2008.10.19)] 2008 IEEE International Workshop on Haptic

such that

|yk−i − yk−i| ≤ d, ∀i ∈ {0, 1, 2, · · · ,M − 1}, (5)

where yk−i is the position measurement at (k − i)T , yk−i =yk − iT vk, and vk = yk−yk−M+1

(M−1)T . Since only the start and

the end measurements in the window are used, the velocity

profile will have overshoots if M is small. To provide ad-

ditional smoothing, all the samples in the window are used

in the velocity estimation with the least-square method. But

does the method really work well? In Fig. 1a, a position

trajectory which has a constant velocity during time interval

((k − 8)T, kT ) is plotted. With the adaptive window method,

the window size M for each sampling point starting from k−6to k will be {2, 2, 3, 3, 4, 2, 4}. As shown in Fig. 1b, the re-

sulted velocity is quite spiky since the least-square fitting has

no much use for too small window sizes. To get an insight of

how often the window size of 2 happens, we simulate a con-

stant position trajectory with 10000 sample points corrupted

with a uniform distributed noise in the Matlab. With 100 runs,

the average number of window size of 2 is 2498. It means

that about 25% of the velocity estimation uses first-order finite

difference method which is doomed to fail for high sampling

rate. For non-constant position trajectory such as human hand

movements, this number of window size of 2 will surely hap-

pen quite often. Therefore, a minimum window size has to be

determined to compress the noise. With this minimum window

size, the least-square fitting does smooth the resulted velocity

estimation. On the other hand, if the window size becomes too

large, it induces too much time delay and affects the stability

margin of the system. Nevertheless, the idea behind is very

important, which is to compress the measurement noise while

capture the transient behavior. In [11], Liu proposes a similar

method to find the window size based on the required relative

velocity accuracy.

4.5

-0.4

-0.73

1.05

0.7

2.77

0.43

k1k n2k3k5k 4k6k7k8k

0

v

real

estimated

d

d

k1k

y

n2k3k5k 4k6k7k8k

(a) position

4.5

-0.4

-0.73

1.05

0.7

2.77

0.43

k1k n2k3k5k 4k6k7k8k

0

v

real

estimated

d

d

k1k

y

n2k3k5k 4k6k7k8k

(b) velocity

Fig. 1. Adaptive window method for velocity estimation

To get accurate estimation at both low and high velocity, Be-

langer et al. also proposed a method which switches between a

time-varying Kalman filter at high velocity and a constant-time

Kalman filtering at low velocity [8]. At the high velocity, the

pulse from the encoder triggers the filtering updates using time-

varying Kalman filter. Therefore, there are more updates for

the high velocity. On the other hand, if the time since the last

pulse is greater than a preset time and still no new pulse comes

in, the estimator will actively read the encoder value and update

with the constant-time Kalman filter. Their experimental setup

is a DC motor whose angular velocity is controlled through a

PD controller and the results show the improvement on the ac-

celeration estimation at the high velocity. But for a multi-joint

haptic interface, the implementation of the approach is more

demanding. Firstly, the low level access of the encoder signal

is needed. Secondly, in the case that one joint has a low veloc-

ity while another joint may have a high velocity at the moment,

to get the linear velocity of the end effector, synchronization of

the estimates from different joints becomes an issue.

In [12], Han et al. estimates the angular acceleration of a

manipulator joint by firstly passing the signal through a triple-

integrator Kalman filter to get raw acceleration estimates and

then feed these raw estimates to a Newton predictor to get the

final smoothed estimates. The assumption to use Newton pre-

dictor is that the acceleration signal can be expressed as a poly-

nomial [13]. An acceleration feedback control for one joint of

a 2 DOF mechatronic system is presented to compare the pro-

posed Newton predictor enhanced Kalman filtering (NPEKF)

method against the separated Kalman filtering (KF) method

and Newton predictor (NP) method. The results show that

the phase lag of the angular acceleration estimated by NPEKF

is 1/8 that estimated by NP and 1/3 by KF for a 10 Hz sine

torque input. Moreover, the NPEKF is able to suppress the

noise within the frequency range of [0,10 Hz] for the acceler-

ation signal. But Newton predictor has very large gains at the

higher frequencies and consequently the noise at the higher fre-

quency gets amplified. Since human arm/hand trajectory has a

bandwidth of 20∼30 Hz, NP is not suitable for serving our

objective.

In summary, the basic criterion of the velocity and the ac-

celeration estimation from discrete position samples is to com-

press the high frequency noise for the low speed while keep

the transient behavior of the primary signal at the high speed.

Therefore, the filtering parameters should be relied on the tra-

jectory itself. But sophisticated filters often suffer from the

model-filter mismatch drawback that their performance de-

grades significantly when the actual motion departs from the

assumed model. Theoretical analysis shows that a second-

order model with parameters varying with muscle activation

and elbow angle was unable to reproduce the experimental ob-

servations of the human arm trajectory. The least complex

competent characterization of human arm movement requires

a fourth-order model [14]. To get a suitable model to describe

the motion of the human manipulated haptic interfaces, some

known human arm trajectory characteristics may be exploited.

III. CONSTRAINT MINIMUM-JERK MOVEMENT

The human arm trajectory formation refers to the planning

and control of the kinematic aspects of arm movements [15].

Page 4: [IEEE 2008 IEEE International Workshop on Haptic Audio visual Environments and Games (HAVE 2008) - Ottawa, ON, Canada (2008.10.18-2008.10.19)] 2008 IEEE International Workshop on Haptic

The trajectory here includes both the configuration of the arm

in space and the higher derivatives of the movements. Skilled

human arm/hand movements are usually smooth and devel-

oped through training and practice. Nelson presented that in

addition to meet the task oriented objectives, many of these

skilled movements appear to satisfy more general physical

principles under different constraints [16]. The cost functions

may include time, force, impulse, energy and jerk. Among

them, jerk, which is mathematically defined as the time deriva-

tive of acceleration, gets the most attraction. Hogan studies the

minimum-jerk cost function which maximize the smoothness

of the resulted trajectory for the single-joint forearm move-

ments in [17]. Flash and Hogan then generalize this principle

to the multi-joint motions in [18]. It states that in moving from

an initial to a final position in a given time duration from t0 to

tf , the cost function to be minimized is

Cj =1

2

∫ tf

t0

{(d3x

dt3)2 + (

d3y

dt3)2 + (

d3z

dt3)2}dt, (6)

where (x(t),y(t),z(t)) is the coordinate of the hand. Flash and

Hogan solved the optimized trajectory with calculus of varia-

tions [18]. The solutions have a zero sixth derivative: x(6) = 0,

y(6) = 0, z(6) = 0. Their general expression is a 5th order

polynomial. The polynomial coefficients can be solved with

the two boundary conditions and the time duration.

The minimum-jerk model can be considered as a special

form of a more generalized hypotheses which is the minimiza-

tion of the time integral of the squared nth-derivative of the

coordinates of the hand. For each order n ∈ (1,∞), it cor-

responds to a different member of the family. In [18], Flash

and Hogan reports that the mean value of the peak to aver-

age velocity rate is close to 1.8 with a standard deviation of

∼10% based on 30 movement measurements which is close

to the minimum-jerk cost function. The peak to average ratio

increase as n increases and finally goes to infinity [19]. There-

fore, the high-oder velocity profiles are incompatible with ex-

periments. By calculating the predicted velocity profiles for

different order n, it is shown that only the minimum-jerk is

compatiable with the experimental data. Daohang et al. stud-

ied reaching movements of human arm on a constraint semi-

sphere surface in [20]. The subjects were asked to move from

one point to another point on a virtual semi-sphere surface by

holding a SensAble Phantom1 3.0 haptic device. The exper-

imental results are consistent with the theoretical analysis of

minimum jerk reaching on the surface of sphere.

IV. PROPOSED APPROACH

A. Estimation in Cartesian Space

When the user holds the end-effector, the endpoint trajec-

tory can be represented in either joint space or Cartesian space.

There are two ways to get the linear velocity of the end effector

1 SensAble Phantom is the trademark of SensAble Technologies, Inc.

0 1000 2000 3000 4000 5000 6000 7000 8000 9000 10000−100

−50

0

50

100

mm

/s

0 2000 4000 6000 8000 10000−50

0

50

samples

mm

/s

Fig. 2. Linear velocity estimation in joint and Cartesian space

in the Cartesian space. The first one is to estimate the joint ve-

locity first and then convert it into the linear velocity with the

Jacobian matrix. The second one is to compute the relative po-

sition of the end effector in Cartesian space first and estimate

the linear velocity from these position measurements directly.

Theoretically, two methods should give the same results. But

it is not the actual case because the estimation needs a model

to describe the signal itself. For a low speed trajectory, they

usually give very close results since Jacobian transformation

can be well approximated by the linearized model. But for a

high speed signal, the differences cannot be ignored. In Fig.

2, velocity estimated with both the methods are compared for

a recorded trajectory using the triple-integrator Kalman filter.

Their differences are quite large (bottom figure) and the second

method gives a much smoother velocity profile (top figure).

There are two main reasons for this specific example: motion

in the joint space does not fit the triple-integrator model well,

and the kinematic transformation between the joint space and

the Cartesian space is nonlinear.

From the perspective of human arm trajectory formation,

some researchers have argued that the trajectories are planned

in the joint variables of the arm while others have argued

that motor control is achieved by planning hand trajectories

in Cartesian space; joint rotations are then tailored to pro-

duce these desired hand movements [21]. The second view has

gained more support from the studies of planar, unconstrained

human movements [15]. The simple experiment of asking sub-

jects to move between two targets shows that the subjects gen-

erally tended to generate roughly straight trajectories with a

single-peak, bell-shaped speed profile no matter where these

two targets are located in the reachable space of the human

arm. These invariant features of movements are a strong indi-

cation that planning takes place in Cartesian space rather than

joint rotations. Furthermore, as aforementioned, it is the user

that moves the device in the Cartesian space which induces the

rotations of the device’s joints in the joint space. Therefore,

direct estimation in the Cartesian space is preferred.

B. Adaptive constraint minimum-jerk estimation

As aforementioned, human arm/hand movement for a

smooth trajectory has at least 5 non-zero derivatives. An accu-

Page 5: [IEEE 2008 IEEE International Workshop on Haptic Audio visual Environments and Games (HAVE 2008) - Ottawa, ON, Canada (2008.10.18-2008.10.19)] 2008 IEEE International Workshop on Haptic

rate model of the motion should include all these derivatives.

But a large number of derivatives make a model difficult to im-

plement in real-time. For example, a typical haptic servo loop

runs around 1 KHz for a continuous force feedback. Therefore,

commonly used models take into account less derivatives. The

model considering the second derivative of the position is re-

ferred as to acceleration model, while the model considering

the rate of the acceleration is referred as to jerk model. In [22],

Mehrotra et al. derive a full 4-state Kalman filter tracking equa-

tion for highly maneuvering target tracking in which the third

derivative of the target position, the jerk, is included. Since hu-

man arm/hand movement has at least 5 non-zero derivatives, it

will be fair to expect the jerk filter to provide a higher accuracy

than the acceleration filter.

Following the Singer model, the representation model of the

correlation function r(τ) associated with the jerk is

r(τ) = E[j(t)j(t + τ)] = σ2j e−α|τ |, α ≥ 0, (7)

where σ2j is the variance of the target jerk and α is the

reciprocal of the maneuver time constant. Through Wiener-

Kolmogorov whitening procedure, the jerk j(t) is represented

as a function driven by a white noise w(t). The differential

equation results from the whitening procedure is

j(t) = −αj(t) + w(t). (8)

Then a full 4-state jerk model Kalman filter tracking equation

for human arm movement in continuous time can be expressed

as

d

dt

xxx...x

=

0 1 0 00 0 1 00 0 0 10 0 0 −α

xxx...x

+

0001

w(t),

where x, x, x,...x denote the position, velocity, acceleration, and

jerk of the target respectively. The derivation of the discrete

model and the initialization parameters for Kalman filtering are

detailed in [22]. For the special case that αT is small, the state

transition matrix, the covariance matrix Q(k) for the process

noise, and the initial covariance matrix of error P reduces to

limαT→0

Φ(T, α) =

1 T T 2/2 T 3/60 1 T T 2/20 0 1 T0 0 0 1

, (9)

limαT→0

Q(k) = 2ασ2j

T 7

252T 6

72T 5

30T 4

24T 6

72T 5

20T 4

8T 3

6T 5

30T 4

8T 3

3T 2

2T 4

24T 3

6T 2

2 T

, (10)

limαT→0

P =

σ2m

σ2m

T

σ2m

T 2 0σ2

m

T

2σ2m

T

3σ2m

T 3

5σ2j T 2

6σ2

m

T 2

3σ2m

T 3

6σ2m

T 4 σ2j T

05σ2

j T 2

6 σ2j T σ2

j

, (11)

Kalman Filter

( )x k( )x k( )v k( )a k

( )j k

max max

min min

If ( ) ( )

? : ;

else

? : ;

t

j j j j j

j j j j j

x k x k

j

Fig. 3. Adaptive constraint minimum-jerk Kalman filtering

where σm is the measurement noise variance and σj is the jerk

variance. The filter assumes the jerk to be constant during the

sampling interval T as αT is sufficiently small.

Considering the constrained minimum-jerk characteristic of

the human arm/hand trajectory, we make the jerk variance σj

adaptive within [σminj , σmax

j ]. The estimation starts with the

minimum jerk variance. After each update, the estimated po-

sition x(k) is compared with the measured position x(k). If

their absolute difference is larger than a predefined threshold

∆t, it means that the current jerk variance is too small to cap-

ture the transient behavior of the trajectory. The jerk variance

is then increased by ∆j . On the other hand, if it is smaller than

the threshold, the jerk variance is decreased by ∆j to honor

the minimum-jerk movement. Fig. 3 illustrates the architec-

ture and the updating procedure of σj . Currently, threshold ∆t

is set to the position resolution of the device. If the human

arm movement is consistent with the constrained minimum-

jerk, the model will give a decent velocity and acceleration

estimation at each sampling instant. At the same time, the

position estimation is within the bound of the resolution ∆t.

The 4-state Kalman filter in the Fig. 3 can be replaced with a

3-state Kalman filter which represents a adaptive constrained

minimum-acceleration model.

V. SIMULATION RESULTS

Fig. 4a plots a 2D minimum-jerk trajectory with 2 via-

points. The trajectory is sampled at 1 KHz and lasts 1 sec-

ond. An uniform distributed noise [-0.03,0.03] mm is added

to the original trajectory. Its position, velocity and accelera-

tion are presented in Fig. 4b. Two estimation methods are

compared: adaptive 4-state Kalman filter and adaptive 3-state

Kalman filter. Least-square method with a window size of

30 is taken as a reference since it gives a smoothed and de-

layed estimation. As shown in Fig.4c and 4d, the constraint

minimum-jerk method outperforms both least-square and con-

straint minimum-acceleration method. In terms of the acceler-

ation estimation, 4-state KF gives a 3.648 mm/s2 mean er-

ror, while 3-state KF and LS give a mean error of 32.811

and 58.503 mm/s2 respectively. Table I lists the respective

mean errors and the standard deviations. Interestingly, if the

maneuvering acceleration variance tends to zero, the adaptive

Page 6: [IEEE 2008 IEEE International Workshop on Haptic Audio visual Environments and Games (HAVE 2008) - Ottawa, ON, Canada (2008.10.18-2008.10.19)] 2008 IEEE International Workshop on Haptic

TABLE I. Estimation Errors for minimum-jerk trajectory

method adaptive range velocity (mm/s) acceleration (mm/s2)

mean std mean std

4-state KF 0.5∼2.0 m/s2 0.047 1.153 3.648 1.315e2

3-state KF 40∼50 m/s3 0.194 1.580 32.811 2.510e2

least square M=30 1.535 17.086 58.503 3.984e2

minimum-acceleration Kalman filtering will converge to the

least square method.

−80 −60 −40 −20 0 20 40 60−60

−40

−20

0

20

40

60

80

mm

mm

(a)

0 100 200 300 400 500 600 700 800 900 1000−100

−50

0

50

100

mm

0 100 200 300 400 500 600 700 800 900 1000−500

0

500

mm

/s

0 100 200 300 400 500 600 700 800 900 1000

−2000

0

2000

samples

mm

/s2

(b)

0 100 200 300 400 500 600 700 800 900 1000

−300

−200

−100

0

100

200

samples

mm

/s

0 100 200 300 400 500 600 700 800 900 1000

−2000

0

2000

mm

/s2

original

least square

4th order KF

(c)

0 100 200 300 400 500 600 700 800 900 1000

−300

−200

−100

0

100

200

samples

mm

/s

0 100 200 300 400 500 600 700 800 900 1000

−2000

0

2000

mm

/s2

original

least square

3rd order KF

(d)

Fig. 4. (a) a minimum jerk trajectory; (b) the original trajectory, velocity and

acceleration; (c) constrained minimum-jerk; (d) constrained

minimum-acceleration).

VI. CONCLUSION AND FUTURE WORK

In this paper, a detailed literature review and discussion

on the velocity and the acceleration estimation from the po-

sition measurements are presented. Since it is the user that ma-

nipulates the end effector in the Cartesian space, we suggest

that the linear velocity and the acceleration of the end effector

should be estimated with the Cartesian position measurements

directly instead of converting from the joint velocity with the

device’s Jacobian matrix. Considering the characteristics of

the minimum-jerk movement and at least 5 non-zero deriva-

tives of the human arm/hand trajectory, a 4-state order adap-

tive Kalman filter is proposed for the velocity and the accel-

eration estimations of the end-effector of the haptic interface

hand-held by the users. The simulation results show the effec-

tiveness of the proposed method for the minimum-jerk trajec-

tory. In the future, we need develop an application to get some

experimental results.

REFERENCES

[1] J. E. Colgate and G. Schenkel, “Passivity of a class of sampled-data sys-tems: application to haptic interfaces,” in Proc. of the American ControlConference, Maryland, Canada, Jun. 1994, pp. 3236–3240.

[2] D. A. Lawrence, “Stability and transparency in bilateral teleoperation,”IEEE Trans. on Robotics and Automation, vol. 9, no. 5, pp. 614–637,Oct. 1993.

[3] J. G. Park and G. Niemeyer, “Haptic rendering with predictive represen-tation of local geometry,” in Proc. of the 12th International Symposiumon Haptic Interfaces for Virtual Environment and Teleoperator Systems(HAPTICS’04), Mar. 27–28, 2004, pp. 331–338.

[4] J. Fiene, K. J. Kuchenbecker, and G. Niemeyer, “Event-based haptictappting with grip force compensation,” in Proc. of the IEEE Symposiumon Haptic Interfaces for Virtual Environment and Teleoperator Systems,Mar. 2006, pp. 117–123.

[5] S. J. Lederman, R. L. Klatzky, C. Tong, and C. Hamilton, “The perceivedroughness of resistive virtual textures: Ii. effects of varying viscositywith a force-feedback device,” ACM Transactions on Applied Perception,vol. 3, no. 1, pp. 15–30, Jan. 2006.

[6] B. Friedland, “Optimum steady-state position and velocity estimationusing noisy sampled position data,” IEEE Transactions on Aerospaceand Electronic Systems, vol. AES-9, no. 6, pp. 906–911, Nov. 1973.

[7] P. R. Belanger, “Estimation of angular velocity and acceleration fromshaft encoder measurements,” in Proc. of the 1992 IEEE InternationalConference on Robotics and Automation, Nice, France, May 1992, pp.585–592.

[8] P. R. Belanger, P. Dobrovolny, A. Helmy, and X. Zhang, “Estimationof angular velocity and acceleration from shaft encoder measurements,”The International Journal of Robotics Research, vol. 17, no. 11, pp.1225–1233, Nov. 1998.

[9] R. A. Singer, “Estimating optimal tracking filter performance for mannedmaneuvering targets,” IEEE Transaction on Aerospace and ElectronicSystems, vol. AES-6, no. 4, pp. 473–483, Jul. 1970.

[10] F. Janabi-Sharif, V. Hayward, and C. J. Chen, “Discrete-time adaptivewindowing for velocity estimation,” IEEE Transactions on Control Sys-tems Technology, vol. 8, no. 6, pp. 1003–1009, Nov. 2000.

[11] G. Liu, “On velocity estimation using position measurements,” in Proc.of the American Control Conference, Anchorage, AK, May 8–12, 2002,pp. 1115–1120.

[12] J. D. Han, Y. Q. He, and W. L. Xu, “Angular acceleration estimation andfeedback control: an experimental investigation,” Mechatronics, vol. 17,no. 9, pp. 524–532, Nov. 2007.

[13] S. J. Ovaska, “Newton-type predictors-a signal processing oriented view-point,” Signal Processing, vol. 25, no. 2, pp. 251–257, Nov. 1991.

[14] N. Hogan, “Controlling impedance at the man/machine interface,” inProc. IEEE International Conference on Robotics and Automation, 1989,Scottsdale, AZ, USA, May 14–19, 1989, pp. 1626–1631.

[15] W. Abend, E. Bizze, and P. Morasso, “Human arm trajectory formation,”Brain, vol. 105(Pt 2), pp. 331–348, Jun. 1982.

[16] W. L. Nelson, “Physical principles for economices of skilled move-ments,” Biological Cybernetics, vol. 46, pp. 135–147, 1983.

[17] N. Hogan, “An organizing principle for a class of voluntary movements,”Journal of Neuroscience, vol. 4, no. 11, pp. 2745–2754, Nov. 1984.

[18] T. Flash and N. Hogan, “The coordination of arm movements: an experi-mental confirmed mathematical model,” Journal of Neuroscience, vol. 5,no. 7, pp. 1688–1703, Jul. 1985.

[19] M. J. E. Richardson and T. Flash, “Comparing smooth arm movementswith the two-thirds power law and the related segmented-control hypoth-esis,” The Journal of Neuroscience, vol. 22, no. 18, pp. 8201–8211, Sep.2002.

[20] D. Sha, J. Patton, and F. A. Mussa-Ivaldi, “Minimum jerk reachingmovements of human arm with mechanical constraints at endpoint,” In-ternational Journal of Computers, Systems, and Signals, vol. 7, no. 1,pp. 41–50, 2006.

[21] N. Bernstein, The Coordination and Regulation of Movements. Oxford:Pergamon Press, 1976.

[22] K. Mehrotra and P. R. Mahapatra, “A jerk model for tracking highly ma-neuvering targets,” Trans. on Aerospace and Electronic Systems, vol. 33,no. 4, pp. 1094–1105, Oct. 1997.