Content uploaded by Ahmad Ataka Awwalur Rizqi
Author content
All content in this area was uploaded by Ahmad Ataka Awwalur Rizqi on Aug 02, 2018
Content may be subject to copyright.
King’s Research Portal
Document Version
Peer reviewed version
Link to publication record in King's Research Portal
Citation for published version (APA):
Ataka, A., Lam, H-K., & Althoefer, K. A. (2018). Magnetic-field-inspired Navigation for Soft Continuum
Manipulator. In Proceedings - IEEE/RSJ International Conference on Intelligent Robots and Systems IEEE.
Citing this paper
Please note that where the full-text provided on King's Research Portal is the Author Accepted Manuscript or Post-Print version this may
differ from the final Published version. If citing, it is advised that you check and use the publisher's definitive version for pagination,
volume/issue, and date of publication details. And where the final published version is provided on the Research Portal, if citing you are
again advised to check the publisher's website for any subsequent corrections.
General rights
Copyright and moral rights for the publications made accessible in the Research Portal are retained by the authors and/or other copyright
owners and it is a condition of accessing publications that users recognize and abide by the legal requirements associated with these rights.
•Users may download and print one copy of any publication from the Research Portal for the purpose of private study or research.
•You may not further distribute the material or use it for any profit-making activity or commercial gain
•You may freely distribute the URL identifying the publication in the Research Portal
Take down policy
If you believe that this document breaches copyright please contact librarypure@kcl.ac.uk providing details, and we will remove access to
the work immediately and investigate your claim.
Download date: 02. Aug. 2018
Magnetic-field-inspired Navigation for Soft Continuum Manipulator*
A. Ataka1,2, A. Shiva1, H.K. Lam1, and K. Althoefer2
Abstract— Taking inspiration from the properties of mag-
netic fields, we propose a reactive navigation method for soft
continuum manipulators operating in unknown environments.
The proposed navigation method outperforms previous works
since it is able to successfully achieve collision-free movements
towards the goal in environments with convex obstacles without
relying on a priori information of the obstacles’ shapes and loca-
tions. Simulations for the kinematic model of a soft continuum
manipulator and preliminary experiments with a 2-segments
soft continuum arm are performed, showing promising results
and the potential for our approach to be applied widely.
I. INTRODUCTION
In the last decade, inspiration from species in nature such
as the octopus has sparked a new trend in robotics aiming
to improve robotic dexterity and manoeuvrability beyond
what is possible with existing rigid link manipulators. This
has given birth to a new breed of robots - robots that
are characterized by a soft, continuum structure such as
the pneumatically actuated robotic arms [1], tendon-driven
manipulators [2], or combination of tendon and pressure
actuation to manoeuvre and, at the same time, control the
stiffness of the mechanical structure [3]. Although this de-
velopment shows encouraging improvement in terms of the
robot’s flexibility, opening the door for applications which
were not possible beforehand, it also creates new challenges
in terms of robot modelling, control, and navigation due
to the nonlinear behaviour of the soft mechanical structure
employed.
As the robot application starts to extend beyond the well-
defined environments of industrial settings, the subject of
robot navigation continues to be an on-going focus of various
works. However, research which focuses on navigating the
continuum manipulator in an unknown environment is still
in its early stages. Most of the previous works employed
optimization-based planning [4]-[5] or sampling-based plan-
ning [6]-[7]. These methods assume to have (at least) near-
complete knowledge of the environment prior to initiating
any robot movement. The same drawback occurs for recent
works employing neural dynamics approach [8], while the
*This work was supported in part by King’s College London, the
EPSRC in the framework of the NCNR (National Centre for Nuclear
Robotics) project (EP/R02572X/1), the STIFF-FLOP project grant from
the European Communities Seventh Framework Programme under grant
agreement 287728, and the Indonesia Endowment Fund for Education,
Ministry of Finance Republic of Indonesia.
1A. Ataka, A. Shiva, and H.K. Lam are with The Centre for Robotics Re-
search (CoRe), Department of Informatics, Kings College London, London
WC2R 2LS, United Kingdom.
2A. Ataka and K. Althoefer are with the Centre for Advanced Robotics
@ Queen Mary (ARQ), Faculty of Science and Engineering, Queen Mary
University of London, Mile End Road, London E1 4NS, United Kingdom.
Corresponding author e-mail: ahmad.ataka@kcl.ac.uk
effort to use supervised learning by demonstration [9] needs
the intervention of human to generate the training data.
Some other studies which try to tackle dynamic environ-
ments are mainly constrained to specific geometries and/or
applications. An adaptive motion planning, used to navigate
the OctArm manipulator in [10], needs the knowledge of
obstacle’s geometry and is limited to planar scenarios.
Taking inspiration from natural physical phenomena is
also useful in robot navigation. Examples include the electric
potential field which took the idea of electrostatic interaction
among charged particles forming the basis for robot obstacle
avoidance and goal tracking [11]. Being relatively simple,
this method has been extensively applied in various robotics
systems, including mobile robots and rigid-link manipulators
[11]. Recent work exploring the application of the electric
potential field for continuum manipulators has been reported
in [12]. However, the global convergence is not guaranteed
in this algorithm. Other inspirations from nature applied the
properties of an artificial magnetic field for navigating rigid-
link manipulators, such as reported in [13]-[14], claiming
to resolve the problem of entrapment in local minima ob-
served when using the electric potential field method. These
methods, though, requires the geometry and location of any
obstacle or its centre point to be known beforehand.
In this paper, we present a reactive navigation algorithm
for soft continuum manipulator which is inspired by the
characteristics of magnetic fields. The algorithm is reactive
in the sense that it only relies on the most-recent sensory
information to navigate the environment without the need
for prior knowledge of the obstacles’ position or geometrical
properties. The backbone of the manipulator is considered as
a means for a virtual current flow, resembling an electrical
wire which induces an artificial electrical current on nearby
objects. The artificial current will then produce a magnetic
field which will impact on the continuum manipulator move-
ments avoiding a collision. To the best of our knowledge, this
is the first work which takes inspiration from nature to navi-
gate soft continuum manipulators in unknown environments.
II. INSPIRATION FROM NATURE
A wire segment of an infinitesimal length dlowith electri-
cal current ioas illustrated in Fig. 1a produces an infinitesi-
mally small magnetic field dB as follows [15]
dB =µ0
4π
iodlo×r
|r|3,(1)
in which rstands the position vector of a point with respect
to the wire, µ0is a permeability constant, and ×denotes the
cross product operation. This magnetic field produces a force
(a) (b)
dl0
r
dB
l0
la
rF
Fig. 1. (a) An electric current induces a magnetic field dB which, in this
figure, points inside towards the paper. (b) Two current-carrying wires with
currents flow opposite to each other, laand lo, produce repulsion force F.
dF on another current-carrying wire with an infinitesimal
length dlaand current ia, as illustrated in Fig. 1b, given by
dF =iadla×B.(2)
The magnetic field also influences a moving particle with
electrical charge dq and velocity vby a force given by
dF =dq v×B.(3)
Substituting (1) to (2) and dropping all the infinitesimal
notation, we can then derive the force interaction between
two current-carrying wires as follows
F=µ0iaio
4π
la×(lo×r)
|r|3.(4)
Inspired by this physical phenomenon, we can see a
soft continuum manipulator as a current-carrying wire with
current direction la, either ”flowing” on the tip or the body of
manipulator, inducing an artificial current loon the obstacle
surface located at position rowith respect to the manipulator.
This current induced on the obstacle will produce magnetic
field Bwhich will produce a force on the robot current in
such a way that the force Fwill guide the robot away from
the obstacle. It is noted that ro=−r, so that equation (4)
can be rewritten in a more general form as follows
F(ro) = cla×(ro×lo)f(|ro|),(5)
where c>0 is a scalar constant and f(|ro|)≥0 is a positive
scalar function. For simplification, a skew-symmetric matrix
ˆ
lis used to replace the vector cross product operation l×of
a vector l=lxlylzTand defined as follows
ˆ
l=
0−lzly
lz0−lx
−lylx0
.(6)
III. NAVIGATION ALGORITHM
A. Tip Navigation
When moving closer to the surface of an obstacle, the tip
of the robot located at location pwill induce an artificial
electric current loon the obstacle surface as follows
lo=la−(lT
aro)ro
|ro|2,(7)
where laand rostand for a unit vector in the direction of the
tip’s velocity and the position of the closest obstacle point
with respect to the robot’s tip, respectively. Eq. (7) ensures
(a) (b)
lo
ro
la
F
rre f
rre f
v
rg
Fig. 2. (a) The tip of the continuum manipulator induces an artificial current
loon the obstacle as a projection of its velocity direction la, producing force
Fas a result. (b) The tip navigation employs the transformation of the robot’s
velocity vand tip-to-goal rgwith respect to reference vector rref .
that the artificial current lois a projection of the tip’s velocity
˙
p(whose direction is described by a unit vector la) on to the
obstacle surface as depicted in Fig. 2a.
To make sure that the robot’s tip changes its motion
direction towards the direction of artificial current lo, the
vector field Fin (5) is modified as follows
F=cla×(lo×la)f(|ro|,|˙
p|).(8)
To make sure that the tip does not touch the obstacle, the
scalar function f(|ro|,|˙
p|)is designed to be proportional to
the tip’s velocity v=|˙
p|and inversely proportional to the
distance towards the obstacle surface r=|ro|when the tip
is closer to the obstacle than a limit distance rlas follows
f(|ro|,|˙
p|) = (v
rif r<rl
0 if r≥rl
.(9)
Using the formulation described in eq. (7)-(9), the vec-
tor field Fhas several properties (which were thoroughly
described in our previous works [16],[17]) as follows:
1) Zero work: The vector field Fdoes not have a com-
ponent in the direction of the tip’s velocity la, leaves the
robot’s speed unchanged, and hence, it does not change the
energy of the system. Combined with a globally-stable goal
attraction, the vector field Fdoes not create local minima.
2) Obstacle Boundary Following: Considering that the
tip’s direction lais not in line with the position of the obstacle
ro, the vector field Fwill always have a component along
the direction of the artificial current loand will force the tip
to follow the obstacle’s boundary.
3) Collision Avoidance: The scalar function in (9) guaran-
tees that the tip will avoid touching the surface of a convex-
shaped obstacle, as long as its movement direction lais not
in line with the position of the obstacle ro.
In reality, we want the tip to not only avoid collision with
an obstacle’s surface but also to be at a safe distance from the
surface. To ensure this, we add an avoidance term inspired
by the behaviour of a pair of current-carrying wires (see Fig.
1b). The tip of the continuum robot will induce an artificial
current lo⊥in the opposite direction of current loin (7). The
avoidance term Facan then be derived following the general
equation in (5) with the scalar function f(|ro|)being chosen
to be inversely proportional to the square of robot-obstacle
distance ras follows
Fa=la×(ro
r×lo⊥)f(|ro|),(10)
f(|ro|) =
c⊥(1
r−1
rb
)1
r2if r<rb
0 if r≥rb
,(11)
where c⊥denotes a positive constant and rb<rldenotes a
limit distance. Similar to vector field Fin (8), the avoidance
field Faalso does no work (i.e. lT
aFa=0). The avoidance
term in (10)-(11) will make sure that the tip is repelled from
the obstacle when it is too close without affecting its speed.
The overall avoidance vector field can then be written as
Fo=F+Fa.(12)
To guide the tip of the continuum manipulator to a desired
position pg, a PD controller can be employed as follows
Fpd =−KP(p−pg)−KD˙
p,(13)
where KPand KDare positive constants. However, when the
tip is located at a considerable distance from the goal, this
approach could force the tip to move at high speeds, leading
to an exorbitantly high avoidance term Fowhich may not be
achievable by the robot’s actuators when avoiding obstacles.
An alternative way to guide the tip towards the goal is by
implementing a geometric control term, originally presented
in [18]. We assume here that the tip of the continuum robot
moves with velocity vas depicted in Fig. 2b. With respect
to a static unit reference vector rre f , vector vis expressed as
a rotation matrix Rvas follows
Rv=I+ˆ
ωv+ˆ
ω2
v
1
1+cosφ,(14)
where ωv=ˆ
rre f v
|v|, cosφ=rT
re f
v
|v|, and I∈R3×3stands for
the 3 ×3 identity matrix. Applying the same approach for
”tip-to-goal” vector rg=pg−p, we can obtain its orientation
Rgwith respect to rre f . We aim to move the tip of the robot
from orientation Rvto orientation Rgby introducing an error
matrix Re=RT
gRvand applying a control law as follows
ˆ
ωg=−Kωlog(Re),(15)
in which Kω≥0 stands for a constant and the operator
log(R)for any R∈SO(3)is defined as log(R) = β
2sin β(R−
RT)where β=arccos(tr(R)−1
2). Using the definition of a
skew-symmetric matrix in (6), we get the angular speed
ωg∈R3from ˆ
ωg. To express the angular speed in the static
frame of rre f , we do matrix transformation ωre f =Rgωg.
Finally, the vector field to produce this angular speed is
Fgc =ˆ
ωre f v.(16)
The vector field Fgc guides the robot towards the direction
of the goal without changing its speed. Hence, to make the
robot starts moving, we add a speed controller as follows
Fv=−Kv(v−vd)d,(17)
where Kv>0 stands for a positive constant, vdis a desired
speed of the tip, and dis defined as d=(rg
|rg|if |v|=0
v
vif |v|>0.
Finally, when the robot is closer to the goal than a limit
distance rgl , we then switch back to the PD controller in
(13) to make the robot asymptotically reach the goal in a
smooth fashion. Hence, the overall vector field guiding the
tip’s movement is given by
Ft=(Fo+Fgc +Fvif |rg| ≥ rgl
Fo+Fpd if |rg|<rgl
.(18)
B. Whole Body Collision Avoidance
Besides the tip, we also apply the magnetic-field-inspired
vector field to the part of the robot’s structure which is closest
to the nearby obstacles. We choose muniformly-distributed
points along the longitudinal axis of the manipulator which
are subjected to the vector field. Vector field Fbwill be
applied to the point which is closest to the nearby obstacle.
For simplicity, we call this point active point located at pa.
Since the body of the manipulator does not have to reach
a certain configuration, the only vector field which we need
is the avoidance term in (12). Since there is no need for the
active point to have a constant speed, we modify the vector
field Fain (10) to simply be a repulsive field Fb=ro
rf(|ro|),
where r=|ro|stands for the distance from the active point
on the manipulator body towards the closest obstacle point.
For the active point, the boundary-following vector field
Fin (8) needs to be used only for a certain condition, i.e.
when at least 2 of the 3 conditions below are satisfied:
1) The active point is occluded by the obstacle from the
goal position pg,
2) The artificial current loinduced by the active point
does not tend to attract the point towards a direction
opposite to the goal,
3) The tip has not reached goal location pg.
Apart from these, the vector field Fcould create unnecessary
movements to the manipulator’s body. To implement these 3
conditions, we introduce 3 weights wa,wb,wcas follows
wa=(0 if cosα<0
1 if cosα≥0,
wb=(0 if cosγ<0
1 if cosγ≥0,
wc=(0 if |p−pg|<rl
1 if |p−pg| ≥ rl
,
(19)
where αstands for the angle between vector rag =pg−pa
and body-to-obstacle vector ro, while γstands for the angle
between vector rag and artificial current induced by active
point lo. Whenever (at least) 2 of these 3 weights are 1, then
the overall weight wtot will be 1, and otherwise will be zero.
Eq. (12) for the active point is then modified into
Fob =wtot F+Fb.(20)
IV. IMPLEMENTATION
The proposed methods were implemented on a kinematic
model of multi-segment continuum manipulator. A modal
kinematic approach, using 11th order multivariate Taylor
series expansion as presented in [19], is used to model the
shape of each segment. Hence, segment ican be described by
a set of actuator space variables qi=li1li2li3Twhere
L0+li j represents the length of tendon jin segment ifor an
initial length L0. For manipulator with static base, the overall
actuator space variables for Nsegments manipulator can then
be written as q=q1q2... qNT, whereas for manipu-
lator with movable base we have q=q0q1... qNT
where q0∈R2represents the base’s position. Any point
along the body of segment ican be described with respect
to the base of segment iusing modal homogeneous trans-
formation matrix i
i−1T(qi,ξi)∈SE(3). A scalar ξi∈[0,1]
corresponds with the location of the corresponding point
along the backbone of segment i. To describe the pose of
any point along the body of multi-segment manipulator with
respect to the base, the complete homogeneous matrix for N
segments manipulator can be derived as follows
N
0T(q,ξ) =
N
∏
i=1
i
i−1T(qi,ξi) = R(q,ξ)p(q,ξ)
01,(21)
where R(q,ξ)∈SO(3)and p(q,ξ)∈R3stand for rotation
matrix and position vector of the corresponding point. A
Jacobian, J(q,ξ)∈R3×(3N)for a static base or J(q,ξ)∈
R3×(3N+2)for a planar mobile base, relating the velocity vec-
tor in the joint space to the task space, can be derived via nu-
merical computation given by [J]kl =[p]k([q]l+δ,ξ)−[p]k([q]l,ξ)
δ,
where [J]kl stands for the component of a Jacobian matrix in
row-kand column-l,[p]kstands for the component of vector
pin row-k, and δstands for small positive constant.
Since we consider only the kinematics of the system,
force Fcomputed using the proposed method needs to be
numerically integrated to produce a task-space velocity ˙
p
given by ˙
p(t+∆t) = ˙
p(t) + F(t)∆t. This equation is used to
produce the task-space tip velocity ˙
ptand body velocity ˙
pb
from the vector field Ftin (18) and Fob in (20) respectively.
To convert this joint-space velocity ˙
pto the actuator space
velocity ˙
q, assuming the segment number N≥3, we exploit
the redundancy of the continuum manipulator in order to
implement several tasks according to priority list as follows:
1) Tip navigation,
2) Whole body obstacle avoidance,
3) Actuator space constraint avoidance.
When the part of the manipulator’s body is close to the
obstacle, the actuator space velocity consists of 3 terms [20]:
˙
q=˙
qt+˙
qb+˙
qc1,
˙
qt=J+
t˙
pt,
˙
qb=λb(Jb(I−J+
tJt))+(˙
pb−JbJ+
t˙
pt),
˙
qc1=λc1(I−J+
tJt)(I−˜
J+˜
J)z
(22)
where +denotes pseudo-inverse operation defined as J+=
JT(JJT)−1,Jtand Jbstand for the Jacobian of the tip and
the active point on the manipulator’s body respectively, λb
and λc1stand for positive constants, while ˜
J=Jb(I−J+
tJt)
and z∈R3Nor z∈R3N+2(depending whether the base
is fixed or mobile) stands for arbitrary vector. When the
part of the manipulator’s body is far from the obstacle, the
actuator space velocity consists of only 2 terms, namely the
tip navigation and constraint avoidance as follows
˙
q=˙
qt+˙
qc2,
˙
qt=J+
t˙
pt,
˙
qc2=λc2(I−J+
tJt)z,
(23)
where λc2is a positive constant. To ensure smooth transition
of (22) and (23), the actuator space velocity is given by
˙
q=˙
qt+˙
qb+˙
qc1+˙
qc2,(24)
while the positive constants λb,λc1, and λc2are defined as
λb=
0 if r≥rl2
cos2(π
2
r−rl1
rl2−rl1)if r≥rl1and r<rl2
1 if r<rl1
,
λc1=λb,λc2=1−λc1,
(25)
where rl1and rl2specify limit distances.
To minimize the possibility of the actuators reaching their
limit (i.e. minimum length lmin or maximum length lmax), the
vector zis designed to attract the length of the tendon to its
middle length lmid =lmin +lmax−lmin
2. Vector zis numerically
integrated from its rate ˙
zgiven by ˙
z= (−KPz
(lmid −lmin)2(q−
lmid I)−KDz ˙
q), for the case of a fixed base. For the mobile
base, the vector zis added to vector z0, which attracts the
base to the projection of the tip position into the xy plane
pxy, whose rate is given by ˙
z0= (−KPz0
(lmid −lmin)2(q0−pxy )−
KDz ˙
q0). To further reduce the probability of the manipulator’s
actuator reaching its maximum length, the artificial current
in (7) for the tip navigation is projected into the xy plane
if the zcomponent is positive. For the active point on the
manipulator’s body, the induced artificial current is projected
into the xy plane straightaway.
Finally, the actuator space velocity in (24) is integrated
to get the actuator space variables (i.e. the chamber length
li j) and transformed into a pressure value for actuation
by equation pi j =EAw
AL0li j, where E,Aw, and Astand for
Young modulus, cross-sectional area of a segment, and cross
sectional area of each chamber in every segment respectively.
V. RESULTS AND ANALYSIS
In this section, we evaluate the performance of the algo-
rithm in the simulation and preliminary experimental sce-
nario. Static obstacles with varying dimension and position
are placed in the vicinity of the manipulator. It is noted that
the manipulator is only able to detect the obstacle when the
distance to the closest obstacle is less than rl2. We compare
the performance of the proposed algorithm with previous
electric-field-based navigation as described in [12]. All the
codes are implemented via the Robot Operating System
(ROS) framework. A video attachment is also available.
A. Simulation Results
In the simulation scenario, the model of a three-segment
continuum manipulator was used. Three points per segment,
distributed uniformly along the backbone of each segment,
(a)
(b)
Fig. 3. The scenario where the 3-segments continuum manipulator is
located in an environment consisting of a planar obstacle (black), using
(a) magnetic-field-inspired and (b) artificial potential field algorithms. The
subpictures are to be viewed from left to right.
(a) (b)
Fig. 4. The plot of (a) the tip trajectory and (b) the position error for a
planar obstacle for magnetic-field-inspired navigation (blue) and artificial
potential field (red).
are chosen to be the active points. We evaluate two cases: one
where the robot has a static base and one where the robot is
situated on a mobile base operating in a planar environment.
We first test the scenario where the environment consists
of a planar obstacle as shown in Fig. 3. In Fig. 3a, we can see
how the magnetic-field-inspired (MFI) navigation algorithm
guides the tip of the continuum manipulator towards the goal
shown as a red dot without colliding with the planar obstacle.
In contrast, the artificial potential field (APF) in Fig. 3b fails
to guide the tip of the continuum manipulator towards the
desired target since the attractive field to the goal is cancelled
by the repulsive field from the planar obstacle, resulting in
an entrapment in a local minimum.
In Fig. 4, we can see how the two algorithms are com-
pared in terms of their tip’s covered path (Fig. 4a) and the
positional error with respect to the goal (Fig. 4b). It is clear
that the proposed algorithm (blue) traverses along a shorter
trajectory as it will force the manipulator to stop moving after
reaching the target position, while the artificial potential field
(red) will not be able to bring the manipulator to a halt, as
the robot fails to reach the goal. It is not surprising to observe
that the proposed navigation algorithm is able to drive the
positional error towards zero as it guides the tip towards the
goal, while the artificial potential field fails to do so.
In the second scenario, we put the continuum manipulator
in an environment consisting of several planar obstacles. The
obstacles are placed at different heights to test whether the
body of the manipulator is also able to avoid collisions with
the obstacles while, at the same time, the tip is navigated
towards the goal position. Fig. 5 shows the step-by-step
(a) (b)
Fig. 5. The scenario where the continuum manipulator is located at
environment consisting of multiple static planar obstacles and the goal is
shown as a red dot for (a) magnetic-field-inspired and (b) artificial potential
field algorithm. The step-by-step configuration starts from the right to the
left.
(a) (b)
Fig. 6. The plot of (a) the tip trajectory and (b) the position error for
multiple obstacles for magnetic-field-inspired navigation (blue) and artificial
potential field (red).
motion of the continuum manipulator using the magnetic-
field-inspired (Fig. 5a) and artificial potential field (Fig. 5b)
algorithms, respectively.
In Fig. 5a, we can observe that the magnetic-field-inspired
navigation is able to guide the tip of the continuum robot to-
wards the goal (red dot) while also ensuring that the body of
the manipulator does not collide with the obstacles. Just like
the tip’s avoidance term, the body avoidance term works by
appropriately moving the manipulator body sideways so that
the manipulator does not get stuck in a local minimum. We
can also observe how the redundancy mechanism employed
helps to ensure that the body movement in avoiding obstacle
does not disturb the movement of the manipulator’s tip. The
constraint avoidance, employed as a part of the redundancy
control, also ensures that the manipulator’s actuator variables
do not get stretched more than the actuators’ capability. This
is in part also influenced by the use of geometric control and
the property of the proposed vector field which keeps the tip
at a constant speed during most of its motion.
In contrast, the artificial potential field applied to the tip
and the body of the manipulator causes the manipulator to be
trapped in a local minimum configuration as shown in Fig.
5b. This can also be observed in Fig. 6, where we can see
that the proposed navigation (blue) is able to guide the tip
to the goal with zero position error (Fig. 6b) despite longer
path (Fig. 6a) compared to the artificial potential field (red).
B. Experimental Results
For the experimental scenario, a two-segment soft contin-
uum manipulator prototype is used to validate the perfor-
mance of the proposed algorithm. The manipulator consists
of a hollow cylinder made of Ecoflex 00-50 Silicone. Each
segment of the manipulator is 47 mm in length with an
outer diameter of 23 mm and an inner diameter of 9 mm.
Three pairs of pneumatically actuated pressure chambers (4.5
Fig. 7. The experimental setup depicts the 2 segments soft continuum
robot actuated by pressure regulators.
Fig. 8. The experiment shows the 2-segments soft continuum manipulator
avoids a simulated plane obstacle (black) using magnetic-field-inspired
navigation.
mm diameter) are accommodated longitudinally in the wall.
Each pair of chambers is connected to one inlet air pipe
receiving regulated air pressure from a pressure regulator.
The experimental setup is shown in Fig. 7. A single plane
obstacle is simulated to be located in the surrounding space.
Although the obstacle is simulated, its closest point is not
known to the robot before it is closer to the obstacle than
limit distance rl2. Since we only employ two segments, we
don’t use the complete redundancy control in (24), but only
the tip navigation term ˙
qt.
In Fig. 8, we can see how the magnetic-field-inspired nav-
igation is able to guide the tip of the 2-segment continuum
manipulator avoiding the simulated plane obstacle drawn
in black. Hence, we can see that the proposed navigation
has a reactive property, i.e. it works without any prior
information of the environment and relies only on a local
information acquired online during the robot’s movement.
This demonstrates the potential of the method to be used
for continuum manipulators operating in difficult scenarios
involving not only unknown but also dynamic environments.
VI. CONCLUSIONS
In this paper, a reactive magnetic-field-inspired navigation
is presented to guide the movement of a continuum ma-
nipulator towards the goal without colliding with unknown
convex-shaped obstacles. The proposed navigation strategy is
implemented in a modal-kinematics model of multi-segment
continuum manipulators. A 2-segment soft continuum ma-
nipulator platform is used to validate the performance of the
algorithm in a real-world scenario. The results show that
the algorithm is able to outperform potential field algorithm
in several scenarios repeatedly suffering from local minima.
It is noted that, in achieving this performance, the proposed
navigation only makes use of local information acquired dur-
ing robot motion. In the future, the practical implementation
of the algorithm in more difficult environments, consisting of
non-convex, cluttered, and even dynamic environments will
be explored. The use of a dynamic model of a continuum
manipulator will also be investigated.
REFERENCES
[1] J. Fras, J. Czarnowski, M. Macias, J. Glowka, M. Cianchetti, and
A. Menciassi, “New STIFF-FLOP module construction idea for im-
proved actuation and sensing,” in Proc. IEEE Int. Conf. Robot. Autom.,
May 2015, pp. 2901–2906.
[2] P. Qi, C. Qiu, H. Liu, J. Dai, L. Seneviratne, and K. Althoefer, “A
novel continuum-style robot with multilayer compliant modules,” in
Proc. IEEE/RSJ Int. Conf. Intell. Robots Syst., Sep. 2014, pp. 3175–
3180.
[3] F. Maghooa, A. Stilli, Y. Noh, K. Althoefer, and H. Wurdemann,
“Tendon and pressure actuation for a bio-inspired manipulator based
on an antagonistic principle,” in Robot. and Autom. (ICRA), 2015 IEEE
Int. Conf. on, May 2015, pp. 2556–2561.
[4] J. Granna, I. S. Godage, R. Wirz, K. D. Weaver, R. J. Webster, and
J. Burgner-Kahrs, “A 3-D Volume Coverage Path Planning Algorithm
With Application to Intracerebral Hemorrhage Evacuation,” IEEE
Robotics and Automation Letters, vol. 1, no. 2, pp. 876–883, Jul. 2016.
[5] M. Neumann and J. Burgner-Kahrs, “Considerations for follow-the-
leader motion of extensible tendon-driven continuum robots,” in 2016
IEEE International Conference on Robotics and Automation (ICRA),
May 2016, pp. 917–923.
[6] C. Bergeles and P. Dupont, “Planning stable paths for concentric tube
robots,” in Proc. IEEE/RSJ Int. Conf. Intell. Robots Syst., Nov. 2013,
pp. 3077–3082.
[7] K. Wu, L. Wu, and H. Ren, “Motion planning of continuum tubular
robots based on centerlines extracted from statistical atlas,” in 2015
IEEE/RSJ International Conference on Intelligent Robots and Systems
(IROS), Sep. 2015, pp. 5512–5517.
[8] Y. Chen, W. Xu, Z. Li, S. Song, C. M. Lim, Y. Wang, and H. Ren,
“Safety-Enhanced Motion Planning for Flexible Surgical Manipulator
Using Neural Dynamics,” IEEE Transactions on Control Systems
Technology, vol. 25, no. 5, pp. 1711–1723, Sep. 2017.
[9] H. Wang, J. Chen, H. Y. K. Lau, and H. Ren, “Motion Planning Based
on Learning From Demonstration for Multiple-Segment Flexible Soft
Robots Actuated by Electroactive Polymers,” IEEE Robotics and
Automation Letters, vol. 1, no. 1, pp. 391–398, Jan. 2016.
[10] J. Xiao and R. Vatcha, “Real-time adaptive motion planning for a
continuum manipulator,” in Proc. IEEE/RSJ Int. Conf. Intell. Robots
Syst., Oct. 2010, pp. 5919–5926.
[11] O. Khatib, “Real-time obstacle avoidance for manipulators and mobile
robots,” in Proc. IEEE Int. Conf. Robot. Autom., vol. 2, Mar. 1985,
pp. 500–505.
[12] A. Ataka, P. Qi, H. Liu, and K. Althoefer, “Real-Time Planner for
Multi-Segment Continuum Manipulator in Dynamic Environments,”
in Proc. IEEE Int. Conf. Robot. Autom., May 2016, pp. 4080–4085.
[13] L. Singh, J. Wen, and H. Stephanou, “Motion planning and dynamic
control of a linked manipulator using modified magnetic fields,” in
Proc. IEEE Int. Conf. Control Applicat., Oct. 1997, pp. 9–15.
[14] S. Haddadin, R. Belder, and A. Albu-Schffer, “Dynamic motion
planning for robots in partially unknown environments,” in IFAC World
Congr., vol. 18, 2011.
[15] J. D. Jackson, Classical electrodynamics, 3rd ed. New York, NY:
Wiley, 1999. [Online]. Available: http://cdsweb.cern.ch/record/490457
[16] A. Ataka, H. K. Lam, and K. Althoefer, “Reactive Magnetic-field-
inspired Navigation for Non-holonomic Mobile Robots in Unknown
Environments,” in Proc. IEEE Int. Conf. Robot. Autom., May 2018,
pp. 6983–6988.
[17] ——, “Reactive Magnetic-field-inspired Navigation Method for
Robots in Unknown Convex 3d Environments,” IEEE Robotics and
Automation Letters, 2018, doi: 10.1109/LRA.2018.2853801.
[18] F. Bullo and R. M. Murray, “Proportional Derivative (PD) Control On
The Euclidean Group,” in In European Control Conference, 1995, pp.
1091–1097.
[19] I. S. Godage, G. A. Medrano-Cerda, D. T. Branson, E. Guglielmino,
and D. G. Caldwell, “Modal kinematics for multisection continuum
arms,” Bioinspiration & Biomimetics, vol. 10, no. 3, p. 035002, 2015.
[Online]. Available: http://stacks.iop.org/1748-3190/10/i=3/a=035002
[20] Y. Nakamura, H. Hanafusa, and T. Yoshikawa, “Task-Priority Based
Redundancy Control of Robot Manipulators,” The International
Journal of Robotics Research, vol. 6, no. 2, pp. 3–15, 1987. [Online].
Available: https://doi.org/10.1177/027836498700600201