13 Joint Coupling and Underactuated HandsTop11 Eigengrasps12 Grasp Planning II - Eigengrasp planning

Contents

12 Grasp Planning II - Eigengrasp planning

This chapter described the grasp planners that run in Eigengrasp space. Unfortunately, they do not share the same framework as the Primitive-based planner described earlier, although from a software engineering viewpoint they probably should, as they are still rooted in the same try-many-grasps concept.

Most of the ideas behind these planners are explained in a lot of detail in the Publications. We strongly recommend reading the Eigengrasp related papers that can be found there before proceeding through this chapter, they will make most of the concepts shown here much clearer.

12.1 Grasp planning in Eigengrasp space

In this family of planners, the task of grasp planning is seen as a search over multiple variables, or as an optimization problem for a high-dimensional function. The variables define the grasp and the optimized function is the quality of the grasp. In general, in order to define a grasp we need two sets of variables: the intrinsic variables (to define hand DOF's) and the extrinsic variables, to define the position of the hand relative to the target object.

For dexterous hands, if we consider one variable for each DOF, the space is too high-dimensional to search efficiently. That is why most of these algorithms only work well in eigengrasp space, where the intrinsic variables are the eigengrasp amplitudes. However, there is nothing in the structure of these planners that prevents them from running in DOF space. In fact, if you load a hand model that does not have Eigengrasps defined, GraspIt! will automatically define the "identity" eigengrasp set, with one eigengrasp corresponding to each DOF. You can then run all Eigengrasp-based planners exactly as you would if "real" Eigengrasps were defined.

An Eigengrasp-based planner is composed of three things:

To start, load a hand and an object model, then use the Grasp -> EigenGrasp Planner menu. The Eigengrasp Planning dialog window appears. The left side of the window is dedicated to the variables that are searched. The right hand side is dedicated to the planning process itself, allowing you to choose from multiple types of planners, see details about the current planning execution, etc.

12.2 Variables

All variables that are being searched are shown in the left panel of the dialog. Variables serve two main purposes: they define hand position and hand posture.

In the GraspIt! code, a state comprising all the variables in search is contained in the SearchState class. Please consult the documentation of this class for many details about these variables, different ways to encode hand position, etc.

Next to each variable, there is an On checkbox, which can be used to enable / disable search over a particular variable. If a variable is disabled (its box is unchecked), it is no longer part of the search, and will maintain its current value in all generated solutions. For each variable, there are also other options marked Input, Target and Confidence. These options are used for a very specialized planning operation, using external input. This type of planning is only described in one of the papers in the Publications section, and not in this manual. For more information, please contact us. In general, just ignore these options and leave them in the default configuration.

12.3 Search energy

The search energy is a way of assessing how good a state encountered during a search really is. It can also be considered a function of the search variables that needs to be optimized. The most straightforward search energy is the one that we have already seen used by the Primitive-based Grasp Planner: use a grasp Quality Measure. However, a traditional QM is only defined when the hand is actually in contact with the object. When planning in Eigengrasp space, many hand states will be very close, but not in perfect contact with the object. One possibility would be to use the AutoGrasp function and close the hand, and compute a QM for the resulting grasp. However, that is a slow process, and we would like to be able to evaluate more hand postures quickly. As a result, we have tried to define a number of implementations of the "Search Energy" concept that do not require hand-object contacts.

The default energy function (pre-selected in the Energy formulation drop-down list) is Hand Contacts. This formulation attempts to bring all links of the hand as close as possible to the target object. The computation of this energy function can be greatly sped-up by pre-specifying "desired" contact locations on each link (see Publications for details). This is the role of the checkbox Preset contacts. Such pre-defined contacts can be loaded from a file. For the Human and Barrett hands, pre-specified contact files are supplied with the distribution. If no contact file has already been loaded, when the Preset contacts checkbox is checked the system will ask the user to select a file to be loaded. Note that it is also possible to specify a pre-defined contacts file in a robot configuration file, so that it is always loaded together with the Robot. From a code standpoint, a pre-defined contact location is loaded into an instance of the VirtualContact class; see that class and its documentation for details.

Other formulations for the search energy are also available, but many of them also incorporate the Hand Contacts formulation in one way or another. For the moment, the code implementing these formulations (the SearchEnergy class) is some of the ugliest in the GraspIt! codebase. We hope to change it soon, at which point we will also provide more documentation. For now, the most tested and trusted energy formulation is Hand Contacts described above.

12.4 Optimization method and planner types

The core optimization methods, that is at the base of all Eigengrasp planners, is Simulated Annealing. The most basic type of planning is to run a Simulated Annealing search using the Hand Contacts energy function, over all Eiegengrasp variables plus hand position parameterized as axis-angle. This is shown in the practical example below. From this, we have tried quite a number of variations on this theme.

One in particular might prove useful, so it is also exemplified below: the MultiThreaded Planner. One of the shortcomings of the Hand Contacts energy function is that is does not guarantee form-closure: it will find states where the hand conforms to the shape of the object, but not necessarily form-closed. To fix this, the MultiThreaded planner runs an optimization exactly as before; however, whenever it finds a state that has a good value for the Hand Contacts energy function, it fires off a child thread which will search that area in more detail, by applying the AutoGrasp function and computing the exact Quality Measure that results. The MultiThreaded planner is your best bet if you need to find form-closed grasps of an arbitrary object with one of the dexterous hands in GraspIt!.

From a code standpoint, the EGPlanner pure abstract class is the base for all of these planners: it contains the functionality for looping, computing a given hand energy formulation, saving the best solutions etc. The one thing that it does not know how to do is run an optimization algorithm. Its direct offspring, the SimAnnPlanner combines that framework with a Simulated Annealing optimization. To get started, check out the EGPlanner class for most details, and the SimAnnPlanner class for an example implementation of it. All other planners inherit from EGPlanner. The setup for this code is OK, but could still take quite a bit of improvement, which we hope to get to at some point.

12.5 Practical example: the Simulated Annealing planner

12.6 Practical example: the Multithreaded planner

Not yet written... Coming soon...


Copyright (C) 2002-2009 Columbia University


13 Joint Coupling and Underactuated HandsTop11 Eigengrasps12 Grasp Planning II - Eigengrasp planningContents