Quickstart: configure a frame system
You will configure three components with a parent-child frame hierarchy (a table-mounted UR5e arm, a gripper attached to its end effector, and a wrist-mounted camera) and verify the hierarchy two ways: by printing each component’s world-frame pose, and by transforming a detected object from the camera frame into the world frame.
Everything runs on fake components. When you later replace any of them with real hardware, the frame configuration and the verification code stay the same.
Expected time: about 15 minutes.
What you will end up with
world
├── my-arm (table-mounted, at world origin)
│ ├── my-gripper (attached to arm end effector)
│ └── my-camera (mounted on arm near gripper)
1. Add the arm
In the Viam app, go to your machine’s CONFIGURE tab.
- Click + and add an arm component.
- Choose the fake model.
- Name it my-arm.
- In the arm’s attributes, set
arm-modelto"ur5e". - Click Frame on the arm’s card. The Frame section opens a JSON editor (there is no form, parent dropdown, or geometry-type picker). Edit the JSON so the frame sits at the world origin:
{
"parent": "world",
"translation": { "x": 0, "y": 0, "z": 0 },
"orientation": {
"type": "ov_degrees",
"value": { "x": 0, "y": 0, "z": 1, "th": 0 }
}
}
Click Save in the top-right of the page (or press ⌘/Ctrl+S).
2. Add the gripper
- Click + and add a gripper component.
- Choose the fake model.
- Name it my-gripper.
- Click Frame on the gripper’s card. Edit the JSON so the parent is the arm and the origin is offset 110 mm along the arm’s z axis (the end of a typical gripper mount):
{
"parent": "my-arm",
"translation": { "x": 0, "y": 0, "z": 110 },
"orientation": {
"type": "ov_degrees",
"value": { "x": 0, "y": 0, "z": 1, "th": 0 }
}
}
Click Save. Because the gripper’s parent is the arm, its world pose moves with the arm automatically.
3. Add the camera
- Click + and add a camera component.
- Choose the fake model.
- Name it my-camera.
- Click Frame on the camera’s card. Edit the JSON so the camera sits 30 mm to the side of the arm’s end effector and 60 mm above it, tilted 30 degrees downward about the x axis:
{
"parent": "my-arm",
"translation": { "x": 0, "y": 30, "z": 60 },
"orientation": {
"type": "ov_degrees",
"value": { "x": 1, "y": 0, "z": 0, "th": -30 }
}
}
Click Save.
4. Verify with the CLI
Before writing any code, confirm the configuration parsed correctly:
viam machines part motion print-config --part "YOUR-PART-NAME"
You should see my-arm, my-gripper, and my-camera in the output
with the translations and orientations you just configured.
Now print the live world poses:
viam machines part motion print-status --part "YOUR-PART-NAME"
You should see something like:
my-arm : X: 0.00 Y: 0.00 Z: 0.00 OX: 0.00 OY: 0.00 OZ: 1.00 Theta: 0.00
my-gripper : X: 0.00 Y: 0.00 Z: 110.00 OX: 0.00 OY: 0.00 OZ: 1.00 Theta: 0.00
my-camera : X: 0.00 Y: 30.00 Z: 60.00 OX: ...
The gripper sits 110 mm above the arm origin. The camera sits 30 mm to the side and 60 mm above, with the downward tilt reflected in the orientation vector.
5. Transform a detected object to the world frame
Imagine the camera detects an object 200 mm in front of it. You want to know where that object is in world coordinates so the arm can reach for it.
import asyncio
from viam.robot.client import RobotClient
from viam.proto.common import PoseInFrame, Pose
async def connect():
opts = RobotClient.Options.with_api_key(
api_key="YOUR-API-KEY",
api_key_id="YOUR-API-KEY-ID",
)
return await RobotClient.at_address("YOUR-MACHINE-ADDRESS", opts)
async def main():
async with await connect() as machine:
# The camera reports the object at (0, 0, 200) in its own frame:
# 200 mm straight ahead along the camera's z axis.
detected = PoseInFrame(
reference_frame="my-camera",
pose=Pose(x=0, y=0, z=200),
)
# Transform to the world frame.
in_world = await machine.transform_pose(detected, "world")
print(
f"object in world: "
f"x={in_world.pose.x:.1f} "
f"y={in_world.pose.y:.1f} "
f"z={in_world.pose.z:.1f}"
)
if __name__ == "__main__":
asyncio.run(main())
Run it. The output shows the object’s world-frame coordinates, computed from the camera’s frame configuration including its translation, downward tilt, and the arm’s current pose.
6. Move the arm and watch the camera frame follow
Change the arm’s joint configuration (through the CONTROL tab or
by calling move_to_joint_positions), then re-run print-status.
You will see my-camera and my-gripper poses change while
my-arm stays at the world origin. That is the parent-child
propagation in action: the camera and gripper frames are fixed
relative to the arm, so they move wherever the arm moves.
What you learned
- Frames form a tree rooted at
world. - Each component’s frame config specifies a parent, a translation in mm, and an orientation.
- Child frames move with their parents automatically.
TransformPoseconverts between any two frames using the current configured tree and live component state.
Where to next
- Allow specific frames to collide: required when the wrist camera sees the arm it is mounted on.
- Move your first arm: if you have not already; now you can give the motion service a pose in the camera frame and have it reach that point.
- Frame system: the concept page with more detail on hierarchy, orientation formats, and geometry.
- Frame system API: the full method list for pose queries and transforms.
Was this page helpful?
Glad to hear it! If you have any other feedback please let us know:
We're sorry about that. To help us improve, please tell us what we can do better:
Thank you!