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

Next Article in Journal
Multi-Robot Task Planning for Efficient Battery Disassembly in Electric Vehicles
Previous Article in Journal
An Aerial Robotic Missing-Person Search in Urban Settings—A Probabilistic Approach
Previous Article in Special Issue
Constraint-Aware Policy for Compliant Manipulation
You seem to have javascript disabled. Please note that many of the page functionalities won't work as expected without javascript enabled.
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Automated Grasp Planning and Finger Design Space Search Using Multiple Grasp Quality Measures

1
Brubotics, Vrije Universiteit Brussel, 1050 Brussels, Belgium
2
Flanders Make, 1050 Brussels, Belgium
3
IMEC, 1050 Brussels, Belgium
4
CodesignS, 3001 Leuven, Belgium
*
Author to whom correspondence should be addressed.
Robotics 2024, 13(5), 74; https://doi.org/10.3390/robotics13050074
Submission received: 1 April 2024 / Revised: 3 May 2024 / Accepted: 6 May 2024 / Published: 9 May 2024
(This article belongs to the Special Issue Advanced Grasping and Motion Control Solutions)
Figure 1
<p>Overview of the workflow adopted in the paper.</p> ">
Figure 2
<p>A view of the parallel-jaw gripper in a pre-grasp pose on the object.</p> ">
Figure 3
<p>Grasp parameterization. The original reference frame of the object is shown along with the gripping axis obtained by the grasp parameters <math display="inline"><semantics> <mrow> <mi mathvariant="bold-italic">g</mi> <mo>=</mo> <mo>(</mo> <mi>θ</mi> <mo>,</mo> <msub> <mi>y</mi> <mi>o</mi> </msub> <mo>)</mo> </mrow> </semantics></math>.</p> ">
Figure 4
<p>Schematic of three-contact gripping.</p> ">
Figure 5
<p>Example base cases. (<b>Left</b>) Grasp at three points on a rectangular object. (<b>Right</b>) grasp at three points on a circular object. The grasp on the circular object has a higher quality measure <math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>f</mi> <mi>c</mi> </mrow> </msub> </semantics></math> because it creates a more uniform distribution of contact forces.</p> ">
Figure 6
<p>Examples for the center of mass measure (<math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>c</mi> <mi>o</mi> <mi>m</mi> </mrow> </msub> </semantics></math>). The grasp on the left has a <math display="inline"><semantics> <mrow> <msub> <mi>Q</mi> <mrow> <mi>c</mi> <mi>o</mi> <mi>m</mi> </mrow> </msub> <mo>=</mo> <mn>1</mn> </mrow> </semantics></math>; it is a symmetric grasp on a circular object. The grasp in the middle is on a rectangular object and the center of mass lies inside the grasp triangle; it has a smaller quality measure (<math display="inline"><semantics> <mrow> <msub> <mi>Q</mi> <mrow> <mi>c</mi> <mi>o</mi> <mi>m</mi> </mrow> </msub> <mo>=</mo> <mn>0.66</mn> </mrow> </semantics></math>) because the friction forces are not equally distributed. The grasp on the right has very low quality (<math display="inline"><semantics> <mrow> <msub> <mi>Q</mi> <mrow> <mi>c</mi> <mi>o</mi> <mi>m</mi> </mrow> </msub> <mo>=</mo> <mn>0.12</mn> </mrow> </semantics></math>) because the center of mass does not lie inside the grasp triangle.</p> ">
Figure 7
<p>Grasping an elliptical object along the major (<b>left</b> image) and minor (<b>right</b> image) diameter. The black circles indicate the position of the grasp points and the line indicates the gripping direction. The grasp along the major diameter has very low robustness compared to the grasp on the right along the minor diameter.</p> ">
Figure 8
<p>Computation of normalized volume of wrench space measure. (<b>a</b>) Bounding box on the object and the relevant dimensions. (<b>b</b>) The standard object and grasp used for computing the normalizing factor.</p> ">
Figure 9
<p>Fingertip design workflow.</p> ">
Figure 10
<p>Workflow for computing fingertip score. Here the label A represents the step for computing fingertip score and B represents the step for computing the best grasp on the object.</p> ">
Figure 11
<p>The steps involved in grasp synthesis and determining grasp quality (labeled B).</p> ">
Figure 12
<p>Visualization of (<b>a</b>) a feasible contact and (<b>b</b>) a non-feasible contact. (<b>a</b>) A feasible contact on Object 1 (grasp parameters: <math display="inline"><semantics> <mrow> <mi>θ</mi> <mo>=</mo> <mn>1.6</mn> <mspace width="0.277778em"/> <mi>rad</mi> </mrow> </semantics></math> and <math display="inline"><semantics> <mrow> <msub> <mi>y</mi> <mi>o</mi> </msub> <mo>=</mo> <mo>−</mo> <mn>5</mn> <mspace width="0.277778em"/> <mi>mm</mi> </mrow> </semantics></math>). (<b>b</b>) A non-feasible contact on Object 1 (grasp parameters: <math display="inline"><semantics> <mrow> <mi>θ</mi> <mo>=</mo> <mn>1.8</mn> <mspace width="0.277778em"/> <mi>rad</mi> </mrow> </semantics></math> and <math display="inline"><semantics> <mrow> <msub> <mi>y</mi> <mi>o</mi> </msub> <mo>=</mo> <mo>−</mo> <mn>5</mn> <mspace width="0.277778em"/> <mi>mm</mi> </mrow> </semantics></math>).</p> ">
Figure 13
<p>Check for object collision.</p> ">
Figure 14
<p>CAD models of objects used for evaluation. The parts are industrial components used in compressor air ends. The z-direction is perpendicular to the top surface of the object and pointing away from the object. The z-direction is also the approach direction for grasp.</p> ">
Figure 15
<p>Three-dimensional-printed parts used for evaluation.</p> ">
Figure 16
<p>Sample grasps on Object 1. The complete data are presented in <a href="#robotics-13-00074-t005" class="html-table">Table 5</a>. The figure visualizes three-point grasps on each object and the corresponding five quality measures below each grasp. The grasp visualizations can help verify the quality measures. The best grasp among the presented sample grasps is Grasp 3 (underlined green), with particularly large <math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>f</mi> <mi>c</mi> </mrow> </msub> </semantics></math>, <math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>c</mi> <mi>o</mi> <mi>m</mi> </mrow> </msub> </semantics></math>, and <math display="inline"><semantics> <msub> <mi>Q</mi> <mi>r</mi> </msub> </semantics></math> values. The worst grasp is Grasp 4 (underlined red) with a particularly small <math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>f</mi> <mi>c</mi> </mrow> </msub> </semantics></math> and <math display="inline"><semantics> <msub> <mi>Q</mi> <mi>r</mi> </msub> </semantics></math>. The location of COM is indicated in each picture.</p> ">
Figure 17
<p>Sample grasps on Object 2. Full data are presented in <a href="#robotics-13-00074-t006" class="html-table">Table 6</a>. Among the sample grasps presented, Grasp 10 (underlined green) is the best overall grasp with high <math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>f</mi> <mi>c</mi> </mrow> </msub> </semantics></math>, <math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>c</mi> <mi>o</mi> <mi>m</mi> </mrow> </msub> </semantics></math>, and <math display="inline"><semantics> <msub> <mi>Q</mi> <mi>r</mi> </msub> </semantics></math> values. Grasp 2 (underlined red) is the worst grasp among the presented grasps. We also observe that for the second object many grasps have a low robustness score.</p> ">
Figure 18
<p>Sample grasps on Object 3. The complete data are presented in <a href="#robotics-13-00074-t007" class="html-table">Table 7</a>. The figure visualizes different three-point grasps on each Object 3 and the corresponding five quality measures below each grasp. The grasp visualizations can help verify the quality measures. The best grasp among the presented sample grasps is Grasp 6 (underlined green) with particularly large <math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>f</mi> <mi>c</mi> </mrow> </msub> </semantics></math> and <math display="inline"><semantics> <msub> <mi>Q</mi> <mi>r</mi> </msub> </semantics></math> values. The worst grasp is Grasp 4 (underlined red) with particularly small <math display="inline"><semantics> <msub> <mi>Q</mi> <mrow> <mi>f</mi> <mi>c</mi> </mrow> </msub> </semantics></math> and <math display="inline"><semantics> <msub> <mi>Q</mi> <mi>r</mi> </msub> </semantics></math> values. The location of COM is indicated in each picture.</p> ">
Figure 19
<p>Variation in the fingertip score (<math display="inline"><semantics> <mrow> <mi>F</mi> <mi>S</mi> </mrow> </semantics></math>) with the fingertip design parameter <math display="inline"><semantics> <msub> <mi>d</mi> <mi>f</mi> </msub> </semantics></math> for OS1.</p> ">
Figure 20
<p>Variation in the fingertip score (<math display="inline"><semantics> <mrow> <mi>F</mi> <mi>S</mi> </mrow> </semantics></math>) with the fingertip design parameter <math display="inline"><semantics> <msub> <mi>d</mi> <mi>f</mi> </msub> </semantics></math> for object set 2 consisting of three parts.</p> ">
Figure 21
<p>Final fingertip design for the two object sets.</p> ">
Figure 22
<p>Grasping experiments performed on the two objects of object set 1: (<b>a</b>) First grasp on Object 1 (one view). (<b>b</b>) First grasp on Object 1 (another view). (<b>c</b>) Grasp on Object 1 with external force. (<b>d</b>) Second grasp on Object 1. (<b>e</b>) Grasp on Object 2. (<b>f</b>) Grasp on Object 2 with external force. The grasp parameters used are shown in <a href="#robotics-13-00074-t012" class="html-table">Table 12</a>.</p> ">
Versions Notes

Abstract

:
As the industry shifts to automated manufacturing and the assembly of parts in smaller batches, there is a clear need for an efficient design of grippers. This paper presents a method for automated grasp planning and finger design for multiple parts using four grasp quality measures that capture the following important requirements for grasping: (i) uniform contact force distribution; (ii) better gravity wrench resistance; (iii) robustness against gripper positioning error; and (iv) ability to resist larger external wrench on the object. We introduce the fingertip score to quantify the grasp performance of a fingertip design over all the objects. The method takes the CAD model of the objects as the input and outputs the optimal grasp location and the best finger design. We use the method for a three-point grasp with a parallel jaw gripper. We validate our method on two sets of objects. Results show how each grasp quality measure behaves on different objects and the variation in the fingertip score with finger design. Finally, we test the effectiveness of the optimal finger design experimentally. The three-point grasp is suitable for grasping objects larger than is possible with shape-matching fingertips.

1. Introduction

Manufacturing and assembly of products in small batches is gaining prevalence, with increasing demands for customization. To meet these demands, a robotic manufacturing unit should have a short switch-over time to a new set of products. Handling a new set of products often requires a redesign of the grippers. Further, the new gripper design should be generated automatically and be capable of handling all the objects in the set, a capability termed as flexible gripping [1]. In this work, we achieve flexible gripping through the automated design of multi-function fingertips. We propose a method that utilizes multiple grasp quality measures for designing gripper fingers for a set of objects.
The paper’s goals are as follows: state the problem we are trying to solve, detail the formulation and behavior of the four grasp quality measures we use in our proposed framework, define the fingertip score used to quantify the finger performance, detail the finger design procedure, and demonstrate the effectiveness of the proposed method for designing gripper fingers in simulation and experiments.
Apart from multi-function fingertips, other solutions for flexible gripping include the following: universal gripping consisting of adaptive multi-fingered hands [2,3,4], soft fingertips [5], shape morphing fingertips [6], granular jamming [7], gripper exchange systems [8], modular gripping [9] consisting of re-configurable jaws designed based on closure analysis [10], and multi-function finger design wherein the design of the fingertip is chosen to handle multiple objects [11]. Multi-function fingers are cheaper, more effective, and more reliable than tool-changing systems and rotary wrist mechanisms. Other solutions like multi-fingered hands and soft grippers are versatile but less robust, delicate, and expensive.
Automated design of multi-function fingers has been performed before; however, earlier works did not use grasp quality measures that have recently shown promise. Further, many previous works were also limited to objects with a polygonal cross-section. We discuss these related works in detail in the next section. Our contributions in this work are as follows:
1.
We propose a method based on multiple grasp quality measures to determine grasps and finger design. The quality measures are chosen to meet the following performance requirements on a grasp: (i) force-closure quality measure to ensure equal distribution of contact forces; (ii) center of mass (COM) quality measure to ensure better resistance of gravity wrench; (iii) grasp robustness measure to ensure robustness against positioning error of the gripper; (iv) volume of wrench space measure to ensure that the grasp can resist larger external forces and torques.
2.
We propose a three-contact finger design to create a strong grasp on a set of objects and propose the method for using the quality measure and feasibility checks for automated grasp and design space search.
3.
We propose a new grasp quality measure—the robust grasp measure with quality threshold.
4.
Definition of new grasp quality measures and the combination for grasping and finger design.
Further, we propose the normalization of each of the quality measures such that they can be applied to a set of objects with different shapes and sizes. This will be useful for gripper design activity using other approaches as well.
To achieve the goal of automated finger design, the study focuses on the formulation and testing of the four grasp quality measures and the finger design procedure. Formulation and testing of the four grasp quality measures is crucial to understanding how each quality measure contributes to the design of the finger. Another key goal of the study is to test the proposed finger design method on an object set in simulation and in experiments.
The paper is organized as follows: Section 2 presents the related works. Section 3 presents the problem description and mathematical background. Section 4 presents the definition and physical interpretation of the grasp quality measures. In Section 5, we present the finger design workflows and details of the steps involved. In Section 6, we validate the proposed approach on two cases. We also show the experimental demonstration of the grasps and finger design. In Section 7, we discuss the results. In Section 8, we present the conclusions from our study.

2. Literature Review

Most previous works adopted a form-closure grasp on an object for designing the fingertips [12,13,14]. This approach has various limitations. First, this limits the size of the object that the fingers can grasp since the fingers are required to cover the object. Second, previous works usually consider one basic grasp quality measure to determine good grasp locations, which might not be capable of satisfying all the requirements for a good grasp. For example, Honarpardaz et al. [14] used the widely used epsilon grasp quality metric [15] that does not take into account the moment due to the weight of the object or the robustness of the grasp—both of which are critical requirements. This implies that the grasp cannot handle larger and heavier objects. Third, the form closure method does not scale well with the number of objects as the local shape of the object is subtracted from a finger blank and, after a few objects, a very small portion of the fingertip is available for additional objects.
Our proposed method overcomes these three constraints of previous research by considering three-contact gripping, allowing us to handle larger and heavier objects, and considering multiple grasp quality measures allowing us to satisfy multiple critical requirements on grasp performance.
We further describe the related works in more detail covering aspects of automated finger design, finger shapes, and grasp quality measures.

2.1. Automated Finger Design Approaches

Although multi-function fingers can be designed manually based on expert knowledge and experimentation, automation opens up the possibility of greater speed, scale, and makes gripper solutions more accessible, especially for small companies and SMEs. Consequently, multiple efforts have been made to automate the design of multi-function as well as single-function fingers [16].
Efforts have been made to generate finger designs based on the CAD description of the parts to be grasped [13,17,18]. Honarpardaz et al. [16] gives a review of the methods for automated finger designs for industrial gripping. In recent works [12,19], the authors present a pipeline for automatic finger design. They utilize a projected surface representation approach as well as a Bezier surface fitting strategy. The finger designs attempt to fit the local geometry of the object. Another approach is the use of evolutionary methods to generate finger designs [20].
The usual workflow for automated design of finger shape [21] starts with a CAD model of a product or a set of products that should be grasped by the multi-function finger [11]. The first task is to find the optimal gripping locations on the object for an optimality criteria taken from the field of optimal grasping [15,22,23,24]. Once optimal gripping locations on the object have been determined, we can generate the shape of the finger. In the case of three-contact grasping, a generic curved finger shape is chosen. Further steps include collision checking and the design of the finger body to be attached to the gripper. Design time is an important criterion for flexible gripping applications. Usual methods to speed up the process are to use sampling-based optimization methods [14] and computationally inexpensive optimality criteria [25]. The final step is experimental verification of the finger shapes [26]—testing the ability of the fingers to resist external forces on the grasped object.
While the works mentioned above perform sequential grasp search and finger shape generation, [27] attempted to co-optimize finger shapes and grasp locations. In our work, we adopt a similar strategy in the sense that fingertip scores are computed while searching for best grasps on the set of objects. Another optimization-based strategy involves the use of contact primitives to optimize finger designs [28]. The fingertip designs match the local geometry of the object, an approach similar to the approaches we have mentioned above.
A related work for automated finger design is presented by Balan and Bone in [29]. They perform grasp planning and jaw design for multiple objects. They use three grasp quality metrics to quantify the goodness of a grasp and the jaw design. The quality measures they use are sensitivity of the finger locations, efficiency in terms of contact forces, and dependence of force-closure on friction. We adopt a similar approach wherein we use four grasp quality measures to design a pair of fingers that make three contacts with the object. However, while the method presented in [29] is applicable only for polyhedral objects, our method can handle arbitrarily shaped objects. Further, we use the grasp robustness measure that is computed from the binary force-closure test using domain randomization and has proven effective in some recent works [30]. Also, we use a quality measure related to the position of the center of mass of the object relative to the grasp locations; this aspect has not been considered in [29] but can be critical, especially for heavier objects. Our measures related to the distribution of contact forces and the volume of wrench space were taken from literature and are similar to the second and third measures used in [29].
Apart from automated gripper design, rule-based gripper selection has also been studied in the literature. The authors of [31] present a rule-based approach to gripper selection. They formalize expert know-how into a set of rules. They adopt a rule-based system as opposed to a coding system adopted in some previous works. Further, generative design approaches to form-fitting grippers have also been explored [32].

2.2. Finger Shapes

Finger shapes can be used to grasp multiple objects (multi-function fingers): flat fingertips, shape-matching fingertips, V-carved fingertips, and multi-contact fingertips. We discuss each of these finger shapes in the following paragraphs.
A simple design is a flat fingertip. Flat fingertips are used for universal picking (UP) [30] of objects—a method that depends on good grasp plans. However, the grasps produced by flat fingertips are useful for pick-and-drop applications wherein movement of objects within the grasp can be tolerated. Flat fingertips have limited capabilities due to the limited contact they can create with the object. Rigid flat fingertips most often create a point contact or a line contact with the object. These contacts have a limited ability to resist external forces and torques. Such forces can act on an object due to external contacts during assembly or due to inertial and gravity forces acting on the object while it is being moved. The grasp can be improved to some extent by using soft and deformable fingertips that distribute the contacts over an area.
A grasp by flat fingertips is especially poor if the gripping axis for two-point/line contact does not pass through the center of mass of the object. In this case, the moments applied by the weight of the object should be resisted by a large gripping force. These issues can be resolved by making multiple contacts with the object on one or both jaws of the parallel jaw gripper. Depending on the separation of the contact points and the relative position of the COM of the object, larger external forces and gravitational forces can be resisted by a grasp. In our work, we use this strategy to design multi-function fingers.
Fingertips designed to match the local shape of the object at the contact locations are called shape-matching fingertips [33]. They are often obtained by performing solid geometry subtraction of the part from a finger blank. Shape matching creates robust grasps because the interaction between the finger and the object is distributed over an area. It also distributes the gripping force over an area that minimizes the possibility of damage to the object. However, such a fingertip design is most suited for one object. To a limited extent, shape-matching gripping can be employed for multiple objects in two ways: (1) Different sections can be provided for in the fingertip for different objects. The fingertip becomes long in this case, and this may create unwanted collisions. (2) If the objects have different areas of interaction, two cuts/grooves can be made in the fingertip to create a shape-matching fingertip.
A finger shape often provided with commercially available grippers is the V-carved fingertip, which can handle a wide range of cylindrical objects. They can also be useful for convex curves; however, they are not suitable for concave objects. V-carved fingertips create two line contacts on a cylindrical object per finger. On a general curved object, they create two point contacts per finger.
The concept of more than one contact as obtained in V-carved fingers can be extended to multiple contacts to obtain a multi-contact finger shape. It creates discrete contacts with the object and can handle a variety of convex and concave shapes. Depending on the separation of the contact points and the relative position of the COM of the object, larger external forces and gravitational forces can be resisted by a grasp. In this work, we use the multi-contact finger design and address two critical questions related to the use of multiple contact parallel jaw gripping: (1) how to plan grasps on an object for multiple contact locations (demonstrated for three contact points) and (2) how to decide the design of the fingertip (the position of the contact locations on the fingertip).

2.3. Grasp Modeling and Planning

Grasp modeling involves modeling the interaction forces between the gripper fingers and the object. Based on the grasp model, the quality of a grasp can be quantified and can aid in grasp planning by determining the best grasps.
To determine the points on the object suitable for grasping, we should check for force-closure. A grasp is force-closure grasp if any external force on the object can be resisted by applying valid contact forces from the contact locations. Here, valid forces are the ones that lie within the friction limits with no upper limit in the magnitude of the normal forces.
Force closure has been extensively studied in the literature. Initial notions of force closure were provided by Salisbury and Roth [34]. Methods for testing form closure and force closure were summarized in [22]. In our analysis, we perform force-closure analysis on parts for determining the best grasp positions and finger design.
Once a force-closure grasp is obtained, we need to check the quality of the grasp. Quality of a grasp is quantified in terms of its performance according to various physical requirements on the grasp. A large number of grasp quality measures have been developed over the years. Roa and Suarez [35] present a review on grasp quality measures in the literature. A slightly different approach to gripping is to focus on grasp planning rather than finger design. Mahler et al. [36] present a method to generate parallel grasp on arbitrarily shaped objects for bin-picking applications. The method has a success rate of around 95 % and the objects in the grasp are not completely immobilized, leading to a loss of precision in grasping. These methods try to achieve universal picking (UP) [30]. Gripper-aware grasping policies are useful when there is a facility of changing the grippers [37]. Other approaches provide grasp locations for complex geometry of fingertips [38].

3. Methods

In this section, we present an overview of the important modules developed in this work, problem description, and mathematical background used in grasp modeling.
Figure 1 shows the overview of the workflow adopted in the paper. Details of the steps in the workflow are provided in Section 3, Section 4, Section 5 and Section 6. The first three modules are used for testing the feasibility of grasp and computing the grasp quality measure, respectively. The fifth module is the parametric finger design, by which a CAD model of the finger can be easily created. The sixth and last module is validating the optimal finger experimentally and involves 3D printing and grasping experiments. Each of these steps is discussed in detail in the rest of the paper.

3.1. Problem Description

In this section, we describe the main aspects of the problem we are trying to solve. This work aims to find one finger shape to grasp a collection of objects. This collection of objects is called an object set. The objects are specified by their CAD model from which a point cloud is generated containing information of the coordinates of object points and surface normals. A sufficiently dense point cloud is used such that contact locations can be reliably extracted. We fix the origin of the object point-cloud reference frame to be at the center of mass of the object and the z-axis pointing towards the gripper approach direction.
The gripper considered in this work is a parallel-jaw gripper (Figure 2). We define the grasp by a pose of the gripper relative to the object. The grasp is denoted by g and is the tuple g = ( θ , y o ) (Figure 3). The grasp g specifies the 2D position and orientation of the object relative to the object reference frame. The gripping axis (line along which the fingers move) is the x-axis of the frame, obtained by rotating the gripper reference frame (initially aligned with the object reference frame) about the z-axis by an angle θ and then translating it by a distance y o along the rotated y-axis (Figure 3). The object reference frame has its origin at the center of mass of the object, and its orientation is determined at the stage when the object CAD is created. Based on the grasp parameterization we used, we consider top grasps on the object. Also, we search grasps at a fixed depth below the top surface of the object. This choice was motivated by the consideration that many industrial parts have a distinct top surface and gripping can be performed on the side surfaces.
The finger shape is determined by the three-contact gripping scenario considered in this work. As shown in Figure 4, the two fingers interact with the object at the three contact points (CPs). Finger 1 has one contact point (CP1) and Finger 2 has two contact points (CP2 and CP3). The distance between the contact points ( d f ) is the finger design parameter. The information of the contact locations on the finger and the grasp pose is used to extract the contact locations on the object that will interact with the gripper. The information of the contact locations on the object is used to determine the quality of the grasp.
To determine good grasps on the object and eventually determine good finger designs, we define grasp quality measures based on the following requirements on gripping: (i) contact forces should be uniformly distributed on the object; (ii) grasp should easily resist the wrench due to the weight of the object; (iii) robustness against positioning error in the gripper; and (iv) grasp resists large external wrenches on the object. Grasp modeling and definition of analytic grasp quality measure is presented in the following section.

3.2. Grasp Modeling

In this section, we present grasp modeling for the interaction between the gripper and the object. Grasp modeling is divided into grasp synthesis and grasp analysis. Grasp synthesis involves developing the grasp matrix for a given grasp (Section 3.2.1) and testing if the grasp is force-closure (Section 3.2.2). Grasp analysis involves computing multiple quality metrics to compare grasps with each other. We also define a net quality measure (Section 4.5) as the weighted average of multiple quality metrics and the fingertip score (Section 4.6) as the performance measure of a fingertip design. The force-closure test is used as a test to reject infeasible grasps, and the quality metrics are used to compare grasps with each other. The use of these measures in the gripper design workflow is presented in Section 5.
Grasp modeling, synthesis, and analysis in this work is based on the following assumptions:
1.
Grasping is performed with a parallel-jaw gripper.
2.
The objects and fingertips are rigid.
3.
Coulomb friction model.
4.
Quasi-static grasping: this means that no dynamic effects are considered during the process of grasping.
5.
We neglect small variations in contact locations due to finger curvature.

3.2.1. Computation of the Grasp Matrix

Grasp modeling involves a mapping of contact forces to the net force on the object. The mapping is performed using the grasp matrix ( G ) [22]. The relationship between the contact forces and the external wrench ( w ) acting on the object is given as follows:
w = G λ
The contact forces ( λ ) are expressed in the contact frame of reference. The contact frame is chosen such that the x-direction of the contact frame is along the inward-pointing normal of the contact point. The y- and z-directions of the contact frame lie in the tangential frame. With this choice of contact frame, the contact force is resolved in the normal and tangential directions at the contact location. This allows us to determine if the friction forces are within the friction limits. In this work, we consider point contact with the friction or hard finger (HF) contact model. If the number of contact points is n c , the number of contact force components is 3 n c . For PwoF, G R 6 × n c , and for HF contact, G R 6 × 3 n c .
For a force f R 3 and torque τ R 3 applied at the object’s center of mass, the external wrench ( w ) is a stacked vector:
w = f τ R 6 ,
and is written in the frame fixed in the body.
The grasp matrix G can be derived as follows:
w = f m = R c 1 O R c 2 O R c 3 O S ( r 1 ) R c 1 O S ( r 2 ) R c 2 O S ( r 3 ) R c 3 O λ c 1 λ c 2 λ c 3 = G λ c 1 λ c 2 λ c 3 = G λ
Here, R c i O is the rotation matrix between the contact frame { C i } at the ith contact location and the object frame { O } . λ ci is the contact force at the ith contact location expressed in frame { C i } . Vectors r 1 , r 2 , and r 3 are the position vectors of the contact locations from the origin of the object frame expressed in the object frame { O } . S ( a ) computes the skew-matrix for a vector a = [ a x , a y , a z ] T and is given by the following expression:
S ( a ) = 0 a z a y a z 0 a x a y a x 0
S ( a ) performs the cross-product operation:
S ( a ) = a ×

3.2.2. Grasp Synthesis: Test for Force-Closure

Force-closure is the condition where a grasp can resist any external force on the object by applying appropriate contact forces. Using the grasp matrix developed in the previous section, we can state the conditions for force-closure [22] as follows:
1.
r a n k ( G ) = 6 ;
2.
λ such that G λ = 0 and λ F C .
Here, F C is the friction cone that defines the friction limits under the Coulomb friction assumption. The problem is of finding the valid non-zero contact forces ( λ ) that can create a zero net force (squeezing) on the object. The condition for valid contact forces is that the normal components at each contact location should be positive and the friction components should be within the friction limits. In the present work, we perform an approximate force-closure test by taking a linear approximation for the friction cone. A friction cone is approximated as a pyramid; the larger the number of sides in the pyramid, the better the approximation. If we consider this linear approximation of friction, we can pose this problem as a linear program [39].
The friction conditions can be stated as follows:
μ 2 λ n , i λ t , i μ 2 λ n , i , i = { 1 , 2 , 3 }
μ 2 λ n , i λ o , i μ 2 λ n , i , i = { 1 , 2 , 3 }
Here, λ n , i is the normal component of the contact force at the ith contact location, λ t , i and λ o , i are the frictional components of the contact force, and μ is the coefficient of friction. The subscripts for the contact forces specify that the contact force corresponds to the ith contact and the direction in which they act. They can act in normal (n), tangential (t), or orthogonal directions (o). Here, tangential and orthogonal directions are in the tangential plane.
In the linearized friction conditions, we limit each component of the friction force to μ 2 λ n , i ; hence, the net friction force is guaranteed to remain within the friction limits. These approximate friction limits are also used in [40], which uses the force-closure test as an analytic grasp quality measure.
We pose the equality and inequality constraints as a linear programming problem:
m a x i m i z e : d
subject to the following equality,
G λ = 0
the following inequalities related to the linearized friction limits,
λ t , i + d μ 2 λ n , i , i = { 1 , 2 , 3 } λ t , i d μ 2 λ n , i , i = { 1 , 2 , 3 } λ o , i + d μ 2 λ n , i , i = { 1 , 2 , 3 } λ o , i d μ 2 λ n , i , i = { 1 , 2 , 3 }
and an additional inequality introduced to limit the magnitude of the solution:
i = 1 3 λ n , i n c
Here, n c is the number of contact locations. In the present case, we have three contacts. We introduce this limit to keep a bound on the magnitude of the solution. Otherwise, the solution becomes unbounded if it exists. The grasp is force closure if d > 0 for the linear programming problem.

4. Grasp Analysis: Definition of Quality of a Grasp

Grasp analysis involves the evaluation of the grasp quality of feasible grasps. In the present work, we consider objects that are relatively larger in size and heavier. For such objects, a basic grasp quality measure like the epsilon measure [15] used in previous works [14,25] is not sufficient. Since the objects are larger, grasps might have gripping axis with an offset from the center of mass of the object. This can lead to large moments due to the weight of the object requiring large contact forces for equilibrium or might increase the chances of grasp failure. In order to take care of this, we use the grasp quality based on the position of center of mass. The center of mass based grasp quality measure favors grasps in which the moment due to the weight of the object is easier to resist by the gripper fingers.
If we consider complex objects, robustness is a critical requirement. During grasping, there might be an error in positioning the gripper or an error in localizing the object. The grasp location should be robust to such errors. To take this into account, we use the robust grasp measure that favors grasps that have good quality even if the grasp is perturbed from its intended location on the object. Additionally, a basic requirement in grasping is that the contact forces should be uniformly distributed among the contact locations. This is captured by the force-closure quality measure we used. Lastly, the objects might be subjected to inertial forces or external forces while being manipulated; hence, the fingers should be capable of resisting external forces on the object. This requirement is catered to by the volume of wrench space measure.
In summary, we chose the grasp quality metrics based on the following important requirement for a good grasp in an industrial grasping scenario: (i) uniform contact force distribution; (ii) better resistance of gravity wrench; (iii) robustness against gripper positioning error; and (iv) ability to resist larger external wrench on the object.
We use the force-closure measure presented in [22] and the fact that it favors grasps with a uniform distribution of contact forces. Here, we distinguish between the binary test for force-closure presented in Section 3.2.2 and the quality of force-closure used in this section, which takes a value between zero and one. The second quality measure is the center of mass measure. We propose a simple measure based on the computation of friction forces required to resist the gravity wrench. The third quality measure is the grasp robustness measure. We propose a robustness measure modified from previous measures presented in [36,41] that includes a quality threshold to rank grasps with better resolution. The fourth measure is the volume of wrench space measure that we have taken from [42]. Here, we present the details for computing the grasp quality measures and their physical interpretation. We present four grasp quality measures, a combined grasp quality measure, and the fingertip score.

4.1. Quality of Force-Closure

Uniform distribution of contact forces is a basic requirement for grasping [1]. We use the quality of force-closure as a grasp quality measure that captures this requirement. The force-closure quality measure we use is presented in [22]. The force-closure quality measure is maximum when the requirement of friction forces for squeezing the object is minimum and the normal forces are of equal magnitude.
The variable d used to parameterize the linear programming problem in Section 3.2.2 (Equation (7)) is chosen as a measure of the quality of force-closure. The maximum value of d is obtained when the friction forces required to squeeze the object are zero and the normal forces are equal in magnitude. From Equation (9), we can see that the maximum value of d is μ / 2 . Therefore, the normalized quality of force closure is defined as follows:
Q f c = d 2 μ
To illustrate how the grasp quality measure behaves, we give the value of grasp quality for two examples. Figure 5 shows the examples. For the rectangular object, we obtain a grasp quality of Q f c = 0.75 , and for the symmetrical placement of gripping locations on the circular object, we obtain a quality measure Q f c = 1.00 (Table 1). Therefore, we can say that the grasp on the circular object is better in terms of force distribution.

4.2. Grasp Quality Based on the Position of the Center of Mass

The position of the center of mass is an important criterion for generating good grasps for industrial objects. We define a quality metric based on the contact forces required to resist the force and moment created by the gravitational force. We compute the contact forces required to resist the external gravitational force using the pseudo-inverse of the grasp matrix. This will give us, importantly, the friction force components required to resist the gravity force moment. For the sake of comparison of different grasp locations, we assume the following gravitational force acting at the center of mass of the object: w = [ 0 N , 0 N , 1 N , 0 Nmm , 0 Nmm , 0 Nmm ] T . This is a force of 1 N in the direction in which the weight of the body acts. The choice of a 1 N force is suitable because we want to perform a comparison of different grasps on the same object. The contact force vector, λ , is computed as follows:
λ = G w
As the quality is better if the contact forces required to resist the gravitational force is smaller, we define the quality of grasp as the inverse of the L norm of the contact force vector.
Q c o m = 1 n c λ
For n-contact gripping, the minimum value of λ is 1 / n c N ; therefore, we divide by a factor of n c to scale the quality measure between zero and one ( Q c o m [ 0 , 1 ] ). In the three-contact gripping scenario considered in this work, n c = 3 .
As test cases for Q c o m , consider the positions of the contact locations shown in Figure 6. The figure shows two different grasps on a rectangular object. The grasp on the right has a smaller quality measure because the grasp is offset from the COM. The direction of gravity is perpendicular to the paper.

4.3. Grasp Robustness

In a real grasping scenario, there can be errors in the positioning of the gripper relative to the object. We define a grasp robustness measure ( Q r ) to quantify the robustness of the grasp against such errors.
We compute the grasp robustness measure by testing the force-closure quality measure of a number of grasps around the target grasp.
In particular, we compute the robustness measure using a binary force-closure quality test ( F i ). The value of F i is one if the quality of the ith random grasp around the target grasp is greater than or equal to a threshold α and zero otherwise. This condition is expressed as
F i = 0 i f Q f c < α F i = 1 i f Q f c α
Here, F i is the value of the binary force-closure quality test at the ith grasp around the target grasp and its value is zero or one, as stated above.
The grasp robustness measure is then computed as
Q r = i = 1 k F i k
Here, k is the total number of random grasps generated around the target grasp to compute the robustness measure and Q r [ 0 , 1 ] .
We generate the random grasp poses by adding normally distributed random errors to the orientation ( θ ) and position ( y o ) of the target grasp pose according to the following scheme:
y o r = y o + y o
θ r = θ + θ
Here, terms y o r and θ r are used to denote the random parameters generated around the target y o and θ , and the random values added to the target values are denoted by terms y o and θ . We generate ten nearby random grasps to compute the grasp robustness measure. Although the number is small, it gives satisfactory results. Therefore, we used it in the interest of computation time.
To illustrate the utility of the grasp robustness measure ( Q r ), we show the results for two grasps on an elliptical object shown in Figure 7. The grasp on the left in Figure 7 is along the major diameter of the ellipse. The black triangles point to the target grasp locations and the gripper closes along the thin black line. We can intuitively understand that a small error in the positioning of the gripper will lead to grasp failure. The grasp robustness measure for this grasp is small ( Q r = 0.1 ), as expected. The grasp on the right in Figure 7 is along the major diameter of the ellipse and the grasp will be successful for small errors in the positioning of the gripper. The grasp robustness measure of the grasp is large ( Q r = 1.0 ), as expected.

4.4. Volume of Wrench Space

We use the volume of wrench space measure ( Q ν ) [42] to quantify the ability of a grasp to resist external forces and torques. The volume of wrench space ( ν ) of the grasp is computed from the singular values ( σ i ) of the grasp matrix as follows:
ν = i = 1 6 σ i
Here, σ i ( i = { 1 , 2 , , 6 } ) are the six singular values of the grasp matrix G . Physically, if the volume of wrench space ( ν ) is larger, the grasp can resist larger external forces and torques.
The volume of wrench space measure scales with the distance between the contact locations and the object size. The measure should be normalized to be used alongside other normalized quality measures. We compute the normalized volume of wrench space measure ( Q ν ) by dividing the volume of wrench space of the given grasp by the volume of wrench space of a standard grasp. The standard grasp is defined as the grasp on a circle of diameter equal to the average length and width of the axis-oriented bounding box of the object (Figure 8). The grasp is made with a three-contact gripper of a given maximum distance between the contact locations ( d f , m a x ). If we specify the volume of wrench space of the standard grasp as ( ν s t d ), the volume of the wrench space quality measure of a grasp is defined as follows:
Q ν = ν ν s t d
Thus, Q v [ 0 , 1 ] .

4.5. Combination of the Quality Measures

Every grasp quality we have defined takes care of specific requirements for grasping and not one of them can be used to satisfy the multiple requirements. For instance, as discussed before, the force-closure measure favors grasps with more uniform force distribution ( Q f c ), whereas the center of mass measure ( Q c o m ) favors grasps that can better resist force and torque due to object weight. Since we want multiple quality measures to contribute to the decision of a good grasp and a good finger design, a crucial aspect of the fingertip design process is to define a net quality measure based on a combination of individual quality measures.
To compute the net quality measure, we take a weighted sum of the four quality measures defined before. We combine the force-closure quality measure ( Q f c ), the center of mass quality measure ( Q c o m ), the robust grasp quality measure ( Q r ), and the volume of wrench space quality measure ( Q ν ) by taking a weighted sum of the measures as follows:
Q n e t = w 1 Q f c + w 2 Q c o m + w 3 Q r + w 4 Q ν
Here, Q n e t [ 0 , 1 ] is the net grasp quality measure and w 1 , w 2 , w 3 , and w 4 are the weights such that
w 1 + w 2 + w 3 + w 4 = 1.0
The weights for the individual grasp quality measures can be chosen based on the importance accorded to each grasp quality measure. For example, if the object will make contact with the surroundings and should resist external forces and torques, the volume of wrench space measure ( Q ν ) can be given a larger weight ( w 4 ). Therefore, the precise values of the weights depends on the judgment of the user. For the results in the paper, we chose equal weights for the four quality metrics implying equal importance accorded to each criterion.

4.6. Fingertip Score

In addition to the quality measures, we also define the fingertip score ( F S ) based on the quality measures. The fingertip score gives us an idea of how good a fingertip is across all the objects in an object set. While the grasp quality measures are used to find the optimal grasp on each object, the fingertip score is used to search for the best fingertip shape. The fingertip score is defined as an average of the net quality measure of the best grasp over all the objects. Mathematically,
F S = i = 1 n Q n e t , g i n
Here, F S [ 0 , 1 ] is the fingertip score. We chose the fingertip design with the highest fingertip score as the final design.

5. Finger Design Procedure

In this section, we present a finger design procedure that utilizes multiple grasp quality measures to determine the best finger shape for a set of objects. The finger design procedure consists of a major step and two minor steps. The major step consists of generating the grasp quality data that are used in the two minor steps to find the best grasp and the best finger design. We chose this structure because the data for multiple grasps can be generated and stored separately; then, ranking can be performed on the generated data to find the best grasp for each finger design and eventually find the best finger design for all the objects. In case a new object is added to the object set, the method enables us to reuse the data generated for the existing objects, which can substantially reduce the time for computing the best finger design.
The finger design procedure is essentially one of computing the fingertip score for finger designs in the discrete design space (D) and choosing the fingertip with the highest score as the final design (Figure 9). This is one of the two minor steps. The fingertip score is, in turn, computed from the grasp quality measure of the best grasps on the objects (Figure 10). This is the other minor step. The best grasp on each object is obtained by comparing grasp quality measures of grasps in a discrete grasp pose space (G) (Figure 11). This is the major step that generates the data used in the two minor steps.
For the major step of computing and comparing the grasp quality measures, we use the steps shown in Figure 11, which are described as follows:
1.
Choose a candidate gripper pose: candidate gripper locations are parameterized by the position and orientation of the gripper and belong to the discrete grasp pose space (G).
2.
Extract contact points: For each gripper location, we need to determine the points where the gripper will contact the object. We consider a particular size of the gripper surface and, correspondingly, we will obtain a bunch of points on the object. We isolate the grasp points by cropping the region on the object surface that will come into contact with the object.
3.
Contact feasibility check (Section 5.1).
4.
Collision check with the finger-base (Section 5.2).
5.
Force-closure check: we check for force-closure of the points based on the method in Section 3.2.2 to determine if the grasp is feasible.
6.
Compute grasp quality measures: we also determine a quality measure for the feasible grasp.
7.
Store results.
8.
Repeat the process for all grasps in the discrete grasp space and the best grasp is chosen from among them.
To generate candidate grasp poses, a grasp g is parameterized as g = ( θ , y o ) . Here, θ [ 0 , 2 π ] is the rotation of the gripping axis about the z-axis and y o is the offset of the gripping axis in the rotated frame of reference, as shown in Figure 3. We assume that the grasping takes place along the z-axis. For a given application, the z-axis has to be suitably defined in the CAD model of the object. The feasible range of d f is decided based on the size limits for custom fingers given in the gripper manual.
For generating the contact points on the object, we first transform the point cloud to the gripper frame of reference and crop the area in between the gripper jaws. The points on the left and right surfaces of the object are the grasp points. We check the force-closure for these points and the question we ask is if a valid force exists that can create an equilibrium on the object.
For generating the CAD of the finger with the parameter d f obtained from the above procedure, we created a parametric design of the finger. The parametric CAD design of the fingertip is made to be attached to a particular parallel jaw gripper. We designed the parametric CAD of the fingertip to fit with the parallel jaw gripper of the Franka Panda robot [43] that we used for experimental validation.

5.1. Contact Feasibility Check

Since our gripper design makes two contacts on the object with one of the fingers, we need to check if a given grasp candidate can make both contacts. We call this the contact feasibility check. For the contact feasibility check, we take the difference of the x-coordinate of the two contact locations. Note that the point cloud is transformed, beforehand, into the gripper reference frame with the x-axis along the gripping axis (direction of movement of the fingers).
We check contact feasibility by applying a threshold on the x-coordinates of the two contacts on the right (positive x) side. The number of feasible grasps, from the fixed sampling, depends on the value of the threshold. In our analysis, we chose a small threshold: 0.1 mm. In general, the smaller the threshold, the more accurate the contact feasibility test. However, this also means that a larger grasp pose space should be used because a large number of grasps will be rejected due to infeasible contact. Figure 12 shows a close-up of a feasible grasp and a non-feasible grasp.

5.2. Collision Check with the Finger-Base

We also check the collision of the object with the finger, which would prevent contact to be made with the target contact locations. This test is especially important for a fingertip with a larger distance d f between CP1 and CP2. It is possible that curvature in the object makes contact with the finger base and not the fingertips. Such contact can result in grasp failure. Our method excludes such cases. A check is performed of the maximum depth (h) of the object between the fingertips. The depth allowed is based on the design of the finger. For our case, we choose h h t , where the total depth of the fingertip is h t = 3 mm . Figure 13 shows the parameters h and h t .

6. Results

In this section, we present the results for finger design using two object sets. We first show illustrative results for several grasps on the objects. We discuss the results for each grasp quality measure and the net grasp quality measure to highlight the features on the object favored by each grasp quality measure.

6.1. CAD Models for Evaluation

The CAD models used for evaluation of the proposed approach are relatively large-size industrial components. The first two components in the object set (Figure 14) are parts of a compressor air end from one of the industry collaborators. The third object was created by us based on the consideration that such an object would be difficult to grasp with flat fingertips as it does not have any parallel opposing surfaces. The bounding-box dimension of the objects in the horizontal plane are 104 mm × 147 mm, 104 mm × 103 mm, and 69 mm × 48 mm, respectively, in the order shown in Figure 14 (CAD model) and Figure 15 (physical). The bounding box size data and weights of the objects are presented in Table 2. The third object is also smaller in size; we expected that this will put some restriction on the contact distance, which is observed in the results.
The first two compressor air end components have complex contours on the side surfaces that can create challenges for planning grasps and designing the fingertips. These parts have many other features like holes in the interior parts that do not affect our process as grasps are tested only on the side surfaces. Previous works mostly consider smaller parts for testing their methods. We present a comparison later in the results section.
We create two object sets with the three parts. The first object set (OS1) consists of Object 1 and Object 2. The second object (OS2) set consists of all three objects (Object 1, Object 2, and Object 3).
The bounding box dimensions of the parts are presented in Table 2.
The discrete grasp pose space used (range and step size for θ and y o is shown in Table 3.
The discrete design space (D) is defined as follows: d f = 7 , 9 , 11 , , 33 , where d f is the distance between contact point 1 and contact point 2 on finger 2 (Figure 4).

6.2. On the Number of Feasible Grasps for a Finger Design

We term a grasp feasible if it passes the three feasibility checks: contact feasibility check, collision check with the finger base, and force-closure check Figure 11. The number of feasible grasp locations decreases with the increase in d f . A smaller number of three-point grasps are possible on an object if the distance d f is larger. The number of feasible grasps for each of the three test objects for different d f values is shown in Table 4. The number of feasible grasps falls sharply and goes to zero with increasing d f for the smallest object. Therefore, the largest d f that can be used is also limited by the smallest object in the object set.

6.3. Sample Grasps

In this section, we present sample grasps and the corresponding quality measures on the three objects. Visualizations of the sample grasps are shown in Figure 16 (Object 1), Figure 17 and Figure 18, and the corresponding quality measure data are presented in Table 5, Table 6 and Table 7. The grasps selected for visualization are the top-performing and worst-performing grasps for each fingertip design. In the following sections, we present results and discussions on the individual quality measures, net quality measure, fingertip score, and final finger design for the two object sets (OS1 and OS2).

6.3.1. Force-Closure Quality Measure ( Q F c )

The force-closure grasp quality measure ( Q f c ) is higher if the following apply:
1.
Low friction force or no friction force is required for squeezing the object.
2.
Contact forces are equally distributed while grasping the object.
As mentioned before, the best score (one) is achieved when creating an equilibrium on the object by squeezing it requires no friction force and the forces required are equal in magnitude. The first condition of low friction requirement is satisfied by a large number of grasps with well-opposed grasp locations. The second condition of equal distribution of contact forces is obtained for grasps in which the contact locations CP2 and CP3 are at a curved surface of the object.
To observe the effect of well-opposed grasp locations, we can note Grasp 8, Grasp 9, and Grasp 10 on Object 2 (Figure 17). These grasps have a well-opposed set of contact locations and correspondingly higher Q f c (Table 6). In contrast, we have Grasp 2 and Grasp 4 on Object 3 (Figure 18) that do not have a well-opposed set of contact locations and a correspondingly lower Q f c (Table 7).

6.3.2. Quality Measure Related to the Center of Mass ( Q C o m )

The quality measure related to the position of the center of mass ( Q c o m ) is higher if the forces required to resist the moment due to the weight of the object is lower. Grasp quality is lower when the grasp locations have an offset from the center of mass of the object. The grasp quality measure is based on the computation of friction forces and, in general, the quality is higher when the center of mass lies within the grasp triangle.
To observe the effect of the quality measures, we can compare Grasps 2 and 4 with Grasp 3 on Object 1 (Figure 16 and Table 5) due to the offset of Grasp 2 and 4 from the COM; these grasps have a low quality measure compared to Grasp 3, in which the offset is smaller. Although this offset can be observed clearly by looking at the distance of the COM from the gripping axis, this is not the correct way because the actual location of the grasp points determines Q c o m . This can be observed in Grasp 10 where there is considerable distance between the COM and the gripping axis but the contact locations are spread wider and can resist gravitational forces and torques well.
It is also interesting to note that the value of Q c o m for grasps on Object 3 is generally low compared to that of other objects. This is because it is not very easy to find grasps with higher Q c o m due to the shape of the object.
An alternative approach to grasping around the COM is to only look for grasps around it. In our scheme of grasp parameterization, this means varying only the parameter θ while keeping y o fixed at y o = 0 . This strategy would likely give feasible grasps such that the COM lies within the grasp triangle. In such a search scheme, we need not define a quality measure that takes into account the position of the center of mass but to simply search for grasps with y o = 0 . However, this search scheme may not be useful in certain cases. In cases when grasp might not be feasible with y o = 0 , a range of y o should be searched for feasible grasps. In other cases, grasp locations around the COM may not be feasible due to process requirements. In such cases, grasp locations away from the COM should be considered. In these cases, we require a notion of goodness of grasp taking into account the position of the COM of the object. This requirement is fulfilled by the COM quality measure. It makes our method more general. In summary, the approach of looking for grasp locations around the COM can be used as a heuristic whereas the quality measure based on COM gives a quantitative measure to compare different grasps.

6.3.3. Quality Measure Based on Grasp Robustness ( Q r )

The robustness measure ( Q r ) we use is based on the binary force-closure measure with a threshold on the minimum force-closure quality. The mean and spread of y o and θ used to compute the normally distributed random grasp parameters in Equations (16) and (17) are given in Table 8.
The values of random variables presented in Table 8 were chosen to simulate small errors in the positioning of the gripper. We referred to the data sheet of the robot to determine the spread of the random variables. The pose repeatability of the robot is less than 0.1 mm. However, we could not find data for angular orientation repeatability. Hence, a small value is chosen to take care of the error in the angular position.
The value of threshold α will determine the robustness measure Q r of the grasps. The threshold α is used to resolve the grasp robustness Q r of the grasps better in the range of zero to one. As an example, compare the following two grasps: Grasp 3 on Object 1 and Grasp 3 on Object 2. The data of Q r of the two grasps for different threshold values ( α ) are shown in Table 9. For low values of α , the two grasps have the same Q r . On increasing α , the grasps start showing different Q r values. The difference is specially marked for α = 0.4 . Physically, this takes place because the grasps around Grasp 3 on Object 1 are also very good. We use this to tie-break between these grasps. Therefore, the threshold ( α ) is very useful to resolve grasps with higher Q r .

6.3.4. Volume of Wrench Space Measure ( Q ν )

The volume of wrench space measure ( Q ν ) gives us an idea of the magnitude of the external forces and torques that the grasp can resist. The larger the volume of wrench space ν , the larger the external wrench the grasp can resist for the same magnitude of the contact force vector. The quality measure ( Q ν ) we use is normalized based on a standard grasp on a standard object. Consequently, the value of the normalized measure ( Q ν ) is usually small. However, the relative values keep the same proportion as the volume of wrench space ( ν ), as the value in the denominator of Equation (19) is the same for an object.

6.4. Optimal Grasps According to Q N e t

The net quality measure is computed as the weighted sum of the four grasp quality measures (Equation (20)). The weights should be chosen based on a subjective assessment of the relative importance of each grasp quality measure. In the present work, we chose equal values of all four weights ( w 1 = w 2 = w 3 = w 4 = 0.25 ). In other words, we took a simple average of all the grasp quality measures.
The best grasp on Object 1 among the sample grasps presented (Figure 16 and Table 5) is Grasp 3. The grasp has decent performance for force-closure, COM, and robust grasp measures and acceptable performance for the volume of wrench space measure. Similarly, the best grasp on Object 2 (Figure 17 and Table 6) is Grasp 10. In this case, the volume of wrench space measure is fairly high. On Object 3, the best grasp (Figure 18 and Table 7) is Grasp 6, which has high force-closure, COM, and robustness measures. We also note that for Object 3, although the volume of wrench space quality is very high for Grasp 9 with a larger d f = 15 mm , the net quality measure is small force-closure and robustness measures.

6.5. Search for Optimal Finger Distance D f

Here, we present the results for the optimal finger distance d f . This is the final result of our method. The parameter d f is used in the parametric CAD model of the fingertip, which is used to manufacture the fingertip for physical use.

6.5.1. Optimal Finger Design for Object Set 1

The values of fingertip score (FS) for different d f values for object set 1 is shown in Table 10. The d f vs. F S plot is shown in Figure 19. For OS1, the highest fingertip score is obtained for d f = 33 mm . This is a relatively large d f as compared to the d f obtained for OS2, as discussed in the next section.
From Figure 19, we also observe that the variation in the fingertip score is large across the design parameter d f . This shows that the fingertip design is highly dependent on the object shapes we are dealing with and the best grasp on the objects for each fingertip design.

6.5.2. Optimal Finger Design for Object Set 2

The result of fingertip scores for OS2 is presented in Table 11 and Figure 20. The highest fingertip score is obtained for d f = 11 mm . This is a relatively small d f compared with that for OS1. This is primarily because the third object in OS2 is smaller relative to other objects in the set. The largest d f feasible for Object 3 is d f = 17 mm —larger d f values are not feasible based on the feasibility checks performed (Figure 11). Thus, this limits the largest feasible d f for object set 2 to 17 mm.

6.6. Experimental Verification

We verified our method experimentally by performing grasping experiments with the designed fingertip and identified grasps with a Franka Panda robot on object set 1. The optimal fingertip design is shown in Figure 21. The fingertip designs are generated from a parametric CAD model of the finger and can be easily manufactured using 3D printing. We added anti-slip tape on the contact surface of the fingers to obtain good friction. The grasp experiments on the objects using the optimal fingertips and optimal grasp are shown in Figure 22. The grasp parameter used for each object is shown in Table 12.
To evaluate the grasp performance, we performed five pick-and-place motions with Object 1 and Object 2. All five pick-and-place motions were successfully executed on both objects. We additionally checked the strength of the grasp by applying a 5 N force (0.5 kg weight) in the z-direction at a location outside the grasp triangle. Grasps on both objects were able to resist the external force. Views from pick-and-place are shown in Figure 22a,b,e. The grasp with the offset external force is shown in Figure 22c,f. The grasping experiments show that the designed fingertips and planned grasps perform well in experiments.

7. Discussion

In this section, we discuss the results.

7.1. Comparison with Previous Works

The key benefits of the presented approach include the possibility to grasp larger objects than is possible by previous approaches. This is because we use a force-closure grasp instead of form closure. This is evidenced by the relatively smaller size of the objects tested in previous works. In [19], objects tested are a key, a battery, and an RJ45 ethernet cable. These are small objects with sizes of around 30 mm. Another work [25] has considered objects like PCB and cover with sizes of around 50 mm. We considered substantially larger objects with a size of around 100 mm.
Further, because we used multiple grasp quality measures, taking care of the robustness of grasp and position of the center of mass, we can grasp objects with more complex contours. The objects we tested are industrial parts with complex contours, which suggests the benefits of the present work over the previous works. We also quantify the benefit in terms of the position of the center of mass in the following section.

7.2. Quantitative Comparison Based on Grasp Quality

Not taking into account the position of center of mass can lead to grasps in which there might be a substantial moment due to the weight of the object. We compare our results with the results obtained from the method presented in Honarpardaz et al. [14]. To do this, we implemented the grasp quality measure used in [14], which is the epsilon quality measure [15]. Since the epsilon quality measure does not take into account the offset of the gripping axis from the center of mass of the object it is likely to produce grasps with a larger moment due to the weight of the object.
The results of the comparison are presented in Table 13. We consider the three objects from the previous analysis. Table 13 lists the best three grasps for each object based on our method and the method in [14]. The grasp quality measure in our method is the net quality obtained from the four grasp quality measures, whereas [14] uses the epsilon quality measure.
A total of nine grasps are presented. For each of these grasps, we compute the moment due to the weight of the object ( M G ) about the gripping axis. The larger the moment, the more the chances of grasp failure. We find that on average, the moment ( M G ) for the grasps in our method is around 34 % smaller that the moments obtained from the method in [14].

7.3. On the Generalizability of the Method

Finally, we discuss here the generalizability of the method we have presented. We list six important components of the workflow, which can be replaced with other specific methods and used in the framework we have presented—hence, they are modular. The main components are as follows: (i) grasp sampling method; (ii) grasp modeling; (iii) grasp quality measures; (iv) feasibility checks; (v) parametric finger design; and (vi) optimization method.
The grasp sampling method we used chooses grasps from a fixed space. However, multiple sampling-based methods exist that can be used to make the procedure faster. For grasp modeling, we used the hard-finger contact model, but the soft-finger contact model can also be chosen. Another set of grasp quality measures can be used. Complex finger shapes can be defined parametrically and the appropriate feasibility checks can be incorporated. Finally, other optimization and parameter search methods can be used to find the optimal designs. One or more of these components can be replaced by new methods. We also discuss some of these in more detail in the next section on challenges and extensions.
The grasp space is restricted to two parameters in this work that assumes top grasp on the object. For a general grasp pose of the gripper relative to the object, we would need to specify six parameters (three positions and three orientations). This would ensure that we consider different approach directions for grasping.

7.4. Challenges and Extensions

7.4.1. Grasp and Finger Design Parameter Search

In this work, we used a fixed sampling, which is a brute force approach. There are three parameters in total that we need to search: two grasp parameters and one finger design parameter. A possible future work is to find the optimal grasp and finger design through a genetic-algorithm-based approach to make the process faster.

7.4.2. Complex Finger Shapes

In the present work, we consider finger-shape parameterized by a single parameter d f . While it is efficient in terms of searching for a solution, it also limits the possibility of obtaining better quality grasps. It will be interesting to explore complex fingertip shapes parameterized by multiple parameters. B-spline curves and surfaces could provide good parameterization of the grasp. The challenge, then, would be to find a computationally efficient way to search for optimal design parameters.

7.4.3. Combining Multiple Grasp Quality Measures

We considered four grasp quality measures in the present work. Two important questions remain: Do these quality measures capture all the requirements in an industrial grasping application? Further, what is the best way to combine these quality measures? The combination of quality measures relies heavily on expert knowledge and trial-and-error (for this reason, we characterize each quality measure in the methods section). Is it possible to remove expert intervention from this process?
If we include a higher number of quality measures, the contribution of each quality measure in the net quality measure decreases. For example, if there are five quality measures and if one of the quality measures goes to nearly zero from nearly one, the effect on the net quality measure will be at most 0.2, which is not a significant value. Therefore, the number of quality measures to include is also an important question, which is presently based on the discretion of an expert.

8. Conclusions

In this paper, we presented an approach for the automated design of fingertips for grasping multiple objects: the multi-function finger design. We chose a three-contact gripping scenario that is suitable for finger design for larger objects that have not been considered in previous works. We use four grasp quality measures to find the best grasps and fingertip designs. Our results show the effectiveness of our approach in finding good three-point grasps on the object utilizing the four grasp quality measures and two feasibility checks. We show through visualization of sample grasps, the effectiveness of the different grasp quality measures in selecting grasps that satisfy various physical requirements on the grasps. For example, the sample grasp visualizations show how the grasp positions where an error in the positioning of the gripper will lead to a failed grasp were given a lower quality score. Further, the results also show that the method of concurrent search for grasps and fingertip design is effective in designing good fingertips for the whole set of objects. This is shown clearly by our results for the second set of objects with three objects. Since the third object is small, the resulting size of the finger is small. We also compare our results with a previous work in the field to show that our grasp quality metrics lead to better finger designs and grasps on the object.
The four grasp quality measures we used capture important requirements on the grasp for industrial applications: (i) The force-closure quality measure that favors grasps with a more uniform distribution of contact forces. (ii) The center of mass measure that favors grasps that can better resist gravity wrench. (iii) The robust grasp measure that favors grasps robust against error in positioning of the gripper. (iv) The volume of wrench space measure that favors grasps that can better resist external forces and torques acting on the object.
The finger design workflow consists of determining the fingertip score for an object set for different fingertip designs. The fingertip score, in turn, is computed from the grasp quality measures. We demonstrate our approach using computations on two object sets composed of industrial parts and also test the finger designs in grasping experiments.

Author Contributions

Conceptualization, R.K.H. and G.V.d.P.; methodology, R.K.H. and G.L.; software, R.K.H. and G.L.; validation, R.K.H.; resources, G.V.d.P., B.V. and T.V.; writing—original draft preparation, R.K.H.; writing—review and editing, B.D., B.S., S.B., B.V., T.V. and G.V.d.P.; supervision, B.V., T.V. and G.V.d.P.; project administration, T.V. and G.V.d.P.; funding acquisition, G.V.d.P. All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported in the FROGS project (Flanders Make—ICON FROGS HBC.2020.2007) by Flanders Make, the strategic research center for the manufacturing industry. Greet Van de Perre is a postdoctoral fellow of the Research Foundation Flanders (FWO) (12APZ24N).

Data Availability Statement

The original contributions presented in the study are included in the article, further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflict of interest.

Nomenclature

Q f c Force-closure-based quality measure
Q c o m Quality measure based on the center of mass
Q r Robustness quality measure
Q v Volume of wrench space quality measure
d f Finger design parameter
iIndex of the grasp
jIndex of the object
d f Optimal finger design parameter value
Q n e t Net quality measure
α Force-closure quality threshold
θ Rotation of the gripper about the z-axis relative to the object
y o Translation of the gripper along the rotated y-axis
h t Maximum finger depth
hCurvature depth for a given object curvature
w i Weight associated with the ith quality measure
ν Volume of wrench space
σ i ith singular value of the grasp matrix
G Grasp matrix
d f , m a x Maximum value of d f based on gripper specifications
w External wrench acting on the object
λ vector of contact forces
μ Coefficient of friction
n c Number of contact locations ( n c = 3 ) in our case

References

  1. Monkman, G.J.; Hesse, S.; Steinmann, R.; Schunk, H. Robot Grippers; John Wiley & Sons: Hoboken, NJ, USA, 2007. [Google Scholar]
  2. Dollar, A.M.; Howe, R.D. The Highly Adaptive SDM Hand: Design and Performance Evaluation. Int. J. Robot. Res. 2010, 29, 585–597. [Google Scholar] [CrossRef]
  3. Ciocarlie, M.; Hicks, F.M.; Holmberg, R.; Hawke, J.; Schlicht, M.; Gee, J.; Stanford, S.; Bahadur, R. The Velo Gripper: A Versatile Single-Actuator Design for Enveloping, Parallel and Fingertip Grasps. Int. J. Robot. Res. 2014, 33, 753–767. [Google Scholar] [CrossRef]
  4. Yako, C.L.; Yuan, S.; Salisbury, J.K. Designing Underactuated Graspers with Dynamically Variable Geometry Using Potential Energy Map Based Analysis. In Proceedings of the 2022 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Kyoto, Japan, 23–27 October 2022; pp. 4638–4645. [Google Scholar]
  5. He, L.; Lu, Q.; Abad, S.-A.; Rojas, N.; Nanayakkara, T. Soft Fingertips with Tactile Sensing and Active Deformation for Robust Grasping of Delicate Objects. IEEE Robot. Autom. Lett. 2020, 5, 2714–2721. [Google Scholar] [CrossRef]
  6. Kan, Z.; Zhang, Y.; Pang, C.; Wang, M.Y. Origami-Based Shape Morphing Fingertip to Enhance Grasping Stability and Dexterity. In Proceedings of the 2020 IEEE 16th International Conference on Automation Science and Engineering (CASE), Hong Kong, China, 20–21 August 2020; pp. 1070–1077. [Google Scholar]
  7. Piskarev, Y.; Devincenti, A.; Ramachandran, V.; Bourban, P.-E.; Dickey, M.D.; Shintake, J.; Floreano, D. A Soft Gripper with Granular Jamming and Electroadhesive Properties. Adv. Intell. Syst. 2023, 5, 2200409. [Google Scholar] [CrossRef]
  8. Berenstein, R.; Wallach, A.; Moudio, P.E.; Cuellar, P.; Goldberg, K. An Open-Access Passive Modular Tool Changing System for Mobile Manipulation Robots. In Proceedings of the 2018 IEEE 14th International Conference on Automation Science and Engineering (CASE), Munich, Germany, 20–24 August 2018; pp. 592–598. [Google Scholar]
  9. Brost, R.C.; Goldberg, K.Y. A Complete Algorithm for Designing Planar Fixtures Using Modular Components. IEEE Trans. Robot. Autom. 1996, 12, 31–46. [Google Scholar] [CrossRef]
  10. Trinkle, J.C. A Quantitative Test for Form Closure Grasps. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Raleigh, NC, USA, 7–10 July 1992; Volume 3, pp. 1670–1677. [Google Scholar]
  11. Honarpardaz, M.; Tarkian, M.; Feng, X.; Sirkett, D.; Ölvander, J. Generic Automated Finger Design. In Proceedings of the International Design Engineering Technical Conferences and Computers and Information in Engineering Conference, Charlotte, NC, USA, 21–24 August 2016; Volume 50169, p. V05BT07A071. [Google Scholar]
  12. Ringwald, J.; Schneider, S.; Chen, L.; Knobbe, D.; Johannsmeier, L.; Swikir, A.; Haddadin, S. Towards Task-Specific Modular Gripper Fingers: Automatic Production of Fingertip Mechanics. IEEE Robot. Autom. Lett. 2023, 8, 1866–1873. [Google Scholar] [CrossRef]
  13. Nagel, M.; Giese, F.; Becker, R. Flexible Gripper Design Through Additive Manufacturing. In Robotic Fabrication in Architecture, Art and Design 2016; Springer: Berlin/Heidelberg, Germany, 2016; pp. 455–459. [Google Scholar]
  14. Honarpardaz, M.; Ölvander, J.; Tarkian, M. Fast Finger Design Automation for Industrial Robots. Robot. Auton. Syst. 2019, 113, 120–131. [Google Scholar] [CrossRef]
  15. Ferrari, C.; Canny, J.F. Planning Optimal Grasps. In Proceedings of the ICRA, Nice, France, 12–14 May 1992; Volume 3, p. 6. [Google Scholar]
  16. Honarpardaz, M.; Tarkian, M.; Ölvander, J.; Feng, X. Finger Design Automation for Industrial Robot Grippers: A Review. Robot. Auton. Syst. 2017, 87, 104–119. [Google Scholar] [CrossRef]
  17. Ramasubramanian, A.K.; Connolly, M.; Mathew, R.; Papakostas, N. Automatic Simulation-Based Design and Validation of Robotic Gripper Fingers. CIRP Ann. 2022, 71, 137–140. [Google Scholar] [CrossRef]
  18. Xu, J.; Wan, W.; Koyama, K.; Domae, Y.; Harada, K. Selecting and Designing Grippers for an Assembly Task in a Structured Approach. Adv. Robot. 2021, 35, 381–397. [Google Scholar] [CrossRef]
  19. Ringwald, J.; Zong, S.; Swikir, A.; Haddadin, S. Automatic Gripper-Finger Design, Production, and Application: Toward Fast and Cost-Effective Small-Batch Production. IEEE Robot. Autom. Mag. 2023, 30, 46–56. [Google Scholar] [CrossRef]
  20. Alet, F.; Bauza, M.; Jeewajee, A.K.; Thomsen, M.; Rodriguez, A.; Kaelbling, L.P.; Lozano-Pérez, T. Robotic Gripper Design with Evolutionary Strategies and Graph Element Networks. In Proceedings of the 34th Conference on Neural Information Processing Systems (NeurIPS), Vancouver, BC, Canada, 6–12 December 2020. [Google Scholar]
  21. Wolniakowski, A.; Lindvig, A.P.; Iversen, N.; Krüger, N.; Kramberger, A. Robotic Finger Design Workflow for Adaptable Industrial Assembly Tasks. In Proceedings of the ROBOVIS, Online, 4–6 November 2020; pp. 69–76. [Google Scholar]
  22. Prattichizzo, D.; Trinkle, J.C. Grasping. In Springer Handbook of Robotics; Springer: Berlin/Heidelberg, Germany, 2016; pp. 955–988. [Google Scholar]
  23. Chen, I.-M.; Burdick, J.W. Finding Antipodal Point Grasps on Irregularly Shaped Objects. IEEE Trans. Robot. Autom. 1993, 9, 507–512. [Google Scholar] [CrossRef]
  24. Brost, R.C. Automatic Grasp Planning in the Presence of Uncertainty. Int. J. Robot. Res. 1988, 7, 3–17. [Google Scholar] [CrossRef]
  25. Honarpardaz, M.; Meier, M.; Haschke, R. Fast Grasp Tool Design: From Force to Form Closure. In Proceedings of the 2017 13th IEEE Conference on Automation Science and Engineering (CASE), Xi’an, China, 20–23 August 2017; pp. 782–788. [Google Scholar]
  26. Honarpardaz, M.; Tarkian, M.; Ölvander, J.; Feng, X. Experimental Verification of Design Automation Methods for Robotic Finger. Robot. Auton. Syst. 2017, 94, 89–101. [Google Scholar] [CrossRef]
  27. Jiang, R.H.; Doshi, N.; Gondhalekar, R.; Rodriguez, A. Parallel-Jaw Gripper and Grasp Co-Optimization for Sets of Planar Objects. In Proceedings of the 2023 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Detroit, MI, USA, 1–5 October 2023; pp. 2455–2462. [Google Scholar]
  28. Song, H.; Wang, M.Y.; Hang, K. Fingertip Surface Optimization for Robust Grasping on Contact Primitives. IEEE Robot. Autom. Lett. 2018, 3, 742–749. [Google Scholar] [CrossRef]
  29. Balan, L.; Bone, G.M. Automated Gripper Jaw Design and Grasp Planning for Sets of 3D Objects. J. Robot. Syst. 2003, 20, 147–162. [Google Scholar] [CrossRef]
  30. Mahler, J.; Matl, M.; Satish, V.; Danielczuk, M.; DeRose, B.; McKinley, S.; Goldberg, K. Learning Ambidextrous Robot Grasping Policies. Sci. Robot. 2019, 4, eaau4984. [Google Scholar] [CrossRef]
  31. Pedrazzoli, P.; Rinaldi, R.; Boer, C.R. A Rule Based Approach to the Gripper Selection Issue for the Assembly Process. In Proceedings of the 2001 IEEE International Symposium on Assembly and Task Planning (ISATP2001), Assembly and Disassembly in the Twenty-First Century, (Cat. No. 01TH8560), Fukuoka, Japan, 29–29 May 2001; pp. 202–207. [Google Scholar]
  32. Ha, H.; Agrawal, S.; Song, S. Fit2Form: 3D Generative Model for Robot Gripper Form Design. In Proceedings of the Conference on Robot Learning, London, UK, 8–11 November 2021. pp. 176–187. [Google Scholar]
  33. Velasco, V.; Newman, W.S. Computer-Assisted Gripper and Fixture Customization Using Rapid-Prototyping Technology. In Proceedings of the 1998 IEEE International Conference on Robotics and Automation (Cat. No. 98CH36146), Leuven, Belgium, 20–20 May 1998; Volume 4, pp. 3658–3664. [Google Scholar]
  34. Salisbury, J.K.; Roth, B. Kinematic and Force Analysis of Articulated Mechanical Hands. J. Mech., Trans. Autom. 1983, 105, 35–41. [Google Scholar] [CrossRef]
  35. Roa, M.A.; Suárez, R. Grasp Quality Measures: Review and Performance. Auton. Robot. 2015, 38, 65–88. [Google Scholar] [CrossRef]
  36. Mahler, J.; Liang, J.; Niyaz, S.; Laskey, M.; Doan, R.; Liu, X.; Ojea, J.A.; Goldberg, K. Dex-Net 2.0: Deep Learning to Plan Robust Grasps with Synthetic Point Clouds and Analytic Grasp Metrics. arXiv 2017, arXiv:1703.09312. [Google Scholar]
  37. Xu, Z.; Qi, B.; Agrawal, S.; Song, S. Adagrasp: Learning an Adaptive Gripper-Aware Grasping Policy. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021; pp. 4620–4626. [Google Scholar]
  38. Etxezarreta, A.; Sagardia, M. Real Time Contact Surface Prediction for Grasping with Complex Geometries. Comput. Graph. 2022, 107, 66–72. [Google Scholar] [CrossRef]
  39. Murray, R.M.; Li, Z.; Sastry, S.S. A Mathematical Introduction to Robotic Manipulation; CRC Press: Boca Raton, FL, USA, 2017. [Google Scholar]
  40. Mahler, J.; Matl, M.; Liu, X.; Li, A.; Gealy, D.; Goldberg, K. Dex-Net 3.0: Computing Robust Vacuum Suction Grasp Targets in Point Clouds Using a New Analytic Model and Deep Learning. In Proceedings of the 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, Australia, 21–25 May 2018; pp. 5620–5627. [Google Scholar]
  41. Weisz, J.; Allen, P.K. Pose Error Robust Grasping from Contact Wrench Space Metrics. In Proceedings of the 2012 IEEE International Conference on Robotics and Automation, Saint Paul, MN, USA, 14–18 May 2012; pp. 557–562. [Google Scholar]
  42. Li, Z.; Sastry, S.S. Task-Oriented Optimal Grasping by Multifingered Robot Hands. IEEE J. Robot. Autom. 1988, 4, 32–44. [Google Scholar] [CrossRef]
  43. Haddadin, S.; Parusel, S.; Johannsmeier, L.; Golz, S.; Gabl, S.; Walch, F.; Sabaghian, M.; Jaehne, C.; Hausperger, L.; Haddadin, S. The Franka Emika Robot: A Reference Platform for Robotics Research and Education. IEEE Robot. Autom. Mag. 2022, 29, 46–64. [Google Scholar] [CrossRef]
Figure 1. Overview of the workflow adopted in the paper.
Figure 1. Overview of the workflow adopted in the paper.
Robotics 13 00074 g001
Figure 2. A view of the parallel-jaw gripper in a pre-grasp pose on the object.
Figure 2. A view of the parallel-jaw gripper in a pre-grasp pose on the object.
Robotics 13 00074 g002
Figure 3. Grasp parameterization. The original reference frame of the object is shown along with the gripping axis obtained by the grasp parameters g = ( θ , y o ) .
Figure 3. Grasp parameterization. The original reference frame of the object is shown along with the gripping axis obtained by the grasp parameters g = ( θ , y o ) .
Robotics 13 00074 g003
Figure 4. Schematic of three-contact gripping.
Figure 4. Schematic of three-contact gripping.
Robotics 13 00074 g004
Figure 5. Example base cases. (Left) Grasp at three points on a rectangular object. (Right) grasp at three points on a circular object. The grasp on the circular object has a higher quality measure Q f c because it creates a more uniform distribution of contact forces.
Figure 5. Example base cases. (Left) Grasp at three points on a rectangular object. (Right) grasp at three points on a circular object. The grasp on the circular object has a higher quality measure Q f c because it creates a more uniform distribution of contact forces.
Robotics 13 00074 g005
Figure 6. Examples for the center of mass measure ( Q c o m ). The grasp on the left has a Q c o m = 1 ; it is a symmetric grasp on a circular object. The grasp in the middle is on a rectangular object and the center of mass lies inside the grasp triangle; it has a smaller quality measure ( Q c o m = 0.66 ) because the friction forces are not equally distributed. The grasp on the right has very low quality ( Q c o m = 0.12 ) because the center of mass does not lie inside the grasp triangle.
Figure 6. Examples for the center of mass measure ( Q c o m ). The grasp on the left has a Q c o m = 1 ; it is a symmetric grasp on a circular object. The grasp in the middle is on a rectangular object and the center of mass lies inside the grasp triangle; it has a smaller quality measure ( Q c o m = 0.66 ) because the friction forces are not equally distributed. The grasp on the right has very low quality ( Q c o m = 0.12 ) because the center of mass does not lie inside the grasp triangle.
Robotics 13 00074 g006
Figure 7. Grasping an elliptical object along the major (left image) and minor (right image) diameter. The black circles indicate the position of the grasp points and the line indicates the gripping direction. The grasp along the major diameter has very low robustness compared to the grasp on the right along the minor diameter.
Figure 7. Grasping an elliptical object along the major (left image) and minor (right image) diameter. The black circles indicate the position of the grasp points and the line indicates the gripping direction. The grasp along the major diameter has very low robustness compared to the grasp on the right along the minor diameter.
Robotics 13 00074 g007
Figure 8. Computation of normalized volume of wrench space measure. (a) Bounding box on the object and the relevant dimensions. (b) The standard object and grasp used for computing the normalizing factor.
Figure 8. Computation of normalized volume of wrench space measure. (a) Bounding box on the object and the relevant dimensions. (b) The standard object and grasp used for computing the normalizing factor.
Robotics 13 00074 g008
Figure 9. Fingertip design workflow.
Figure 9. Fingertip design workflow.
Robotics 13 00074 g009
Figure 10. Workflow for computing fingertip score. Here the label A represents the step for computing fingertip score and B represents the step for computing the best grasp on the object.
Figure 10. Workflow for computing fingertip score. Here the label A represents the step for computing fingertip score and B represents the step for computing the best grasp on the object.
Robotics 13 00074 g010
Figure 11. The steps involved in grasp synthesis and determining grasp quality (labeled B).
Figure 11. The steps involved in grasp synthesis and determining grasp quality (labeled B).
Robotics 13 00074 g011
Figure 12. Visualization of (a) a feasible contact and (b) a non-feasible contact. (a) A feasible contact on Object 1 (grasp parameters: θ = 1.6 rad and y o = 5 mm ). (b) A non-feasible contact on Object 1 (grasp parameters: θ = 1.8 rad and y o = 5 mm ).
Figure 12. Visualization of (a) a feasible contact and (b) a non-feasible contact. (a) A feasible contact on Object 1 (grasp parameters: θ = 1.6 rad and y o = 5 mm ). (b) A non-feasible contact on Object 1 (grasp parameters: θ = 1.8 rad and y o = 5 mm ).
Robotics 13 00074 g012
Figure 13. Check for object collision.
Figure 13. Check for object collision.
Robotics 13 00074 g013
Figure 14. CAD models of objects used for evaluation. The parts are industrial components used in compressor air ends. The z-direction is perpendicular to the top surface of the object and pointing away from the object. The z-direction is also the approach direction for grasp.
Figure 14. CAD models of objects used for evaluation. The parts are industrial components used in compressor air ends. The z-direction is perpendicular to the top surface of the object and pointing away from the object. The z-direction is also the approach direction for grasp.
Robotics 13 00074 g014
Figure 15. Three-dimensional-printed parts used for evaluation.
Figure 15. Three-dimensional-printed parts used for evaluation.
Robotics 13 00074 g015
Figure 16. Sample grasps on Object 1. The complete data are presented in Table 5. The figure visualizes three-point grasps on each object and the corresponding five quality measures below each grasp. The grasp visualizations can help verify the quality measures. The best grasp among the presented sample grasps is Grasp 3 (underlined green), with particularly large Q f c , Q c o m , and Q r values. The worst grasp is Grasp 4 (underlined red) with a particularly small Q f c and Q r . The location of COM is indicated in each picture.
Figure 16. Sample grasps on Object 1. The complete data are presented in Table 5. The figure visualizes three-point grasps on each object and the corresponding five quality measures below each grasp. The grasp visualizations can help verify the quality measures. The best grasp among the presented sample grasps is Grasp 3 (underlined green), with particularly large Q f c , Q c o m , and Q r values. The worst grasp is Grasp 4 (underlined red) with a particularly small Q f c and Q r . The location of COM is indicated in each picture.
Robotics 13 00074 g016
Figure 17. Sample grasps on Object 2. Full data are presented in Table 6. Among the sample grasps presented, Grasp 10 (underlined green) is the best overall grasp with high Q f c , Q c o m , and Q r values. Grasp 2 (underlined red) is the worst grasp among the presented grasps. We also observe that for the second object many grasps have a low robustness score.
Figure 17. Sample grasps on Object 2. Full data are presented in Table 6. Among the sample grasps presented, Grasp 10 (underlined green) is the best overall grasp with high Q f c , Q c o m , and Q r values. Grasp 2 (underlined red) is the worst grasp among the presented grasps. We also observe that for the second object many grasps have a low robustness score.
Robotics 13 00074 g017
Figure 18. Sample grasps on Object 3. The complete data are presented in Table 7. The figure visualizes different three-point grasps on each Object 3 and the corresponding five quality measures below each grasp. The grasp visualizations can help verify the quality measures. The best grasp among the presented sample grasps is Grasp 6 (underlined green) with particularly large Q f c and Q r values. The worst grasp is Grasp 4 (underlined red) with particularly small Q f c and Q r values. The location of COM is indicated in each picture.
Figure 18. Sample grasps on Object 3. The complete data are presented in Table 7. The figure visualizes different three-point grasps on each Object 3 and the corresponding five quality measures below each grasp. The grasp visualizations can help verify the quality measures. The best grasp among the presented sample grasps is Grasp 6 (underlined green) with particularly large Q f c and Q r values. The worst grasp is Grasp 4 (underlined red) with particularly small Q f c and Q r values. The location of COM is indicated in each picture.
Robotics 13 00074 g018
Figure 19. Variation in the fingertip score ( F S ) with the fingertip design parameter d f for OS1.
Figure 19. Variation in the fingertip score ( F S ) with the fingertip design parameter d f for OS1.
Robotics 13 00074 g019
Figure 20. Variation in the fingertip score ( F S ) with the fingertip design parameter d f for object set 2 consisting of three parts.
Figure 20. Variation in the fingertip score ( F S ) with the fingertip design parameter d f for object set 2 consisting of three parts.
Robotics 13 00074 g020
Figure 21. Final fingertip design for the two object sets.
Figure 21. Final fingertip design for the two object sets.
Robotics 13 00074 g021
Figure 22. Grasping experiments performed on the two objects of object set 1: (a) First grasp on Object 1 (one view). (b) First grasp on Object 1 (another view). (c) Grasp on Object 1 with external force. (d) Second grasp on Object 1. (e) Grasp on Object 2. (f) Grasp on Object 2 with external force. The grasp parameters used are shown in Table 12.
Figure 22. Grasping experiments performed on the two objects of object set 1: (a) First grasp on Object 1 (one view). (b) First grasp on Object 1 (another view). (c) Grasp on Object 1 with external force. (d) Second grasp on Object 1. (e) Grasp on Object 2. (f) Grasp on Object 2 with external force. The grasp parameters used are shown in Table 12.
Robotics 13 00074 g022
Table 1. Quality measures for the two example cases in Figure 5. Here, p and n are the stacked position vectors and normal vectors, respectively, of the contact locations. The reference frame as shown for each case has its origin at the center of the geometry.
Table 1. Quality measures for the two example cases in Figure 5. Here, p and n are the stacked position vectors and normal vectors, respectively, of the contact locations. The reference frame as shown for each case has its origin at the center of the geometry.
Example #p, n Q fc
Object 1 p = [ 3 , 5 , 0 , 3 , 5 , 0 , 0 , 5 , 0 ]
n = [ 0 , 1 , 0 , 0 , 1 , 0 , 0 , 1 , 0 ]
0.75
Object 2 p = [ 5 3 , 5 , 0 , 5 3 , 5 , 0 , 0 , 10 , 0 ]
n = [ 3 / 2 , 1 / 2 , 0 , 3 / 2 , 1 / 2 , 0 , 0 , 1 , 0 ]
1.00
Table 2. Bounding box dimension of the parts used for testing.
Table 2. Bounding box dimension of the parts used for testing.
Object #Dimension (mm)Weight (gm)Coefficient of Friction ( μ )
1 104 × 147 × 28 3000.6
2 104 × 103 × 31 200
3 69 × 48 × 10 30
Table 3. Parameters for generating the discrete grasp pose space (G). The parameters were chosen to find a balance between the density of grasp poses and the computation time.
Table 3. Parameters for generating the discrete grasp pose space (G). The parameters were chosen to find a balance between the density of grasp poses and the computation time.
Grasp ParameterRangeStep
y o [−10 mm,10 mm]1 mm
θ [0.0 rad, 2 π rad]0.1 rad
Table 4. Number of feasible grasp points for different finger design parameter ( d f ) values. A larger number of grasps are feasible for smaller d f .
Table 4. Number of feasible grasp points for different finger design parameter ( d f ) values. A larger number of grasps are feasible for smaller d f .
Number of Feasible Grasps
d f Object 1Object 2Object 3
5 mm211437
11 mm1478
15 mm572
25 mm340
Table 5. Sample grasps on Object 1. The grasps are visualized in Figure 16.
Table 5. Sample grasps on Object 1. The grasps are visualized in Figure 16.
Grasp and Finger Design ParametersGrasp Quality Metrics
Grasp No. d f  (mm) θ  (rad) y o  (mm) Q fc Q com Q r Q v Q net
Grasp 174.850.660.351.00.080.52
Grasp 272.8130.740.160.60.090.39
Grasp 3154.830.630.671.00.160.62
Grasp 4152.0−130.230.300.40.150.27
Grasp 5210.0−50.790.620.70.180.57
Grasp 6211.0−130.520.390.40.200.37
Grasp 7254.670.560.620.60.270.51
Grasp 8251.4−10.400.660.20.260.38
Grasp 9330.0−50.730.710.50.360.57
Grasp 10333.0−90.330.550.20.270.33
Table 6. Sample grasps on Object 2. The grasps are visualized in Figure 17.
Table 6. Sample grasps on Object 2. The grasps are visualized in Figure 17.
Grasp and Finger Design ParametersGrasp Quality Metrics
Grasp No. d f  (mm) θ  (rad) y o  (mm) Q fc Q com Q r Q v Q net
Grasp 170.4−30.550.480.60.120.44
Grasp 274.0110.190.180.20.110.17
Grasp 3151.410.310.771.00.160.56
Grasp 4154.8110.150.350.20.130.21
Grasp 5214.8−90.380.500.50.220.40
Grasp 6211.490.160.470.00.220.21
Grasp 7251.6−110.370.470.80.250.48
Grasp 8254.8130.580.460.10.230.34
Grasp 9311.6−70.540.680.70.320.56
Grasp 10331.6−70.610.700.80.340.61
Table 7. Sample grasps on Object 3. The grasps are visualized in Figure 18.
Table 7. Sample grasps on Object 3. The grasps are visualized in Figure 18.
Grasp and Finger Design ParametersGrasp Quality Metrics
Grasp No. d f  (mm) θ  (rad) y o  (mm) Q fc Q com Q r Q v Q net
Grasp 175.460.750.311.00.080.54
Grasp 274.7110.160.170.30.090.18
Grasp 395.460.790.380.90.100.54
Grasp 494.8120.120.200.10.120.13
Grasp 5111.3−90.100.330.10.150.17
Grasp 6135.460.810.500.80.140.56
Grasp 7131.3−90.140.380.40.170.27
Grasp 8151.7−150.570.270.40.180.36
Grasp 9150.570.120.450.10.390.26
Grasp 10175.190.170.430.20.180.24
Table 8. Mean and spread of the parameters used for computing the grasps around the target grasp.
Table 8. Mean and spread of the parameters used for computing the grasps around the target grasp.
ParameterMeanSpread
y o 0 0.5 mm
θ 0 0.05 rad
Table 9. Variation in the robustness measure with threshold α for two sample grasps. The smallest α that gives a major difference in the value of Q r is highlighted.
Table 9. Variation in the robustness measure with threshold α for two sample grasps. The smallest α that gives a major difference in the value of Q r is highlighted.
α Q r
(Object 1, Grasp 3)
Q r
(Object 2, Grasp 3)
None1.01.0
0.11.01.0
0.20.90.8
0.30.90.7
0.40.80.2
0.50.70.1
0.60.70.0
0.70.40.0
0.80.00.0
0.90.00.0
1.00.00.0
Table 10. Fingertip score for object set 1. The finger design with the highest fingertip score is highlighted.
Table 10. Fingertip score for object set 1. The finger design with the highest fingertip score is highlighted.
d f ( mm ) Object 1Object 2FS
50.540.450.50
70.540.440.49
90.550.510.53
110.570.510.54
130.590.460.52
150.610.560.58
170.540.490.52
190.570.410.49
210.570.400.48
230.550.510.53
250.510.470.49
270.470.560.51
290.470.550.51
310.570.560.57
330.570.610.59
Table 11. Fingertip score for object set 2. The finger design with the highest fingertip score is highlighted.
Table 11. Fingertip score for object set 2. The finger design with the highest fingertip score is highlighted.
d f ( mm ) Object 1Object 2Object 3FS
50.540.450.500.50
70.540.440.530.50
90.550.510.540.54
110.570.510.590.56
130.590.460.560.54
150.670.560.360.51
170.540.490.240.43
Table 12. Grasp parameters for best grasp on each object for the two optimal fingertip designs. Here, θ and y o are grasp parameters that define the pose of the gripper relative to the object.
Table 12. Grasp parameters for best grasp on each object for the two optimal fingertip designs. Here, θ and y o are grasp parameters that define the pose of the gripper relative to the object.
Object Set 1
d f = 33 mm
Grasps θ  (rad) y o  (mm) Q net
Object 1 (Figure 22a)0.0-50.57
Object 1 (Figure 22d)3.0-90.33
Object 2 (Figure 22e)1.6-70.61
Table 13. Comparison of the moment due to the weight of the object about the gripping axis for top three grasps on each object obtained from our method and the method of Honarpardaz et al. [14].
Table 13. Comparison of the moment due to the weight of the object about the gripping axis for top three grasps on each object obtained from our method and the method of Honarpardaz et al. [14].
Our MethodHonarpardaz et al. [14]
Obj # Grasp
Parameters
M G   (Nmm) Grasp
Parameters
M G  (Nmm)
Rank # θ  (rad) y o  (mm) θ  (rad) y o  (mm)
1Rank 11.5−514.701.6−617.64
Rank 24.838.825.1−25.88
Rank 35.012.941.8−1029.40
2Rank 11.4−11.961.5−59.80
Rank 26.259.800.0−35.88
Rank 34.8−917.641.6−815.68
3Rank 13.341.173.420.59
Rank 25.461.765.630.88
Rank 33.420.591.3−92.65
Average moment due
to the weight (Nmm)
6.59 9.82
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Hota, R.K.; Liu, G.; Decraemer, B.; Swevels, B.; Burggraeve, S.; Verstraten, T.; Vanderborght, B.; Van de Perre, G. Automated Grasp Planning and Finger Design Space Search Using Multiple Grasp Quality Measures. Robotics 2024, 13, 74. https://doi.org/10.3390/robotics13050074

AMA Style

Hota RK, Liu G, Decraemer B, Swevels B, Burggraeve S, Verstraten T, Vanderborght B, Van de Perre G. Automated Grasp Planning and Finger Design Space Search Using Multiple Grasp Quality Measures. Robotics. 2024; 13(5):74. https://doi.org/10.3390/robotics13050074

Chicago/Turabian Style

Hota, Roshan Kumar, Gaoyuan Liu, Bieke Decraemer, Barry Swevels, Sofie Burggraeve, Tom Verstraten, Bram Vanderborght, and Greet Van de Perre. 2024. "Automated Grasp Planning and Finger Design Space Search Using Multiple Grasp Quality Measures" Robotics 13, no. 5: 74. https://doi.org/10.3390/robotics13050074

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop