orientation-based reachability map for robot base placement* · the robot’s reachable space. a...

6
Orientation-based Reachability Map for Robot Base Placement* Jun Dong 1 and Jeffrey C. Trinkle 2 Abstract— Mobile humanoid robots have the capability of ac- complishing complex tasks in human dominated environments. In order to execute a task with its arm, a robot needs to place its base reasonably first. In previous work, a position- based reachability map solved this problem by matching a pre- computed inverse kinematics database with discretized versions of the task path. However, its capability is restricted to the end effector with which the database was computed. This paper proposes an orientation-based reachability map which supports on-line end effector frame extensions. The added extension capability enables robots to handle partially constrained task paths with different tool frames, which would be non-trivial for previous methods without recomputing a reachability map. We discuss the differences between the new method and its predecessors, and analyze extension transformation matrix to provide mathematical proof for the extension capability of our reachability map. Our experimental results show that the orientation-based reachability map is as fast as the position- based reachability map while benefiting from the additional extension capability. I. I NTRODUCTION For a robot to perform a manipulation task, it must know that every point of the required end effector path is reachable. Two types of path specifications are common. First, the position of the origin of the end effector frame and its orientation are completely specified at every point along the path. Second, the position is fully specified, but the orientation is only partially constrained. For example, when using a glue as shown in Figure 1, the robot needs to move the glue’s tip along a certain positional path, but the orientation of the glue is much less important. Having fewer constraints in orientation can greatly increase the chance that a path is fully reachable by the robot’s end effector. The ability of a robot to execute a task depends on the pose of its base. In the DARPA Robotics Challenge, the (difficult) job of the operator was to direct the robot to walk to a pose from where manipulation tasks could be done with fixed legs. Since the workspaces of the arms were singular in many locations (relative to the task paths) and nonlinear, it was very difficult for the operator to determine good base poses. *This work was supported by the National Science Foundation through the National Robotics Initiative (grant CCF-1208468) and the Independent Research and Development program, and Lockheed-Martin. Any opinions, findings, and conclusions or recommendations expressed in this material are those of the author(s) and do not necessarily reflect the views of the funding agencies. 1 Jun Dong is a PhD student in Computer Science Department, Rensselaer Polytechnic Institute, Troy, NY 12180, USA. [email protected] 2 Jeffrey C. Trinkle is a program director at the Division of Information and Intelligent Systems of NSF as well as a professor in Computer Science Department, Rensselaer Polytechnic Institute, Troy, NY 12180, USA. [email protected] x y z Tool Tip Frame T E 0 z y x Hand Frame T n 0 Fig. 1. The transformation from the Hand Frame to the Tool Tip Frame on the glue is an example of an end effector extension. Therefore, some previous research aimed to solve such problems. Diankov et al. [5] considered that the standing pose for grasping an object can benefit from a model of the robot’s reachable space. A similar idea for grasping capability modeling was proposed by Gienger et al. [6] to optimize robot motion in grasping tasks. Zacharias et al. [2] used the reachability map developed in Zacharias et al. [3] to pose the robot base for constrained linear task paths. Zacharias et al. [1] further discussed how the reachability map can be used for general 3d paths. For comparing their work to our method, we refer to their method by “position- based reachability map” or “PBR map”. Vahrenkamp et al. [7] and Vahrenkamp et al. [8] are two other papers that solve the base placement problem using a reachability map, referred to as a “reachability distribution” in their papers. They construct an inverse distribution of the PBR map so that each probability entry of the result distribution represents how likely the pose implied by the entry is a good base placement for the target end effector pose. We henceforth refer to their method as “inverse position-based reachability map” or “inverse PBR map”. In this paper, we describe the “orientation-based reachabil- ity map”, or “OBR map” method that we developed as part of the DARPA Robotics Challenge competition. It is similar to the PBR map (that will be discussed in detail later), but eliminates a drawback that turnes out to be critical in the Challenge. In particular, the Challenge requires the robot to use several tools (e.g., a drill and a cutting tool). For each tool, the final transformation of the forward kinematic map of the robot is different; not only because the tool is different, but because the grasp of the tool is different from trial to trial. The problem will be even worse if the robot needs to use an unknown tool. Then it will not have the reachability map computed in advance. This situation could

Upload: others

Post on 13-Oct-2020

1 views

Category:

Documents


0 download

TRANSCRIPT

Page 1: Orientation-based Reachability Map for Robot Base Placement* · the robot’s reachable space. A similar idea for grasping capability modeling was proposed by Gienger et al. [6] to

Orientation-based Reachability Map for Robot Base Placement*

Jun Dong1 and Jeffrey C. Trinkle2

Abstract— Mobile humanoid robots have the capability of ac-complishing complex tasks in human dominated environments.In order to execute a task with its arm, a robot needs toplace its base reasonably first. In previous work, a position-based reachability map solved this problem by matching a pre-computed inverse kinematics database with discretized versionsof the task path. However, its capability is restricted to the endeffector with which the database was computed. This paperproposes an orientation-based reachability map which supportson-line end effector frame extensions. The added extensioncapability enables robots to handle partially constrained taskpaths with different tool frames, which would be non-trivialfor previous methods without recomputing a reachability map.We discuss the differences between the new method and itspredecessors, and analyze extension transformation matrix toprovide mathematical proof for the extension capability ofour reachability map. Our experimental results show that theorientation-based reachability map is as fast as the position-based reachability map while benefiting from the additionalextension capability.

I. INTRODUCTION

For a robot to perform a manipulation task, it mustknow that every point of the required end effector path isreachable. Two types of path specifications are common.First, the position of the origin of the end effector frameand its orientation are completely specified at every pointalong the path. Second, the position is fully specified, butthe orientation is only partially constrained. For example,when using a glue as shown in Figure 1, the robot needs tomove the glue’s tip along a certain positional path, but theorientation of the glue is much less important. Having fewerconstraints in orientation can greatly increase the chance thata path is fully reachable by the robot’s end effector.

The ability of a robot to execute a task depends on the poseof its base. In the DARPA Robotics Challenge, the (difficult)job of the operator was to direct the robot to walk to a posefrom where manipulation tasks could be done with fixed legs.Since the workspaces of the arms were singular in manylocations (relative to the task paths) and nonlinear, it wasvery difficult for the operator to determine good base poses.

*This work was supported by the National Science Foundation throughthe National Robotics Initiative (grant CCF-1208468) and the IndependentResearch and Development program, and Lockheed-Martin. Any opinions,findings, and conclusions or recommendations expressed in this material arethose of the author(s) and do not necessarily reflect the views of the fundingagencies.

1Jun Dong is a PhD student in Computer Science Department, RensselaerPolytechnic Institute, Troy, NY 12180, USA. [email protected]

2Jeffrey C. Trinkle is a program director at the Division of Informationand Intelligent Systems of NSF as well as a professor in ComputerScience Department, Rensselaer Polytechnic Institute, Troy, NY 12180,USA. [email protected]

xyz

Tool Tip Frame TE0

z

yx

Hand Frame Tn0

Fig. 1. The transformation from the Hand Frame to the Tool Tip Frameon the glue is an example of an end effector extension.

Therefore, some previous research aimed to solve suchproblems. Diankov et al. [5] considered that the standingpose for grasping an object can benefit from a model ofthe robot’s reachable space. A similar idea for graspingcapability modeling was proposed by Gienger et al. [6] tooptimize robot motion in grasping tasks. Zacharias et al.[2] used the reachability map developed in Zacharias et al.[3] to pose the robot base for constrained linear task paths.Zacharias et al. [1] further discussed how the reachabilitymap can be used for general 3d paths. For comparing theirwork to our method, we refer to their method by “position-based reachability map” or “PBR map”. Vahrenkamp et al.[7] and Vahrenkamp et al. [8] are two other papers thatsolve the base placement problem using a reachability map,referred to as a “reachability distribution” in their papers.They construct an inverse distribution of the PBR map sothat each probability entry of the result distribution representshow likely the pose implied by the entry is a good baseplacement for the target end effector pose. We henceforthrefer to their method as “inverse position-based reachabilitymap” or “inverse PBR map”.

In this paper, we describe the “orientation-based reachabil-ity map”, or “OBR map” method that we developed as partof the DARPA Robotics Challenge competition. It is similarto the PBR map (that will be discussed in detail later), buteliminates a drawback that turnes out to be critical in theChallenge. In particular, the Challenge requires the robotto use several tools (e.g., a drill and a cutting tool). Foreach tool, the final transformation of the forward kinematicmap of the robot is different; not only because the tool isdifferent, but because the grasp of the tool is different fromtrial to trial. The problem will be even worse if the robotneeds to use an unknown tool. Then it will not have thereachability map computed in advance. This situation could

Page 2: Orientation-based Reachability Map for Robot Base Placement* · the robot’s reachable space. A similar idea for grasping capability modeling was proposed by Gienger et al. [6] to

arise in a disaster, like the nuclear leak in Fukushima. Theproblem with the PBR map is that the map (which cantake hours to compute) is valid only for one end effectorextension transformation, which means a PBR map will notbe available for an unknown tool immediately. Without areachability map for the tool’s tip, the robot will not beable to plan for less orientation-constrained paths (whichcan result in stabler base pose or longer reachable paths)regarding the tool’s tip. Since the inverse PBR map is basedon the inverse of a corresponding PBR map, it has thesame drawback. By contrast, an OBR map needs to becomputed only once for a given robot arm structure, sinceit is insensitive to the final tool transformation. A new OBRmap can be constructed for the tip of an unknown toolwithin a few seconds after the robot perceives the geometryof the tool. Therefore, the OBR map approach facilitatesrobots with a much more powerful base placement systemby allowing an extension transformation and less constrainedtask paths.

II. REACHABILITY

Let q ∈ Rp×Sn−p be the vector of joint displacements ofan n-link serial-chain robot arm where Rp represents the p-dimensional Euclidean space and Sn−p represents the (n-p)-dimensional torus. Let Tn

0 (q) ∈ SE(3) represent the forwardkinematic map of the arm where SE(3) is the Euclideangroup in 3-dimensional space, namely the set of all possiblerigid body poses in 3D. Tn

0 (q) can be defined as a productof homogeneous transformations as follows:

Tn0 (q) = T 1

0 (q1) · T 21 (q2) · ... · Tn

n−1(qn)

where T ii−1 is the homogeneous transformation from the

frame fixed in link (i-1) of the robot to the frame fixed inlink (i) and qi is the ith joint displacement in the vector qfor i ∈ [1, n] ∩ Z. Two other transformations that will beuseful are T 0

W and TEn , which are the transformations from

the world frame to the base of the robot and from the lastlink of the arm to the tip of the tool.

Let G̃ be a continuous curve segment in SE(3) definingthe task in world frame and G = G1G2...Gm be a m-length list of uniformly distributed samples of G̃. The curvesegment between consecutive reachable samples is assumedto be reachable if the sampling step size is small enough.1

We say that G̃ is “reachable” from T 0w if for every point Gi

of G, there exists at least one valid value of q for whichT 0W · Tn

0 (q) · TEn = Gi.

For the remaining discussion, we will represent Tn0 (q)

with Tn0 and express homogeneous transforms as (4 × 4)

matrices:

T ji =

[Rj

i P ji

0 0 0 1

](1)

where Rji is the 3 × 3 rotation matrix in T j

i and P ji is the

3× 1 position vector in T ji .

1Possible singularities along the curve should be addressed in future work.

xy

z

(a) (b)

Fig. 2. 3D PBR map.

The matrix multiplication gives the following result:

Tn0 · TE

n =

[Rn

0 ·REn Rn

0 ·PEn + P n

00 0 0 1

](2)

Later, we will use equation (2) to analyze the extensioncapability of both PBR map and OBR map.

Since the PBR map method in Zacharias et al. [1] is theinspiration for our OBR map method, we first present theirmethod in the next section to give the reader the context tounderstand our contribution.

III. POSITION-BASED REACHABILITY MAP

In general, a reachability map characterizes a robot’sworkspace by recording solvability of the inverse kinematics(IK) problems for a large number of sample poses relative tothe robot’s base frame. To find a good base pose for the robotto execute the task G̃, the discretized task G is overlaid onthe reachability map with different orientations and movedacross the whole map to find a location where each Gi of Gmatches with a sample pose recorded “reachable”.

A. Construction of PBR Map

In the PBR map proposed by Zacharias et al [3], a robot’sworkspace relative to its base frame is divided equally intosmall cubes in R3. As shown in Figure 2(a), each cubeis represented with a sphere centered at the cube’s center,corresponding to a possible end effector frame’s position.Assume we have np such different positions. To samplethe orientations, nd z axis directions are equally distributed,represented by the sticks through the sphere in Figure 2(b).The frame is then rotated around each z axis for nr differentangles equally placed from 0 to 2π. Each rotated framethus represents a possibly reachable pose sample for theend effector. The IK problem is then attempted for each ofthese poses. Whenever a valid solution is found for a pose,1 will be recorded in the PBR map. Otherwise, 0 will bewritten to represent an unreachable pose. For simplificationand clarification, we call each recorded number (1 or 0) areachability element.

From an implementation perspective, a PBR map is ba-sically a multi-dimensional array of reachability elements,the first three dimensions of which are the three positionindices, x, y and z, followed by the fourth index for the z axisdirection and the fifth index for rotation around z axis. Otherparameters that need to be recorded in the map are the lowerbounds for x, y and z values, the positional sampling step

Page 3: Orientation-based Reachability Map for Robot Base Placement* · the robot’s reachable space. A similar idea for grasping capability modeling was proposed by Gienger et al. [6] to

(a) (b)

(c) (d)

Fig. 3. 2D PBR map pattern matching

size, the total number of steps along x, y and z, the numberof possible z axis directions and the number of possiblerotations around each z axis. These parameters together tellthe actual pose represented by each index combination.

B. Use of PBR Map

The algorithm for using a general reachability map tofind good base poses is summarized in Algorithm 1. Thebasic idea is to give the robot base different orientationsand hence match the path with the reachability map fromdifferent angles. A complete match is found only when allthe path points match with reachable elements. A simple 2DPBR map example for one robot base orientation is given inFigure 3 to illustrate the algorithm.

The construction of the 2D PBR map is described inFigure 3(a). First, the volume around the base of the robot isdiscretized into cubes (represented by the circles in the figuresince it is 2D). Then for each cube, one attempts to solvend · nr IK problems defined by the center of the circle andeach orientation from the set of nd ·nr orientations. If at leastone IK problem is solvable, then the circle is colored lightblue. For every IK problem that was solved, the orientation isrecorded (in the figure, these are represented by the dark bluelines). Attempting to solve the IK problems for all positionsand orientations yields the PBR map. It is known as position-based, because it is arranged in terms of positions.

Next, given a task path G (the red dots in Figure 3(b))fixed in world frame, the robot base is first assigned differentorientations relative to world frame so that the PBR map canbe overlaid by the path with different relative orientationsbetween them. For each relative orientation, the path G isthen projected onto a pattern (represented by the squares inFigure 3(b)) that coincides with the PBR map. This is doneby selecting all the squares that cover the path points Gi.Each path point’s orientation is also passed to the squarethat covers it. This is represented by the dashed red linein each square, which does not necessarily overlay with adiscretized orientation line.

As shown in Figure 3(c) and 3(d), if a red dashed line in a

Algorithm 1 Base Posing with Reachability Map1: procedure GET-FEASIBLE-BASE-POSES2: Input: Discretized trajectory, G ≈ G1, ..., Gm

3: Output: List of T 0w from which G is reachable

4: Choose nk samples (R0w)1, ..., (R

0w)nk

5: for i := 1..nk do6: Rotate trajectory by G = (R0

w)i ·G7: Generate pattern P that approximates G8: Run FIND-PATTERN-MATCHES with P9: Find base poses according to matched locations

10: return all found base poses11: procedure FIND-PATTERN-MATCHES12: Input: Pattern P = P1P2...Pnl

13: Output: Matched locations {(idx, idy, idz)}14: for all valid matching locations (idx, idy, idz) do15: reachable = true16: for i := 1..nl do17: if Pi matches with unreachable element then18: reachable = false; break19: if reachable == true then20: record (idx, idy, idz)21: return all recorded locations

square is closest to a solid blue line, the square is reachablein the orientation it needs. If all the squares are reachable attheir needed orientations, then a complete match is found.By moving the pattern across the entire reachability map,it is easy to find all such complete matches under currentrelative orientation between the path and the PBR map. Theconfiguration in Figure 3(c) is more likely to be infeasiblewhile Figure 3(d) indicates a better placement.

The corresponding base pose for a complete match iscalculated with the following equation:

T 0W = TE

W · (Tn0 · TE

n )−1 (3)

where T 0W is the base pose, TE

W is one of the path points inSE(3) relative to world frame and Tn

0 · TEn is the transfor-

mation from the robot base to the end effector, which canbe referred from the matching location in the PBR map.

C. Restriction of Position-based Reachability Map

One core feature of a PBR map is that all the reachabilityelements that share a same position are clustered together.This makes sure that a reachability element can be accessedin O(1) time given we know the target position and orienta-tion for the end effector. When we add an extension frameto the end effector, however, the position clustering featuredoes not transfer to the new frame.

Suppose the original PBR map has two elements thatshare a same position Pn

0 but with different orientations(Rn

0 )1 and (Rn0 )2, from equation (2) we know their extended

counterparts are as follows[(Rn

0 )1·REn (Rn

0 )1·PEn + P n

00 0 0 1

](4)

Page 4: Orientation-based Reachability Map for Robot Base Placement* · the robot’s reachable space. A similar idea for grasping capability modeling was proposed by Gienger et al. [6] to

(a) (b)

Fig. 4. Restriction of PBR map[(Rn

0 )2·REn (Rn

0 )2·PEn + P n

00 0 0 1

](5)

We can see from equations (4) and (5) that the twoextended elements have positions (Rn

0 )1·PEn + Pn

0 and(Rn

0 )2·PEn + Pn

0 . Since (Rn0 )1 and (Rn

0 )2 are different, thetwo positions are also different unless PE

n is zero vector.If PE

n is not zero vector, namely non-zero translation isincluded, the extended map will not inherit the positionclustering feature.

The restriction is illustrated in Figure 4. Figure 4(a) showsa very simple 2D PBR map where there are only two possiblepositions and two reachable orientations for each. The darkblue orientation lines indicate the reachable y axis directionsof the 2D end effector frame. If a (0,1) translational extensionis added onto the end effector, namely the end effector isprolonged for length 1 in y direction, the result reachabilitymap will be in Figure 4(b). The reachability elements allmove toward the directions of their own y axis direction andthe structure of the original PBR map is destroyed. Eachof the solid circles in Figure 4(b) does not have all thereachability elements either. For example, the leftmost circleonly has one reachability element, while we do not knowwhether the other three orientations are reachable or not.

D. Extension Equation Observation

Besides the analysis with equations (4) and (5), twoobservations from equation (2) are interesting: a) The ex-tended position term Rn

0 ·PEn + Pn

0 involves both positionand orientation. b) The extended orientation term Rn

0 ·REn

only involves orientation.The first observation explains why the PBR map cannot be

extended. The second observation, on the other hand, impliesan invariance of the extension equation: if two reachabilityelements have a same unextended orientation, they will stillhave a same orientation after the extension regardless of theirpositions.

Specifically, suppose we have two elements with the sameorientation matrix Rn

0 but with different positions (Pn0 )1 and

(Pn0 )2. With equation (2), their extended counterparts will

be: [Rn

0 ·REn Rn

0 ·PEn +(P n

0 )10 0 0 1

](6)

[Rn

0 ·REn Rn

0 ·PEn +(P n

0 )20 0 0 1

](7)

As shown in equations (6) and (7), the two elementsstill have a same orientation matrix Rn

0 ·REn , which is just

rotated from their original orientation. The positions of thetwo elements also translate for a same vector Rn

0 ·PEn . These

Orientation 1

Orientation 2

Orientation nd · nr

...Ori

enta

tion-

base

dR

each

abili

tyM

ap

xy

z

1 0OR

Fig. 5. Orientation-based reachability map is composed of multiple layersof reachability elements. The blue balls in each layer represent reachabilityelements and are arranged according to their positions.

features are good for building an extendable reachabilitymap.

IV. ORIENTATION-BASED REACHABILITY MAP

Based on the observation in the last section, we proposea new structure of reachability map, the OBR map. It isillustrated in Figure 5 by the multiple layers of spheres. Eachlayer represents a unique orientation, and all the reachabilityelements (represented by the blue spheres) within that layershare this orientation. A notable difference from PBR mapis that a sphere here only represents a single reachabilityelement instead of nd · nr elements.

A. Construction of OBR Map

The construction phase of an OBR map is similar to that ofa PBR map. We use the same orientation selection method asin Zacharias et al. [3] for fair comparison between the two.Thus there should be nd · nr unique orientations. Then, arobot’s workspace relative to its base frame is divided equallyinto np small cubes in R3, represented by the spheres in eachorientation layer. Similarly, the centers of the spheres implydifferent positions. IK is then calculated for all possible

Page 5: Orientation-based Reachability Map for Robot Base Placement* · the robot’s reachable space. A similar idea for grasping capability modeling was proposed by Gienger et al. [6] to

np · nd · nr poses (pairs of position and orientation) andthe solutions are recorded as reachability elements.

In our implementation, OBR map also uses multi-dimensional array to store reachability elements. But insteadof letting the first three dimensions be position indices, OBRmap makes orientation index first, followed by the threeposition indices x, y and z.

B. Use of OBR mapThe same algorithm, Algorithm 1, can be applied to an

OBR map for posing robot base given task paths.When task paths are fully specified without extension, an

OBR map works exactly as a PBR map does. Although thetwo maps have different index order, none of the steps inalgorithm 1 is affected by the order. The only concern is onthe pattern generated in the process. Visually, one can thinkof the pattern for an OBR map as separated parts of a wholepattern, with each part assigned onto a different layer withrespect to its orientation. When the pattern translates acrossthe reachability map, all the parts on different layers translatetogether. This does not make OBR map work differentlyfrom a PBR map since the reachability of pattern elementsis checked one after another, as described in the secondprocedure of Algorithm 1.

When task is fully specified in position but partiallyconstrained in orientation, however, there are two impor-tant differences in implementing the algorithm: 1) Multipleorientations need to be checked for reachability at a givenposition instead of just one. 2) Equation (3) cannot be usedin base pose calculation since TE

W is not fully specified. Analternative method to obtain the base pose from a patternmatch is to find just the base position since base orientation(R0

W )i is already selected in the beginning of every iteration.This is done with the equation below:

P 0W = PE

W −R0W · PE

0 (8)

where P 0W is the needed base position, PE

W is a path point’sposition in world frame, R0

W is the selected base orientationand PE

0 is end effector’s position relative to base frame,which can be referred from the matching location.

C. Extension Capability IllustrationOur observation of the invariance in the extension equation

is further illustrated with Figure 6. This is the OBR versionof the same PBR map shown in Figure 4. There are fourlayers in total, each of which represents a set of poses withthe same orientation. The orientations are drawn on all thereachability elements with solid blue lines in the circles.Figure 6(a) shows the unextended version of the OBR map.The applied extension is a translation of (0,1) followed by a30 degrees counterclockwise rotation. The result is shown inFigure 6(b). It is easy to notice that all the elements in onelayer moves towards one same direction, the one that all theelements in the layer originally point to with their y axes (thesolid blue lines in Figure 6(a)). The 30 degrees rotation alsorotates the elements together, thus all those in one layer stillhave a same orientation. The result map is therefore anotherOBR map.

(a) (b)

Fig. 6. Illustration of extension capability: (a) is before extension and(b) is after that. The applied extension is (0,1) translation represented inend effector frame, followed by 30 degrees counterclockwise rotation. Thesolid lines in the orientation circles represent the orientations’ y directions,namely the directions that length 1 extension is added in.

D. Use of OBR Map with Extension

Since different layers of the OBR map translate towarddifferent directions during an extension, the displacementsbetween the layers need to be considered in the patternmatching process. Each layer’s position lower bound changeis given by the term Rn

0 ·PEn . The number of steps to shift is

calculated by dividing the change by the step size of theOBR map. These shift steps need to be subtracted fromthe reachability indices whenever the actual reachabilityelements are requested.

V. EVALUATION

In this section, we evaluate the OBR map by posingrobot base for the two types of task paths mentioned insection I. Our experiments involved software 2 only andwere conducted on a 64-bit Ubuntu 12.04 system with 16Gmemory and 8 CPUs at 3901.000 MHz. The robot modelwe used was the Atlas robot in the DRC. We set the “torso”link as the robot base and only the seven joints on the rightarm were used. The unextended end effector link used forgenerating the OBR map was the “r hand” link, which isnear the wrist of the right arm.

Specifically, we experiment with the following two typesof tasks: 1) Robot base posing with a rigid extension forfully specified pose paths; 2) Robot base posing with a rigidextension for position-direction paths.

The Atlas robot’s torso frame has its x axis pointingforward, y axis pointing to the left and z axis pointingupward. We only captured a portion of the overall reachablespace of the right arm, which had x ranging from 0.1m to0.9m, y ranging from -0.8m to 0m and z ranging from -0.3mto 0.7m. The step size along the three axes were all 0.05m.We equally distributed 128 points on a sphere using themethod in Saff et al. [4], representing the 128 directions for

2The code can be found on http://homepages.rpi.edu/˜dongj2/

Page 6: Orientation-based Reachability Map for Robot Base Placement* · the robot’s reachable space. A similar idea for grasping capability modeling was proposed by Gienger et al. [6] to

Method Type OBR PBRNum. of Tests 500 500Avg. Extension Time (ms) 0.723 N/AAvg. Placement Time (ms) 15.355 15.716Avg. Result Checking Time (ms) 803.667 804.764Num. of Returned Placements 2500 2500Num. of Valid Placements 2343 2332Ratio of Valid Placements (%) 93.72 93.28

TABLE IPOSE PATH WITH EXTENSION

the z axis of the end effector. Around each z axis direction,16 rotations were equally spaced. In total, 128 x 16 = 2048orientations were sampled. The PBR map and the OBR mapwere then constructed as described in previous sections. Withour 7-DOF IKFast solver, the construction took around 15hours for each database.

In the first experiment, 500 tests were conducted and thetiming and accuracy results are in table I. For each test, atask path G was generated randomly using the followingapproach. A basic pose G0 was first generated with randomorientation and random position whose x, y ∈ [−2, 2) andz ∈ [−0.3, 0.7). Every Gi+1 was then generated by addingGi with an additional random transformation whose rotationangle was less than 0.1 rad and whose translation was lessthan 0.05m in each axis direction. A total of 10 pointswere generated in the same way. The points from G1 toG10 thus represented the random path. The extension framewas generated similar to the basic pose G0, with the onlydifference that its translation part was constrained in [-0.05,0.05) along each axis direction.

The result shows that an OBR map works as efficientas a PBR map does, using only about 15 ms to return5 placements in each test. The slight time difference forobtaining base placements could be from randomness. Thelong result checking time is due to the performance ofthe IK solver. We check the validity of each placement bycalculating IK solutions for all trajectory points from thebase placement. The overall memory footprint was 51124kbfor this experiment.

The second experiment dealt with position-direction pathswith extension. Similarly, 500 tests were conducted. For eachtest, a task path G was generated randomly. First, a basicposition and a basic direction, which together representedG0, were randomly generated with x, y, z ∈ [0, 1). Thedirection vector was normalized after that. Each followingpoint Gi+1 was generated by adding Gi with another ran-dom position and random direction respectively. The addedposition was constrained in [0, 0.05) along each axis, whilethe added direction vector was constrained in [0, 0.1] ineach direction. The element-wise addition result of directionswas normalized for every point Gi. The extension framewas generated with random orientation and random positionwhose x, y, z ∈ [−0.05, 0.05).

The result for the second experiment is shown in table II.Only the OBR map method was run since the PBR mapmethod does not naturally handle position-direction pathswith extension. About 43 ms in average was spent on the

Method Type OBRNum. of Tests 500Avg. Extension Time (ms) 0.746Avg. Placement Time (ms) 42.627Num. of Returned Placements 2500

TABLE IIPOSITION DIRECTION PATH WITH EXTENSION

posing, compared to about 15 ms in the first experiment.This computation time increase was expected because fewerconstraints in orientation means more reachability elementsto check. The validity check of the placements will be in ourfuture work due to the need of a reliable direction IK solver.The overall memory footprint was 51320kb.

VI. CONCLUSION

This paper proposed the OBR map that supports on-lineend effector extension. We evaluated the new method bycomparing its speed to that of the PBR map on fully specifiedpose paths with a rigid extension and by implementing itscorresponding approach to find good base poses for position-direction paths. The evaluation results show that the OBRmap has nearly the same speed as the PBR map while ithas the additional extension capability, which is essentialwhen robots need to use different tools and have task pathsspecified in the tool frame.

One future directions for this work include checking valid-ity of base placements for position direction paths, compar-ing validity rates with different discretization parameters anddealing with the possible singularities between consecutivereachable path points. The latter might be achieved by addinga manipulability check for every point on the path afterfinding the base placement.

REFERENCES

[1] Zacharias, Franziska, Wolfgang Sepp, Christoph Borst, and GerdHirzinger. ”Using a model of the reachable workspace to positionmobile manipulators for 3-d trajectories.” In Humanoid Robots, 2009.Humanoids 2009. 9th IEEE-RAS International Conference on, pp. 55-61. IEEE, 2009.

[2] Zacharias, Franziska, Christoph Borst, Michael Beetz, and GerdHirzinger. ”Positioning mobile manipulators to perform constrainedlinear trajectories.” In Intelligent Robots and Systems, 2008. IROS2008. IEEE/RSJ International Conference on, pp. 2578-2584. IEEE,2008.

[3] Zacharias, Franziska, Christoph Borst, and Gerd Hirzinger. ”Capturingrobot workspace structure: representing robot capabilities.” In Intelli-gent Robots and Systems, 2007. IROS 2007. IEEE/RSJ InternationalConference on, pp. 3229-3236. Ieee, 2007.

[4] Saff, Edward B., and A. BJ Kuijlaars. ”Distributing many points on asphere.” The Mathematical Intelligencer 19, no. 1 (1997): 5-11.

[5] Diankov, Rosen, Nathan Ratliff, Dave Ferguson, Siddhartha Srinivasa,and James Kuffner. ”Bispace planning: Concurrent multi-space explo-ration.” Proceedings of Robotics: Science and Systems IV 63 (2008).

[6] Gienger, Michael, Marc Toussaint, Nikolay Jetchev, Achim Bendig,and Christian Goerick. ”Optimization of fluent approach and graspmotions.” In Humanoid Robots, 2008. Humanoids 2008. 8th IEEE-RAS International Conference on, pp. 111-117. IEEE, 2008.

[7] Vahrenkamp, Nikolaus, Tamim Asfour, and Rdiger Dillmann. ”Effi-cient inverse kinematics computation based on reachability analysis.”International Journal of Humanoid Robotics 9, no. 04 (2012).

[8] Vahrenkamp, Nikolaus, Tamim Asfour, and Rdiger Dillmann. ”Robotplacement based on reachability inversion.” In Robotics and Automa-tion (ICRA), 2013 IEEE International Conference on, pp. 1970-1975.IEEE, 2013.