Nothing Special   »   [go: up one dir, main page]

Skip to main content
NIHPA Author Manuscripts logoLink to NIHPA Author Manuscripts
. Author manuscript; available in PMC: 2022 Apr 1.
Published in final edited form as: IEEE Robot Autom Lett. 2021 Mar 17;6(2):3987–3994. doi: 10.1109/lra.2021.3066962

Backward Planning for a Multi-Stage Steerable Needle Lung Robot

Janine Hoelscher 1, Mengyu Fu 1, Inbar Fried 1, Maxwell Emerson 2, Tayfun Efe Ertop 2, Margaret Rox 2, Alan Kuntz 3, Jason A Akulian 4, Robert J Webster III 2, Ron Alterovitz 1
PMCID: PMC8087253  NIHMSID: NIHMS1690655  PMID: 33937523

Abstract

Lung cancer is one of the deadliest types of cancer, and early diagnosis is crucial for successful treatment. Definitively diagnosing lung cancer typically requires biopsy, but current approaches either carry a high procedural risk for the patient or are incapable of reaching many sites of clinical interest in the lung. We present a new sampling-based planning method for a steerable needle lung robot that has the potential to accurately reach targets in most regions of the lung. The robot comprises three stages: a transorally deployed bronchoscope, a sharpened piercing tube (to pierce into the lung parenchyma from the airways), and a steerable needle able to navigate to the target. Planning for the sequential deployment of all three stages under health safety concerns is a challenging task, as each stage depends on the previous one. We introduce a new backward planning approach that starts at the target and advances backwards toward the airways with the goal of finding a piercing site reachable by the bronchoscope. This new strategy enables faster performance by iteratively building a single search tree during the entire computation period, whereas previous forward approaches have relied on repeating this expensive tree construction process many times. Additionally, our method further reduces runtime by employing biased sampling and sample rejection based on geometric constraints. We evaluate this approach using simulation-based studies in anatomical lung models. We demonstrate in comparison with existing techniques that the new approach (i) is more likely to find a path to a target, (ii) is more efficient by reaching targets more than 5 times faster on average, and (iii) arrives at lower-risk paths in shorter time.

Keywords: Surgical Robotics, Planning, Surgical Robotics, Steerable Catheters/Needles, Motion and Path Planning

I. Introduction

LUNG cancer is responsible for the most cancer-related deaths in the United States [1]. Physicians can identify suspicious nodules in a patient’s lung using medical imaging, but it is currently not possible to definitively diagnose those nodules with sufficient accuracy via imaging alone. While biopsies are the gold standard for diagnosis, existing approaches are not always sufficient: (i) transoral approaches (i.e., through the mouth) cannot reach many regions in the lung as these approaches are restricted to the airways accessible by a bronchoscope; and (ii) percutaneous approaches that insert a needle through the chest wall carry high risks such as lung collapse [2]. As early diagnosis increases a patient’s chance of survival, a reliable procedure bearing lower risk could be transformative for lung cancer diagnostics and patient care.

To enable a minimally invasive lung biopsy procedure that is both effective and safe, we are developing a new steerable needle lung robot [3]. The robot combines the advantages of both the transoral and percutaneous approaches by combining low-risk transoral deployment with the ability to reach targets in the peripheral lung using a steered needle. Our robot includes three stages that must be sequentially deployed during a procedure. First, a physician deploys a bronchoscope into the patient’s airways. Then, the physician utilizes a sharpened piercing tube to pierce through the airway wall and into the lung parenchyma. Subsequently, the system extends a steerable needle from the piercing tube and into the lung parenchyma, where it automatically steers to the target location.

In this paper, we introduce a new motion planner for the steerable needle lung robot that integrates planning for all three robot stages to enable fast robot deployment to a target location. In this process, it is crucial to minimize patient risk. Therefore, the planner has to avoid piercing critical anatomic structures–such as large blood vessels or airways–which could lead to severe complications. Fig. 1 shows planned trajectories in lung anatomy extracted from a preoperative 3D CT scan. Motion planning for the steerable needle lung robot requires creating plans for each of the three stages, where each stage’s start pose depends on the previous stage’s end pose. When computing plans, prior planning algorithms considered the stages in the order of their deployment. Based on the observation that planning from a point (the target) to a region (the bronchial tubes) is faster than planning from a region to a point, our new planner considers the stages in reverse order to achieve significant computation time reduction.

Fig. 1.

Fig. 1.

Our algorithm computes motion plans for a 3-stage steerable needle lung robot to reach a target (red sphere) in the lung. The robot’s stages include a bronchoscope (blue), piercing tube (cyan), and steerable needle (green). Significant obstacles such as blood vessels (red), airways (beige), and the lung boundary (grey) are extracted from a CT scan. Here, an ex-vivo porcine lung scan is shown. The sampling-based planner avoids these obstacles and creates safe robot trajectories planning backwards from the target toward the airways. Each needle plan has a cost representing the amount of small blood vessels it crosses, as shown in the close-up. Lower cost is depicted in lighter shades of green.

Specifically, prior work [4] used a forward planning approach that first randomly samples a bronchoscope and piercing tube pose. From the sampled piercing tube’s tip pose the needle planner then starts to iteratively build a search tree toward the target. In case no plan is found from this randomly sampled start pose, the pose is rejected and the full process is repeated. This includes repeated construction of new needle search trees, which is very computationally expensive.

In this work, we propose the inversion of the problem by constructing a needle search tree from the target location and by integrating planning for all three stages into one search tree. Once this tree approaches a region near the airways, the algorithm attempts to locate a straight piercing trajectory that leads into the center of an airway reachable by the bronchoscope. If no successful piercing pose is found, the search tree is grown further, extending existing paths until the planner is successful. This is much more efficient than restarting the entire planning process and relinquishing all previous exploration. This process relies on pre-computing a model of regions reachable by the bronchoscope inside the airway structure. Furthermore, we introduce two speedup strategies for the planner: one is based on combined geometric constraints of all three robot stages, and the other biases search tree growth toward target regions.

We evaluate our new motion planner for a three-stage robot in simulation using hardware specifications of the robot shown in Fig. 2. We use anatomy from ex-vivo and in-vivo porcine lungs, which provide a good model for human lungs [5]. On average, our approach finds a plan to a random target more than five times faster than prior work.

Fig. 2.

Fig. 2.

The complete steerable needle lung robot setup (left) consists of three stages: a bronchoscope with a flexible tip, a piercing tube that helps deploy a steerable needle into the lung parenchyma, and a steerable needle with an asymmetric bevel tip, which semi-automatically steers to a target [3]. The right image shows a close-up of the bronchoscope tip with an extended piercing tube and a steerable needle.

II. Related Work

Chest CT scans are the standard for lung cancer imaging [6]. To plan safe deployment of our steerable needle lung robot, we require an accurate geometric representation of the planning environment, which we obtain by segmenting a patient-specific CT scan. A large number of algorithms for segmentation of different lung structures are available as summarized by Van Rikxoort et al. [7]. The segmentation approach used in this work is described in [8].

Graph and tree data structures are common ways for describing airway branching structures [9]. Applications that use such tree representations include motion planning for bronchoscopies [10], branch point matching for lung registration [11], and trachial stenosis diagnostics through imaging [12]. Popular methods for extracting such a tree structure are thinning or skeletonization algorithms. We apply the parallelized thinning algorithm by Lee et al. [13] in an implementation as developed by Homann et al. [14] to our airway segmentation. Skeleton representations can be parsed voxel by voxel to extract a directed graph representation [15]. The links in such a graph are often modeled as cylinders representing the varying radii of airway branches [16], [17], [18]. We use such a representation to model the region in the airways that can be reached by the bronchoscope.

Robotic steerable needles are a promising approach for minimally invasive procedures to operate in parts of the body not safely reachable with conventional instruments [19]. Bevel tip steerable needles apply asymmetric force on tissue when they are inserted, which causes them to curve in the direction of the bevel [20]. By axially rotating the needle during insertion, different curving directions can be achieved. Using duty cycling with axial rotation results in varying insertion curvatures [21].

Different motion planning approaches for steerable needles have been previously introduced, including fractal-based planning [22] and optimization methods [23]. Sampling-based motion planning is another planning approach that has been proven to be effective in many different high-dimensional applications [24]. The Rapidly-exploring Random Tree algorithm (RRT) [25] provides an efficient way to plan a path from a start to a specific target by constructing a search tree structure. One source of difficulty in sampling-based motion planning for steerable needles is the needle’s non-holonomic constraints (i.e., its minimum radius of curvature). Connecting two samples in SE(3) under these constraints requires solving a difficult two-point boundary value problem [26]. Many sampling-based algorithms such as RRT* [27] that require connecting two arbitrary configurations can therefore not be directly applied to needle planning. One solution to this problem is to first find a plan and then smooth it such that it complies with the constraints [28]. Our work builds on a sampling-based method by Patil et al. [29], which creates a search tree fully compliant with non-holonomic constraints. This needle planner was extended to a 3-stage motion planner for robot lung procedures by Kuntz et al. [4]. To our knowledge, this is the only existing work integrating a needle planner into a multi-stage planning process. In addition, needle planning methods exist that explicitly consider deformations [30], [31] or consider uncertainty [32], [33]. Berenson et al. [34] present an RRT approach for planning toward a goal region instead of a single target which is based on inverse kinematics and bidirectional planning from the goal region and the start location simultaneously. This method is not directly applicable to our planning problem as our goal regions are large and a bidirectional search would therefore be very inefficient. Nevertheless, it inspired our strategy for target region biasing, which encourages RRT growth toward the airways and results in a significant speedup.

III. Problem Definition

Each of the three robotic system stages has physical constraints that need to be considered in the planning process. We visualize these constant hardware limitations in Fig. 3. A bronchoscope has a diameter dbronch that determines how far it can be extended into the airways. A piercing tube is represented by a maximum insertion length ltube beyond the bronchoscope tip, a diameter dtube, and a maximum piercing angle θtube that signifies how much the piercing tube’s direction can deviate from the bronchoscope tip’s medial axis. A steerable needle’s hardware parameters are defined by its minimum steering radius of curvature rcurve, cross-sectional diameter dneedle, and maximum insertion length lneedle.

Fig. 3.

Fig. 3.

Bronchoscope (blue), piercing tube (cyan) and steerable needle (green) deployment are limited by the hardware constraints visualized. The piercing tube pierces out of the airways (beige) and into the parenchyma, where the steerable needle is deployed.

The planning algorithm produces a deployment path ρ to the target location ptarget based on the consecutive system stages: ρ = [ρbronch, ρtube, ρneedle]. We define a path of stage s as ρs = [Qs,1, …, Qs,I], an ordered list of I configurations. The bronchoscope, piercing tube, and needle paths consist of L,M,N configurations, respectively. Configurations are described by poses, denoted as 4 × 4 homogeneous transformation matrices

Qs,i=(Rs,ips,i01),

where ps,i3 is the position and Rs,iSO(3) is the orientation relative to a world coordinate frame.

The first piercing tube position ptube,1 is equal to the final bronchoscope position pbronch,L and deviates from the bronchoscope tip’s orientation by up to θtube degrees. Qtube,pierce denotes the pose in which the piercing tube pierces out of the airways, and the last piercing tube pose Qtube,M is equal to the first needle pose Qneedle,1. The needle plan ends at the target: pneedle,N = ptarget.

Each point along a plan has an associated cost C:3[0,). The cost for a plan ρ is defined as

C(ρ)=01C(p(s))ds

where s ∈ [0, 1] and p:[0,1]3 is a mapping of configurations along ρ into 3D space. A plan is only valid if its total cost is C(ρ) < ∞, which signifies that it pierces no critical anatomical structures.

Finding an optimal motion plan in this setting can be expressed as an optimization problem:

ρ=argminρC(ρ)

Subject to:

C(p)<p[ptube,pierce,,ptube,M]ρneedle
gbronch(ρbronch)0
gtube(ρtube)0
gneedle(ρneedle)0
pbronch,L=ptube,1
Qtube,M=Qneedle,1
pneedle,N=ptarget

where ρ* is an optimal plan. The general inequalities gbronch(ρbronch), gtube(ρtube), and gneedle(ρneedle) represent the stages’ kinematic constraints, in particular the bronchoscope’s ability to reach areas in the airways limited by its diameter, the maximum piercing angle, and the needle’s minimum radius of curvature.

IV. Methods

Planning a safe robot path toward a target includes sampling configurations for the bronchoscope, piercing tube, and steerable needle while avoiding critical obstacles and aiming to find the lowest cost plan. When planning backwards from the target, the planner attempts to find a path to the reachable bronchoscope region. Moreover, the planner has to consider hardware constraints such as a limitation for piercing angles and the steerable needle’s minimum radius of curvature. In the following, we will describe each element of the planning process in detail.

A. Anatomical Environment Representation

To ensure a safe procedure, collisions with critical structures need to be avoided. Using the method in [8], we create a cost map IC where each voxel is assigned a cost value:

C(p)={ifvoxelpIAIBIR[0,1]otherwise

where IA, IB, and IR are sets of voxels representing the airway, large blood vessels and the region outside the lung, respectively. Collisions with smaller blood vessels are common during clinical procedures, but they should still be avoided when possible. We choose a cost metric that reduces the risk of piercing vessels during robot deployment. To compute this cost, we extract smaller blood vessels IV, which are assigned values [0,1] in IC. Higher values indicate a higher risk of piercing through small vessels at each voxel [8]. Our framework also supports other cost metrics to evaluate the path quality such as clearance from obstacles and path length. We determine all locations inside the airways that are reachable by the bronchoscope tip. We model this region by first extracting the airways’ medial axes by applying a 3D thinning algorithm [13] to binary image IA. A resulting skeleton binary representation is shown in Fig. 4a. This representation is parsed to extract a directed tree representation. We construct such a tree T(n, e), where each branch point in the skeleton is a node n and each branch is an edge e. We parse all voxels in the skeleton image starting from a manually selected voxel in the trachea. Bronchoscope deployment is limited by its diameter in comparison to the diameter of corresponding airway branches. To determine bronchoscope reachability, we create a simplified airway model by approximating each branch by a cylinder. For each edge e in the tree structure we connect the start and end node locations to form a cylinder’s medial axis and iteratively test positions along this axis for radii inside the airway. For each position we determine the largest circle around it in the plane perpendicular to the medial axis that is fully contained inside the airways. To avoid overestimation of the airway diameter, the smallest radius found along the axis is chosen to be the representing cylinder’s radius.

Fig. 4.

Fig. 4.

The medial axis representation (black) of the airways (beige) is used to determine which branches the bronchoscope can reach (light green). The reachable bronchoscope region B (yellow) and the piercing region P (dark green) are constructed from cylinders.

Positions in the airway that can be reached by the bronchoscope are determined in a recursive way utilizing tree T. Starting in root node n1 located in the trachea, we conduct a depth-first search following each edge until its associated diameter becomes smaller than the bronchoscope’s diameter. The result of this search is a set of cylinders B = {b1, …, bn} that represents all reachable airway branches. A cylinder bB representing the reachable part of edge e is defined as b={pb,pb,vb,lb,rb}. The start position pb3 is equivalent to the coordinates of ni, the node the edge starts from. The end position pb3 is the last reachable position along e. The cylinder’s direction vb3 is defined as the vector connecting the edge’s start node and end node vb = njni. The cylinder’s length is lb=pbpb2. The radius rb is the smallest radius determined along the reachable part of e subtracted by 0.5dbronch to represent regions inside the branch that the center of the bronchoscope tip can reach. In addition, we define the piercing region P as a cylinder set representing the region the piercing tube tip can reach. Here, we extend the length of each cylinder in B by the piercing tube’s maximum length ltube and the radius of each cylinder by ltube sin(θtube) to define an outer boundary of all points the piercing tube can reach if extended to its maximum. The cylinder sets are visualized in Fig. 4b. It is highly discouraged to puncture the pleura between lung lobes due to potential lung collapse. Therefore, we always restrict the planning process to the lobe the target is located in.

Algorithm 1.

Backward Planning

graphic file with name nihms-1690655-t0009.jpg

Algorithm 2.

Sampling a Configuration

graphic file with name nihms-1690655-t0010.jpg

B. Backward Planning

We reverse the planning problem and plan backwards from the target position ptarget toward the airways where the plan has to fulfill a set of constraints to accurately represent the process of piercing the airway wall. To create such a plan, we apply an RRT algorithm that constructs a search tree consisting of robot configurations. Our method is outlined in Algorithms 1 and 2. Black code is part of the basic algorithm described in this subsection, whereas blue and pink lines refer to speedup additions described in the next subsection. The algorithm takes into account the non-holonomic constraints of the needle represented in gbronch, gtube, and gneedle.

Our method for growing the RRT is based on the approach described in [26]. Starting from ptargets our algorithm extends the RRT by sampling new needle tip configurations (Alg. 1, line 4). It first samples only a position p3 (Alg. 2, line 10). Then, it determines its nearest neighbor N in the existing RRT using a custom distance function that only considers tree nodes whose orientation allows for reaching the new sample under the needle’s curvature constraint. It connects the nearest neighbor and the sample by an arc with a constant radius of curvature. The algorithm takes a step of length s from neighbor N toward p along the arc, which results in the new configuration Q (Alg. 2, line 11). The connecting process determines the full configuration of Q as the arc connection provides its orientation.

For efficient collision detection we add all center points of voxels with IC(p) = ∞ representing critical obstacles to a nearest neighbor search structure NN. A position p along a needle path is considered in collision if the distance to its nearest neighbor obstacle voxel NN(p) = v is smaller than or equal to the radius of a sphere enveloping the voxel:

Collision(p)=pv2rvoxelrvoxel=x2+y2+z2+dneedle2, (1)

where (x×y ×z) is the voxel size. Only configurations with a collision-free connection to their nearest neighbor are added to the RRT (Alg. 1, line 6).

The orientation of the first node in the search tree ptarget is not known a priori because the target can be reached from any direction. To solve this problem, we add a subroutine (Alg. 2, line 3) that randomly samples a needle tip configuration, including its orientation. The algorithm then determines a constant curvature arc connection from the configuration to ptarget. This process determines the target’s orientation. Additionally, this subroutine is called with a probability of Prstart throughout the planning process. This results in growing multiple intertwined search trees from the target location at the same time.

If a sample located inside the piercing region P is added to the needle search tree, this sample is considered to be the first element Qneedle,1 of needle path candidate ρneedle, and we attempt to find a connection to the reachable bronchoscope region B. Piercing tube deployment is limited by constraints represented in gtube: the straight tube is only able to move in the direction of its medial axis up to a maximum length ltube. It is deployed from the bronchoscope, deviating from the bronchoscope tip’s orientation by an angle of at most θtube. To determine a candidate piercing tube path ρtube, we sample tube tip configurations along a straight line segment starting at Qtube,M = Qneedle,1 with a step size z. We add configurations to the path until it either reaches a cylinder in B or it surpasses the maximum length ltube (Alg. 1, line 8). Each sampled point is checked for collisions with blood vessels in IB, in which case the sample is rejected. If a sampled point is in collision with IA, the piercing tube path has reached the airways. It cannot leave the airways again to avoid additional piercing of the airway walls. If the line segment reaches B, we consider this pose as the piercing tube’s start pose Qtube,1 of path ρtube. We compare its direction vtube to the direction of the colliding cylinder bi:

cosθ=vtubevbivtubevbi,

where θ is the approximate angle at which the airway walls are pierced. This angle has to be smaller than the maximum achievable piercing angle θtube. If this condition is met, a full three-stage plan was found, as the bronchoscope can reach all positions in B. We construct a bronchoscope path where pbronch,L = ptube,1 is the desired bronchoscope tip position. From this position we utilize tree T to backtrace edges to the trachea resulting in a bronchoscope deployment path ρbronch. As T represents all poses the bronchoscope can reach, ρbronch fulfills the bronchoscope kinematic constraints gbronch. The path construction and evaluation process is visualized in Fig. 5. If the piercing tube path does not reach region B or θ is larger than θtube, the algorithm resumes extending the RRT until it finds the next candidate piercing tube pose Qtube, M. The same RRT structure is extended until a valid path reaching B is found (Alg. 1, line 10).

Fig. 5.

Fig. 5.

If a new sample added to the RRT is located inside the piercing region P (grey), it is considered the start pose of a candidate needle path ρneedle (dark green). The sample is extended to a piercing tube path ρtube (cyan). If this path pierces into the airways (beige) and reaches the bronchoscope region B (yellow) with a piercing angle θ < θtube, a bronchoscope plan ρbronch (blue) is constructed. In this case, a full three-stage plan was found.

If a 3-stage plan ρ is found, it is recorded alongside its cost. After the algorithm found a plan, it restarts the planning process including construction of a new RRT. We run the planner in an anytime manner, i.e., over time, it finds plans with lower cost as computation time permits.

C. Speeding up Backward Planning

As it has been shown that a goal bias speeds up planning toward a target [35], we add a subroutine that samples positions inside the reachable bronchoscope region B. The function sampleFromCylinders:{ci}3, where {ci} is a set of cylinders, uniformly samples a position p3 from the volume of the bronchoscope reachable region B (see Alg. 7 line 6). The new sample is then added to the search tree. This subroutine is performed periodically instead of standard sampling with a probability of Prbias, causing the search tree to expand toward the reachable airways (Alg. 2 line 6 in blue).

Furthermore, we restrict new samples in the search tree by geometric constraints, adding only those samples to the RRT that potentially lead to a solution. We represent each cylinder in B by spheres of the same radius. The spheres’ centers are aligned with the cylinder’s medial axis, and they are spaced rvoxel apart, as defined in Equation 1. To validate a sample we first test its backward reachability toward B. A sample’s reachable workspace is defined by its orientation and the needle’s minimum radius of curvature rcurve, resulting in a funnel shape as shown in Fig. 6a. Only spheres within this workspace can be reached from the sample.

Fig. 6.

Fig. 6.

At least one bronchoscope reachable sphere (blue) has to fulfill all 3 constraints visualized in (a)-(c) with respect to the current sample p (red). Otherwise, the sample does not contribute to finding a plan and is rejected.

In addition, piercing tube deployment is limited to an angular range defined by the maximum piercing angle θtube. We define a second funnel shape representing the workspace of a particular sphere shown in Fig. 6b. This funnel’s base is defined as a circular cross-section of the sphere. The base is normal to the medial axis of the cylinder it is representing. The funnel extends from the base with an angle of θtube and follows curvature rcurve. The sample can only be reached from a sphere if it is located within its workspace.

Furthermore, we test if the sample is within reach from any of the spheres, as depicted in Fig. 6c. We compare its distance from a sphere s and its distance to the target with the needle’s and piercing tube’s maximum insertion length:

lneedle+ltubepps2+DistRRT(p)rs,

where ps is the sphere’s center position, rs is its radius, and DistRRT(·) is a function providing the distance from p to ptarget following the edges of the search tree.

This subroutine is applied to each new sample before it is added to the RRT (Alg. 1 line 5 in pink). For each new sample at least one sphere has to be found for which all three geometric constraints–the backward reachability constraint, the angular constraint, and the length constraint–are valid. All other samples are discarded.

V. Evaluation

We evaluated our algorithm based on CT scans of porcine lungs, which closely match the anatomy of human lungs [5] and will be used in pre-human trials of the steerable needle lung robot. We acquired CT scans of porcine lungs using a Siemens Biograph mCT scanner (Siemens Healthineers, Erlangen, Germany). Scans were reconstructed with a voxel size of (0.6 × 0.6 × 1.0) applying a pulmonary B70F kernel. We used scans of two inflated ex-vivo porcine lungs and one in-vivo porcine lung with 150 randomly selected targets in each. In the two ex-vivo lungs we sampled targets in 5 lobes (right caudal, left caudal, middle, accessory, and left cranial lobes) that correspond to the 5 lobes in a human lung [5]. The in-vivo lung is significantly smaller (approximate lung volume 1.7 liters) than an adult human lung. Therefore, only the two caudal lobes are reachable with our system and we sampled targets in these lobes only. The in-vivo scan was taken during a single breath hold.

We only selected targets with a safety margin of at least 1 mm in addition to the minimum distance to the closest obstacle voxel as defined in Equation 1. We assumed the bronchoscope’s diameter is dbronch = 6mm. The piercing tube had a diameter of dtube = 2mm and a maximum insertion length of ltube = 50mm. We chose a maximum piercing angle of θtube = 45 degrees based on experimental capabilities. The needle’s diameter was dneedle = 1.0mm with a maximum insertion length of lneedle = 120mm. A conservative measure of its minimum radius of curvature is rcurve = 100mm [36], [3], [37].

We compare our backward planning approach for a 3-stage robot against prior work, which used a forward planning method [4]. The prior work forward planner randomly samples bronchoscope and piercing tube poses that serve as a start pose for building an RRT for the needle stage. Needle configuration samples for the RRT are geometrically constrained to the needle’s reachable workspace. The forward planner employs goal biasing by adding ptarget to the RRT with probability Prbias. This is different from our biasing strategy, which consists of adding random samples from within the reachable airway region to the search tree. For fair comparison we set Prbias = 0.1 for both algorithms and we set Prstart = 0.05.

Additionally, we set a timeout t = 3 sec for the needle planning stage in the forward planner to avoid wasting compute time if the needle planning problem is infeasible for a specific combination of start pose and target position. The backward planner does not require timeouts for any of its subroutines as it keeps extending the RRT from the target until a solution is found.

For each target, we ran the planning process 10 times for a duration of 60 seconds for each algorithm, respectively. All simulations were run on a 3.2GHz 16-core Intel Xeon E5–2667 CPU with 64GB of RAM. We implemented all motion planner variants discussed in this paper based on the Motion Planning Template (MPT) library [38], which provides functionality for parallelized search tree construction. For efficient collision detection we used the nigh library [39] for nearest neighbor search. We evaluated the algorithms with respect to three different performance metrics: the ability to find a plan to a variety of targets, computational speed, and path costs.

First, we analyzed planning success for each target location. A successful planning process finds at least one plan within 60 seconds. The ex-vivo scenarios are simpler planning problems since blood vessel segmentation is limited as vessels are no longer filled with blood. Furthermore, the inflated ex-vivo lungs are significantly larger than the in-vivo lung providing more space for the needle to curve towards a target. In the two ex-vivo scenarios our backward algorithm found at least one plan for 290 out of 300 target location, whereas the forward planner only found solutions for 234 targets. In the in-vivo scenario our backward planner found plans for 128 out of 150 targets, while the forward planner only found plans to 61 targets. There is no target the forward algorithm found a plan for that our backward algorithm did not. Fig. 7 depicts that most targets for which only the backward algorithm was successful are located close to the airways. This illustrates a fundamental disadvantage of the forward planner: finding a plan to a target close to the airways is highly dependent on the highly random poses sampled in the first two stages.

Fig. 7.

Fig. 7.

We tested our algorithm in three porcine lungs with 150 random target locations each. Our backward planning algorithm found plans to significantly more target locations than the forward planning approach in 60 seconds. There is no target the forward approach found a plan to but the backward approach did not.

Second, we were interested in the duration of the planning process as it is critical to quickly find a safe plan during a procedure. We define success rate as the percentage of targets for which a plan has been found during a single run evaluated for all 450 targets. We recorded how the success rate changes throughout the time interval of 60 seconds and display an average over 10 such runs in Fig. 8a. It is evident that even the basic backward algorithm is significantly faster at finding plans than the prior forward approach. In addition, we see that both the geometric constraints and the biasing speedup strategies contribute to faster planning. Combining both strategies resulted in finding plans for 92.53% (±0.37% standard deviation) of targets in under 60 seconds. The backward approach with speedup takes on average 2.48 seconds to find the first plan per target, whereas the forward approach takes 13.90 seconds taking into account only targets with a plan found at least once by both algorithms.

Fig. 8.

Fig. 8.

Simulation results for 450 random targets in three lung planning scenarios. For each target the planner ran for 60 seconds of planning time and we repeated this process 10 times. (a) shows that all backward planning variants find plans to more targets faster than the forward planner. (b) shows that through this speedup the planner finds lower cost plans faster.

Third, we were interested in minimizing path cost, which is equivalent to minimizing the piercing of smaller blood vessels. Thus, plan cost is a measure of plan safety. During each planning process, the cost to reach the target is updated whenever a less expensive plan is found. We computed the average cost progression across all targets for each of the 10 runs. For each time step we determined all targets for which at least one plan was found and we computed the average of their current costs, resulting in the average cost progression over time for one run. We computed the average and standard deviation across all 10 runs, as shown in Fig. 8b. For fair comparison we considered only targets for which all algorithm variants found at least one plan. Fig. 8b shows the average cost progression and its standard deviation across all runs. It can be seen that our backward algorithm found less expensive plans significantly faster than the forward algorithm and that both speedup strategies contributed to better results.

VI. Conclusion

In this work, we introduce a new planning approach for a multi-stage steerable needle lung robot designed for lung interventions. Our approach is based on backward planning, which allows for more efficiency. In addition, we introduce two speedup strategies. One strategy is based on imposing geometric constraints on the search space and the other one biases tree extension toward regions of interest. We compared our approach to an existing forward planning method. For three different anatomical scenarios we demonstrated (i) that our approach is more likely to find a path to a target; (ii) it does so faster; and (iii) it produces lower-risk paths in shorter time. The main advantage of our new backward approach over the forward approach is that it performs the most complex part of the planning process - the creation of a needle search tree - only once instead of repeating it many times.

While our backward planning approach shows promising results, there are still some features to be optimized. For instance, to accelerate the process of finding lower cost plans, locally optimizing existing plans for lower cost is an option to be explored.

Similar to previous experiments [40], we are planning on evaluating the algorithm by performing a biopsy procedure in an ex-vivo porcine lung. Clinical translation introduces new challenges including but not limited to deformable image registration of a pre-operative scan to the lung and modeling tissue motion from breathing and heartbeats. From a planning perspective, rapid re-planning for some or all of the robot stages may be required to adjust for uncertainty. We hope that the increased efficiency of our 3-stage planner will be an enabler to successful clinical experiments.

Acknowledgments

This paper was recommended for publication by Editor Pietro Valdastri upon evaluation of the Associate Editor and Reviewers’ comments. This research was supported by the U.S. National Institutes of Health (NIH) under award R01EB024864.

References

  • [1].American Cancer Society, “Cancer facts and figures,” American Cancer Society Tech. Rep, 2018. [Google Scholar]
  • [2].Wiener RS, Schwartz LM, Woloshin S, and Welch HG, “Population-based risk for complications after transthoracic needle lung biopsy of a pulmonary nodule: an analysis of discharge records,” Annals of internal medicine, vol. 155, no. 3, pp. 137–144, 2011. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [3].Amack SR, Rox MF, Mitchell JE, Ertop TE, Emerson M, Kuntz A, Maldonado F, Akulian J, Gafford JB, Alterovitz R, and Webster RJ III, “Design and control of a compact, modular robot for transbronchial lung biopsy,” in SPIE Medical Imaging, vol. 10951, 2019. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [4].Kuntz A, Torres LG, Feins RH, Webster RJ, and Alterovitz R, “Motion planning for a three-stage multilumen transoral lung access system,” in Proc. IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), 2015, pp. 3255–3261. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [5].Judge EP, Hughes JL, Egan JJ, Maguire M, Molloy EL, and O’Dea S, “Anatomy and bronchoscopy of the porcine lung. a model for translational respiratory medicine,” American Journal of Respiratory Cell and Molecular Biology, vol. 51, no. 3, pp. 334–343, 2014. [DOI] [PubMed] [Google Scholar]
  • [6].Laurent F, Montaudon M, and Corneloup O, “CT and MRI of lung cancer,” Respiration, vol. 73, no. 2, pp. 133–142, 2006. [DOI] [PubMed] [Google Scholar]
  • [7].Van Rikxoort EM and Van Ginneken B, “Automated segmentation of pulmonary structures in thoracic computed tomography scans: a review,” Physics in Medicine & Biology, vol. 58, no. 17, p. R187, 2013. [DOI] [PubMed] [Google Scholar]
  • [8].Fu M, Kuntz A, Webster RJ, and Alterovitz R, “Safe motion planning for steerable needles using cost maps automatically extracted from pulmonary images,” in Proc. IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). IEEE, 2018, pp. 4942–4949. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [9].Aykac D, Hoffman EA, McLennan G, and Reinhardt JM, “Segmentation and analysis of the human airway tree from three-dimensional x-ray CT images,” IEEE Transactions on Medical Imaging, vol. 22, no. 8, pp. 940–950, 2003. [DOI] [PubMed] [Google Scholar]
  • [10].Kiraly AP, Helferty JP, Hoffman EA, McLennan G, and Higgins WE, “Three-dimensional path planning for virtual bronchoscopy,” IEEE Transactions on Medical Imaging, vol. 23, no. 11, pp. 1365–1379, 2004. [DOI] [PubMed] [Google Scholar]
  • [11].Li B, Christensen GE, Hoffman EA, McLennan G, and Reinhardt JM, “Establishing a normative atlas of the human lung: intersubject warping and registration of volumetric ct images,” Academic radiology, vol. 10, no. 3, pp. 255–265, 2003. [DOI] [PubMed] [Google Scholar]
  • [12].Sorantin E, Halmai C, Erdohelyi B, Palagyi K, Nyúl LG, Ollé K, Geiger B, Lindbichler F, Friedrich G, and Kiesler K, “Spiral-CT-based assessment of tracheal stenoses using 3-d-skeletonization,” IEEE Transactions on Medical Imaging, vol. 21, no. 3, pp. 263–273, 2002. [DOI] [PubMed] [Google Scholar]
  • [13].Lee T-C, Kashyap RL, and Chu C-N, “Building skeleton models via 3-d medial surface axis thinning algorithms,” CVGIP: Graphical Models and Image Processing, vol. 56, no. 6, pp. 462–478, 1994. [Google Scholar]
  • [14].Homann H, “Implementation of a 3d thinning algorithm,” Insight Journal, vol. 421, 2007. [Google Scholar]
  • [15].Tschirren J, Palagyi K, Reinhardt JM, Hoffman EA, and Sonka M,´ “Segmentation, skeletonization, and branchpoint matching—a fully automated quantitative evaluation of human intrathoracic airway trees,” in Proc. International Conference on Medical Image Computing and Computer-Assisted Intervention. Springer, 2002, pp. 12–19. [Google Scholar]
  • [16].Schlathoelter T, Lorenz C, Carlsen IC, Renisch S, and Deschamps T, “Simultaneous segmentation and tree reconstruction of the airways for virtual bronchoscopy,” in Medical Imaging 2002: Image Processing, vol. 4684. International Society for Optics and Photonics, 2002, pp. 103–113. [Google Scholar]
  • [17].Kitaoka H, Takaki R, and Suki B, “A three-dimensional model of the human airway tree,” Journal of Applied Physiology, vol. 87, no. 6, pp. 2207–2217, 1999. [DOI] [PubMed] [Google Scholar]
  • [18].Spencer RM, Schroeter JD, and Martonen TB, “Computer simulations of lung airway structures using data-driven surface modeling techniques,” Computers in Biology and Medicine, vol. 31, no. 6, pp. 499–511, 2001. [DOI] [PubMed] [Google Scholar]
  • [19].Cowan NJ, Goldberg K, Chirikjian GS, Fichtinger G, Alterovitz R, Reed KB, Kallem V, Park W, Misra S, and Okamura AM, “Robotic needle steering: Design, modeling, planning, and image guidance,” in Surgical Robotics. Springer, 2011, pp. 557–582. [Google Scholar]
  • [20].Webster III RJ, Kim JS, Cowan NJ, Chirikjian GS, and Okamura AM, “Nonholonomic modeling of needle steering,” The International Journal of Robotics Research, vol. 25, no. 5–6, pp. 509–525, 2006. [Google Scholar]
  • [21].Minhas DS, Engh JA, Fenske MM, and Riviere CN, “Modeling of needle steering via duty-cycled spinning,” in Proc. International Conference of the IEEE Engineering in Medicine and Biology Society. IEEE, 2007, pp. 2756–2759. [DOI] [PubMed] [Google Scholar]
  • [22].Pinzi M, Galvan S, and Rodriguez y Baena F, “The adaptive hermite fractal tree (ahft): a novel surgical 3d path planning approach with curvature and heading constraints,” International Journal of Computer Assisted Radiology and Surgery, vol. 14, no. 4, pp. 659–670, 2019. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [23].Duindam V, Xu J, Alterovitz R, Sastry S, and Goldberg K, “Three-dimensional motion planning algorithms for steerable needles using inverse kinematics,” The International Journal of Robotics Research, vol. 29, no. 7, pp. 789–800, 2010. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [24].LaValle SM, Planning algorithms. Cambridge University Press, 2006. [Google Scholar]
  • [25].—, “Rapidly-exploring random trees: A new tool for path planning,” TR 98–11, Computer Science Dept., Iowa State Univ., 1998. [Google Scholar]
  • [26].Patil S, Burgner J, Webster RJ, and Alterovitz R, “Needle steering in 3-d via rapid replanning,” IEEE Transactions on Robotics, vol. 30, no. 4, pp. 853–864, 2014. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [27].Karaman S and Frazzoli E, “Sampling-based algorithms for optimal motion planning,” The International Journal of Robotics Research, vol. 30, no. 7, pp. 846–894, 2011. [Google Scholar]
  • [28].Favaro A, Cerri L, Galvan S, Rodriguez y Baena F, and De Momi E, “Automatic optimized 3d path planner for steerable catheters with heuristic search and uncertainty tolerance,” in Proc. IEEE International Conference on Robotics and Automation (ICRA). IEEE, 2018, pp. 9–16. [Google Scholar]
  • [29].Patil S and Alterovitz R, “Interactive motion planning for steerable needles in 3d environments with obstacles,” in Proc. IEEE RAS & EMBS International Conference on Biomedical Robotics and Biomechatronics, 2010, pp. 893–899. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [30].Alterovitz R, Goldberg K, and Okamura A, “Planning for steerable bevel-tip needle insertion through 2d soft tissue with obstacles,” in Proc. IEEE International Conference on Robotics and Automation (ICRA). IEEE, 2005, pp. 1640–1645. [Google Scholar]
  • [31].Patil S et al. , “Motion planning under uncertainty in highly deformable environments,” Robotics science and systems: online proceedings, 2011. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [32].Park W, Kim JS, Zhou Y, Cowan NJ, Okamura AM, and Chirikjian GS, “Diffusion-based motion planning for a nonholonomic flexible needle model,” in Proc. IEEE International Conference on Robotics and Automation (ICRA). IEEE, 2005, pp. 4600–4605. [Google Scholar]
  • [33].Alterovitz R, Branicky M, and Goldberg K, “Motion planning under uncertainty for image-guided medical needle steering,” The International Journal of Robotics Research, vol. 27, no. 11–12, pp. 1361–1374, 2008. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [34].Berenson D, Srinivasa SS, Ferguson D, Collet A, and Kuffner JJ, “Manipulation planning with workspace goal regions,” in Proc. IEEE International Conference on Robotics and Automation (ICRA). IEEE, 2009, pp. 618–624. [Google Scholar]
  • [35].LaValle SM and Kuffner JJ Jr, “Randomized kinodynamic planning,” The International Journal of Robotics Research, vol. 20, no. 5, pp. 378–400, 2001. [Google Scholar]
  • [36].Swaney PJ, Mahoney AW, Hartley BI, Remirez AA, Lamers E, Feins RH, Alterovitz R, and Webster III RJ, “Toward transoral peripheral lung access: Combining continuum robots and steerable needles,” Journal of Medical Robotics Research, vol. 2, no. 01, p. 1750001, 2017. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [37].Rox M, Emerson M, Ertop TE, Fried I, Fu M, Hoelscher J, Kuntz A, Granna J, Mitchell J, Lester M, Maldonado F, Gillaspie EA, Akulian JA, Alterovitz R, and Webster RJ, “Decoupling steerability from diameter: Helical dovetail laser patterning for steerable needles,” IEEE Access, vol. 8, pp. 181411–181419, 2020. [DOI] [PMC free article] [PubMed] [Google Scholar]
  • [38].Ichnowski J and Alterovitz R, “Motion planning templates: A motion planning framework for robots with low-power CPUs,” in Proc. IEEE International Conference on Robotics and Automation (ICRA). IEEE, 2019, pp. 612–618. [Google Scholar]
  • [39].—, “Concurrent nearest-neighbor searching for parallel sampling-based motion planning in SO(3), SE(3), and euclidean spaces,” Springer, 2018. [Google Scholar]
  • [40].Kuntz A, Swaney PJ, Mahoney A, Feins RH, Lee YZ, Webster III RJ, and Alterovitz R, “Toward transoral peripheral lung access: Steering bronchoscope-deployed needles through porcine lung tissue,” in Proc. Hamlyn Symposium on Medical Robotics, 2016, pp. 9–10. [Google Scholar]

RESOURCES