IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION (SUBMITTED)
1
Choosing Good Distance Metrics and Local Planners for Probabilistic Roadmap Methods
Nancy M. Amato, O. Burchan Bayazit, Lucia K. Dale, Christopher Jones, Daniel Vallejo Abstract | This paper presents a comparative evaluation of dierent distance metrics and local planners within the context of probabilistic roadmap methods for planning the motion of rigid objects in three-dimensional workspaces. The study concentrates on cluttered three-dimensional workspaces typical, e.g., virtual prototyping applications such as maintainability studies in mechanical CAD designs. Our results include recommendations for selecting appropriate combinations of distance metrics and local planners for such applications. Our study of distance metrics shows that the importance of the translational distance increases relative to the rotational distance as the environment becomes more crowded. We nd that each local planner makes some connections than none of the others do | indicating that better connected roadmaps will be constructed using multiple local planners. We propose a new local planning method we call rotate-at-s that often outperforms the common straight-line in C-space method in crowded environments. Keywords | Motion Planning, Probabilistic Roadmaps, Distance Metrics, Local Planners
I. Introduction
Automatic motion planning has application in many areas such as robotics, virtual reality systems, and computeraided design. Although many dierent motion planning methods have been proposed, most are not used in practice since they are computationally infeasible except for some restricted cases, e.g., when the robot has very few degrees of freedom (dof) [11], [14]. For this reason, attention has focused on randomized methods, such as randomized potential eld methods (e.g., [5]). Recently, a class of randomized motion planning methods, called probabilistic roadmap methods (prms), has gained much attention (see, e.g., [1], [4], [10], [12], [19]). These methods use randomization during preprocessing to construct a graph in C-space (a roadmap). Queries are processed by connecting the initial and goal con gurations to the roadmap, and then nding a path in the roadmap between these two connection points. prms have been shown to perform well in practice, answering dicult queries in fractions of seconds [4], [12]. prm roadmap construction is generally performed in two A preliminary version of this paper appeared in the Proc. of the IEEE International Conference on Robotics and Automation, 1998. This research supported in part by NSF CAREER Award CCR9624315, NSF Grant IRI-9619850,and by the Texas Higher Education Coordinating Board under grant ARP-036327-017. The authors are with the Department of Computer Science at Texas A&M University, College Station, TX 77843-3112, USA. Email famato,burchanb,dalel,cvj3341,
[email protected]. Bayazit is supported in part by the Turkish Ministry of Education, Dale is supported in part by a GE Foundation Graduate Fellowship and a Department of Education GAANN Fellowship, and Vallejo is on leave from Universidad de las Americas-Puebla, Mexico, and is supported in part by a Fulbright-CONACYT scholarship.
stages: node generation and connection. In the node generation stage, collision-free con gurations of the robot are generated according to some sampling strategy in C-Space (e.g., uniformly [12], near constraint surfaces [4], [6], or on the medial axis [19]). In the connection stage, connections (edges) are made between node pairs if a path connecting them can be found by a `local' planning method. Although prms may vary in terms of high-level node generation and connection strategies, they all make heavy use of primitive operations such as collision detection, local planners (for connecting roadmap nodes), and distance computations (to select which connections to attempt, since it is infeasible to try them all). Thus, the choice of appropriate techniques for these operations can crucially impact the eciency and success of the prm. This paper presents a comparative evaluation of distance metrics and local planners in the context of prms. Our study concentrates on motion planning for rigid objects in cluttered three-dimensional workspaces typical, e.g., of virtual prototyping applications such as maintainability studies in mechanical CAD designs [7]. Such applications present dicult motion planning problems which typically require nding paths through narrow passages in the con guration space [10]. We believe such problems are amenable to solution by prms | but this will require a ne-tuning of every prm component, including primitive operations such as distance computations and local planners. Our study contributes to this goal by providing recommendations for selecting appropriate combinations of distance metrics and local planners for use with prms for rigid bodies moving in cluttered three-dimensional workspaces. Our study of distance metrics shows that the importance of the translational distance increases relative to the rotational distance as the environment becomes more crowded. We nd that each of the local planners makes some connections than none of the others do | which indicates that better connected roadmaps will be constructed using multiple local planners. We also propose a new local planning method, called rotate-at-s, that often outperforms the common straight-line in C-space method in crowded environments. II. Distance Metrics Distance metrics are used in prms to determine which
nodes one should attempt to connect using a local planner. A good metric will limit the number of calls to the local planner by classifying enough connectable nodes as close. It must also be fast to compute, since distance calculations are one of the most numerous operations in a prm.
IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION (SUBMITTED)
TABLE I
Distance Metrics Studied Euclidean Scal. Euclidean Minkowski Mod. Minkowski Manhattan Center of Mass Bounding Box
d(c1 ;c2 ) 1 P 2+ Q (q)2 2 P ( p ) q 12 p 12 ? P 1 P s p P12 (p)2 + (1 ? s) q Q12 (q)2 2 ?P 1 P P (p)r + q Q12 (q)r r p 12 1 ?P P P (p)r1P + q Q12 (q)r2 r3 P p 12 Q (q) q 12 p P12 (p) + ?P
dist. between center of masses max. dist. between BB vertices
4.6 4.7 11.6 24.2 4.4 18.4 33.7
A. C-Space Representation
Con gurations of rigid objects in three-space are represented by six-tuples c = (x; y; z; ; ; ), where the rst three coordinates de ne the position and the last three the orientation. The orientation coordinates are represented as values in [0 ? 1). Orientational dierences are measured in the shortest direction. To obtain generalizable results, we normalize the orientation coordinates (range [0 ? 1)) with respect to the position coordinates (no xed range); see [2] for details. B. Distance metrics evaluated
Our study considered ve C-Space and two workspace distance metrics. In Table I, P12(p) = jc2(p) ? c1 (p)j, where p 2 fx; y; z g, and Q12(q) = n12jc2(q) ? c1 (q)j, where q 2 f; ; g, and n12 is the normalization factor. Times shown are averages of 10,000 computations. Five C-space metrics were selected for evaluation based on eectiveness and eciency concerns (see, e.g., [9], [17]). The Euclidean distance in C-space considers C-Space as a Cartesian space and gives both position and orientation the same importance. The scaled Euclidean distance changes the relative importance of the position and orientation components through the scale parameter s. The Minkowski distance is the generalized form of the Euclidean distance which uses a parameter r in place of the 2; as with Euclidean, both position and orientation are given the same importance. Our so-called modi ed Minkowski metric distinguishes between the position and orientation coordinates using the parameters r1 (position) and r2 (orientation). The Manhattan metric is the usual Manhattan distance in IR6. Note the Minkowski metric approaches the Manhattan distance as r tends to in nity. The workspace metrics we chose to study are both simple metrics based on Euclidean distances in the workspace. The rst is the Euclidean distance between the center of mass of the robot in the two con gurations (the center of mass is approximated by averaging all object vertices). The second workspace metric makes use of the bounding box of the robot, and nds the maximum Euclidean distance between any vertex of the bounding box in one con guration and its corresponding vertex in the other con guration. Although there are many other types of metrics, such as Riemannian metrics [17], Hausdor distance [9], rota-
2
tion distance [20], growth distance [15], or the minimum distance between any point on the robot in the two con gurations (e.g., [8], [16]), they were not selected because they were either too expensive for use in prms or were only applicable to convex objects. III. Local Planners Local planners are used in prms to make connections
between nodes when building the roadmap. They must be fast (so many connections can be attempted) and deterministic (so paths don't have to be saved). A. Local Planner Resolution Issues
Start and goal con gurations of the robot are denoted by c1 = (x1 ; y1; z1 ; 1; 1 ; 1) and c2 = (x2; y2 ; z2; 2; 2; 2 ), respectively. The paths tested by our local planners consist of a sequence of con gurations that dier from their predecessors and successors by at most some xed resolution (in each coordinate). The resolution diered for position and orientation coordinates, and also varied according to the environment. Given (c1; c2), and a resolution for each coordinate, our planners calculate an increment vector I which is used to determine the neighboring con gurations tested by the planners. B. Local planners evaluated
Our rst planner is the common straight-line in Cspace method (see, e.g., [12]), which interpolates without bias along a six-dimensional straight line from con guration c1 to c2 , and checks all points at some xed resolution on that line for collision. We call our second (parameterized) family of local planners rotate{at{s, 0 s 1. This planner rst translates from c1 to an intermediate con guration c0, rotates to a second intermediate con guration c00, and nally translates to c2 . The parameter s represents the fractional part of the translational distance between c1 and c2 that the robot travels from c1 to c0 . The straight-line planner is used to plan between (c1; c0), between (c0 ; c00), and between (c00 ; c2). Note that the paths will have smaller swept-volumes than the straight-line paths. Our study considered s = 0; 21 ; 1. We also study two A -like planners: A -clearance and A -distance. The basic A strategy is to compute a set of neighbors of c1 , select the most promising neighbor c0 , and iterate with c0 . The process terminates when c2 is reached, no further movement is possible, or after some set number of iterations (see, e.g., [13], [18]). To make our A -like methods faster, we limit the number of steps to some small multiple (e.g., 6) of the steps taken by the straight-line planner, and we consider just three neighbors: con gurations where (i) both the position and orientation, (ii) only the position, and (iii) only the orientation, coordinates are incremented towards the goal. Both methods move to neighbor (i) if it is collision-free. Otherwise, A -clearance selects the neighbor with maximum clearance from the workspace obstacles, and A -distance selects the neighbor that has minimum distance to the goal.
IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION (SUBMITTED)
Fig. 1. 6-cube (hard)
Fig. 2. Alpha-puzzle (hard) TABLE II
Local Planner Connections by Environments
cube/Str-Line cube/R-at-1/2 cube/A-clear alpha/Str-Line alpha/R-at-1/2 alpha/A-clear
Easy 20.2% 22.2% 24.1% 11.6% 14.2% 25.6%
Mod 14.2% 16.1% 16.1% 10.3% 13.8% 22.3%
Hard 10.6% 11.4% 12.5% 8.6% 11.8% 19.7%
Succ. N/A N/A N/A 1025 1035 3755
IV. Experimental Design
Fail N/A N/A N/A 56 80 170
3
(iii) select local planners for environments, and (iv) study the bene ts of using multiple local planners. We generated 600 free con gurations (RdmpCfgs) near C-obstacle surfaces (simulating roadmap nodes). We also generated 100 free con gurations (TestCfgs) as test nodes; 50 of the TestCfgs were near C-obstacle surfaces and 50 were generated at random (generally not near C-obstacles, referred to as free con gurations). We used the method described in [3] to generate con gurations near the surfaces of C-Space obstacles, and the method described in [12] for free space nodes. For each local planner, we tried to connect each con guration in TestCfgs to every con guration in RdmpCfgs. To rate a metric (for a given local planner), we computed the distances using that metric between each node in TestCfgs and every node in RdmpCfgs, sorted these distances, and analyzed those connections made to the closest k nodes. In [2], we analyze results for k = 25; 50; 100; in this paper, we show only the results for k = 25 since they are the most relevant to prms. V. Experimental Results
The experiments described below were coded in C and A. Computational requirements C++, and conducted on SGI O2 workstations.1 Since prms perform a huge number of distance computations and local planning queries, their computation times A. Environments are important factors to consider when choosing among Our study considers two basic environments representa- them. Distance metric evaluation times are shown in Tative of cluttered three-dimensional workspaces, and three ble I; values are averages of 10,000 computations. The average number of collision detection calls for a set of 200 local diculty levels of each basic environment. planning queries (successful and unsuccessful) in the hard The rst environment consists of seven unit cubes (12 alpha puzzle environment is shown in Table II. Generally, triangles each); six cubes were obstacles and one was the the straight-line rotate-at-s planners have comparable moving object (see Fig. 1). The centers of the obstacle costs, while the and -like planners are roughly three times A cubes were placed on three parallel planes, one each on the front and back planes, and four in the middle plane, ar- slower (the dierence increases with the distance). ranged so that they surround a cubical region centered on B. Selecting parameters for distance metrics the middle plane. The hardness of the problem was controlled by varying the distance between the front, middle, Three of our metrics require parameters: scaled Euand back planes: 1:1 (hard), 1:6 (moderate), and 2 (easy). clidean (s), Minkowski (r), and modi ed Minkowski (r1; r2; r3). To determine good values for these parameters, we The second environment contains two twisted ( shaped) and tested several and selected the best for further evaluation. tubes (1008 triangles each); one tube is the obstacle and the For each local planner, we evaluated each distance metother the moving object (see Fig. 2). The reader might be ric parameter. We de ned a scoring mechanism intended familiar with the puzzle where the objective is to separate to give higher scores to parameter values which identi ed the intertwined tubes. The `hardness' of this problem was more \close" nodes that be connected by that local controlled by scaling the obstacle tube in one dimension, planner. For each TestCfgcould , the RdmpCfgs were partitioned which widened the gap between the two prongs of the . into ve sets according to relative distance as determined The scale factors were 1 (hard), 1:5 (moderate), and 2:5 by the metric/parameter(s) under consideration: 1 (closest (easy). 10), 2 (next 15), 3 (next 25), 4 (next 50), and 5 To calibrate the relative diculty of our environments ing 500). The score of a metric/parameter(s) for a(remainspeci c we compared the total number of connections made in each local planner was version. Table II shows these statistics for three local plann2 ) + 2( n3 ) + 1( n4 ); ners; the other planners showed similar trends. 4( n101 ) + 3( 15 25 50 B. Experiments
where ni is the number of connections that planner made in set i. Our experiments were designed to: (i) select parameters A selected summary of our results for the scaled Eufor distance metrics, (ii) select metrics for local planners, clidean and Minkowski metrics is contained in Table III. A 1 Complete experimental results can be found in [2]. general observation was that the relative importance of the
IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION (SUBMITTED)
4
TABLE III
The best scaled Euclidean and modified Minkowski values
6-cube easy 6-cube mod 6-cube hard alpha easy alpha mod alpha hard
Score 2.71 2.86 1.23 2.38 1.77 1.51
6-cube easy 6-cube mod 6-cube hard alpha easy alpha mod. alpha hard
Score 2.79 2.74 1.15 2.07 1.35 1.16
s
Score 2.82 2.98 0.95 1.01 0.91 0.82
r
Score 3.0 2.88 0.94 0.98 0.86 0.73
.25 .75 .75 .90 .90 .90
5.0 3.0 1.5 1.5 0.5 0.5
1 2
Score 3.38 3.13 1.84 4.71 3.96 3.56
r
Score 3.45 2.93 1.74 4.24 3.11 3.02
.50 .75 .75 .75 .75 .90 1 2
s
8.0 3.0 2.5 2.5 1.5 2.5
TABLE IV
Distance Metric Recommendations by Planner/Env
good recom. good recom. E, SE,MM SE(.50) SE, MM,CM SE(.75) SE, M, MM SE(.75) SE,MM, CM SE(.90) SE,M, MM SE(.50) SE,MM, CM SE(.75) SE,MM SE(.90) SE,MM,CM SE(.90) SE, M, MM SE(.50) SE, MM SE(.75) SE, MM SE(.90) SE, MM SE(.90) Distance Metrics Used: E=Eucl. SE=Sc. Eucl. M=Mink. MM=Mod. Mink. CM=Cent. Mass BB=Bd. Box
StrLine cube alpha R-at- 12 cube alpha A -clear cube alpha
translational (rotational) distance between the two con gurations increased (decreased) as the environments became harder. Also, we noted that the straight-line and rotateat- 21 were similar, as were the two A -like planners. For the scaled Euclidean metric, the optimal s value increases as the environment gets harder for all local planners and environments. For the surface to surface connections, the optimal s is usually higher in the alpha puzzle than in the 6-cube environments. Overall, s = :75 and s = :90 performed well. Our results for the Modi ed Minkowski values were generally supportive of these results as well. For the Minkowski metric in the 6-cube environments, most local planners reached their peak at r = 1:5 for surface to surface connections, and r = 4 for free to surface connections. In the alpha puzzle environments, the best values were r = 1:5 for surface to surface connections and r = 2:5 or r = 3 for free to surface connections. C. Selecting metrics for local planners
After selecting interesting parameter values for the various metrics, we were left with a total of 12 dierent distance metrics for each environment. All four non-parameterized metrics (Euclidean, Manhattan, Center of Mass, and Bounding Box) were analyzed in both environments. In the 6-cube environment, we selected the Scaled Euclidean with s = f:25; :5; :75; :9g, the Minkowski with r =
s
Score 8.38 8.35 8.58 4.61 4.47 4.33
r
Score 7.84 7.83 8.17 4.48 4.42 4.23
.50 .75 .75 .75 .90 .90
5.0 1.5 1.5 1.5 1.5 1.5
s
Score 8.66 8.69 9.10 5.67 5.80 5.47
r
Score 8.03 8.07 8.53 5.53 5.45 5.24
.90 .90 .90 .75 .75 .75
3.0 4.0 4.0 2.5 2.5 3.0
1 2
Score 8.61 8.79 9.14 8.08 8.28 7.89
r
Score 8.02 8.23 8.66 8.01 8.06 7.70
.90 .90 .90 .75 .90 .90 1 2
s
4.0 4.0 4.0 2.5 3.0 3.0
s
.90 .90 .90 .75 .75 .75
r
4.0 4.0 4.0 4.0 2.5 3.0
f1:5; 4g, and the Modi ed Minkowski with (r1; r2; r3) = f(2; 0:5; 2); (2; 2:5; 2)g. In the alpha puzzle environment, we selected Scaled Euclidean with s = f:25; :75; :9g, Minkowski with r = f1:5; 2:5g, and Modi ed Minkowski with (r1 ; r2; r3) = f(2; 1:5; 2); (2; 2:5; 2); (2:5; 2; 2)g. In each
of the six environments, each local planner was evaluated with the 12 selected metrics. A selected summary of distance metric recommendations for three local planners in the easy and hard environments is shown in Table IV. Generally, the best metrics placed more importance on the translational distance than on the rotational distance. Our recommendations take both eciency and eectiveness into account. When results differed for free to surface and surface to surface connections, a compromise is proposed. When the best metric is computationally expensive, we suggest a more ecient alternative (with comparable eectiveness). For example, it can be seen in Table IV that in many cases when the best performer was the Minkowski or Modi ed Minkowski metric, we instead recommend using the Scaled Euclidean. Our recommendations were based on the fact that the Scaled Euclidean's performance was almost as good and its computational requirements are about 40% and 20% those of the Minkowski and Modi ed Minkowski, respectively (see Table I). The individual scores for each metric/planner/environment combination can be found in [2]. Generally, the metrics performed comparably in all environments. An exception was the bounding box, which performed worse in the alpha puzzle than in the 6-cube environments, likely because the bounding box is not a good approximation of the -shape. D. Selecting local planners for environments
After determining which distance metrics were best suited for each local planner in each type of environment, we then compared the local planner and distance metric combinations. The straight-line and rotate-at- 21 planners had similar behavior, while the A -like planners were gen-
IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION (SUBMITTED)
5
Different Local Planners in Six-Cube Environments (for first 25 nodes) Surface Free
LP1:straight-line LP2:rotate-at-s [0.00] LP3:rotate-at-s [0.50] LP4:rotate-at-s [1.00] LP5:A*-clearance LP6:A*-distance D1 :Euclidean D2 :Scaled Euclidean[0.25] D4 :Scaled Euclidean[0.75] D5 :Scaled Euclidean[0.90] D6 :Minkowski[1.50] D7 :Minkowski[4.00] D8 :Mod.Mink.[2.00:0.50:2.00]
2500
# Connections
2000
1500
1000
Different Local Planners in Alpha-Puzzle Environments (for first 25 nodes)
3000
Surface Free
LP1:straight-line LP2:rotate-at-s [0.00] LP3:rotate-at-s [0.50] LP4:rotate-at-s [1.00] LP5:A*-clearance LP6:A*-distance D3 :Scaled Euclidean[0.75] D4 :Scaled Euclidean[0.90] D7 :Mod.Mink.[2.00:1.50:2.00] D9 :Mod.Mink.[2.50:2.00:2.00] D11:Center of Mass
2500
# Connections
3000
2000
1500
1000
500
500
0
0 LP1 LP2 LP3 LP4 LP5 LP6 D7 D8 D7 D2 D4 D4 Easy Environment
LP1 LP2 LP3 LP4 LP5 LP6 D8 D5 D8 D6 D4 D8 Moderate Environment
LP1 LP2 LP3 LP4 LP5 LP6 D8 D8 D8 D1 D8 D8 Hard Environment
Fig. 3. Comparison of LPs in 6-cube environments. Local Planners / Distance Metrics
erally the most eective (and expensive). The 6-cube environment results are shown in Fig. 3. In the graphs, there is one bar for each local planner/distance metric combination, and the black (white) portion of each bar represents the surface to surface (free to surface) connections made. We see that the best local planners in all 6-cube environments are the A -like planners, followed by the rotate-at- 12 planner. In general, rotate-at- 12 outperforms the straight-line planner, probably because its swept volume is smaller. The dramatic dierence between the rotate-at-0 and rotate-at-1 for the free to surface connections (white portion) is because the goal con guration is always near a C-obstacle surface (i.e., rotation at the goal, s = 1, will likely cause collision). The alpha puzzle environment results, shown in Fig. 4, are similar to the 6-cube, with the advantage of rotate-at- 21 over the straight-line being more pronounced. E. Using multiple local planners
The results shown in Table V indicate that dierent local planners do indeed make dierent connections. In each row (environment), the percentage of the connections made only by that local planner is shown. The straight-line is not shown because all its connections were made by the A -like methods. Similarly, the rotate-at- 12 values are low because most of its connections were also made by one of the A like methods. Finally, the values for both A -like methods are low since they made many of the same connections (they are both biased to neighbor (i), which increments the position and orientation coordinates towards the goal). When we included only one of the A -like methods in the analysis, in every environment at least 22% of the total connections were made only by the A -like planner; this percentage increased with the diculty. Table VI shows the comparison of two local planners. In the top half of the table, column one shows connections made by the straight-line but not the rotate-at- 21 planner, and vice versa in column two. Column four shows the percentage of the total connections made by the combination of the two planners, which was generally more than 50%. The results of the rotate-at- 21 and A -clearance combination (bottom half of the table) show that more than 80%
LP1 LP2 LP3 LP4 LP5 LP6 D3 D7 D3 D9 D9 D9 Easy Environment
LP1 LP2 LP3 LP4 LP5 LP6 D7 D7 D7 D4 D7 D7 Moderate Environment
LP1 LP2 LP3 LP4 LP5 LP6 D11D11 D7 D3 D7 D7 Hard Environment
Fig. 4. Comparison of LPs in alpha environments. Local Planners / Distance Metrics
TABLE V
Connections made by only one local planner.
6-cube easy 6-cube mod 6-cube hard alpha easy alpha mod alpha hard
11.5% 8.7% 1.7% .5% .7% 2.4%
1 2
1.1% 1.5% 1.3% 3.8% 11.7% 10.0%
TABLE VI
2.1% 2.5% 2.3% 3.2% 4.8% 5.9%
.4% .6% .4% .4% .6% 1.0%
.4% .3% .3% .9% .9% 1.0%
Combinations of Two Local Planners
6-cube easy 6-cube mod 6-cube hard alpha easy alpha mod alpha hard 6-cube easy 6-cube mod 6-cube hard alpha easy alpha mod alpha hard
1 2
3.4% 1.1% 1.1% 16.2% 9.9% 6.4% 1 2 1 2
17.2% 40.3% 38.3% 1.9% 3.3% 11.7%
22.9% 42.8% 40.1% 18.3% 17.8% 21.0%
1 2
49.9% 12.4% 12.2% 24.1% 21.1% 13.0%
76.3% 56.3% 53.5% 58.6% 48.8% 40.4%
55.6% 14.9% 14.0% 40.5% 35.5% 22.3%
96.4% 95.7% 96.1% 91.8% 82.2% 82.8%
23.5% 40.5% 43.8% 49.3% 43.4% 48.7%
of all connections are made by this pair. VI. Conclusion
The main goal of our study was to determine good combinations of distance metrics and local planners for use by prms for planning the motion of rigid objects in cluttered environments. Our results (Table IV), include recommendations for selecting distance metrics for various local planners in dierent types of environments. Generally, a good choice is the Scaled Euclidean metric, where more weight is placed on the position coordinates as the environment becomes more cluttered. Although it was not always the absolute best metric, its performance was comparable and it is quite ecient to compute. The most powerful local planners were the A -like planners. Among the less expensive planners, the rotate-at- 21 planner was the best, outperforming the common straight-
IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION (SUBMITTED)
6
line local planner. However, we also found that each of the [20] J. Xiao and L. Zhang. Computing rotation distance between contacting polyhedra. In Proc. IEEE Int. Conf. Robot. Autom. tested local planners made some connections that the oth(ICRA), volume 1, pages 791{797, 1996. ers did not. Thus, roadmap connectivity will be enhanced if the prm uses multiple local planners. Based on our experience, we would recommend the following order: rst, the rotate-at- 21 and straight-line planners, next, the rotate-at-0 and rotate-at-1 planners, and nally, the A planners. Acknowledgment
The alpha puzzle was designed by Boris Yamrom of the Computer Graphics & Systems Group at GE CRD. [1] [2] [3] [4] [5] [6] [7] [8] [9] [10] [11] [12] [13] [14] [15] [16] [17] [18] [19]
References J. M. Ahuactzin and K. Gupta. A motion planning based approach for inverse kinematics of redundant robots: The kinematic roadmap. In Proc. IEEE Int. Conf. Robot. Autom. (ICRA), pages 3609{3614, 1997. N. M. Amato, O. B. Bayazit, L. K. Dale, C. V. Jones, and D. Vallejo. Choosing good distance metrics and local planners for probabilistic roadmap methods. Technical Report 98-010, Dept. of Computer Science, Texas A&M University, May 1998. A preliminary version of this paper appeared in ICRA'98. N. M. Amato, O. B. Bayazit, L. K. Dale, C. V. Jones, and D. Vallejo. OBPRM: An obstacle-basedPRM for 3D workspaces. In Proc. Int. Workshop on Algorithmic Foundations of Robotics (WAFR), pages 155{168, 1998. N. M. Amato and Y. Wu. A randomized roadmap method for path and manipulation planning. In Proc. IEEE Int. Conf. Robot. Autom. (ICRA), pages 113{120, 1996. J. Barraquand and J.-C. Latombe. Robot motion planning: A distributed representation approach. Int. J. Robot. Res., 10(6):628{649, 1991. V. Boor, M. H. Overmars, and A. F. van der Stappen. The gaussian sampling strategy for probabilistic roadmap planners. In Proc. IEEE Int. Conf. Robot. Autom. (ICRA), 1999. To appear. H. Chang and T. Y. Li. Assembly maintainabilitystudy with motion planning. In Proc. IEEE Int. Conf. Robot. Autom. (ICRA), pages 1012{1019, 1995. E. G. Gilbert, D. W. Johnson, and S. S. Keerthi. A fast procedure for computing the distance between complex robots in three-dimensional space. IEEE Trans. Robot. Automat., 4:193{ 203, 1988. B. Grunbaum. Convex Poyltopes. Wiley-Intersciences, 1967. D. Hsu, L. Kavraki, J-C. Latombe, R. Motwani, and S. Sorkin. On nding narrow passages with probabilisticroadmapplanners. In Proc. Int. Workshop on Algorithmic Foundations of Robotics (WAFR), 1998. Y. K. Hwang and N. Ahuja. Gross motion planning { a survey. ACM Computing Surveys, 24(3):219{291, 1992. L. Kavraki, P. Svestka, J. C. Latombe, and M. Overmars. Probabilistic roadmaps for path planning in high-dimensional con guration spaces. IEEE Trans. Robot. Automat., 12(4):566{580, August 1996. K. Kondo. Motion planning with six degrees of freedom by multistrategic bidirectional heuristic free space enumeration. IEEE Trans. Robot. Automat., 7(3):267{277, 1992. J. C. Latombe. Robot Motion Planning. Kluwer Academic Publishers, Boston, MA, 1991. C. J. Ong and E. G. Gilbert. Growth distances: New measures for object separation and penetration. IEEE Trans. Robot. Automat., 12(6):888{903, 1996. S. Quinlan. Ecient distance computation between non-convex objects. In Proc. IEEE Int. Conf. Robot. Autom. (ICRA), pages 3324{3330, 1994. M. Spivak. Comprehensive Introduction to Dierential Geometry. Publish or Perish, Wilmington, DE, 1979. P. Watterberg, P. Xavier, and Y. Hwang. Path planning for everyday robotics with sandros. In Proc. IEEE Int. Conf. Robot. Autom. (ICRA), pages 1170{1175, 1997. S. A. Wilmarth, N. M. Amato, and P. F. Stiller. Motion planning for a rigid body using random networks on the medial axis of the free space. In Proc. ACM Symp. on Computational Geometry (SoCG), 1999. To appear.