Back to Projects

Dual-Arm Grasp Dataset Generator

Abstract: While single-arm robotic grasping has seen massive datasets and benchmarks, dual-arm manipulation remains data-scarce. This post details my implementation of a pipeline that transforms single-arm grasp data into verified, force-closure dual-arm pairs. By adapting the logic from state-of-the-art research for cluttered, small-object scenarios, I aim to enable learning-based approaches for coordinated bimanual manipulation.


The Motivation

I recently read the DG16M paper, which presented a massive dataset for dual-arm grasping. It was an inspiring piece of work, but as I dug into the methodology, I noticed two specific constraints that I wanted to overcome:

  1. The "Large Object" Bias: DG16M focused primarily on large objects (tables, boxes, bins). Because the objects were huge, collision avoidance between the two arms was trivial—simple distance pruning worked because the arms were naturally far apart. I wanted a system that could handle smaller objects, where the arms are forced into close proximity, making collision management critical.
  2. Model vs. Scene: DG16M generated grasps using DexNet as a base, which relies on clean 3D object models. I wanted to build my generation pipeline on top of GraspNet-1B. This dataset provides dense grasps in cluttered, real-world scenes captured with RGB-D cameras. By building on this, any network trained on my dataset can learn directly from depth images rather than requiring perfect CAD models.

System Overview

The goal is straightforward but computationally heavy: Take a scene full of valid single-arm grasps and find every combination of two grasps that results in a stable, collision-free dual-arm hold.

The pipeline I built moves through four distinct phases:

  1. Preprocessing: Cleaning up the noisy GraspNet-1B data.
  2. Pairing: The combinatorial explosion of matching left and right hands.
  3. Pruning: Geometric checks to ensure the robots don't smash into each other.
  4. Verification: The physics math (Force Closure) to ensure the object doesn't fall.

Grasp Representation

Before diving into the pipeline, it's important to understand how grasps are represented. Each parallel-jaw grasp is encoded as a 17-dimensional vector:

g=[s,w,h,d,R,t,o]TR17\mathbf{g} = [s, w, h, d, \mathbf{R}, \mathbf{t}, o]^T \in \mathbb{R}^{17}

where:

  • s[0,1]s \in [0, 1]: Grasp quality score from GraspNet
  • ww: Gripper opening width (meters)
  • hh: Gripper finger height
  • dd: Approach depth
  • RSO(3)\mathbf{R} \in SO(3): Rotation matrix (9 elements, flattened) defining the gripper orientation
  • tR3\mathbf{t} \in \mathbb{R}^3: Translation vector (grasp center position)
  • oo: Object ID

The rotation matrix R=[x    y    z]\mathbf{R} = [\mathbf{x} \; | \; \mathbf{y} \; | \; \mathbf{z}] defines the grasp frame where x is the approach direction, y is the grasp axis (from jaw to jaw), and z completes the right-handed frame. The gripper jaw endpoints are computed as:

g1=tw2y,g2=t+w2y\mathbf{g}_1 = \mathbf{t} - \frac{w}{2} \cdot \mathbf{y}, \quad \mathbf{g}_2 = \mathbf{t} + \frac{w}{2} \cdot \mathbf{y}

Phase 1: Cleaning the Data (NMS)

GraspNet-1B is fantastic, but it provides too many grasps. A single good grasp point might have hundreds of slightly varied orientations annotated around it. If we try to pair every single one of these, the computation time grows quadratically (O(N2)O(N^2)).

To solve this, I used Non-Maximum Suppression (NMS). We calculate a distance metric between grasps that combines both their translation (position) and rotation (orientation):

d(gi,gj)=titj2+αdrot(Ri,Rj)d(g_i, g_j) = \|\mathbf{t}_i - \mathbf{t}_j\|_2 + \alpha \cdot d_{rot}(\mathbf{R}_i, \mathbf{R}_j)

The rotational distance is computed using the geodesic distance on the rotation manifold:

drot(Ri,Rj)=arccos(tr(RiTRj)12)d_{rot}(\mathbf{R}_i, \mathbf{R}_j) = \arccos\left(\frac{\text{tr}(\mathbf{R}_i^T \mathbf{R}_j) - 1}{2}\right)

This gives us the angle of rotation needed to align the two grippers. With α=0.00025\alpha = 0.00025 as a weight factor, we balance translational and rotational components. If two grasps are physically too close (within 3cm) and oriented similarly (within 30° or π/6\pi/6 radians), we keep the one with the higher quality score and discard the other. This drastically reduces the search space while preserving grasp diversity.


Phase 2: The Pairing & The "Small Object" Problem

For an object with nn valid single-arm grasps, the number of possible dual-arm pairs is n(n1)2\frac{n(n-1)}{2}. For 500 grasps, that’s over 124,000 pairs to check.

This is where my implementation diverges from methods that focus on large objects. When grasping a small object (like a mug or a drill), the two grippers are dangerously close to each other. We need rigorous geometric pruning before we even think about physics.

I implemented three specific pruning criteria:

1. Center-to-Center Distance (dc2cd_{c2c}): This ensures grasps are sufficiently separated. The metric incorporates an axis alignment penalty:

dc2c(g1,g2)=t1t22+αdaxisd_{c2c}(g_1, g_2) = \|\mathbf{t}_1 - \mathbf{t}_2\|_2 + \alpha \cdot d_{axis}

where the axis distance penalizes parallel grasps:

daxis=2πarccos(y1y2)d_{axis} = \frac{2}{\pi} \arccos(|\mathbf{y}_1 \cdot \mathbf{y}_2|)

When y1y2=1|\mathbf{y}_1 \cdot \mathbf{y}_2| = 1 (parallel grasps), daxis=0d_{axis} = 0 and provides no penalty reduction. When y1y2=0|\mathbf{y}_1 \cdot \mathbf{y}_2| = 0 (perpendicular grasps), daxis=1d_{axis} = 1 and provides maximum penalty. This is crucial because parallel grasps cannot resist torques about their common axis—a fundamental limitation in achieving force closure.

2. Wrist-to-Wrist Distance (dw2wd_{w2w}): We project the gripper position backward along its approach vector to simulate the wrist/arm location:

w=tdapproachx\mathbf{w} = \mathbf{t} - d_{approach} \cdot \mathbf{x}

where dapproach=0.1d_{approach} = 0.1 m and x\mathbf{x} is the approach direction (first column of R\mathbf{R}). Then:

dw2w(g1,g2)=w1w22d_{w2w}(g_1, g_2) = \|\mathbf{w}_1 - \mathbf{w}_2\|_2

If the wrists are too close (< 0.1m), the robot arms will physically collide.

3. Threshold Selection: A pair is retained only if:

valid(g1,g2)=(dc2c>τc2c)(dw2w>τw2w)\text{valid}(g_1, g_2) = (d_{c2c} > \tau_{c2c}) \land (d_{w2w} > \tau_{w2w})

with primary thresholds τc2c=0.06\tau_{c2c} = 0.06 m and τw2w=0.1\tau_{w2w} = 0.1 m. If no pairs pass, we fall back to τc2c=0.045\tau_{c2c} = 0.045 m to ensure we get some candidates.

Distances

Phase 3: The Physics (Force Closure)

Once we have a geometrically valid pair, we have to answer the most important question: Will it stick?

This is determined by Force Closure—the ability of the grasp to resist arbitrary external wrenches (forces and torques).

Step A: Finding Contact Points

We can't assume the gripper touches the object exactly at the center. I use Signed Distance Functions (SDF) to trace a "line of action" from the gripper jaws.

For each gripper jaw, starting from the endpoint gi\mathbf{g}_i, the line extends along the grasp axis:

L1={g1+λy    λ[0,w]}\mathcal{L}_1 = \{\mathbf{g}_1 + \lambda \cdot \mathbf{y} \; | \; \lambda \in [0, w]\} L2={g2λy    λ[0,w]}\mathcal{L}_2 = \{\mathbf{g}_2 - \lambda \cdot \mathbf{y} \; | \; \lambda \in [0, w]\}

The SDF ϕ:R3R\phi: \mathbb{R}^3 \rightarrow \mathbb{R} encodes the distance to the object surface, where ϕ(p)<0\phi(\mathbf{p}) < 0 means the point is inside the object. Contact occurs at the first zero-crossing along the line:

c=argminpLpgs.t.ϕ(p)0\mathbf{c} = \arg\min_{\mathbf{p} \in \mathcal{L}} \|\mathbf{p} - \mathbf{g}\| \quad \text{s.t.} \quad \phi(\mathbf{p}) \leq 0

For a dual-arm grasp, we compute four contact points: c1,c2\mathbf{c}_1, \mathbf{c}_2 from gripper 1 and c3,c4\mathbf{c}_3, \mathbf{c}_4 from gripper 2.

Step A.5: Surface Normals and Grasp Maps

Once we have contact points, we need surface normals. The normal at a contact point is the normalized gradient of the SDF:

n=ϕ(c)ϕ(c)\mathbf{n} = \frac{\nabla \phi(\mathbf{c})}{\|\nabla \phi(\mathbf{c})\|}

Critical detail: The normals must point inward (toward the object interior) for the contact model to work correctly.

Now comes the grasp map construction. For each contact ii, I construct a contact frame Ti\mathbf{T}_i with rotation Ri=[t1    t2    ni]\mathbf{R}_i = [\mathbf{t}_1 \; | \; \mathbf{t}_2 \; | \; \mathbf{n}_i] where t1,t2\mathbf{t}_1, \mathbf{t}_2 are tangent vectors spanning the contact plane. The grasp map relates contact forces to object wrenches via the adjoint transformation:

Gi=AdTiBR6×3\mathbf{G}_i = \text{Ad}_{\mathbf{T}_i} \cdot \mathbf{B} \in \mathbb{R}^{6 \times 3}

where the adjoint is:

AdT=[R0[p]×RR]R6×6\text{Ad}_{\mathbf{T}} = \begin{bmatrix} \mathbf{R} & \mathbf{0} \\ [\mathbf{p}]_\times \mathbf{R} & \mathbf{R} \end{bmatrix} \in \mathbb{R}^{6 \times 6}

and [p]×[\mathbf{p}]_\times is the skew-symmetric cross-product matrix. For point contact with friction, the basis matrix is:

B=[I3×303×3]\mathbf{B} = \begin{bmatrix} \mathbf{I}_{3\times3} \\ \mathbf{0}_{3\times3} \end{bmatrix}

The combined grasp map for all four contacts is:

G=[G1    G2    G3    G4]R6×12\mathbf{G} = [\mathbf{G}_1 \; | \; \mathbf{G}_2 \; | \; \mathbf{G}_3 \; | \; \mathbf{G}_4] \in \mathbb{R}^{6 \times 12}

A necessary condition for force closure is rank(G)=6\text{rank}(\mathbf{G}) = 6. If this fails, we immediately reject the grasp pair.

Step B: The Optimization

For a dual-arm grasp, we have 4 contact points (2 per gripper). We need to determine if there exists a set of contact forces that can balance out gravity and external disturbances without slipping.

This is formulated as a Second-Order Cone Program (SOCP):

minf1,f2,f3,f4G1f1+G2f2+G3f3+G4f4+wext2subject to[fi,x,fi,y]T2μfi,z,i=1,2,3,4fi2fmax,i=1,2,3,4\begin{aligned} \min_{\mathbf{f}_1, \mathbf{f}_2, \mathbf{f}_3, \mathbf{f}_4} \quad & \|\mathbf{G}_1\mathbf{f}_1 + \mathbf{G}_2\mathbf{f}_2 + \mathbf{G}_3\mathbf{f}_3 + \mathbf{G}_4\mathbf{f}_4 + \mathbf{w}_{ext}\|_2 \\ \text{subject to} \quad & \|[f_{i,x}, f_{i,y}]^T\|_2 \leq \mu \cdot f_{i,z}, \quad i = 1,2,3,4 \\ & \|\mathbf{f}_i\|_2 \leq f_{max}, \quad i = 1,2,3,4 \end{aligned}

The friction cone constraints encode Coulomb friction: tangential forces (in the contact plane) must not exceed μ\mu times the normal force. These are second-order cone constraints—hence SOCP rather than standard linear programming.

The external wrench represents gravitational loading:

wext=[00mg000]\mathbf{w}_{ext} = \begin{bmatrix} 0 \\ 0 \\ -mg \\ 0 \\ 0 \\ 0 \end{bmatrix}

where I use m=10×m = 10 \times actual object mass to test robustness. I used a friction coefficient μ\mu of 0.3-0.4 (typical for rubber/plastic) and fmax=60f_{max} = 60 N.

A grasp achieves force closure if:

loss=Gf+wext2<ϵ\text{loss}^* = \|\mathbf{G}\mathbf{f}^* + \mathbf{w}_{ext}\|_2 < \epsilon

where ϵ=105\epsilon = 10^{-5} is my convergence threshold. The optimized forces f\mathbf{f}^* represent the contact forces in the contact frame, which I transform back to the object frame for visualization.


Results and Conclusion

The output of this pipeline is a set of verified dual-arm grasp configurations, scored by their ability to resist external forces.

By shifting the base data from DexNet to GraspNet-1B and implementing better collision detection, this generator allows us to create datasets for cluttered scenes containing small objects. This can be used toward training neural networks that can look at a messy table via a depth camera and decide how to use two hands to pick up an object safely.

References

  1. GraspNet-1Billion: Fang, H., et al. (CVPR 2020)
  2. DG16M: A Large-Scale Dual-Arm Grasp Dataset