Autonomous Timed Movement based on Attractor Dynamics in a Ball
Hitting Task
Farid Oubbati and Gregor Sch¨oner
Institut f¨ur Neuroinformatik, Ruhr–Universit¨at Bochum, Bochum, Germany
Keywords:
Attractor Dynamics, Timed Movement, Behavioral Organization.
Abstract:
Timed robotic actions so that they are initiated or terminated just in time can be crucial in many tasks and
scenarios in which the robot has to coordinate with other robotic agents or to interact with external entities
such as moving objects. The analogy with human movement coordination has motivated an approach in
which timed movements are generated from stable periodic solutions of dynamical systems, which are turned
on and off in time to initiate and terminate a timed motor act. Here we extend this approach to generate
sequences of timed motor actions required to intercept and hit a rolling ball on an inclined plane. The proposed
system combines attractor dynamics for the robot’s end-effector heading direction, fixed point attractor for
end-effector postural states, limit cycle attractor dynamics for the end-effector speed and competitive neural
dynamics to organize the different behaviors and movement phases. The ball interception point and time to
contact are predicted based on a Kalman estimate of the ball’s kinematics. The work is implemented on a
redundant manipulator CoRA platform and the ball motion is monitored by the manipulator’s vision system.
1 INTRODUCTION
Timed movement is defined in terms of the stability
of its temporal structure, in such a way that an inher-
ent acceleration or deceleration actions are performed
so as to restore as much as possible the overall move-
ment time (Schoener, 2002). Such behavior can be
observed in most of the biological movements. For
instance, in human reaching tasks, the hand opening
is adapted to the reaching movement, i.e accelerated
or decelerated accordingly (Jeannerod, 1984). This
principle of coordination is crucial in many action-
perception human tasks such as juggling, catching,
hitting (Warren, 2006). In rhythmic movement, tim-
ing can be achieved by inserting couplings into a dy-
namical system that stabilize the phase relationships
among periodic attractors, exemplified by the con-
cept of central pattern generators and their coordina-
tion (Ijspeert, 2008). To control the timing of indi-
vidual discrete motor acts, similar ideas can be used
(Schoener, 1990). The problem is more complicated,
as the stable periodic solutions must be initiated and
terminated autonomously, requiring a form of behav-
ioral organization (Steinhage and Schoener, 1998).
In this work, we propose an architecture that com-
bines the timing of discrete motor acts directed toward
moving objects and the behavioral organizationof this
timed movements in a ball hitting task scenario. The
different task movements are planned by a non lin-
ear dynamical system in which fixed points attrac-
tors models postural states, and limit cycles attractors
are used for movement states. The behavioral organi-
zation of these different states is achieved through a
set of switching variables controlled by coupled non-
linear dynamics. The autonomous initiation and ter-
mination of the different task movements through the
switching dynamics is itself controlled by some per-
ceptual variables or parameters received from a track-
ing and prediction mechanism that involves a kalman
filter for ball position and speed estimations and a
process that delivers an estimate of the ball point
of impact (p
2c
) and time to contact (τ
2c
). Accord-
ing to these perceptual parameters, the system initi-
ate an interception and then a hitting movement ’just
in time’ returning after that to a base line ready to
initiate the next hitting task. The proposed architec-
ture is able to handle different situations like aborting
the hitting sequence if this may lead the manipulator
out of its reachable work space or reseting the hole
system if the maximum speed of the manipulator is
reached. This behavioral flexibility emerges from the
continuous-time dynamics of the variables.
Similar efforts to exploit attractor dynamics to
generate timed movements have been made in the
304
Oubbati F. and Schöner G..
Autonomous Timed Movement based on Attractor Dynamics in a Ball Hitting Task.
DOI: 10.5220/0004324003040311
In Proceedings of the 5th International Conference on Agents and Artificial Intelligence (ICAART-2013), pages 304-311
ISBN: 978-989-8565-38-9
Copyright
c
2013 SCITEPRESS (Science and Technology Publications, Lda.)
realm of the rhythmic movement underlying legged
locomotion (Raibert, 1986). A network of coupled
central pattern generators whose output could be su-
perposed with discrete trajectories has been proposed
as an integration of discrete and rhythmic movement
(S. Degallier, 2006), demonstrated in a drumming
task. The discrete movement was not, however, timed
in the sense we define this here. The learning of
movement patterns in imitation scenarios has been
successfully demonstrated using an oscillatory dy-
namical system as the substrate (A. J. Ijspeert, 2002;
S. Schaal, 2003). Comparing the attractor dynam-
ics approach to the potential field approach (Khatib,
1986) reveals a number of differences (B. R. Fajen,
2003). By choice of variable, movement is generated
while the system is in an attractor rather than while
the system is relaxing to an attractor. This facilitates
the design of the dynamical systems, making it easier
to avoid spurious attractors, and reduces oscillations.
Because the motor plan has stability properties in the
attractor dynamics approach, coupling to on-line sen-
sory input is unproblematic. The generation of tra-
jectory plans from limit cycle attractors supports sta-
ble timing. The notion of stabilizing movement time
through a mechanism of on-line updating has been ad-
dressed in scenarios of target tracking and obstacle
avoidance by a mobile robot (M. Tuma, 2009).
In this paper, we sketch how the attractor dynam-
ics approach to autonomous robotics that was orig-
inally developed in the domain of vehicle motion
(Schoener and Dose, 1992)(E. Bicho, 1996) and has
been extended to trajectory generation in robotic ma-
nipulators (Iossifidis and Schoener, 2004) can be used
to organize flexible and complex sequences of timed
actions in a relatively complex ball hitting task sce-
nario. The proposed architecture is able to initiate
and terminate the different task movements through
coupling to on-line sensory information and is imple-
mented on a redundant manipulator platform.
The remainder of the paper is organized as follows
: in Sec.2 the hardware setup, composed of a robotic
and vision systems is presented. A detailed descrip-
tion of the robotic architecture including the timed
trajectory generation is given in Sec.3. Experimen-
tal results are shown in Sec.4. Finally, a conclusion
and outlook can be found in Sec.5.
2 SETUP
This section introduces the two main components of
the experimental setup : the robotic system and the
vision system.
2.1 Robotic System
The robotic demonstration of timed movement coor-
dinated with perceived object motion employs the 8
(DoF) CoRA manipulator Fig. 1. CoRA is equipped
with a vision system for tracking and prediction of
a ball that moves on an inclined plane. The robot
arm holds a paddle of 3.5[cm] in radius that serves as
end-effector to intercept and hit the ball with a timed
movement.
The end-effector trajectory is generated in the task
space from which the corresponding joint angles are
computed through the inverse kinematics closed form
solution (Iossifidis and Schoener, 2004). The ori-
entation of the end-effector is kept constant and an
elevated elbow posture is chosen to accommodate
CoRAs work space constraints. For real time per-
formance, the implementaion was done in C++ under
Linux environment.
Figure 1: The anthropomorphic robotic assistant CoRA.
2.2 Vision System
The sensory information is acquired by a FireWire
camera (SONY DFW VL500) mounted as part of the
CoRA stereo vision system. The camera is oriented
toward the inclined plane (Pan = 0[
], Tilt = 50[
])
and operated with a frame rate of 30 [f/s] providing a
new measurement estimate every 33 [ms].
3 ROBOTIC ARCHITECTURE
The overall structure of the robotic demonstration of
timed movement coordinated with perceived object
motion is depicted in Fig. 2. it has three main mod-
ules : ball tracking, ball prediction and robot timed
trajectory generation.
In the first module, ball tracking is performed
based on visual sensor information. In the sec-
ond module, a dynamical model of the ball is
used to predict the necessary perceptual parame-
ters time to contact (τ
2c
) and point to contact (p
2c
)
based on the sensor feedback. The third module
goes through the dynamics that genertate the differ-
ent movement components that compose the ball hit-
AutonomousTimedMovementbasedonAttractorDynamicsinaBallHittingTask
305
Figure 2: The robotic architecture.
ting task. The three modules will be described in the
following subsections.
3.1 Ball Tracking Module
Different vision based techniques for object track-
ing exists (A. Yilmaz, 2006), reflecting different con-
straints on object motion and different processing
time requirements. To achieve a robust ball tracking
in the presence of image noise and non uniform light-
ing conditions, we use a color based object tracking
process: first, by building an HSV histogram-based
color model in HSV color space as an observation
system and then we used a color-based segmentation
process to estimate the ball position p
b
(t) in image
plane (Fig. 3).
The position estimate is projected to the world co-
ordinates by the camera transformation matrices. The
position measurements are then fed to a Kalman fil-
ter (Schutter, 1999) to estimate the speed of the ball
along the two movement axes of the inclined plane.
The tracking process was implemented in a multipro-
cessing pipeline so that the vision system runs in par-
allel to the robot control process enabling real time
performance with a relatively low processing time in
the control loop.
3.2 Ball Prodiction Module
The ball position and speed estimates provided by the
tracking module is then fed to the dynamics model of
the ball Eq. 1 in order to predict the time to contact
(τ
2c
) and point to contact (p
2c
).
V
j+1
= V
j
+ a
j
·t,
P
j+1
= P
j
+V
j
·t + a
j
·
t
2
2
, (1)
Where a
j
denotes the acceleration vector, V
j
and
P
j
are the velocity and position vectors respectively.
The main movement acceleration is along the y axes
pointing along the inclination of the plane:
a
y
=
g·sin(α)·m·r
2
m·r
2
+ I
(2)
Figure 3: Color-based segmentation process.
Where m is the ball mass, g is the gravitational
constant, α is the plane’s inclination, r is the ball ra-
dius and I is the ball inertia. Horizontal acceleration,
a
x
, is mainly determined by the rolling friction Eq.
3 related to movement speed and direction. Elastic
bounces of the ball off the side walls of the inclined
plane are modeled through a coefficient of restitution
C
r
representing the ratio of speeds before and after the
bounce and determined experimentally. The ball spin
is difficult to observe and model, so its contribution
is neglected as is the air drag which has negligible ef-
fects. The rolling friction, on the other hand, is mod-
eled and is empirically tuned with a non negligible
effect on the accelerations in both movement axes:
F
r
= N·
U
r
r
(3)
Here N is the Normal force, r is the ball radius and
Ur is the coefficient of rolling friction.
3.3 Timed Trajectory Generation
Robot trajectories are generated as stable solutions of
a non linear dynamical system formulated on two lay-
ers of description.
The first level is a switching dynamics for the se-
quential organization of behaviors representing the
start, execution, and termination phases of the move-
ment, each calculated depending on sensor signals
and internal measures.
At the second level of description, a dynamics for
all behavioral variables that define the robot’s kine-
matic state is integrated. The behavioral variables
ICAART2013-InternationalConferenceonAgentsandArtificialIntelligence
306
comprise the end-effector heading directions φ (az-
imuth) and θ (elevation) and the end-effector veloc-
ity V
e,j
. The generated end-effector trajectories P
e,j
=
(x
e,j
,y
e,j
,z
e,j
) are transformed into joint angles trajec-
tories q
des
(t) using the inverse kinematics and a feed-
back measurement is accomplisched through the for-
ward kinematics.
Running the vision system and the trajectory gen-
erator in parallel processes allows a robot movement
step time of 20 [ms] with a negligible effect of the tiny
dis-synchronization.
3.3.1 Movement Components
The ball hitting task consists of the following move-
ment components:
The Interception Movement: executed at con-
stant speed along a predefined base line at the bot-
tom and parallel to the inclined plane. This move-
ment must bring the robot end-effector as close as
possible to the predicted point to contact (p
2c
).
The Hitting Movement: a timed movement gen-
erated on the basis of the predicted end-effector
posture to intercept the approaching ball.
The Return Movement: a movement taking a
fixed amount of time and brings the robot end-
effector back to the base line, ready to start
another inteception-hitting-return task sequence
whenever sensory information flags a predicted
point to contact and time to contact within a de-
fined window.
The hitting movement must be initiated just in
time to hit the ball just before it has reached the
bottom of the inclined plane. Different measures
and factors are continuously monitored or updated
by the visual system and included as parameters in
the dynamical systems for trajectory generation and
behavioral organization. These include reachabil-
ity, time to contact (τ
2c
) and point to contact (p
2c
).
These parameters control the initiation of the hit-
ting movement when the ball point to contact time is
within the time to contact criterion and the ball is in-
side the robot’s work space. The hitting movement is
stopped if the ball falls out of the inclined plane after
an unsuccessful hitting attempt so that the ball is no
longer detected by the visual sensor.
3.3.2 Switching Dynamics
The switching dynamics are formulated for each of
the three ”neural” activation variables u
i
which con-
trol the different behavioral states, i = init, hopf,final
(see below), by specifying which contribution to the
behavioral dynamics is active. Values near ±1 mean
the corresponding behavior is active, values near 0
mean the corresponding behavior is inactive. The
switch between the different behavioral states of the
trajectory generator dynamics depend on sensory in-
formation and internal conditions (e.g., reaching a
critical time to contact, target reached,...). As these
factors are continuously updated and may fluctuate,
the activation states are stabilized. The switching dy-
namics is based on the normal form of a degenerate
pitchfork bifurcation for each variable, coupled com-
petitively :
τ
u
˙u
i
= µ
i
u
i
|µ
i
|u
3
i
ν
a6=i
u
2
a
u
i
(4)
Where the competitive advantages, µ
i
, determine
which activation variable is eligible for being turned
on. In general, the activation variable with the highest
positive competitive advantage is activated. The pa-
rameter, ν, controls the strength of competition and τ
u
is the dynamics time constant. The values of ν = 2.1
and 1.5 µ
i
3.5 lead to a reasonable trade-off be-
tween stability and flexibility. Neuronal weights are
linked to sensory and internal signals through a set
of quasi-boolean parameters b
i
[0, 1]. These param-
eters are normalized to keep the competitive advan-
tages within the desired range:
µ
i
= 1.5+ 2·b
i
(5)
For a more detailed illustration of this switching
mechanisms and its use in movement (re)initialization
and termination see (Steinhage and Schoener, 1998).
3.3.3 Behavioral Dynamics
Based on estimates of the point to contact p
2c
=
(x
tar
,y
tar
,z
tar
) and the current end-effector position
P
e,j
= (x
e,j
,y
e,j
,z
e,j
), two heading directions φ
tar
(az-
imuth) and θ
tar
(elevation) are defined under which
the target point is seen from the current position of
the end-effector. These set attractor states for the
end-effector, azimuthal and elevational, heading di-
rections dynamics:
˙
φ = λ
tar
·sin(φ φ
tar
) (6)
˙
θ = λ
tar
·sin(θ θ
tar
) (7)
For more details see (Iossifidis and Schoener,
2004). At each time step, the arm end-effector ve-
locity is set as the state variable x that evolves jointly
with an auxiliary state variable y according to the fol-
lowing dynamical system:
τ
v
˙x
˙y
= c
1
·u
2
init
x
y
+ u
2
hopf
· f
hopf
(x R
h
,y)
c
2
·u
2
final
x
y
(8)
AutonomousTimedMovementbasedonAttractorDynamicsinaBallHittingTask
307
Here c
1
and c
2
are scaling parametersand f
hopf
is a
Hopf oscillator of radius R
h
(time dependant, see Eq.
11). The activation variables, u
i
(u
init
,u
hopf
,u
final
),
defined in eq. 4 are used to switch between the three
different regimes : stable oscillation (Hopf oscilla-
tion) activated by u
hopf
and two initial and final fixed
point attractors activated by u
init
and u
final
. The postu-
ral states are (x,y) = (0, 0), keeping the robot at rest
before and after the movement. During the movement
phase, the velocity dynamics is governed by a Hopf
oscillator described by the normal form of the Hopf
bifurcation:
f
hopf
(x R
h
,y) =
λ ω
ω λ
x R
h
y
γ(x R
h
)
2
γy
2
x R
h
y
(9)
The fact that the limit cycle attractor can be deter-
mined analytically facilitates the interpretation of the
parameters: The angular frequency ω defines the cy-
cle time T =
2π
ω
and hence the total movement time.
The parameters λ > 0 and γ > 0 together set the oscil-
lator radius R
h
:
R
h
=
s
λ
γ
(10)
The time scale of the velocity dynamics is set to a
relaxation time of τ
v
= 0.02, ten times slower than the
relaxation time of the neuronal switching dynamics.
Generating speed profiles instead of position trajecto-
ries, gives complete control over the robot movement
speed for the hitting and return movements, a very im-
portant constraint in order to achieve safe and stable
movement within the limits of the hardware. Com-
bining the heading and velocity dynamics, the manip-
ulator end-effector trajectories become fully defined.
Timing and competitive neural dynamics of the tra-
jectory generator are numerically integrated using the
Euler method.
3.3.4 Temporal Stabilization
The presence of sensory noise and measurement er-
rors in addition to the time varying prediction of the
point to contact requires that the movement parame-
ters are updated continuously. Therefore, the hitting
movement must be parametrically updating while it is
in execution. Continuously updating the target posi-
tion (p
2c
) in the heading dynamics requires adapting
the velocity dynamics to accelerate or decelerate ac-
cording to the remaining distance to be traveled by the
end-effector with the objective of keeping the hitting
time as invariant as possible. We use this update rule
for the amplitude of the Hopf oscillation R
h
in Eq. 9:
R
h
(t) =
ω
2π
·D(t)/(1
t
T
+
sin(2π·
t
T
)
2π
) (11)
Here, D(t) is the remained distance to be traversed
at the current speed. For a complete explanation of
this update rule and a detailed illustration of its per-
formance see (M. Tuma, 2009).
3.3.5 Behaviors Specifications
The autonomous initiation, continuation, and termi-
nation of the three movement components, inter-
ception movement, hitting movement and return
movement are controlled by two sensory signals
time to contact (τ
2c
) and point to contact (p
2c
) as
well as a number of internal conditions. All these fac-
tors are expressed through the quasi-boolean parame-
ters. The conditions make use of a sigmoid function
σ(.) which returns values near 0 for negative argu-
ment and near 1 for positive argument. The predicted
time to contact is used to predict the total rolling time
of the ball on the inclined plane: (1) τ
2c
< 0 if the ball
is not detected or the ball trajectory cannot be pre-
dicted immediately after a hit; (2) τ
2c
> τ
crit
> 0 if the
ball contact is not within a criterion time to contact;
(3) 0 < τ
2c
< τ
crit
if the ball contact is predicted within
a criterion time.
1) Interception Movement. The interception move-
ment occurs at constant speed along the base line
parallel to and at the bottom of the inclined plane,
(y = 379.6[mm],z = 80[mm]). The movement is ini-
tiated and stopped by the parameter b
inter
taking on
values of 1 or 0, respectively.
b
inter
= σ(d
target
d
offset
)
·σ(τ
2c
τ
crit
)·σ(τ
2c
) (12)
Here the parameter d
target
is the distance from
the current end-effector position to the the target
or point to contact p
2c
computed continuously and
d
offset
is a small offset distance indicating that the tar-
get is reached. The choice of using a constant speed
movement instead of a timed movement was moti-
vated by the relatively major fluctuation of the early
predicted landing position. Such strong fluctuations
may induce an oscillator with the update rule to gen-
erate very large speeds that exceed the capacity of our
hardware. The speed of the interception movement,
I
speed
, is generated through a simple attractor dynam-
ics that switches smoothly between 0 and a safe max-
imum speed, max
speed
:
˙
I
speed
= λ
inter
·(I
speed
(b
inter
·max
speed
)) (13)
ICAART2013-InternationalConferenceonAgentsandArtificialIntelligence
308
Here λ
inter
sets the strength of attraction.
2) Hitting Movement. When the ball contact is
within a criterion time to contact 0 < τ
2c
< τ
crit
,
the hitting movement is initiated through the quasi-
boolean parameter:
b
hit
= b
detected
·b
reachable
·(1 σ(τ
2c
τ
crit
))
·(1 m
ret
)·σ(τ
2c
) (14)
The parameter, b
detected
, is a flag set to 1 by the vi-
sion system to indicate that the ball is being tracked.
The parameter, b
reachable
, is a flag set internally to 1 if
the ball can be hit without crashing the end-effector
into the borders of the workspace. m
ret
is a flag set to
0 initially and set to 1 dynamically when the hitting
movement is finished. Once the hitting movement is
initiated, the Hopf oscillator generate the speed pro-
file and together with heading dynamics, the hitting
movement is started. Two other parameters b
cohit
and
b
sthit
, standing for continue the hitting movement and
stop the hitting movement respectively, are evaluated
continuously during movement generation:
b
cohit
= b
detected
·(1 f
maxspeed
)·σ(τ
2c
) (15)
b
sthit
= (1 σ(d
target
d
offset
))
+ σ(d
target
d
offset
)
·σ(t
current
hit
cycletime
) (16)
Herein, d
target
is the current distance from the cur-
rent end-effectorposition to a new target position cho-
sen to be beyond the actual predicted point to contact
(p
2c
= (x
tar
,y
tar
,z
tar
)) but at equal distance with the
initial end-effector position before the hitting initi-
ation P
e,0
= (x
e,0
,y
e,0
,z
e,0
) in order to hit the ball
around the maximum speed. t
current
is the current ex-
ecution time and hit
cycletime
= 1.8[s] is the fixed hit-
ting cycle time. Stopping is indicated when b
cohit
is
set to 0, for example, when the ball becomes invisible
b
detected
= 0 or when maximum speed exceeded by the
movement plan, f
maxspeed
= 1. The condition b
sthit
is
set to 1 if the target is reached or if the oscillator time
is elapsed.
3) Return Movement. The return movement back to
the base line is initiated when the hitting is finished or
terminated:
b
ret
= (1 σ(τ
2c
τ
crit
))·(1 m
hit
) (17)
The flag, m
hit
, is set 1 initially and set to 0 dynam-
ically when the return movement is finished. Like in
the hitting movement, two other parameters b
coret
and
b
stret
are tested continuously during speed generation:
b
coret
= (1 f
maxspeed
) (18)
4) Switching between Hitting and Return Move-
ments. The flags m
hit
and m
ret
permit a correct se-
quencing between hitting and return movements so
that the return movement is initiated only once the
hitting has been initiated and terminated. Similarly,
the hitting movement is executed only after returning
to the base line. During the hitting movement, switch-
ing the flags m
hit
to 0 and m
ret
to 1 is done using two
neural variables in a competitive dynamics Eq. 4 with
these conditions:
b
mhit
= b
cohit
·(1 b
sthit
) (19)
b
mret
= (1 b
cohit
) + b
cohit
·b
sthit
(20)
Similarly, during the return movement, switching
the flags m
ret
to 0 and m
hit
to 1 is related to these con-
ditions:
b
mret
= b
coret
·(1 b
stret
) (21)
b
mhit
= (1 b
coret
) + b
coret
·b
stret
(22)
5) Maximum Speed Handling. The movementspeed
during hitting and return phases is constantly moni-
tored and when the maximum speed is reached, the
flag f
maxspeed
is set to 1 through a neuron. If the flag
f
maxspeed
is set to 1 during the hitting movement, the
Hopf oscillator is turned off by setting b
hopf
to 0 and
b
final
to 1 as well as by setting the flags, m
hit
to 0 and
m
ret
to 1, initiating the return movement. If the flag,
f
maxspeed
, is set to 1 during the return movement, an
initialization movement is started through the param-
eter:
b
initmov
= f
maxspeed
(23)
This movement brings autonomously the robot to
its initial position (in the middle of the base line)
through an oscillator with a relatively large cycle
time. An internal b
stinitmov
flag controls the termina-
tion of this phase, and the flag f
maxspeed
is set to 0
again. To organize the sequence of movement phases
in Eq. 4 of the three movement types, the competitive
advantages µ
i
in Eq. 5 were chosen to depend on a
set of logical conditions corresponding to the move-
ment component, here we show the conditions for the
hitting movement but the same conditions hold for
the return and initialization movements just by replac-
ing the parameters b
hit
, b
cohit
and d
target
by the corre-
sponding in each movement component:
b
init
= (1 b
hit
) (24)
b
hopf
= b
cohit
·(1 σ(t
current
t
offset
))
·σ(d
target
d
offset
) (25)
b
final
= (1 b
cohit
)
+ b
cohit
·σ(t
current
t
offset
)
+ b
cohit
·(1 σ(t
current
t
offset
))
·(1 σ(d
target
d
offset
)) (26)
AutonomousTimedMovementbasedonAttractorDynamicsinaBallHittingTask
309
4 RESULTS & EVALUATION
In order to evaluate the overal robotic architecture for
the ball hitting task, the following experiment was
conducted : a ball is lauched on the inclined plane
toward the top by a human operator. The ball trajec-
tory was tracked by the vision system. Based on the
predicted perceptual parameters τ
2c
and p
2c
, a timed
trajectory for the end-effector is generated.
In the following, experiemntal results for one hit-
ting task performed by the robot Fig. 1 is illustrated as
well as numerical results of multiple trials performed
in simulation.
4.1 Robot System Results
The vision system provides the trajectory generator
with a new τ
2c
and p
2c
predictions every 33 [ms].
The latter typically reaches the necessary precision of
< 4 [cm] for hitting only about a τ
2c
of 100 [ms].
The maximum speed of the end-effector is set to 400
[mm/s] observed to be the maximum limit for a safe
and stable movements. Fig. 4 shows the trajectories
of the paddle and the ball when the CoRA manipula-
tor successfully hits an approaching ball.
0 100 200 300 400 500 600 700 800
−100
0
100
200
300
400
500
600
Inclined plane x − axes [mm]
Inclined plane y − axes [mm]
x − y positions of Ball and Paddle
Ball
Paddle
interception line
hitting point
Figure 4: The movements of the paddle and the ball on the
real setup for a successful hit. The hitting point is indicated
by the black triangle.
The interception movement is started as soon as
the ball is detected by the vision system and predicted
by the kalman filter. When τ
2c
becomes smaller than a
critical value (here 1 [s]), the interception movement
is stopped and the hitting movement is initiated by the
parameter b
hit
setting the boolean parameter b
hopf
to 1
which triggers the corresponding neuron u
hopf
to start
the speed generation and with the heading dynamics,
the end-effector is driven toward the p
2c
to hit the ball.
0 0.5 1 1.5 2 2.5 3 3.5 4 4.5 5
0
200
400
timing variables
0 0.5 1 1.5 2 2.5 3 3.5 4 4.5 5
0
0.5
1
1.5
neurons
0 0.5 1 1.5 2 2.5 3 3.5 4 4.5 5
0
2
4
time [s]
t_2c
x
y
threshold reached
uinit
uhopf ufinal
hitting
return
interception
hitting occures
Figure 5: Trajectories of the timing and neural variables
of an autonomous hit and return movements. The top two
panels represent timing and neural variables. The bottom
panel shows the time to contact, which crosses a threshold
at about 1 [s]. At this moment, the arm initiates its timed
movement.
The hitting is accomplished approximately at
maximum movement speed, here 310 [mm/s], to pro-
vide the maximum momentum during the hit. When
the hitting movement ends, the return movement, in a
similar manner, is initiated immediately, b
ret
set to 1,
bringing the robot to the base line ready to initiate the
next hitting sequence. These results show an inher-
ent resistance of the timing sequence against sensor
noise and the noisy prediction of the time to contact
and point to contact which demonstrates the robust-
ness of the approach. Fig. 5 shows the time courses
of the relevant dynamics variables for this success-
ful hit. Fig. 6 shows a sequence of snapshots of the
movements involved to execute the ball hitting task.
4.2 Simulation Results
The approach was evaluated in a simulation frame-
work of the CoRA manipulator coupled to sensory in-
formation about the real ball motion and among 500
random throws of the ball on the inclined plane, the
system was able in 61% of the trials to cross the pre-
dicted point to contact in time with a mean standard
deviation of the paddle-ball contact point of 2.2 [cm].
In 25% of the trials, the hit was not successful
because of the inaccurate point to contact prediction.
14% of the trials led to an initialization movement.
Setting the end-effectormaximum speed to 550 [m/s]
increases the hitting performance to 75%, which illus-
trates the effect of the hardware limitations.
ICAART2013-InternationalConferenceonAgentsandArtificialIntelligence
310
(a) Interception started (b) Interception stopped
(c) Hitting (d) Return
Figure 6: The different movements composing a ball hitting
task in the real robot.
5 CONCLUSIONS
Based on attractor dynamics, an autonomous mech-
anism of timed movement generation was imple-
mented for a ball hitting task. The approach was eval-
uated in simulation and successfully brought onto a
real manipulator, enabling the robot to repeatedly in-
tercept and hit a ball rolling on an inclined plane. Sta-
bility and targetted instabilities are inherent properties
of the nonlinear dynamics for trajectory generation
and behavioral organization through which the gen-
erated behavior can be updated online and adjusted
depending on the current situation. This behavioral
flexibility enabled the robot to perform the hitting task
autonomously. The system is capable of responding
quickly and flexibly to changes in the sensed environ-
ment or movement conditions while keeping timing
stable. Limitations in the system’s performance were
primarily due to the small framerate imposed by the
employed camera. The robot’smodest maximal speed
affected the hitting performance on the real robot.
We are currently working on overcoming these
limitations by improving the vision system’s predic-
tion performance through a faster camera and so, an
improved Kalman estimation system. We will also
transfer the implementation to a new robotic platform,
the KUKA lightweight arm, which permits much
faster movements and is, therefore, a more suitable
platform for this application.
REFERENCES
A. J. Ijspeert, J. Nakanishi, S. S. (2002). Movement imi-
tation with nonlinear dynamical systems in humanoid
robots. In IEEE Int Conf on Robotics and Automation.
ICRA.
A. Yilmaz, O. Javed, M. S. (2006). Object tracking: A sur-
vey. In ACM Journal of Computing Surveys. Vol. 38,
No. 4.
B. R. Fajen, W. H. Warren, S. T. L. P. K. (2003). A dynami-
cal model of visually-guided steering, obstacle avoid-
ance and route selection. In International Journal of
Computer Vision. 54(1-2) vol 54 13-34.
E. Bicho, G. S. (1996). The dynamic approach to au-
tonomous robotics demonstrated on a low-level vehi-
cle platform. In International Symposium on Intelli-
gent Robotic Systems. SIRS 96.
Ijspeert, A. J. (2008). Central pattern generators for loco-
motion control in animals and robots. In Neural Net-
works Review. vol. 21, no. 4, pp. 642-653.
Iossifidis, I. and Schoener, G. (2004). Autonomous reach-
ing and obstacle avoidance with the anthropomorphic
arm of a robotic assistant using the attractor dynamics
approach. In IEEE Int Conf on Robotics and Automa-
tion. ICRA.
Jeannerod, M. (1984). The timing of natural prehension
movements. In Journal of Motor Behavior. vol 16,
235-254.
Khatib, O. (1986). Real time obstacle avoidance for manip-
ulators and mobile robots. In International Journal
Robotics Research. vol. 5, pp. 90-98.
M. Tuma, I. Iossifidis, G. S. (2009). Temporal stabiliza-
tion of discrete movement in variable environments
an attractor dynamics approach. In IEEE Int Conf on
Robotics and Automation. ICRA.
Raibert, M. H. (1986). Legged robots that balance. MIT
Press, Massachusetts, 1st edition.
S. Degallier, C. Santos, L. R. A. I. (2006). Movement gen-
eration using dynamical systems: a humanoid robot
performing a drumming task. In International Con-
ference on Humanoid Robots. IEEE-RAS.
S. Schaal, A. Ijspeert, A. B. (2003). Computational ap-
proaches to motor learning by imitation. In Philo-
sophical Transactions of the Royal Society. vol 358
537-547.
Schoener, G. (1990). A dynamic theory of coordination of
discrete movement. In Biological Cybernetics 63. vol
63, 257-270.
Schoener, G. (2002). Timing, clocks and dynamical sys-
tems. In Brain and Cognition. vol 48, pp. 31-51.
Schoener, G. and Dose, M. (1992). A dynamical systems
approach to task-level system integration used to plan
and control autonomous vehicle motion. In Robotics
and Autonomous Systems. vol 10, 253-267.
Schutter, J. D. (1999). Kalman filters: A tutorial. In Journal
of Computing Surveys. vol. 40 (4).
Steinhage, A. and Schoener, G. (1998). Dynamical systems
for the behavioral organization of autonomous robot
navigation. In Sensor Fusion and Decentralized Con-
trol in Robotic Systems. Proc SPIE.
Warren, W. H. (2006). The dynamics of perception and
action. In Psychological Review 113(2). vol 113, 358-
389.
AutonomousTimedMovementbasedonAttractorDynamicsinaBallHittingTask
311