Previous
Move a Gantry
You need to pick up an object from a workspace. This requires detecting the object with a camera, determining its 3D position, planning a collision-free approach path, and controlling the gripper to grasp it.
Use a vision service to detect the object in 2D, then transform its position to the world frame.
from viam.services.vision import VisionClient
from viam.proto.common import PoseInFrame, Pose
vision = VisionClient.from_robot(machine, "my-detector")
# Get detections from the camera
detections = await vision.get_detections_from_camera("my-camera")
if not detections:
print("No objects detected")
exit()
target = detections[0]
print(f"Detected: {target.class_name} ({target.confidence:.2f})")
# For 3D localization, use GetObjectPointClouds
objects = await vision.get_object_point_clouds("my-camera")
if objects:
obj = objects[0]
# The center of the first geometry is the object's position
# in the camera's reference frame
center = obj.geometries.geometries[0].center
obj_in_camera = PoseInFrame(
reference_frame="my-camera",
pose=Pose(x=center.x, y=center.y, z=center.z)
)
# Transform to world frame
obj_in_world = await machine.transform_pose(obj_in_camera, "world")
print(f"Object position in world: "
f"x={obj_in_world.pose.x:.1f}, "
f"y={obj_in_world.pose.y:.1f}, "
f"z={obj_in_world.pose.z:.1f}")
Move the arm to a position above the object (pre-grasp pose) before descending to grasp.
from viam.services.motion import MotionClient
motion_service = MotionClient.from_robot(machine, "builtin")
# Pre-grasp: 100mm above the object, end effector pointing down
pre_grasp = PoseInFrame(
reference_frame="world",
pose=Pose(
x=obj_in_world.pose.x,
y=obj_in_world.pose.y,
z=obj_in_world.pose.z + 100,
o_x=0, o_y=0, o_z=-1, theta=0
)
)
await motion_service.move(
component_name="my-arm",
destination=pre_grasp,
world_state=world_state
)
print("At pre-grasp position")
from viam.components.gripper import Gripper
gripper = Gripper.from_robot(machine, "my-gripper")
# Open gripper
await gripper.open()
# Descend to grasp position
grasp_pose = PoseInFrame(
reference_frame="world",
pose=Pose(
x=obj_in_world.pose.x,
y=obj_in_world.pose.y,
z=obj_in_world.pose.z,
o_x=0, o_y=0, o_z=-1, theta=0
)
)
await motion_service.move(
component_name="my-arm",
destination=grasp_pose,
world_state=world_state
)
print("At grasp position")
# Close gripper to grasp
grabbed = await gripper.grab()
if grabbed:
print("Object grasped")
else:
print("Grasp failed")
# Lift the object
lift_pose = PoseInFrame(
reference_frame="world",
pose=Pose(
x=obj_in_world.pose.x,
y=obj_in_world.pose.y,
z=obj_in_world.pose.z + 200,
o_x=0, o_y=0, o_z=-1, theta=0
)
)
await motion_service.move(
component_name="my-arm",
destination=lift_pose,
world_state=world_state
)
print("Object lifted")
CollisionSpecification constraints to allow the gripper to contact the
target object during the grasp phase.is_moving or force feedback
before proceeding.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!