Skip to content

Commit 32ec9b0

Browse files
frame system: document configuring physical properties through frame (#5033)
1 parent afb0703 commit 32ec9b0

4 files changed

Lines changed: 119 additions & 25 deletions

File tree

docs/hardware/common-components/add-a-gripper.md

Lines changed: 32 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -66,24 +66,52 @@ For a physical gripper, you'll typically configure the connection to the
6666
gripper controller. Check your module's documentation for the full list of
6767
attributes.
6868

69-
### 3. Configure a frame (recommended)
69+
### 3. Configure a frame
7070

71-
If you're using the gripper with an arm and motion planning, add a frame to
72-
define the gripper's position relative to the arm:
71+
For motion planning, the gripper must declare two things through its frame:
72+
the position of the tool center point (TCP) relative to the arm's tool flange,
73+
and the collision volume of the gripper body. The TCP is the point you want
74+
the planner to drive to. The motion service reads both from
75+
`frame.translation` and `frame.geometry`, not from `attributes`.
76+
77+
For a typical parallel-jaw gripper that bolts directly to the arm flange and
78+
projects 120 mm forward, with an 80 × 80 × 120 mm body:
7379

7480
```json
7581
{
7682
"frame": {
7783
"parent": "my-arm",
78-
"translation": { "x": 0, "y": 0, "z": 0 },
84+
"translation": { "x": 0, "y": 0, "z": 120 },
7985
"orientation": {
8086
"type": "ov_degrees",
8187
"value": { "x": 0, "y": 0, "z": 1, "th": 0 }
88+
},
89+
"geometry": {
90+
"type": "box",
91+
"x": 80,
92+
"y": 80,
93+
"z": 120,
94+
"translation": { "x": 0, "y": 0, "z": -60 }
8295
}
8396
}
8497
}
8598
```
8699

100+
Two things to notice in the JSON. `frame.translation.z: 120` puts the frame
101+
origin at the TCP, 120 mm out from the arm flange. `geometry.translation.z: -60`
102+
sits the box's center halfway back toward the flange, so the box covers the
103+
gripper body from the flange to the TCP. Measure `translation.z` to the point
104+
you want the planner to drive to: jaw tip for a finger gripper, suction cup
105+
face for a vacuum tool. If the gripper module ships its own kinematics (call
106+
`GetKinematics` to check), you can omit `geometry` because the kinematic model
107+
already carries the collision shape.
108+
109+
Symptoms of a wrong offset: motion plans validate, then the gripper tip lands
110+
short or long of the target, or the planner returns "outside workspace" for
111+
poses the arm can clearly reach. See
112+
[When the model has no physical-extent attribute](/motion-planning/frame-system/overview/#when-the-model-has-no-physical-extent-attribute)
113+
for the broader pattern.
114+
87115
### 4. Save and test
88116

89117
Click **Save**, then expand the **Test** section.

docs/motion-planning/frame-system/arm-gripper-camera.md

Lines changed: 15 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -101,44 +101,38 @@ In the sidebar, click your gripper component to open its card. On the card, clic
101101
#### Pick where the gripper frame origin sits
102102

103103
A point near the center of the gripper jaws is usually the most
104-
convenient frame origin. When you later call the motion service to move
105-
the gripper to a target pose, whatever point you pick here is what gets
106-
moved to that pose.
104+
convenient frame origin. The point you pick here is what `translation`
105+
measures _to_, and what gets moved to a target pose when you later call
106+
the motion service.
107107

108108
#### Configure the frame
109109

110110
In the JSON, set `parent` to your arm's component name, `translation` to
111-
the gripper frame origin's offset in mm from the arm's end effector, and
112-
`orientation` to the gripper's rotation relative to the arm.
111+
the offset in mm from the arm's end effector to the gripper frame
112+
origin, and `orientation` to the gripper's rotation relative to the arm.
113113

114-
If the gripper attaches directly to the arm's end effector with no
115-
adapter plate and no rotation, use a zero offset:
114+
For a parallel-jaw gripper that bolts directly to the arm's end effector
115+
with the frame origin at the jaw tip, the offset is the gripper's body
116+
length. 120 mm is typical:
116117

117118
```json
118119
{
119120
"parent": "my-arm",
120-
"translation": { "x": 0, "y": 0, "z": 0 },
121+
"translation": { "x": 0, "y": 0, "z": 120 },
121122
"orientation": {
122123
"type": "ov_degrees",
123124
"value": { "x": 0, "y": 0, "z": 1, "th": 0 }
124125
}
125126
}
126127
```
127128

128-
If the gripper is mounted through an adapter plate or flange that adds
129-
height, set the z translation to the adapter height in millimeters. For
130-
example, with a 50 mm adapter plate:
129+
If the gripper is mounted through an adapter plate or flange, add the
130+
plate height to `translation.z`. For a 50 mm plate plus the 120 mm
131+
gripper above, use `z: 170`.
131132

132-
```json
133-
{
134-
"parent": "my-arm",
135-
"translation": { "x": 0, "y": 0, "z": 50 },
136-
"orientation": {
137-
"type": "ov_degrees",
138-
"value": { "x": 0, "y": 0, "z": 1, "th": 0 }
139-
}
140-
}
141-
```
133+
A wrong `translation.z` produces silent failures: motion plans validate,
134+
then the physical gripper tip lands short or long of the target, or the
135+
planner returns "outside workspace" for poses the arm can clearly reach.
142136

143137
Click **Save**.
144138

docs/motion-planning/frame-system/overview.md

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -141,6 +141,28 @@ it relative to the frame.
141141
For detailed information about obstacle geometry, see
142142
[Define obstacles](/motion-planning/obstacles/).
143143

144+
### When the model has no physical-extent attribute
145+
146+
Many component models, including every `fake` model and some real ones, have an
147+
empty or near-empty `attributes` block. Their physical extent is not configured
148+
through attributes; it is configured through the frame.
149+
150+
- For a gripper that has no length attribute, set `frame.translation.z` to the
151+
offset from the arm's tool flange to the tool center point (TCP), and
152+
`frame.geometry` to the collision shape.
153+
- For a camera that has no mount-offset attribute, set `frame.translation` to
154+
the camera's position relative to its parent.
155+
- For an IMU that has no mounted-orientation attribute, set `frame.orientation`
156+
to its physical mounting rotation.
157+
158+
If you skip this step, the planner treats the component as a zero-volume point
159+
at the parent's origin. Motion plans validate, then the physical robot misses
160+
its target by the unconfigured offset, or reachability checks fail for poses
161+
the robot can clearly reach.
162+
163+
For a worked example with a gripper, see
164+
[Configure a frame for an arm, gripper, and camera](/motion-planning/frame-system/arm-gripper-camera/).
165+
144166
## Edit a frame in the Viam app
145167

146168
To configure a frame, open the **CONFIGURE** tab in the Viam app, click

docs/reference/components/gripper/fake.md

Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,4 +35,54 @@ Configure a `fake` gripper to test implementing a gripper on your machine withou
3535
No attributes are available for fake grippers.
3636
See [GitHub](https://github.com/viamrobotics/rdk/blob/main/components/gripper/fake/gripper.go) for API call return specifications.
3737

38+
## Configure physical properties through the frame
39+
40+
The `fake` gripper has no attribute for length or collision volume. The motion
41+
planner reads both from the component's `frame` field. Set `frame.translation.z`
42+
to the offset from the arm's tool flange to the tool center point (TCP) you
43+
want the planner to drive to, and `frame.geometry` to the collision shape.
44+
45+
For a typical 120 mm parallel-jaw gripper bolted directly to the arm flange:
46+
47+
```json
48+
{
49+
"name": "my-fake-gripper",
50+
"model": "fake",
51+
"api": "rdk:component:gripper",
52+
"attributes": {},
53+
"frame": {
54+
"parent": "my-arm",
55+
"translation": { "x": 0, "y": 0, "z": 120 },
56+
"orientation": {
57+
"type": "ov_degrees",
58+
"value": { "x": 0, "y": 0, "z": 1, "th": 0 }
59+
},
60+
"geometry": {
61+
"type": "box",
62+
"x": 80,
63+
"y": 80,
64+
"z": 120,
65+
"translation": { "x": 0, "y": 0, "z": -60 }
66+
}
67+
}
68+
}
69+
```
70+
71+
`frame.translation.z: 120` puts the frame origin at the TCP, 120 mm out from
72+
the arm flange. `geometry.translation.z: -60` sits the box's center halfway
73+
back toward the flange, so the box covers the gripper body from the flange to
74+
the TCP.
75+
76+
Why this matters: motion planning, reachability checks, and approach and
77+
retract poses all drive the TCP, not the tool flange, to a target pose. With
78+
no `frame`, the planner has no TCP defined and treats the gripper as a
79+
zero-volume point at the flange.
80+
81+
Symptoms if wrong: motion plans validate, then the physical gripper tip lands
82+
short or long of the target, or the planner returns "outside workspace" for
83+
poses the arm can clearly reach.
84+
85+
For the broader pattern and worked examples for cameras and IMUs, see
86+
[When the model has no physical-extent attribute](/motion-planning/frame-system/overview/#when-the-model-has-no-physical-extent-attribute).
87+
3888
{{< readfile "/static/include/components/test-control/gripper-control.md" >}}

0 commit comments

Comments
 (0)