HHS Public Access Author manuscript Author Manuscript

Int J Rob Res. Author manuscript; available in PMC 2015 September 01. Published in final edited form as: Int J Rob Res. 2014 September ; 33(10): 1361–1374. doi:10.1177/0278364914526627.

Needle path planning and steering in a three-dimensional nonstatic environment using two-dimensional ultrasound images Gustaaf J. Vrooijink1, Momen Abayazid1, Sachin Patil2, Ron Alterovitz3, and Sarthak Misra1 1MIRA—Institute

Author Manuscript

for Biomedical Technology and Technical Medicine (Robotics and Mechatronics), University of Twente, The Netherlands 2Department of Electrical Engineering and Computer Sciences, University of California at Berkeley, USA 3Department of Computer Science, University of North Carolina at Chapel Hill, USA

Abstract

Author Manuscript

Needle insertion is commonly performed in minimally invasive medical procedures such as biopsy and radiation cancer treatment. During such procedures, accurate needle tip placement is critical for correct diagnosis or successful treatment. Accurate placement of the needle tip inside tissue is challenging, especially when the target moves and anatomical obstacles must be avoided. We develop a needle steering system capable of autonomously and accurately guiding a steerable needle using two-dimensional (2D) ultrasound images. The needle is steered to a moving target while avoiding moving obstacles in a three-dimensional (3D) non-static environment. Using a 2D ultrasound imaging device, our system accurately tracks the needle tip motion in 3D space in order to estimate the tip pose. The needle tip pose is used by a rapidly exploring random tree-based motion planner to compute a feasible needle path to the target. The motion planner is sufficiently fast such that replanning can be performed repeatedly in a closed-loop manner. This enables the system to correct for perturbations in needle motion, and movement in obstacle and target locations. Our needle steering experiments in a soft-tissue phantom achieves maximum targeting errors of 0.86 ± 0.35 mm (without obstacles) and 2.16 ± 0.88 mm (with a moving obstacle).

Keywords Flexible needle; path planning; three-dimensional steering; two-dimensional ultrasound images

Author Manuscript

1. Introduction Percutaneous needle insertion into soft tissue is a component of many minimally invasive medical procedures. Percutaneous needles are used for diagnostic and therapeutic procedures, including biopsy to extract tissue samples for diagnosis and brachytherapy for implanting radioactive sources into tumors for cancer treatment. These procedures are typically performed under image guidance using imaging modalities such as computed tomography (CT), magnetic resonance (MR), fluoroscopy, or ultrasound. Imaging provides

Reprints and permissions: sagepub.co.uk/journalsPermissions.nav Corresponding author: Sarthak Misra, RAM-EWI, PO Box 217, Enschede 7500 AE, The Netherlands. [email protected].

Vrooijink et al.

Page 2

Author Manuscript

crucial information about the locations of the clinical target, anatomical obstacles, and the needle itself during the procedure. Accurate guidance of the needle tip is often crucial to the success of such image-guided procedures. For example, inaccurate needle tip placement may result in misdiagnosis during biopsy and unsuccessful cancer treatment during brachytherapy (Bogdanich, 2009).

Author Manuscript

We introduce a needle steering system capable of autonomously and accurately guiding a steerable needle using two-dimensional (2D) ultrasound imaging to a moving target while avoiding a moving obstacle in three-dimensional (3D) anatomy. Ultrasound imaging is an ideal imaging modality to use during needle insertion procedures because of its low cost compared to CT and MR, and because it does not rely on ionizing radiation, which can be harmful to the patient when used in large doses during continuous CT or fluoroscopy imaging (Brenner and Hall, 2007). However, ultrasound is challenging to use for needle tracking because of its low resolution and high noise. We use a novel technique to track and steer flexible needles in 3D using 2D ultrasound images. The 2D ultrasound transducer is placed at the tissue surface perpendicular to the direction of needle insertion (Figure 1). During needle insertion, the method automatically repositions the transducer such that the needle tip is in the imaging plane. Our method also processes the images to estimate the needle tip pose, enabling online tracking of the needle tip in 3D anatomy.

Author Manuscript

Author Manuscript

Needle insertion is traditionally performed using rigid needles, but recent advancements in steerable needles have the potential to enable clinicians to more accurately reach clinical targets while simultaneously avoiding anatomical obstacles (Abolhassani et al., 2007; Cowan et al., 2011). Unlike rigid needles that are restricted to approximately straight line paths from the needle entry location to the clinical target, flexible needles with an asymmetric, bevel tip naturally move along a curve when inserted into soft tissue (Webster et al., 2006; Misra et al., 2010). A steerable needle’s insertion trajectory can be adjusted during a procedure to improve the accuracy of reaching moving targets, e.g. target perturbations of approximately 7.0 mm are common during clinical interventions in breast tissue (Deurloo et al., 2001; Op den Buijs et al., 2011a,b; Abayazid et al., 2012). The ability to control a steerable needle along curved trajectories also enables these needles to reach previously inaccessible targets while avoiding anatomical obstacles, including impenetrable structures such as bones and sensitive structures such as blood vessels or nerves.

In this study, we integrate ultrasound tracking into a complete system capable of automatic needle steering in non-static environments in which obstacles and targets may move. The system includes a motion planner that, given the pose of the needle estimated from ultrasound, computes a feasible trajectory that optimizes a clinical criterion and steers the needle around obstacles to a target in a 3D environment. The system is capable of considering and correcting for obstacle and target motions, and perturbations in the trajectory of the needle due to real-world uncertainties. This is possible because of the motion planner which is sufficiently fast such that it can be executed in a closed-loop manner. Closed-loop planning enables the needle trajectory to be continuously updated as online feedback is obtained from ultrasound tracking. Our system provides a novel approach to controlling steerable needles in 3D under 2D ultrasound image guidance.

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 3

Author Manuscript

To the best of our knowledge, our results are the first to experimentally demonstrate a needle steering system that, (a) integrates 3D steerable needle tracking using 2D ultrasound images and 3D motion planning, and (b) successfully guides the needle to a moving target while avoiding a moving obstacle. Our system is capable of accurately placing the needle tip at the desired target location (e.g. a lesion), which is essential for successful diagnosis or therapy in many clinical applications. Potential applications that could benefit from this kind of system include breast biopsy and prostate brachytherapy.

2. Related work Our work builds on the following two main areas of research for improving the accuracy of needle guidance in soft tissues: needle tracking and needle steering.

Author Manuscript Author Manuscript

A key aspect of improving needle targeting accuracy is accurately tracking the needle tip during a clinical procedure, which is complicated by the limitations of medical imaging modalities. The spatial resolution of 3D ultrasound images is limited and the refresh rate of a 3D image is low (Novotny et al., 2007). The use of X-ray-based imaging such as CT or fluoroscopy exposes the patient to high doses of ionizing radiation (Fred, 2004; Brenner and Hall, 2007). MR imaging suffers from low refresh rate and incompatibility with ferromagnetic materials (DiMaio et al., 2007). Electromagnetic position tracking sensors (Glossop et al., 2002; Abolhassani et al., 2007) can be used for 3D needle tracking, but their accuracy is sensitive to ferrous materials in the range of measurement. Further, studies by Hong et al. (2004) and Neubach and Shoham (2010) provided ultrasound-based tracking methods for needles, but motion is limited to the imaging plane. A study by Neshat and Patel (2008) used 2D ultrasound images to construct a volume, but the volume size remains limited by the available acquisition time in real-time applications. Recently, Vrooijink et al. (2013) presented a method to online track flexible needles in 3D using 2D ultrasound images. Our study expands on this technique to track and steer the needle using 2D ultrasound images in the presence of both obstacle and target motion.

Author Manuscript

Needle steering techniques and devices have been introduced that enable clinicians to improve targeting accuracy by adjusting the needle path within tissue. Such needle steering techniques and devices include bevel-tip flexible needles (Webster et al., 2006), symmetrictip needles that can be steered by applying forces at the base (DiMaio and Salcudean, 2005; Glozman and Shoham, 2007), curved style tips (Okazawa et al., 2005), programmable beveltip needles (Ko et al., 2011), and pre-bent concentric tubes (Dupont et al., 2010; Webster III and Jones, 2010). We focus on bevel-tip flexible needles. Significant advancements have been made in modeling bevel-tip steerable needles (Cowan et al., 2011). Webster et al. (2006) developed and experimentally validated a kinematic-based model based on a unicycle. Minhas et al. (2007) showed that the curvature of the needle path can be controlled through duty cycled spinning of the needle during insertion. Misra et al. (2010) and Majewicz et al. (2012) modeled the characteristics and mechanics of steerable needles in soft-tissue phantoms and biological tissue, respectively. There is extensive research on motion planning and control of steerable needles in a plane (2D) (Alterovitz et al., 2008; Asadian et al., 2011; Reed et al., 2011; Bernardes et al., 2013).

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 4

Author Manuscript

DiMaio and Salcudean (2005) presented a path planning algorithm that relates the needle motion at the base (outside the soft-tissue phantom) to the tip motion inside the soft-tissue phantom. Motion planners have been developed for needle steering in 3D environments with obstacles. Duindam et al. (2010) proposed a fast planner based on inverse kinematics, but which offers no completeness guarantee. Park et al. (2010) proposed a path-of-probability algorithm that considers uncertainty in needle motion using diffusion-based error propagation, but the planner is not guaranteed to be complete when obstacles are present. Several studies presented 3D path planning approaches based on rapidly exploring random trees (RRTs) (Xu et al., 2008; Patil and Alterovitz, 2010). These studies demonstrated results in simulations and have not been validated experimentally in 3D under closed-loop ultrasound image guidance.

Author Manuscript Author Manuscript

Needle steering algorithms to control the needle to follow a planned path have been developed. Glozman and Shoham (2007) created an image-guided closed-loop control algorithm for steering flexible needles using fluoroscopic images for feedback of the needle position during insertion. Neubach and Shoham (2010) and Abayazid et al. (2013b) used ultrasound images for 2D steering. A recent study by Bernardes et al. (2013) demonstrated a robot-assisted approach for automatic steering of flexible bevel-tipped needles. The 2D needle steering method operates in closed-loop using camera images for feedback, while intra-operative trajectory replanning is used to deal with obstacles and dynamic workspaces. Another study by Abayazid et al. (2013a) uses Fiber Bragg grating sensors for 3D closedloop needle steering without path-planning. Hauser et al. (2009) developed a 3D feedback controller that steers the needle along a helical path, but the results were only validated in simulations. van den Berg et al. (2010) proposed a framework for planning and linearquadratic-Gaussian (LQG)-based feedback control of a steerable needle under motion and sensing uncertainty, which was extended by Patil et al. (2011) for deformable workspaces. Despite these advances, prior LQG-based methods may fail due to control saturation, which is a practical concern for needle steering. Furthermore, these prior LQG-based methods cannot respond in real-time to significant perturbations that are not considered a priori.

Author Manuscript

The majority of the mentioned studies demonstrated needle steering in 2D. Even fewer studies investigated 3D steering that are also experimentally evaluated. Our study is the first to describe an ultrasound-guided 3D needle steering system capable of avoiding obstacles and reaching targets in non-static environments. This novel system effectively integrates the online ultrasound-based 3D tracking method described by Vrooijink et al. (2013) with the motion planner presented by Patil et al. (2011), which we extend in this study to execute in a closed-loop manner under ultrasound guidance. We use duty cycled spinning to achieve variable needle curvature in order to steer the flexible needle along the trajectory computed by the motion planner. The integrated system is capable of steering needles in non-static environments while compensating for uncertainties such as perturbations in needle motion and a priori unknown motions in obstacle and target locations. We experimentally evaluated the targeting accuracy of the system in static and non-static scenarios using a soft-tissue phantom.

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 5

Author Manuscript

3. Methods In this section, we present methods to enable robot-assisted tracking and steering of flexible bevel-tipped needles. We summarize the needle tip tracking method which uses 2D ultrasound images to estimate the pose of the needle tip during insertion. The tip pose is used in motion planning and steering, which allows the needle to be steered in a non-static environment with obstacle and target motion. 3.1. Ultrasound image processing

Author Manuscript

Our system processes ultrasound images to estimate the needle tip pose, which is used for needle steering. The 2D ultrasound transducer is placed perpendicular to the needle insertion axis, as shown in Figure 1. The resulting 2D ultrasound image provides a radial crosssectional view of the needle, which has ideally a circular shape. However, the radial crosssectional view of the needle is deformed by an artifact known as reverberation (Figure 2(a)). The artifact occurs when sound waves reflect repeatedly between materials with different acoustic impedances (Aldrich, 2007). The acoustic impedance difference between needle and soft tissue causes sound waves to bounce multiple times inside the needle before exiting. If the angle of the reflected sound waves are almost perpendicular to the receivers in the transducer, the reflected sound waves will produce an artifact. The artifact, often referred to as a comet tail artifact (CTA), is visible in ultrasound images and has a tail-shaped structure of equally spaced echoes along the sound wave (Huang et al., 2007). The length of the tailshaped structure depends on the amount of bouncing echoes that are received by the transducer.

Author Manuscript

We developed an image processing method to locate the needle centroid from the radial cross-sectional view of the needle which is affected by the CTA. Our method consists of a series of image processing techniques used to determine the needle centroid independent of the influences of the CTA. In this study, we assume that ultrasound images are properly dewrapped and scaled. We first process the ultrasound images to enhance the needle using a series of basic image processing techniques, including median filtering, thresholding, and erosion and dilation in Figures 2(b), (c), and (d), respectively. The enhanced image of the needle is used to determine the needle centroid. We apply to the enhanced image a feature extraction algorithm based on the Hough transform to compute a set of vertical line segments which describe the needle cross section and CTA. The length of each line segment must be equal or greater than the needle diameter. The algorithm then computes the mean

Author Manuscript

line segment of the set of vertical line segments (Figure 2(e)). The line segment describes the location and height of needle cross section and CTA under the assumption that the tail-shaped structure of the CTA is symmetric along the sound wave. Variations in the size of the tail-shaped structure are dependent on the amount of echoes that return to the transducer and affect the mean line segment at B. Point A of mean line segment is not affected by the CTA, and represents a point on the surface of the needle which is used to determine the needle centroid location. We estimate the needle centroid (yc, zc) as the point on the line segment between A and B a distance equal to the radius of the needle from A (Figure 2(f)). By positioning the transducer at the needle tip during insertion, we can

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 6

Author Manuscript

estimate the needle tip position (centroid (yc, zc)), which can be used to estimate the needle tip pose as described below. 3.2. Needle tip pose estimation The coordinate frames required to determine the needle tip pose during insertion are shown in Figure 3. The needle is inserted in the soft-tissue phantom along the x-axis (frame (Ψ0)) with insertion velocity (vi) using a needle insertion device (NID). The NID also enables needle rotation about the x-axis (frame (Ψ0)), which allows the needle to bend in a controlled direction. In order to determine the needle tip pose as it moves through the softtissue phantom, the needle tip position, (1)

Author Manuscript

with respect to the fixed reference frame (Ψ0) is evaluated. The needle centroid (yc, zc), describes the estimated tip frame (Ψt̂) in the ultrasound image frame (Ψu). The frames (Ψu and Ψp) are considered coincident for computational simplicity. Frame (Ψp) is attached to the positioning device end-effector, and is used to describe the transducer position with respect to fixed reference frame (Ψ0). Thus, by using coordinate transformations, the estimated needle tip position

can be expressed in the fixed reference frame (Ψ0).

In order to estimate the needle tip position , the ultrasound image plane must be located at the tip. Therefore, the transducer needs to be repositioned along the insertion axis (x-axis of frame (Ψ0)) according to the needle tip motion. It is assumed that the needle does not equals the insertion velocity

Author Manuscript

buckle during insertion. Hence, the needle tip velocity (‖vi‖) at the base, (2)

This relation can be used to estimate the required transducer motion along the x-axis (frame (Ψ0)) to compensate for the needle tip motion. Thus, by rewriting (2), the required transducer motion is given by (3)

where the insertion velocity is corrected by estimated tip velocities ( derivatives of needle tip positions (p̂y and p̂z), respectively.

and

) which are the

Author Manuscript

In order to determine the needle tip pose, orientations about the x-(ψ)-, y-(θ)-, and z-(ϕ)-axes are required. The NID controls the needle tip orientation (ψ) about its x-axis. If we assume no torsional flexibility about the needle shaft, the bevel tip orientation of the needle (about the x-axis of frame (Ψt)) can be determined from the NID (frame (Ψn)). The orientation of the needle about the y-(θ)- and z-(ϕ)-axes are computed by

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 7

Author Manuscript

(4)

respectively, where Δp̂x, Δp̂y, and Δp̂z represent small displacements along the x-, y-, and zaxes of frame (Ψ0), respectively. The rotation matrix

is computed using the tip

orientations (ψ, θ, and ϕ). The tip pose is known, since position known. Thus, the homogeneous transformation

and orientation

are

is estimated by (5)

Author Manuscript

which describes the estimated needle tip frame (Ψt̂) with respect to the reference frame (Ψ0). In order to estimate the needle tip pose during insertion, we implemented a controller to accurately position the ultrasound transducer at the needle tip. 3.3. Ultrasound image-guided controller The ultrasound transducer is positioned at the needle tip using the controller architecture presented in Figure 4. The needle tip position is denoted by p, and its corresponding time derivative representing the tip velocity is given by ṗ. Unless otherwise stated, the variables used in this subsection are expressed in the fixed reference frame (Ψ0), which is not included for notational simplicity. The transducer moves in the needle insertion direction (x-axis of frame (Ψ0)) using a compensator according to the estimated needle tip velocity

(3).

Author Manuscript

Estimation errors in the needle tip velocity caused by sideways cutting or needle deformation results in a positioning error between transducer and needle tip along the x-axis (frame (Ψ0)), which is considered to be the transducer aberration denoted by λ (Figure 3). The aberration is given by (6)

where px represents the needle tip position and p̂x the estimated tip position by the controller. The transducer aberration (λ) introduces an error in the estimated needle tip pose , (7)

Author Manuscript

represents the pose error between frames (Ψt and Ψt̂), which ideally equals where the identity matrix. Closed-loop control is applied to reduce the transducer aberration (λ) that introduces the needle tip pose error

. This is achieved by adding a gain (Ke) to the estimated needle tip

velocity . Thus, by scheduling of Ke, the transducer velocity can be increased (Ke > 1 to move faster than the needle) or decreased (Ke < 1 to move slower than the needle) when the needle is in- or out-of-plane, respectively. The velocity gain is scheduled according to

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 8

Author Manuscript

(8)

where closed-loop control is achieved by estimating Ke empirically. The imposed gain scheduling controller forces the transducer to move towards the needle tip, and thus, minimizes λ and therefore minimizes the needle tip pose error

.

Author Manuscript

A standard proportional-derivative (PD) controller is used to control the transducer motion along the y-axis (frame (Ψ0)), which allows the needle tip to move beyond the transducer image width (5.5 cm). The transducer motion along the z-axis (frame (Ψ0)) is used to maintain contact between the transducer and surface of the soft-tissue phantom to provide clear ultrasound images. In order to minimize the influence of process and measurement noise on the states (p and ṗ), a Kalman observer is included (Bar-Shalom et al., 2001). The discrete state-space representation is given by x(k + 1) = Ax(k) and y(k) = Cx(k), where k is the discrete-time index, x = [p ṗ]T, C = [1 0], 1 and 0 are 1 × 3 row vectors filled with ones and zeros, respectively, and A = [a0 a1], where a0 = [I 03]T, a1 = [ΔtI I]T, I is a 3 × 3 identity matrix, 03 is a 3 ×3 matrix filled with zeros, and Δt = 0.04 s denotes the sampling time of the Kalman observer. The system and measurement covariances are given

by Q = [q0 q1], where and and R = 0.1, respectively. A schematic representation of the Kalman observer is described in Figure 5. Another important role of the Kalman observer is to provide state estimation when the transducer moves ahead of the needle (which results in loss of needle visibility). This allows the compensator described in Figure 4 to reposition the ultrasound transducer according to

Author Manuscript

(3). The uncertainty of the projected states increases the estimated needle tip velocity over time without measurement updates. Hence, it is essential to minimize the duration of measurement absence. Upon return of measurement data, the Kalman gain (Kk) is adapted according to the increased uncertainty of the projected states, ensuring a decrease in estimation error.

Author Manuscript

The images of the ultrasound machine are transferred to a computer and processed at 25 frames-per-second. The controller architecture with the Kalman observer, depicted in Figure 4, operates at 25 Hz. This facilitates repositioning of the ultrasound transducer in order to track the needle during insertions with velocities 1–5 mm/s. Higher insertion velocities could be considered, but this is associated with an increase of the aberration in transducer position. Tracking according to the proposed method was validated with maximum mean errors of 0.64±0.11 mm, 0.25±0.06 mm, and 0.27 ± 0.06 mm along the x-, y-, and z-axes, respectively. The error in tip orientations about the y-(θ)- and z-(ϕ)-axes are 2.68° ± 1.22 and 2.83° ± 1.36, respectively. We experimentally evaluated transducer position aberration using insertion velocities 1–5 mm/s, which resulted in a mean aberration of 0.24–0.64 mm. We refer the reader to Vrooijink et al. (2013) for details regarding the experiments performed to evaluate needle tip tracking. Please see the video in supplementary material for a representative result of 3D needle tracking using 2D ultrasound images. The proposed

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 9

Author Manuscript

method evaluates the needle tip pose at 25 Hz during insertion. The estimated needle tip pose is used in a separate motion planning loop in order to steer the needle to a desired target while avoiding obstacles as described below. 3.4. Motion planning

Author Manuscript

We use a fast motion planner to automatically compute motions that steer the needle’s tip to a moving target while avoiding a moving obstacle in a 3D environment. Given preoperative medical images, we assume the user specifies the clinical target as well as obstacles, including sensitive structures such as glands or blood vessels and impenetrable structures such as bones. The objective of the motion planner is to quickly compute a sequence of feasible motions that steer the needle’s tip from its current pose to the target while avoiding obstacles. Our motion planner, described below, is fast enough to execute in a closed-loop manner to correct for perturbations in needle motion, obstacle location, and target location as they occur. At the core of our closed-loop motion planning approach is a sampling-based rapidly exploring random tree (RRT) planner (LaValle, 2006) that is customized for needle steering (Patil and Alterovitz, 2010), as outlined in Algorithm 1.

Author Manuscript

Prior work on motion planning for steerable needles in 3D assumes a constant curvature kinematic model, which severely restricts the range of motion of the needle tip (Xu et al., 2008; Duindam et al., 2010). This makes it difficult for planners to compute a feasible motion plan in 3D environments with obstacles. In contrast, our planner assumes a variable curvature kinematic model that allows us to compute trajectories composed of circular arcs of bounded curvature and uses duty cycled spinning during insertion to adjust the needle’s net curvature (Minhas et al., 2007), as described in the next subsection. The planner also makes use of reachability-guided sampling for efficient expansion of the rapidly exploring search tree to significantly improve planner performance (Shkolnik et al., 2009). These customizations help us to achieve orders-of-magnitude reduction in computation time compared to prior sampling-based planners (Xu et al., 2008). In this work, we extend the motion planner to operate in a closed-loop manner with ultrasound imaging feedback.

Author Manuscript

The input to the planner is the estimated needle tip pose a target region ( target), and the computation time (Δ) allotted for planning. The planner incrementally builds a tree ( ) over the state space, while satisfying non-holonomic motion constraints of the needle and avoiding obstacles in the environment. To expand the tree ( ), a random point (prand ∈ ℝ3) is sampled from the workspace. The algorithm then identifies a node (Hnear) in the tree, that is closest (i.e. minimizes distance) to the sample (prand). For fast performance, we use a distance metric customized for steerable needles that accounts for the needle’s nonholonomic constraint (Patil and Alterovitz, 2010). Since the needle has a natural maximum curvature (κ0), not all sampled points will be reachable from a given state because of the nonholonomic constraints of the needle. The reachable set from a state consists of all points that can be connected to pnear by a circular arc that has a radius r ≥ 1/κ0 and is tangent to the xnear-axis of the local coordinate frame Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 10

Author Manuscript

attached to the needle tip. We then define the distance metric as the length of such a circular arc connecting prand and Hnear if prand is in the reachable set of Hnear, and infinity otherwise. This strategy restricts the search domain to only those nodes that are within the reachable set of the nearest node (Hnear), thus increasing the likelihood of coverage of the state space (Shkolnik et al., 2009). Algorithm 1

Ψ ← needle_RRT_planner(

,

target,

Δ)

1: ← initialize_tree

Author Manuscript

2:

Ψ←∅

3:

while (compute_time() < Δ) do

4:

  prand ← random_point_in_ℝ3 ()

5:

  Hnear ← nearest_neighbor(prand,

6:

  Hnew ← circular_arc(Hnear, prand)

7:

  if collision_free(Hnear, Hnew) then

8:

    

← add_vertex(Hnew)

9:

    

← add_edge(Hnear, Hnew)

Author Manuscript

10:

  end if

11:

  if Hnew ∈

12:

    Ψ ← Ψ ∪ extract_plan(

13:

  end if

14:

end while

15:

return Ψ

target

)

then , Hnew)

The sampled point (prand) can then be connected to Hnear directly using a circular arc parameterized by [l, ϕ, r]T, where l is the arc length, ϕ is the change in orientation of the needle tip coordinate frame (Hnear) around the xnear-axis, and r is the arc radius. We limit the length (l) of the arcs that are added. Let Hnew be the state reached by traversing along the circular arc starting from Hnear and traveling a maximum distance of l ≤ lmax. We add Hnew and the edge connecting Hnear and Hnew to the tree ( ) if the circular arc connecting the two states is collision free. When the position pnew of a newly added state (Hnew) is found to lie in the target region ( goal), we extract a planned path by traversing the tree ( ) backwards from Hnew to the root. We refer the reader to Patil and Alterovitz (2010) for further details on our RRT-based planning approach.

Author Manuscript

The output of the planner is a set of plans (Ψ) that can be computed in the time (Δ) allotted for planning. We then select the best plan based on clinically motivated criteria such as minimizing path length or maximizing clearance from obstacles. In each period, multiple feasible motion plans are computed and a high quality plan is selected based on clinically motivated criteria. In our experiments, we minimize the length of the path (to minimize tissue cut) when no obstacles are present, and we maximize clearance from obstacles (to maximize safety) when obstacles are present. Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 11

Author Manuscript

The system executes the motion planner repeatedly during the procedure until the target is reached (see Figure 6). After the user specifies the environment, the planner first computes an initial plan. The system then enters a closed-loop in which the planner is periodically reexecuted every Δ seconds. The closed-loop motion planner as depicted in Figure 6 is given a fixed planning time (Δ) of 0.6 seconds. At the beginning of each period of duration Δ, the

Author Manuscript

motion planner obtains the actual needle tip pose from the ultrasound tracking system. The NID then executes the first Δ time of the previously computed plan. Simultaneously, the motion planner computes an updated plan that will be ready for execution in Δ time. The new motion plan is computed from a prediction of the needle tip pose after Δ time, where the prediction is based on the prior plan. The planner also uses the current positions of the target and the obstacles at each re-planning period. At the end of each period, the control outputs, consisting of the needle insertion and rotational velocities for the next Δ, are sent to the NID for execution, and the process is repeated until the needle reaches the target. 3.5. Duty cycled needle steering

Author Manuscript

When a flexible bevel-tipped needle is inserted into soft tissue, the bevel tip causes the needle to follow a circular path with a radius of curvature that is approximately constant (Webster et al., 2006). However, the planner computes a sequence of variable curvature circular arcs that steers the needle from the specified needle tip pose to the target. We approximate any curvature (κ) between 0 and the maximum natural curvature (κ0) by duty cycling the rotation (spinning) of the needle (Minhas et al., 2007). The variable curvature (duty cycling) is achieved by alternating between (I) insertion with rotations, in which the needle moves straight by rotating (spinning) at a constant velocity, and (II) insertion without rotation, in which the needle follows a path of constant curvature. Needle spinning must be a multiple of full rotations in order to preserve the same bevel tip orientation every cycle. Duty cycling is implemented for needle steering by inserting the needle a fixed distance each cycle and spinning with a fixed rotational velocity (ωspin). Let δ be the duration of each duty cycling interval, which is composed of a spin interval of duration (δspin) and an insertion interval of duration (δins), as illustrated in Figure 7(a). Let α (0 ≤ α ≤ 1) be the proportion of the time spent in spin intervals, i.e. α = δspin/δ, where δ = δspin + δins. The empirical relationship between κ and α is expressed as, (9)

Author Manuscript

where h(κ) is dependent on the mechanical properties of the needle and soft tissue, and is determined by fitting a polynomial function to the empirical data gathered during characterization experiments as described below. Given a circular arc of desired curvature (κ), we use (9) to determine α. Since the needle tip preserves the same bevel tip orientation at the end of each spin interval, the duration of the spin interval is given by δspin = (2kπ/ωspin), k ∈ ℤ. We then compute the quantities δ = (δspin/α) and δins = (δ − δspin). The low level control inputs (NID) for the insertion velocity (v(t)) and rotational velocity (ω(t)) during a duty cycle interval are given by

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 12

Author Manuscript

(10)

(11)

where vins is the default insertion velocity of the needle, j ∈ {0, 1, …, Δ/δ}, and Δ/δ is the total number of duty cycle intervals required to span the duration of each replanning step (Δ). This allows us to compute the control outputs required for actuation (insertion and rotation) of the needle.

Author Manuscript

Duty cycling requires that we characterize the maximum curvature (κ0) of the needle and determine the empirical relationship (h(κ)) between the curvature (κ) and the duty cycling factor (α). We empirically determine that h(κ) is dependent on the mechanical properties of the needle and the tissue and is not necessarily linear as demonstrated by prior work with duty cycled needle steering (Minhas et al., 2007). In order to estimate the relationship (α = h(κ)) (9) for the soft-tissue phantom described in Section 4, we performed repeated needle insertions up to 50 mm. We varied the value of α between 0 and 1 in increments of 0.2, and computed the duration of the duty cycling interval (δ) for a time interval Δ = 0.6 seconds. Given a fixed insertion velocity (vins = 3 mm/s) and rotational velocity (ωspin = 5 rotations/s), we command the actuators during each duty cycling interval with control outputs computed using (11). The application of these controls causes the needle tip to traverse a circular arc of some curvature κ in a plane.

Author Manuscript

In order to determine the effective curvature (κ) of the planar arc, we recorded the needle tip pose after the end of each duty cycling interval for N such intervals. We observed that the needle tip deviates from the plane because of initialization errors and other sources of ,t uncertainty. To robustly estimate κ, we fit a circle to the set of 3D points given by = 0, …, N. We accomplished this by first computing a best-fit plane that minimized the sum of the squared orthogonal distances from each point to the plane by performing principal component analysis (PCA) on the set of points. We then projected the points onto the first two principal components that span the plane and then fitted a circle to the set of projected 2D points using a robust circle fitting algorithm (Taubin, 1991). The curvature (κ) was obtained by taking the reciprocal of the radius of this fitted circle. Figure 7(b) shows the relationship (α = h(κ)) for needle insertion in soft-tissue phantom used for our experiments. The needle achieved a maximum curvature κ0 = 0.016 mm−1 in the soft-tissue phantom.

Author Manuscript

We used the experimental measurements of α to compute a best-fit polynomial curve with a fixed maximum degree (= 3) that minimized the sum of the squared errors of the data points from the curve. This curve defines the relationship (α = h(κ)). An important point to note is that the smaller the distance (vinsδ) traveled by the needle tip in every duty cycling interval, the better the approximation of κ. We divided time duration (Δ) into a single duty cycling interval (δ = βΔ, with β = 1). This results in an insertion distance of vinsδ = 1.8 mm per duty cycling interval.

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 13

Author Manuscript

4. Experiments In this section, we evaluate our 3D needle steering system described in Section 3. We experimentally evaluate the system in a soft-tissue phantom in different environments. In four experimental scenarios, we steer the needle to reach (moving) targets while avoiding (moving) obstacles. 4.1. Experimental setup and materials

Author Manuscript

In order to facilitate needle steering, all components of the experimental setup are integrated into a unified system (hardware and software for planning and ultrasound-guided control) in order to work together effectively. The experimental setup (Figure 8) can be divided into two parts. First, the NID robotically inserts and rotates the needle about its axis. A telescopic sheath surrounds the needle to prevent buckling during insertion into the soft-tissue phantom. For the details of the NID we refer the reader to Roesthuis et al. (2011) and van Veen et al. (2012). Second, the transducer positioning device positions the 2D ultrasound transducer in 3D space. The positioning device consists of three orthogonally placed linear translation stages. The linear stages LX30, LX26, and LX20 (Misumi Group Inc., Tokyo, Japan) facilitate motion in x-, y-, and z-axes (frame (Ψ0)) (Figure 3), respectively. In order to actuate the linear stages, Maxon ECMax22 motors with GP32/22 gearheads (Maxon Motor, Sachseln, Switzerland) are used. The velocity of each stage is controlled by an Elmo Whistle 2.5/60 motor controller (Elmo Motion Control Ltd, Petach-Tikva, Israel). The positioning accuracies of the device are 27 µm, 35 µm, and 41 µm along the x-, y-, and z-axes, respectively. The ultrasound transducer is mounted to the positioning device end-effector using a perfectly fitting clamp.

Author Manuscript

The ultrasound images are obtained using an 18 MHz transducer connected to a Siemens Acuson S2000 ultra-sound machine (Siemens AG, Erlangen, Germany). The ultrasound machine is linked to a computer using an S-video cable that transfers the images (720 × 576 pixels) with a frame rate of 25 frames per second. The ultrasound images are used to track the needle during insertion into a soft-tissue phantom. The soft-tissue phantom is obtained by a weight based mixture of 84.1% water, 14.9% gelatin powder (Dr Oetker, Ede, The Netherlands) and 1.0% silica gel 63 (E Merck, Darmstadt, Germany). The elasticity of the gelatin mixture used to mimic human breast tissue is 35 kPa (Young’s Modulus) (Gefen and Dilmoney, 2007). Silica powder is added to the mixture to simulate the acoustic scattering of human tissue in ultrasound images (Cook et al., 2011). The flexible needle, which is a solid wire, is made of Nitinol alloy (nickel and titanium). The Nitinol needle has a diameter of 0.5 mm with a bevel angle (at the tip) of 30°.

Author Manuscript

4.2. Experimental scenarios To evaluate the performance of our system that integrates ultrasound-based needle tracking and motion planning algorithms, we conducted experiments in which our system steers the needle to a target (e.g. lesion) in 3D non-static environments while avoiding obstacles. We evaluate our system’s targeting accuracy in four experimental scenarios (Figure 9). We execute our system 10 times for each experimental scenario. The needle insertion and rotational velocities used during the experiments are 3 mm/s and 5 rotations/s, respectively.

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 14

Author Manuscript

In our experiments we used virtual obstacles and targets. The target and obstacle locations are expressed in (x [mm], y [mm], z [mm])-coordinates of the fixed reference (frame (Ψ0)). •

In Scenarios I-A, -B, -C, and -D, the needle is steered to reach a moving target at four different locations (A, B, C, and D), respectively.



In Scenario II, the needle is steered to reach a stationary target while avoiding a stationary obstacle.



In Scenario III, the needle is steered to reach a moving target while avoiding a stationary obstacle.



In Scenario IV, the needle is steered to reach a moving target while avoiding a moving obstacle.

Author Manuscript Author Manuscript

The initial target locations for experimental Scenarios I-A, -B, -C, and -D are (100,−20,10), (100,20,10), (100,−20,−10), and (100,20,−10), respectively. The initial target location for experimental Scenarios II–IV is (100,−10,−10). The target depth of 100 mm is within the range of typical biopsy depths of lesions and tumors (retroperitoneal) which are approximately 35–115 mm (Tomozawa et al., 2011). The target size is 2 mm, which is currently the smallest detectable size of a lesion in a breast mammography (Onuigbo et al., 2001). Target motion is simulated in Scenarios I, III, and IV to investigate the effects of target motion on the needle steering accuracy. During insertion, the needle exerts a force on the target (in the positive x-axis of frame (Ψ0)), which causes target motion. After 20 seconds of needle insertion, the target starts to move with a constant velocity of 0.4 mm/s in the positive x-axis (frame (Ψ0)) until the needle reaches the target. The simulated target motion results in a displacement of approximately 7.0 mm, which is commonly observed during clinical interventions in breast tissue (Deurloo et al., 2001; Op den Buijs et al., 2011a,b; Abayazid et al., 2012; Vos, 2013). In order to evaluate the maneuverability of the needle during steering, an obstacle is positioned in the direct path of the needle to reach the target (Scenarios II–IV). The proposed obstacle has a cylindrical shape (e.g. bone) with a 20 mm diameter, and is located (center of the cylinder) at (60,4,0). Obstacle motion is introduced in Scenario IV to simulate the non-static behavior of organs which constantly move. During the first 10 seconds of needle insertion, the obstacle moves with a constant velocity of 0.3 mm/s in the negative yaxis (frame (Ψ0)) (towards the needle path). After 10 seconds, obstacle motion is stopped and a total displacement of 3 mm is achieved. 4.3. Experimental results

Author Manuscript

The experimental results of Scenarios I–IV are provided in Table 1. A representative result for each of the Scenarios I(-A, -B, -C, and -D), II, III, and IV are given in Figures 10(a), (b), (c), and (d), respectively. After the needle is steered to reach the target, its final estimated needle tip location from ultrasound tracking is evaluated with respect to the target location. The mean absolute errors (MAE) with standard deviations in the needle tip position with respect to the target along x-(εx)-, y-(εy)-, and z-(εz)-axes (frame (Ψ0)) are reported. The MAE are determined in order to evaluate the distance between tip and target. Experimental results of Scenarios I-A, -B, -C, and -D show MAE of 0.59 mm, 0.54 mm, 0.86 mm, and

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 15

Author Manuscript

0.82 mm, respectively. In Scenario II, an MAE of 1.76 mm is observed. For Scenario III, an MAE of 1.33 mm is reported, while for Scenario IV, an MAE of 2.16 mm is observed.

Author Manuscript

The experimental results of Scenarios I(-A, -B, -C, and -D) show targeting errors less than 1 mm. Note, that the smallest detectable lesions in breast mammography are reported to be 2 mm (Onuigbo et al., 2001), with most lesions close to 11 mm in diameter (Güth et al., 2008). Therefore, the proposed tracking and steering method is capable of targeting the smallest detectable lesions in scenarios without obstacles in applications such as breast biopsy. We observe that absence of an obstacle (Scenarios I(-A, -B, -C and -D)) results in better targeting accuracy as compared to the other scenarios. This could be attributed to the fact that once the needle is steered around the obstacle according to a computed motion plan (Scenarios II–IV), the maneuverability of the needle and its ability to correct for perturbations is constrained. Hence, the range of feasible motion plans to the target diminishes due to the obstacle. Further, the decrease in performance (Scenarios II–IV) may be due to torsional flexibility of the needle, which results in needle tip pose estimation errors.

Author Manuscript

We observe better targeting accuracy in Scenario III (stationary obstacle and moving target) as compared to Scenario II (both stationary obstacle and target). A possible explanation is that once the needle is steered around the obstacle, the motion planner has more options and more time to correct for uncertainties when the target moves away from the obstacle. However, as observed in Scenario IV, the presence of obstacle motion results in decreased targeting accuracy. This can be explained by the reduced range of motion plans which are feasible due to the substantial target and obstacle motion, especially when obstacle motion reduces the space of feasible paths that reach the target. Nonetheless, even in the challenging scenario of target and obstacle motion, our method still achieves errors that are typically at or below 2.16 mm. Experienced clinicians inserting radioactive seeds into the prostate gland for brachytherapy prostate cancer treatment experience average placement errors of 6.3 mm, about 15% of the prostate’s diameter (Taschereau et al., 2000). Further, a study by Blumenfeld et al. Blumenfeld et al. (2007) concluded that prostate biopsies using rigid needles performed by experienced clinicians show average targeting errors between 5.5–6.5 mm. We evaluate our system using soft-tissue phantoms which leads to several simplifications as opposed to studies in biological tissue. Nonetheless, our method demonstrates needle steering that appears comparable to an experienced clinician in terms of accuracy while providing new obstacle avoidance capabilities. This indicates that our system, with further development, is on track to be applicable to wide class of clinical applications.

Author Manuscript

5. Conclusions and future work We present and evaluate a needle steering system capable of autonomously and accurately guiding a steerable needle to a target in a non-static 3D environment using 2D ultrasound images. Our system achieves high accuracy in non-static environments by effectively integrating two major components: a safe, ultrasound-based tracker of the needle pose and a fast needle motion planner that reacts to perturbations in target and obstacle locations. To

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 16

Author Manuscript

accurately track the needle tip, we use a clinically available 2D ultrasound transducer which is orientated perpendicular to the direction of insertion and does not require that the procedure be performed in a single plane. The system estimates the needle tip pose by controlling the position of the ultrasound transducer to obtain images at the the needle tip and using image processing algorithms. The needle tip pose is used in motion planning to compute feasible paths that reach a target while avoiding an obstacle. The planner is sufficiently fast such that the system can repeatedly execute it as new tip pose estimates are obtained from the ultrasound tracker, enabling the system to compensate for uncertainties in steering and to correct for perturbations in obstacle and target locations. In experiments in which the targets moves approximately 7 mm over the course of the procedure (which is typical in breast biopsies), the system achieves low MAE of 0.86 mm (without obstacles) and 2.16 mm (with a moving obstacle).

Author Manuscript Author Manuscript

In future work, we will build on this system and investigate additional avenues to reduce needle placement errors in non-static tissue environments while avoiding anatomical obstacles. We plan to investigate the effects of variations in tissue elasticity on needle curvature (the empirical relationship α = h(κ) in Section 3.5) and to incorporate methods that compensate for torsional flexibility of the needle. Further, we will also investigate improving targeting accuracy and reducing tissue damage by integrating different needle steering methods with motion planning (Abayazid et al., 2013b). In order to provide a more realistic testing scenario, needle steering in biological tissue, including tracking of real targets, will be investigated. Our ultrasound-based tip tracking algorithm evaluates the needle location that is affected by CTA. Some preliminary research indicates that artifacts such as CTA are also observed in biological tissue, although effort is required to properly correct for distortions such as warping that are often observed in ultrasound images of biological tissue. So with some modifications, we believe our proposed ultrasound-guided tracking and control method would be applicable to biological tissue. In addition to experiments in biological tissue, advancements in instrument design need to be made to enable biopsies with flexible needles. Further, we are currently adapting our transducer positioning device to move on curved surfaces using additional degrees of freedom and a force sensor to maintain transducer-tissue contact. While we aim to continue to improve the system, our current study demonstrates the feasibility and potential of tracking and steering flexible needles, which has clinical applications for procedures such as breast and prostate biopsies and brachytherapy.

Supplementary Material Refer to Web version on PubMed Central for supplementary material.

Author Manuscript

Acknowledgments Funding This work was supported by funds from the Netherlands Organization for Scientific Research (NWO—project number 11204) and Dutch Technology Foundation STW (iMIT-Instruments for Minimally Invasive Techniques Interactive Multi-Interventional Tools (Project: MULTI)), by the United States National Science Foundation (grant numbers IIS-0905344 and IIS-1149965), and by the United States National Institutes of Health (grant numbers R21EB011628 and 1R21EB017952)

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 17

Author Manuscript

References

Author Manuscript Author Manuscript Author Manuscript

Abayazid, M.; Buijs, op den, J.; de Korte, C., et al. Effect of skin thickness on target motion during needle insertion into soft-tissue phantoms. Proceedings of the IEEE RAS/EMBS International conference on biomedical robotics and biomechatronics (BioRob); 24–27 June 2012; Rome, Italy. 2012. p. 755-760. Abayazid, M.; Kemp, M.; Misra, S. 3D flexible needle steering in soft-tissue phantoms using fiber Bragg grating sensors. Proceedings of the IEEE International conference on robotics and automation (ICRA); 6–10 May 2013; Karlsruhe, Germany. 2013a. p. 5823-5829. Abayazid M, Roesthuis RJ, Reilink R, et al. Integrating deflection models and image feedback for realtime flexible needle steering. IEEE Transactions on Robotics. 2013b; 29(2):542–553. Abolhassani N, Patel RV, Moallem M. Needle insertion into soft tissue: A survey. Medical Engineering and Physics. 2007; 29(4):413–431. [PubMed: 16938481] Aldrich JE. Basic physics of ultrasound imaging. Critical Care Medicine. 2007; 35(5):S131–S137. [PubMed: 17446771] Alterovitz R, Branicky M, Goldberg K. Motion planning under uncertainty for image-guided medical needle steering. The International Journal of Robotics Research. 2008; 27(11–12):1361–1374. [PubMed: 19890445] Asadian A, Kermani M, Patel R. Robot-assisted needle steering using a control theoretic approach. Journal of Intelligent and Robotic Systems. 2011; 62(3–4):397–418. Bar-Shalom, Y.; Li, XR.; Kirubarajan, T. Estimation with Applications to Tracking and Navigation. New York: John Wiley and Sons; 2001. Bernardes M, Adorno B, Poignet P, et al. Robot-assisted automatic insertion of steerable needles with closed-loop imaging feedback and intraoperative trajectory replanning. Mechatronics. 2013; 23(6): 630–645. Blumenfeld P, Hata N, DiMaio S, et al. Transperineal prostate biopsy under magnetic resonance image guidance: A needle placement accuracy study. Journal of Magnetic Resonance Imaging. 2007; 26(3):688–694. [PubMed: 17729363] Bogdanich W. At V.A. Hospital, a rogue cancer unit. 2009 Available at: http://www.nytimes.com/ 2009/06/21/health/21radiation.html. Brenner DJ, Hall EJ. Computed tomography—An increasing source of radiation exposure. New England Journal of Medicine. 2007; 357(22):2277–2284. [PubMed: 18046031] Cook JR, Bouchard RR, Emelianov SY. Tissue-mimicking phantoms for photoacoustic and ultrasonic imaging. Biomedical Optics Express. 2011; 2(11):3193–3206. [PubMed: 22076278] Cowan, NJ.; Goldberg, K.; Chirikjian, G., et al. Robotic needle steering: Design, modeling, planning, and image guidance. In: Rosen, J.; Hannaford, B.; Satava, RM., editors. Surgical Robotics. New York: Springer; 2011. p. 557-582. Deurloo EE, Gilhuijs KG, Kool LJS, et al. Displacement of breast tissue and needle deviations during stereotactic procedures. Investigative Radiology. 2001; 36(6):347–353. [PubMed: 11410756] DiMaio SP, Salcudean SE. Needle steering and motion planning in soft tissues. IEEE Transactions on Biomedical Engineering. 2005; 52(6):965–974. [PubMed: 15977726] DiMaio, SP.; Samset, E.; Fischer, G., et al. Dynamic MRI scan plane control for passive tracking of instruments and devices. Proceedings of the 10th International conference on medical image computing and computer-assisted intervention (MICCAI); 29 October–2 November 2007; Brisbane, Australia. 2007. p. 50-58. Duindam V, Xu J, Alterovitz R, et al. Three-dimensional motion planning algorithms for steerable needles using inverse kinematics. The International Journal of Robotics Research. 2010; 29(7): 789–800. Dupont PE, Lock J, Itkowitz B, et al. Design and control of concentric-tube robots. IEEE Transactions on Robotics. 2010; 26(2):209–225. [PubMed: 21258648] Fred H. Drawbacks and limitations of computed tomography: views from a medical educator. Texas Heart Institute Journal. 2004; 31(4):345–348. [PubMed: 15745283]

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 18

Author Manuscript Author Manuscript Author Manuscript Author Manuscript

Gefen A, Dilmoney B. Mechanics of the normal woman’s breast. Technology and Health Care. 2007; 15(4):259–271. [PubMed: 17673835] Glossop, ND.; Cleary, K.; Kull, L., et al. Needle tracking using the aurora magnetic position sensor. Proceedings of the International society for computer assisted orthopaedic surgery (CAOS); Santa Fe, CA, USA. 2002. p. 90-92. Glozman D, Shoham M. Image-guided robotic flexible needle steering. IEEE Transactions on Robotics. 2007; 23(3):459–467. Güth U, Huang DJ, Huber M, et al. Tumor size and detection in breast cancer: Self-examination and clinical breast examination are at their limit. Cancer Detection and Prevention. 2008; 32(3):224– 228. [PubMed: 18790576] Hauser, K.; Alterovitz, R.; Chentanez, N., et al. Feedback control for steering needles through 3D deformable tissue using helical paths. Proceedings of Robotics: Science and systems (RSS); Seattle, WA, USA. 2009. Hong J, Dohi T, Hashizume M, et al. An ultrasound-driven needle-insertion robot for percutaneous cholecystostomy. Physics in Medicine and Biology. 2004; 49(3):441–455. [PubMed: 15012012] Huang J, Triedman J, Vasilyev N, et al. Imaging artifacts of medical instruments in ultrasound-guided interventions. Journal of Ultrasound in Medicine. 2007; 26(10):1303–1322. [PubMed: 17901134] Ko SY, Frasson L, Rodriguez y Baena F. Closed-loop planar motion control of a steerable probe with a “programmable bevel” inspired by nature. IEEE Transactions on Robotics. 2011; 27(5):970–983. LaValle, SM. Planning Algorithms. Cambridge; New York: Cambridge University Press; 2006. Available at: http://planning.cs.uiuc.edu. Majewicz A, Marra SP, van Vledder MG, et al. Behavior of tip-steerable needles in ex vivo and in vivo tissue. IEEE Transactions on Biomedical Engineering. 2012; 59(10):2705–2715. [PubMed: 22711767] Minhas, DS.; Engh, JA.; Fenske, MM., et al. Modeling of needle steering via duty-cycled spinning. Proceedings of the IEEE International conference on engineering in medicine and biology society (EMBC); 23–26 August 2007; Lyon, France. 2007. p. 2756-2759. Misra S, Reed KB, Schafer BW, et al. Mechanics of flexible needles robotically steered through soft tissue. International Journal of Robotic Research. 2010; 29(13):1640–1660. Neshat, H.; Patel, R. Real-time parametric curved needle segmentation in 3D ultrasound images. Proceedings of the IEEE RAS EMBS International conference on biomedical robotics and biomechatronics (BioRob); 19–22 October 2008; Scottsdale, AZ, USA. 2008. p. 670-675. Neubach Z, Shoham M. Ultrasound-guided robot for flexible needle steering. IEEE Transactions on Biomedical Engineering. 2010; 57(4):799–805. [PubMed: 19709957] Novotny PM, Stoll JA, Vasilyev NV, et al. GPU based real-time instrument tracking with threedimensional ultrasound. Medical Image Analysis. 2007; 11(5):458–464. [PubMed: 17681483] Okazawa S, Ebrahimi R, Chuang J, et al. Hand-held steerable needle device. IEEE/ASME Transactions on Mechatronics. 2005; 10(3):285–296. Onuigbo MAC, Cuffy-Hallam ME, Dunsmore NA, et al. Mammography reveals a 2-mm intraductal breast carcinoma. Hospital Physician. 2001; 37(5):61–64. Op den Buijs, J.; Abayazid, M.; de Korte, CL., et al. Target motion predictions for pre-operative planning during needle-based interventions. Proceedings of the IEEE International conference on engineering in medicine and biology society (EMBC); 30 August–3 September 2011; Boston, MA, USA. 2011a. p. 5380-5385. Op den Buijs J, Hansen HHG, Lopata RGP, et al. Predicting target displacements using ultrasound elastography and finite element modeling. IEEE Transactions on Biomedical Engineering. 2011b; 58(11):3143–3155. [PubMed: 21846601] Park W, Wang Y, Chirikjian G. The path-of-probability algorithm for steering and feedback control of flexible needles. The International Journal of Robotics Research. 2010; 29(7):813–830. [PubMed: 21151708] Patil, S.; Alterovitz, R. Interactive motion planning for steerable needles in 3D environments with obstacles. Proceedings of the IEEE RAS and EMBS International conference on biomedical robotics and biomechatronics (BioRob); 26–29 September 2010; Tokyo, Japan. 2010. p. 893-899.

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 19

Author Manuscript Author Manuscript Author Manuscript

Patil, S.; van den Berg, J.; Alterovitz, R. Motion planning under uncertainty in highly deformable environments. Proceedings of Robotics: Science and systems (RSS); Los Angeles, CA, USA. 2011. Reed KB, Majewicz A, Kallem V, et al. Robot-assisted needle steering. IEEE Robotics Automation Magazine. 2011; 18(4):35–46. [PubMed: 23028210] Roesthuis, RJ.; van Veen, YRJ.; Jayha, A., et al. Mechanics of needle-tissue interaction. Proceedings of the IEEE International conference on intelligent robots and systems (IROS); 25–30 September 2011; San Francisco, CA, USA. 2011. p. 2557-2563. Shkolnik, A.; Walter, M.; Tedrake, R. Reachability guided sampling for planning under differential constraints. Proceeding of the IEEE International conference on robotics and automation (ICRA); 12–17 May 2009; Kobe, Japan. 2009. p. 2859-2865. Taschereau R, Pouliot J, Roy J, et al. Seed misplacement and stabilizing needles in transperineal permanent prostate implants. Radiotherapy and Oncology. 2000; 55(1):59–63. [PubMed: 10788689] Taubin G. Estimation of planar curves, surfaces, and non-planar space curves defined by implicit equations with applications to edge and range image segmentation. IEEE Transactions on Pattern Analysis and Machine Intelligence. 1991; 13(11):1115–1138. Tomozawa Y, Inaba Y, Yamaura H, et al. Clinical value of ct-guided needle biopsy for retroperitoneal lesions. Korean Journal of Radiology. 2011; 12(3):351–357. [PubMed: 21603294] Van den Berg, J.; Patil, S.; Alterovitz, R., et al. LQG-based planning, sensing, and control of steerable needles. Workshop on algorithmic foundations of robotics (WAFR); 13–15 December 2010; Singapore. 2010. p. 373-389. Van Veen YRJ, Jahya A, Misra S. Macroscopic and microscopic observations of needle insertion into gels. Proceedings of the Institution of Mechanical Engineers, Part H: Journal of Engineering in Medicine. 2012; 226(6):441–449. Vos, PJD. Bachelor’s Dissertation. The Netherlands: Faculty of Science and Technology, University of Twente; 2013. Effect of system parameters on target motion. Vrooijink, GJ.; Abayazid, M.; Misra, S. Real-time three-dimensional flexible needle tracking using two-dimensional ultrasound. Proceedings of the IEEE International conference on robotics and automation (ICRA); 6–10 May 2013; Karlsruhe, Germany. 2013. p. 1680-1685. Webster RJ, Kim JS, Cowan NJ, et al. Nonholonomic modeling of needle steering. The International Journal of Robotics Research. 2006; 25(5–6):509–525. Webster RJ III, Jones BA. Design and kinematic modeling of constant curvature continuum robots: A review. The International Journal of Robotics Research. 2010; 29(13):1661–1683. Xu, J.; Duindam, V.; Alterovitz, R., et al. Motion planning for steerable needles in 3d environments with obstacles using rapidly-exploring random trees and backchaining. Proceedings of the IEEE International conference on automation science and engineering (CASE); 23–26 August 2008; Washington, DC, USA. 2008. p. 41-46.

Appendix: Index to Multimedia Extension The multimedia page is found at: http://www.ijrr.org

Author Manuscript

Table of Multimedia Extension Extension

Media type

Description

1

Video

This video demonstrates some representative results (Scenarios I-A and IV) of 3D needle steering.

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 20

Author Manuscript Author Manuscript

Fig. 1.

A flexible bevel-tipped needle is steered in the soft-tissue phantom by using a device that robotically inserts and rotates the needle. The needle deflects along a curved trajectory in the direction of the bevel tip. A 2D ultrasound transducer, which is orientated perpendicularly to the needle insertion direction, is used to track the needle tip in 3D space during insertion. A transducer positioning device is used to track the needle tip during insertion in order to estimate the needle tip pose. The needle tip pose is used to plan and control the needle motion to reach a moving target while avoiding possibly moving obstacles.

Author Manuscript Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 21

Author Manuscript Fig. 2.

Author Manuscript

The ultrasound image processing steps performed to determine the needle centroid position (yc, zc). (a) The ultrasound image shows a radial cross-sectional view of the needle affected by the comet tail artifact (CTA). A cropped portion is used for image processing. (b) A median filter is applied to reduce speckle in the ultrasound image. (c) Thresholding is used to obtain a binary image of the needle. (d) Erosion and subsequently dilation are applied to remove the remaining speckle in the ultrasound image. (e) A feature extraction algorithm , which describes (Hough transform) is used to find a vertical line segment denoted by the needle with CTA. (f) The needle centroid position (yc, zc) is evaluated from A in the direction of B at a distance equal to the needle radius, and displayed as the center of the red circle.

Author Manuscript Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 22

Author Manuscript Author Manuscript

Fig. 3.

Author Manuscript

The coordinate frames used to estimate the needle tip pose: frame (Ψ0) is used as fixed reference frame located at the needle entry point; frame (Ψn) is attached to the needle insertion device end-effector, while frame (Ψp) is located at the end-effector of the transducer positioning device; frame (Ψu) is fixed to the ultrasound image plane; frame (Ψt) is located at the needle tip, while frame (Ψt̂) is fixed at the estimated needle tip location; the ultrasound transducer aberration along the needle insertion axis (x-axis of frame (Ψ0)) is denoted by ±λ.

Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 23

Author Manuscript Fig. 4.

Author Manuscript

An overview of the controller architecture to control the transducer motion in order to enable online three-dimensional needle tip tracking. The transducer motion along the x-axis (frame (Ψ0)) is evaluated by the compensator using the needle insertion velocity (vi) according to (3). In order to provide closed-loop control, gain scheduling of Ke according to (8) is applied. In-plane motion (y-axis of frame (Ψ0)) of the needle tip is compensated for by a proportional-derivative-(PD)-controller (proportional gain (Kp = 0.4) and derivative gain (Kd = 0.1)). The needle tip motion in the z-axis (frame (Ψ0)) is not compensated for. The zaxis (frame (Ψ0)) is used to position the transducer on the surface of the soft-tissue phantom. The transducer motion is enabled by a Cartesian positioning device to provide the needle tip position (p). The needle tip velocity (ṗ) is obtained by taking the time derivative of p. The tracker reference position and velocity signals are denoted pr and ṗr, while the tracker position and velocity errors are denoted e and ė, respectively. The influence of process (w) and measurement (v) noise on the states (p and ṗ) are minimized by a Kalman observer, which also predicts the subsequent state. The estimated needle tip position and velocity are denoted by p̂ and

, respectively.

Author Manuscript Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 24

Author Manuscript Author Manuscript Author Manuscript

Fig. 5.

A schematic representation of the Kalman observer. During the time update, predictions of the state (x̂k|k−1) and the error covariance (Pk|k−1) are performed. Subsequently, if the needle is detected in the ultrasound image, a measurement update is performed with Kalman gain (Kk) and needle tip position measurement (pk).

Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 25

Author Manuscript Fig. 6.

Author Manuscript

We use closed-loop motion planning to steer the needle to a target. Given a needle tip pose and the locations of a target region and obstacles, our fast, randomized motion planner computes in the available time many feasible motion plans (left). The method selects the best plan based on clinically motivated optimization criteria such as minimizing path length or maximizing clearance from obstacles (middle). The needle insertion device then executes the first control output of the plan (right). The planner is periodically executed every Δ seconds, closing the loop. At the beginning of each period, the ultrasound system returns an estimate of the needle tip pose, and the motion planner executes for the next period while the needle insertion device executes the previously computed control output. Closed-loop motion planning enables the system to automatically steer the needle to targets in 3D environments while avoiding obstacles and correcting for perturbations in needle motion and obstacle and target locations as they occur.

Author Manuscript Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 26

Author Manuscript Author Manuscript

Fig. 7.

(a) The time duration (Δ) is split into multiple (e.g. three) intervals of duration δ, each for β = 1/3. Each interval is then composed of two intervals: (I) a spin interval of duration (δspin) given by δspin =(2kπ/ωspin), k ∈ ℤ in which the needle is both inserted and rotated, and (II) an insertion interval of duration δins in which the needle is only inserted without any rotation. (b) Characterization of the relationship (α = h(κ)) for needle insertion in the softtissue phantom.

Author Manuscript Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 27

Author Manuscript Author Manuscript Author Manuscript

Fig. 8.

The experimental setup used to track and steer a flexible needle to reach a target while avoiding an obstacle. The needle, which is controlled at its base (inset) by a needle insertion device ① is inserted into the soft-tissue phantom ②. The two-dimensional ultrasound transducer ③ is positioned at the needle tip during insertion by a transducer positioning device ④, which provides feedback for steering.

Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 28

Author Manuscript Author Manuscript Fig. 9.

Author Manuscript

Experimental needle steering scenarios: (a) The needle is steered to a moving spherical target at four different locations: A, B, C and D in Scenarios I-A, -B, -C and -D, respectively. (b) The needle is steered around a cylindrical-shaped obstacle (e.g. bone) which is in the direct path of the needle to reach a spherical target (Scenarios II–IV). In Scenario II, the needle is steered to reach a stationary target while avoiding a stationary obstacle. In Scenario III, the needle is steered to reach a moving target while avoiding a stationary obstacle. In Scenario IV, the needle is steered to reach a target in an environment with obstacle and target motion.

Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Vrooijink et al.

Page 29

Author Manuscript Fig. 10.

Author Manuscript

Representative experimental needle steering results and mean absolute errors (MAE) in targeting accuracy: (a) Scenario I (moving target)—MAE: (I-A) 0.59 mm, (I-B) 0.54 mm, (I-C) 0.86 mm, and (I-D) 0.82 mm. (b) Scenario II (both stationary obstacle and target)— MAE: 1.76 mm. (c) Scenario III (stationary obstacle and moving target)—MAE: 1.33 mm. (d) Scenario IV (both moving obstacle and target)—MAE: 2.16 mm. The initial position of the cylindrical obstacle (bone) is shaded red, while its end position is solid red. The shaded blue sphere represents the initial target location, while the final target location is represented by a solid blue sphere. Please see the video in supplementary material (Multimedia Extension 1) that demonstrates some representative results (Scenarios I-A and IV) of three-dimensional needle steering.

Author Manuscript Author Manuscript Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Author Manuscript

Author Manuscript

Author Manuscript

0.06±0.02

I

0.05±0.03

0.05±0.04

0.06±0.03

IV

0.05±0.03

D

III

0.06±0.03

C

II

0.05±0.03

B

A

εx [mm]

Scenario

1.37±0.68

1.11±0.55

1.63±1.06

0.53±0.40

0.66±0.37

0.46±0.35

0.18±0.13

εy [mm]

1.56±0.82

0.54±0.71

0.53±0.66

0.57±0.44

0.41±0.35

0.21±0.27

0.51±0.37

εz [mm]

2.16±0.88

1.33±0.47

1.76±1.02

0.82±0.52

0.86±0.35

0.54±0.39

0.59±0.30

MAE [mm]

For each scenario, MAE for targeting accuracy are evaluated. Each experiment is conducted 10 times.

Targeting errors for ultrasound needle tracking and steering experiments (Scenarios I–IV). Mean absolute errors (MAE) for needle tip targeting along x(εx)-, y-(εy)-, and z-(εz)-axes (frame (Ψ0)) are provided. The targeting errors are evaluated using the estimated needle tip pose from ultrasound tracking.

Author Manuscript

Table 1 Vrooijink et al. Page 30

Int J Rob Res. Author manuscript; available in PMC 2015 September 01.

Needle path planning and steering in a three-dimensional non-static environment using two-dimensional ultrasound images.

Needle insertion is commonly performed in minimally invasive medical procedures such as biopsy and radiation cancer treatment. During such procedures,...
3MB Sizes 0 Downloads 4 Views