Content uploaded by Ahmad Ataka Awwalur Rizqi
Author content
All content in this area was uploaded by Ahmad Ataka Awwalur Rizqi on Mar 02, 2018
Content may be subject to copyright.
Real-Time Planner for Multi-segment Continuum Manipulator in
Dynamic Environments*
Ahmad Ataka, Peng Qi, Hongbin Liu, and Kaspar Althoefer
Abstract— In this paper, a potential-field-based real-time path
planning algorithm for a multi-segment continuum manipulator
is proposed. This planner is employed to enable a continuum-
style manipulator to move autonomously in dynamic environ-
ments in real-time. The classic potential field method is modified
to make it applicable for a kinematics model based on the
constant-curvature assumption. The contribution of this paper
lies in the design of a novel potential field in the actuator space
satisfying the mechanical constraints of the manipulator. The
planning algorithm is tested and validated in real-time sim-
ulation for a 3 segments continuum manipulator. Preliminary
tests for a tendon-driven single-segment continuum manipulator
prototype confirm the performance of the proposed planner.
I. INTRODUCTION
Nowadays, continuum manipulators, such as those inspired
by the octopus [1] or the snake [2] have gained much
popularity in the field of robotics due to their flexibility
and dexterity. In recent years, researchers tried to implement
continuum manipulators in application areas where a high
risk may be posed if tasks were handled by rigid-link
manipulators - examples include surgery and other medical-
related areas. However, although the robot’s ability to bend
at any point along its backbone makes it particularly safe to
be used in the medical field, automation is still needed to
further improve safety and ensure high maneuverability.
In the last decade, various continuum robot structures
have been reported by several researchers [3]- [5]; studies
on the kinematic modelling, Jacobian, dynamic modelling,
and control of continuum manipulator start to appear as
reported in [6]. However, research on continuum manipulator
navigation is still in its infancy and clearly a challenging
problem, largely because of the complexity of the manipu-
lator’s model.
One recent study on path planning for continuum manip-
ulator’s which uses a simple and fast geometrical inverse
kinematic solution of a constant-curvature steerable needle
was reported in [7]. However, this method cannot be used
to deal with obstacles dynamically changing their position,
because it assumes a static and well-defined environment.
Most works which use optimization-based planning [8]- [10]
*The work described in this paper is partially supported by the STIFF-
FLOP project grant from the European Communities Seventh Framework
Programme under grant agreement 287728, the Four By Three grant from
the European Framework Programme for Research and Innovation Horizon
2020 under grant agreement no 637095, and the Indonesia Endowment Fund
for Education, Ministry of Finance Republic of Indonesia.
Ahmad Ataka, Peng Qi, Hongbin Liu, and Kaspar Althoefer is with The
Centre for Robotics Research (CoRe), Department of Informatics, Kings
College London, London WC2R 2LS, United Kingdom. Corresponding
author e-mail: ahmad ataka awwalur.rizqi@kcl.ac.uk
and sampling-based planning [11]- [13] also suffer from the
same drawback.
Studies on path planning for real-time applications have
been reported in recent years. Xiao proposed a real-time
adaptive motion planning approach for OctArm manipulator
in dynamic environments [14]. However, the algorithm is
limited to the planar case and does not produce solutions
in actuator space limiting its applicability. Chen proposed
inverse-Jacobian-based planning which provides solutions in
actuator space [15], but it is specifically designed to guide
the movement of manipulator inside a tubular environment.
Another research work reported by Godage [16] exploits the
null space of a highly redundant multi-segment continuum
manipulator model. However, its mathematical calculation
is costly due to the fact that it involves successive matrix
multiplication. Besides, the hard-limiting function used to
model the mechanical constraint influences the smoothness
of manipulator’s movement when the tendons are close to
their limits.
One of the popular works in this area is the artificial
potential field method [17]. It is largely used for robots such
as mobile robots and rigid manipulators, especially because
of its simplicity and straightforward way of implementing.
Some researchers have applied potential field method to
continuum robots, such as steerable needle [18]. Although
the algorithm does not ensure global convergence, a global
map of the environment is not needed and, hence, it can be
used in dynamic and unknown environments, thus, makes it
suitable for real-time applications.
In this work, we propose potential-field-based real-time
path planning for a multi-segment continuum manipulator.
The planner presented in [17] is modified to make it ap-
plicable to a constant-curvature kinematic model. We also
propose a novel potential field for the actuator space to
satisfy the mechanical constraints of the manipulator. The
novel potential field in actuator space also improves the
standard hard-limiting function usually employed to satisfy
mechanical constraints due to the fact that the proposed
method does not disturb the smoothness of the manipulator
motion. The planning algorithm is tested and validated in a
real-time simulation on a 3 segment continuum manipulator.
Conducting tests on a real tendon-driven single-segment
continuum manipulator prototype (previously described in
[19]) confirms the performance of the proposed planner in a
real-world application.
(a) (b)
Fig. 1. (a) The single-segment tendon-driven continuum manipulator used
in the experiment. (b) Three segments continuum manipulator with movable
base. A point P located at δs3along the backbone of the third segment can
be expressed with the help of the scalar coefficient vector ξ= [1 1 δ]T
II. CONTINUUM MANIPULATOR MODEL
In this section, the constant-curvature kinematic model is
described. We assume that every segment of the manipulator
acts like the arc of a circle with a constant radius of curvature
along each individual robot segment. Hence, assuming the
manipulator moves in R3, each segment can be parameterized
by three configuration space variables ki=κiφisiT.
These variables represent the curvature (κi), rotational de-
flection angle (φi), and arc length (si) of a segment-i. The
homogeneous transformation matrix describing the tip pose
of segment iwith respect to the base, i
i−1T(ki)∈SE(3), can
be expressed as function of kias given in [6].
We assume the base of the continuum manipulator is
movable with 6 degrees of freedom, such that the pose of the
end effector with respect to the world frame for Nsegments
manipulator can be expressed as follows
N
0T(k) = TB
N
∏
i=1
i
i−1T(ki)(1)
where k=k1k2... kNTand TB∈SE(3)represents
the standard homogeneous transformation matrix of the
frame attached to the base with 6 degrees of freedom.
Further mapping is needed to construct the relation be-
tween the previous configuration space variables kto the
actuator space variables q. For a tendon-driven continuum
manipulator, the actuator space variables of segment-ican
be expressed as qi=li1li2li3Twhere li j represents the
length of tendon- jin segment-i. The overall actuator space
variables for Nsegments manipulator can then be written as
q=q0q1... qNTwhere q0∈R6represents the base’s
position and orientation. The configuration space variables of
segment-i,ki, can be expressed as function of manipulator’s
cross-section radius dand tendon length in segment-i,qi, as
expressed in [6].
The scalar coefficient vector, defined in [16], is used
to express the pose of any point along the backbone of
the manipulator. A scalar ξi∈[0,1]is assigned to each
segment to specify the point along the segment, from the
base (ξi=0) to the tip (ξi=1) of segment-i. The set
of scalars of all segments are then formed into a vector,
ξ=ξ1ξ2... ξNT. The value of the vector is defined
as ξ={ξr=1 : ∀r<i,ξi,ξr=0 : ∀r>i}.An example is
presented in Figure 1b.
Hence, the complete forward kinematic relation can be
expressed as follows
N
0T(q,ξ) = R(q,ξ)x(q,ξ)
01×31(2)
where R(q,ξ)∈SO(3)denotes the rotation matrix and
x(q,ξ)∈R3denotes the position vector of the point along
the body of manipulator. A Jacobian, defined as J(q,ξ) =
∂x(q,ξ)
∂q∈R3×(3N+6), relates the velocity vector as follows
˙
x(q,ξ) = J(q,ξ)˙
q⇔˙
q=J(q,ξ)−1˙
x(q,ξ).(3)
III. POTENTIAL-FIELD-BASED PATH PLANNING
A. Classic Potential Field
The planning algorithm, used in this paper, is based on
[17]. The manipulator in general moves in configuration
space (C-Space) filled employing an artificial potential field
U(q)which attracts the manipulator to the desired target
configuration, whilst repelling it from configurations where
the manipulator would touch obstacles (C-obstacle region).
The generalized force which guides the movement of the
manipulator can be expressed as
F(q) = −∇U(q).(4)
The attractive parabolic potential function for a desired
configuration qdcan be expressed as
Ud(q) = 1
2k(q−qd)T(q−qd),(5)
where kis constant gain. The repulsive potential produced
by obstacles Ocan be expressed as follows
UO(q) = (1
2η(1
ρ−1
ρ0)2if ρ<ρ0
0 if ρ>ρ0
(6)
where ρ=p(q−qO)T(q−qO)is the closest Euclidean
distance between the manipulator’s configuration and the C-
obstacle region in C-Space, ηis positive constant, and ρ0is
the limit distance of the potential influence.
The resulting potential is given by a linear combination
of attractive and repulsive potentials from all obstacles. An
illustration is shown in Figure 2a.
B. Modified Potential Field
The potential field can be easily applied in a C-Space.
However, to construct the C-Space for Nsegments contin-
uum manipulator with a movable base, which has 3N+6
degrees of freedom, is not feasible especially for real-time
planning purpose. Hence, we can use the same approach
applied to rigid-link manipulator [17] or steerable-needle
[18] by producing a potential function U(x)in the workspace
of manipulator.
Since we will use the kinematic model of a continuum
manipulator, a generalized force Fin the classic algorithm
is considered as the velocity of the manipulator ˙
x. Hence,
the spatial velocity ˙
x(x), derived from the gradient of the
potential U(x), is then mapped to an actuator space velocity
˙
q(q)by an inverse Jacobian relation in (3).
The attractive velocity in workspace is given by
˙
xxd(x) = −∇Ud(x) = −k(x−xd),(7)
where xdrepresents the desired end effector’s position in
the workspace. The repulsive velocity can be calculated as
follows
˙
xOb(x) = −∇UOb(x) = (η(1
ρb−1
ρ0)1
ρ2
b
∂ ρb
∂xif ρb<ρ0
0 if ρb>ρ0
.
(8)
Here, ρb=p(x−xOb)T(x−xOb)represents the closest Eu-
clidean distance between the manipulator’s end effector’s
position and the obstacle-bin workspace.
Applying the repulsive velocity to the end effector alone
is not sufficient to ensure that the whole body of the
manipulator will avoid the obstacles. An approach given
in [17] applied the repulsive force on each point subjected
to potential (PSP) along the body of the manipulator. The
higher the number of PSPs along the body of the manipulator,
the more collisions with obstacles are avoided.
Finally, we transform each spatial velocity, applied in the
end effector and PSPs, to the corresponding actuator space
velocity. For mnumber of PSP and nnumber of point
obstacles in the vicinity of the robot, the total velocity in
the actuator space can be expressed as follows
˙
q(q) = Je(q)+˙
xxd(x) +
m
∑
a=1
n
∑
b=1
Ja(q)+˙
xOb(x)(9)
where Jeand Jastands for the Jacobian of the end effector’s
and the Jacobian of the PSP-arespectively, with the elements
value of scalar coefficient vector ξdepending on the position
of the PSP along the backbone of the manipulator. The
(+) operation represents the pseudo-inverse matrix operation
based on [20] defined as
J+=JT(JJT)−1.(10)
C. Mechanical Constraint Avoidance
The novelty of this work compared to previous works is
the utilization of a novel potential field in the actuator space
to guide the continuum manipulator to avoid limits due to
the mechanical design of the manipulator. The continuum
manipulator used in this paper is assumed to have mechan-
ical constraint in its tendon length, namely it can only be
extended or shortened with ratio ζ. In other words, the length
of each tendon is inside the region (1−ζ)L<li j <(1+ζ)L
where Lstands for the normal length without contraction or
elongation.
Rather than applying the repulsive potential for these
limits, which will disturb the movement’s smoothness when
the tendons’ length are close to the limits, we apply an
attractive potential to plane lij =L. In other words, this
potential will attract the tendon’s length towards the normal
length L, which in turn will ensure that mechanical constraint
conditions are avoided.
The proposed potential function can be expressed as
follows
Ulim(q) =
N
∑
i=1
3
∑
j=1
σ(li j −L
ζL)2,(11)
where σis positive constant. The attractive velocity field is
as follows
˙
qlim (q) = −2σ1
ζ2L2(l−L),(12)
where l=l11 ... l13 l21 ... lN3Tand L=L13N×1.
However, producing a potential field with this behavior
will reduce the accuracy of the end effector planning to reach
a desired position in workspace. It is caused by the fact that
this new added potential will keep the resultant velocity field
in the actuator space equals zero although the end effector
does not reach the desired target point yet. Thus, we need to
define a weight function which will reduce the newly-added
potential field’s contribution as the end effector approaches
the target position as follows
w(x) = (1−e−µk(x−xd)k),(13)
where µis positive constant. An illustration of the potential
as a function of the tendon’s length and the distance between
the end effector and the target is shown in Figure 2b. The
overall actuator space potential field is added to (9). This
potential does not affect the base’s movement, ˙
q0∈R6, so
the total new potential ˙
qnew(q)∈R(3N+6)can be expressed
as follows
˙
qnew(q,x) = 06×1
w(x)˙
qlim (q)(14)
The total potential field in the actuator space can be
expressed as
˙
q(q) = Je(q)+˙
xxd(x) +
m
∑
a=1
n
∑
b=1
Ja(q)+˙
xOb(x) + ˙
qnew(q,x)
(15)
IV. SIMULATION RESULTS
The algorithm is implemented in a constant-curvature
kinematic model of a continuum manipulator in the Robot
Operating System (ROS) Environment. All simulations in
this section are run in real-time. The simulation is imple-
mented on a computer platform with an Intel Core i3 @2.40
TABLE I
PROP ERT IE S OF MA NI PU LATO R AN D POTE NT IA L FIE LD
Number of segments (N) 3
Total Number of PSPs (m) 9
Number of Obstacles (n) 2
Manipulator’s radius (d) 0.0134 m
Attractive Field Constant (k) 5.0 (s) or 0.1 (e)
Repulsive Field Constant (η) 3 ×10−7(s) or 2 ×10−9(e)
Limit of Potential Influence (ρ0) 0.025
Maximum extension ratio (ζ) 0.3
Normal length (L) 0.012 m
Constraint-Potential-Field constant (σ) 0.04167
Weight constant (µ) 2.5
−10
0
10
−10
0
10
0
2
4
x (m)
y (m)
Potential Function
(a)
−0.05
0
0.05
0
0.5
0
0.5
1
1.5
2
2.5
Length (m)
Distance (m)
Potential Function
(b)
Fig. 2. (a) Illustration of combined attractive and repulsive potential
function applied to a manipulator whose C-Space is in R2. (b) Illustration of
the proposed potential function designed to satisfy mechanical constraint as
function of the tendon’s length and end-effector-to-target Euclidean distance.
GHz and 1.5 GB RAM running the Linux Mint 13 Operating
System.
We use a three-segment manipulator (N=3) with a 6-
degree-of-freedoms movable base. We choose 3 PSPs dis-
tributed uniformly along the body of each segment. The
obstacles are assumed to have a spherical form with a radius
equals 0.01 m. The complete properties of the manipulator
and the potential field constants, both in simulation (s) and
experiment (e) are given in Tab. I.
A. Moving Obstacle with a Static Target
In the first simulation, we simulate two dynamic obstacles
moving in a space close to the manipulator. The tip’s target
position is assumed to be constant. The initial value of
actuator space variables are chosen such that the initial
position of the end effector coincides with the target. Each
obstacle moves in XY -plane with a constant velocity.
From Figure 3, we can see that the manipulator success-
fully avoids the dynamic obstacles (black spheres) moving
close to its body. Besides the repulsive avoid-obstacle move-
ment, the attractive go-to-goal potential is still applied to the
end effector of the manipulator, resulting in its movement
back to the target point (small red dot) when the obstacle
influence disappears after moving farther away from the
manipulator’s body, as shown in the lower right picture. In
Figure 4, the moving obstacle moves in the vicinity of the
bottom segment. We can see how the manipulator with its
movable base avoids the obstacle while at the same time
ensures that the end effector stays on the target position.
The comparison is made in terms of average execu-
tion time per cycle between the proposed algorithm and
a previous proposed approach [16] employing real-time
redundancy-based-obstacle avoidance as shown in Tab. II.
Employing the same simulation environment and machine
specification, it is shown that the proposed algorithm has an
execution time per cycle of 0.2423 s compared to previously
proposed redundancy-based planning with an execution time
per cycle of 1.1751 s. This is due to the fact that the computa-
tional load of the proposed method is lower when compared
to the computational load of the previous approach. Hence,
the proposed algorithm is relatively more efficient and more
suitable for high-speed real-time applications.
Fig. 3. The movement of the 3-segments-continuum-manipulator with a
static target position (small red dot) when 2 obstacles (2 black spheres)
move in the vicinity of the manipulator’s tip. The order of movement is as
follows: upper left picture, upper right picture, lower left picture, and finally
lower left picture.
B. Static Obstacle with a Moving Target
In the second simulation, the environment consists of two
static obstacles floating in space close to the manipulator’s
desired trajectory. The tip’s target position is assumed to
move with a constant velocity (k˙
xdk=0.001 m/s) at each
iteration. The velocity vector points from the initial target
position to the final target position. The initial value of the
tendon length and target position are chosen to have the same
value as in the first simulation. The obstacles are located in
space close to the target’s path.
From Figure 5, we can see that the manipulator starts
to track the moving target point (small red dot). When the
tendons’ length approach the limits, the proposed potential
field term ˙
qnew(q,x)will be big enough to avoid the tendon
increasing its length. This will in turn lead to a motion of
the redundant, movable base in the direction of the moving
target as a result of the attractive field. Hence, the proposed
Fig. 4. The movement of the 3-segments-continuum-manipulator with a
static target position (small red dot) when moving obstacle (black sphere)
move in the vicinity of the manipulator’s bottom segment. The order of
movement is as follows: upper left picture, upper right picture, lower left
picture, and finally lower left picture.
TABLE II
AVERA GE EXECUTION TIM E PE R CYC LE COMPARISON
Case Execution Time per Cycle (s)
Proposed Algorithm Redundancy-based Algorithm
A 0.2423 1.1751
B 0.1841 1.1050
potential field enables the manipulator to track the target
smoothly and without violating its mechanical constraints.
Our mechanical-constraint-potential-field method is superior
to standard hard-limiting function used to satisfy the me-
chanical constraint, since the proposed method does not
disturb the smoothness of the movement of the continuum
manipulator. Besides that, the manipulator also successfully
avoids the obstacles on its path.
As with the previous simulation, in terms of average
execution time per cycle shown in Tab. II, the proposed
algorithm is more efficient (with an average execution time
per cycle of 0.1841 s) than the redundancy-based path
planning algorithm in [16] (with an average execution time
per cycle of 1.1050 s).
V. EXPERIMENTAL RESULTS
A. System Description
The proposed algorithm is implemented in a tendon-driven
single segment continuum manipulator, as presented in [19],
as shown in 1a. In this experiment, it is assumed that the
Fig. 5. The movement of the 3-segments-continuum-manipulator with
a moving target position (small red dot) and 2 static obstacles (2 black
spheres) floating in space close to the manipulator’s desired path. The order
of movement is as follows: upper left picture, upper right picture, lower left
picture, and finally lower left picture.
0.05
0.1 −0.06−0.04−0.0200.02
0.08
0.1
0.12
y (m)
x (m)
z (m)
(a)
0 20 40 60 80
0.025
0.03
0.035
Time (s)
Distance (m)
(b)
Fig. 6. (a) The manipulator’s tip (red line) tracks the desired trajectory
(blue line) and avoids static obstacle (black spheres) nearby. (c) The graph
shows the closest distance from the obstacle to the estimated manipulator’s
body (red line) and to the target (blue line) respectively.
PSP is located only at the tip. The obstacle is assumed to be
a point located close to the manipulator’s tip.
We use three Maxon DC Motors as actuators. Each motor,
equipped with encoders to ensure precise velocity control,
is connected to the manipulator’s tendons via a gearbox
with a 128:1 reduction ratio. The rotational speed of the
motors governs the tendons’ linear velocities and changes
the tendons’ lengths.
The end effector position is measured by tracking the
electromagnetic-based Aurora sensor coil embedded in the
tip of the manipulator. The second sensor coil is hung in the
air by a thread to represent the center of the static spherical
obstacle with a radius of 0.01 m. The information is fed
to the computer via the NDI Aurora tracking system. The
target’s trajectory is chosen to be a straight line measured
with respect to the base of the robot.
B. Results and Discussion
In Figure 6a, the target’s movement is drawn with a blue
line, the tip’s movement is drawn with a red line, and the
obstacle is drawn as black spheres. The tip’s manipulator
starts to track the desired trajectory because of the attractive
field induced by the target. The repulsive movement occurs
when a part of the manipulator’s body enters the region of
the obstacle’s influence so that the tip’s movement deviates
from the desired path away from the obstacle.
Figure 6b shows the closest Euclidean distance from
the obstacle to the estimated manipulator’s body (drawn
with a red line) and to the target (drawn with a blue
line) respectively. We can observe that when the distance
between the obstacle and the tip is less than ρ0=0.025
m (i.e. the limit distance of obstacle’s influence), the tip
does not monotonically follow the target, but instead keeps
a certain distance from the obstacle until the moment when
the distance between target and obstacle is greater than ρ0.
This confirms that the obstacle-avoidance movement works
well for the continuum manipulator prototype in real-time.
One important thing to be noted is that the experiment
does not yet guarantee the whole body of the manipulator
to be safe from colliding just like in the simulation section.
It is due to the fact that the Aurora tracker sensor is only
located at the tip.
VI. CONCLUSIONS AND FUTURE WORKS
We propose a potential-field-based real-time path planning
algorithm for a multi-segment continuum manipulator. The
continuum manipulator’s constant-curvature kinematic model
is used to test the algorithm. The manipulator moves in
space under the influence of artificial potential fields. We also
propose a novel potential field in actuator space to satisfy
mechanical limits of the manipulator. The overall strategy is
tested and verified in a real-time simulator for a 3-segment
continuum manipulator and a test is successfully conducted
for a tendon-driven single-segment continuum manipulator
prototype. The path planning algorithm shows promising
result and can be further implemented for real-time planning
of other continuum manipulators.
In the future, the algorithm can be equipped with a non-
linear observer used to estimate the actuator space variables
of the manipulator so that the position of the PSP along the
backbone of manipulator can be estimated. This will reduce
the risk of collisions between the robot and obstacles. It
can also be combined with priori global information of the
environment to solve local minima problems.
REFERENCES
[1] W. McMahan, V. Chitrakaran, M. Csencsits, D. Dawson, I. Walker,
B. Jones, M. Pritts, D. Dienno, M. Grissom, and C. Rahn, “Field trials
and testing of the OctArm continuum manipulator,” in Robotics and
Automation, 2006. ICRA 2006. Proceedings 2006 IEEE International
Conference on, May 2006, pp. 2336–2341.
[2] S. Hirose, Biologically inspired robots: snake-like loco-
motors and manipulators, ser. Oxford science publica-
tions. Oxford University Press, 1993. [Online]. Available:
https://books.google.co.uk/books?id=TaIQAQAAMAAJ
[3] Y.-J. Kim, S. Cheng, S. Kim, and K. Iagnemma, “A Novel Layer
Jamming Mechanism With Tunable Stiffness Capability for Minimally
Invasive Surgery,” Robotics, IEEE Transactions on, vol. 29, no. 4, pp.
1031–1042, Aug. 2013.
[4] T. Mahl, A. Hildebrandt, and O. Sawodny, “A Variable Curvature
Continuum Kinematics for Kinematic Control of the Bionic Handling
Assistant,” Robotics, IEEE Transactions on, vol. 30, no. 4, pp. 935–
949, Aug. 2014.
[5] 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 Robotics and Automation (ICRA),
2015 IEEE International Conference on, May 2015, pp. 2556–2561.
[6] R. J. Webster, III and B. A. Jones, “Design and Kinematic Modeling
of Constant Curvature Continuum Robots: A Review,” Int. J. Rob.
Res., vol. 29, no. 13, pp. 1661–1683, Nov. 2010. [Online]. Available:
http://dx.doi.org/10.1177/0278364910368147
[7] V. Duindam, J. Xu, R. Alterovitz, S. Sastry, and K. Y.
Goldberg, “Three-dimensional Motion Planning Algorithms for
Steerable Needles Using Inverse Kinematics,” I. J. Robotic
Res., vol. 29, no. 7, pp. 789–800, 2010. [Online]. Available:
http://dx.doi.org/10.1177/0278364909352202
[8] G. Niu, Z. Zheng, and Q. Gao, “Collision free path planning based
on region clipping for aircraft fuel tank inspection robot,” in Robotics
and Automation (ICRA), 2014 IEEE International Conference on, May
2014, pp. 3227–3233.
[9] D. Palmer, S. Cobos-Guzman, and D. Axinte, “Real-time
method for tip following navigation of continuum snake
arm robots,” Robotics and Autonomous Systems, vol. 62,
no. 10, pp. 1478 – 1485, 2014. [Online]. Available:
http://www.sciencedirect.com/science/article/pii/S0921889014001080
[10] L. Lyons, R. Webster, and R. Alterovitz, “Motion planning for active
cannulas,” in Intelligent Robots and Systems, 2009. IROS 2009.
IEEE/RSJ International Conference on, Oct. 2009, pp. 801–806.
[11] L. Torres and R. Alterovitz, “Motion planning for concentric tube
robots using mechanics-based models,” in Intelligent Robots and
Systems (IROS), 2011 IEEE/RSJ International Conference on, Sep.
2011, pp. 5153–5159.
[12] C. Bergeles and P. Dupont, “Planning stable paths for concentric tube
robots,” in Intelligent Robots and Systems (IROS), 2013 IEEE/RSJ
International Conference on, Nov. 2013, pp. 3077–3082.
[13] J. Xu, V. Duindam, R. Alterovitz, and K. Goldberg, “Motion planning
for steerable needles in 3d environments with obstacles using rapidly-
exploring Random Trees and backchaining,” in Automation Science
and Engineering, 2008. CASE 2008. IEEE International Conference
on, Aug. 2008, pp. 41–46.
[14] J. Xiao and R. Vatcha, “Real-time adaptive motion planning for a
continuum manipulator,” in Intelligent Robots and Systems (IROS),
2010 IEEE/RSJ International Conference on, Oct. 2010, pp. 5919–
5926.
[15] G. Chen, M. T. Pham, and T. Redarce, “Sensor-based
guidance control of a continuum robot for a semi-
autonomous colonoscopy,” Robotics and Autonomous Systems,
vol. 57, no. 67, pp. 712 – 722, 2009. [Online]. Available:
http://www.sciencedirect.com/science/article/pii/S0921889008002042
[16] I. Godage, D. Branson, E. Guglielmino, and D. Caldwell, “Path
planning for multisection continuum arms,” in Mechatronics and
Automation (ICMA), 2012 International Conference on, Aug. 2012,
pp. 1208–1213.
[17] O. Khatib, “Real-time obstacle avoidance for manipulators and mo-
bile robots,” in Robotics and Automation. Proceedings. 1985 IEEE
International Conference on, vol. 2, Mar. 1985, pp. 500–505.
[18] S. DiMaio and S. Salcudean, “Needle steering and motion planning in
soft tissues,” Biomedical Engineering, IEEE Transactions on, vol. 52,
no. 6, pp. 965–974, Jun. 2005.
[19] P. Qi, C. Qiu, H. Liu, J. Dai, L. Seneviratne, and K. Althoefer,
“A novel continuum-style robot with multilayer compliant modules,”
in Intelligent Robots and Systems (IROS 2014), 2014 IEEE/RSJ
International Conference on, Sep. 2014, pp. 3175–3180.
[20] B. Siciliano, “Kinematic control of redundant robot manipulators:
A tutorial,” Journal of Intelligent and Robotic Systems,
vol. 3, no. 3, pp. 201–212, 1990. [Online]. Available:
http://dx.doi.org/10.1007/BF00126069