Honeycomb Repacking
This example demonstrates how to use Tzara, the Telekinesis Physical AI Agent, to build a repackaging pipeline. Tzara generates code that picks parts from a regular rectangular source grid and places them into a staggered honeycomb destination grid, where alternating rows have different slot counts and an x-offset between them. The gripper uses a partial open width during picks to avoid disturbing tightly packed neighbours. Contributed by Arjun Vir Datta.
Demo
UR10e packing parts into a staggered honeycomb grid
The Natural Language Instruction
I want to do a repackaging task where the parts are placed in a rectangular grid
and need to be placed into another grid where there is a fixed offset on the x
axis and the y axis, and every other row is offset from the previous row.
The first row has n slots, second m, third n, etc. Every other row
is identical. When picking up the parts do not open the gripper all the way as the
parts are close together. Start and end the program at a home position.The Generated Code
python
# Telekinesis pipeline: UR10e + OnRobot RG6 honeycomb repackaging
# Picks from a regular rows x cols source grid and places into a staggered destination
# grid with alternating row slot counts (n, m, n, m, ...).
# Gripper uses partial open at source to avoid disturbing packed neighbours.
import numpy as np
from loguru import logger
from telekinesis.synapse.robots.manipulators.universal_robots import UniversalRobotsUR10E
from telekinesis.synapse.tools.parallel_grippers.onrobot import OnRobotRG6
ROBOT_IP = "192.168.1.2"
GRIPPER_IP = "192.168.1.1"
HOME_POSE = [0.00, 0.7800, 0.380, 180.0, 0.0, 90.0]
TOOL_RX, TOOL_RY, TOOL_RZ = 180.0, 0.0, 45.0
Z_APPROACH = 0.340
Z_PICK = 0.205
Z_PLACE = 0.220
SRC_ORIGIN_XY = (0.0310, 0.8540)
SRC_ROWS = 4
SRC_COLS = 6
SRC_DX = 0.048
SRC_DY = -0.048
DST_ORIGIN_XY = (-0.3710, 0.8620)
DST_N = 6
DST_M = 5
DST_DX = 0.0310
DST_DY = -0.0245
DST_STAGGER_X = DST_DX / 2.0
GRIP_OPEN_FULL_MM = 115.0
GRIP_OPEN_PARTIAL_MM = 55.0
GRIP_CLOSE_MM = 0.0
GRIP_FORCE_N = 40.0
MOVE_SPEED = 0.3
MOVE_ACCEL = 0.5
robot = UniversalRobotsUR10E()
robot.connect(ROBOT_IP)
gripper = OnRobotRG6()
gripper.connect(ip=GRIPPER_IP, protocol="MODBUS_TCP")
gripper.set_unit("position", "mm")
gripper.set_unit("force", "N")
def src_pose(r, c, z):
return [SRC_ORIGIN_XY[0] + c * SRC_DX, SRC_ORIGIN_XY[1] + r * SRC_DY, z, TOOL_RX, TOOL_RY, TOOL_RZ]
def dst_pose(flat_idx, z):
rem, row = flat_idx, 0
while True:
slots = DST_N if row % 2 == 0 else DST_M
if rem < slots:
break
rem -= slots
row += 1
x_off = 0.0 if row % 2 == 0 else DST_STAGGER_X
return [DST_ORIGIN_XY[0] + rem * DST_DX + x_off, DST_ORIGIN_XY[1] + row * DST_DY, z, TOOL_RX, TOOL_RY, TOOL_RZ]
def at_z(pose, z):
p = list(pose); p[2] = z; return p
try:
gripper.move(position=GRIP_OPEN_FULL_MM, force=GRIP_FORCE_N, asynchronous=False)
robot.set_cartesian_pose(HOME_POSE, speed=MOVE_SPEED, acceleration=MOVE_ACCEL)
flat_index = 0
for r in range(SRC_ROWS):
for c in range(SRC_COLS):
pick = src_pose(r, c, Z_PICK)
place = dst_pose(flat_index, Z_PLACE)
logger.info(f"[{flat_index}] pick src(r={r},c={c}) -> dst flat={flat_index}")
gripper.move(position=GRIP_OPEN_PARTIAL_MM, force=GRIP_FORCE_N, asynchronous=False)
robot.set_cartesian_pose(at_z(pick, Z_APPROACH), speed=MOVE_SPEED, acceleration=MOVE_ACCEL)
robot.set_cartesian_pose(pick, speed=MOVE_SPEED, acceleration=MOVE_ACCEL)
gripper.move(position=GRIP_CLOSE_MM, force=GRIP_FORCE_N, asynchronous=False)
robot.set_cartesian_pose(at_z(pick, Z_APPROACH), speed=MOVE_SPEED, acceleration=MOVE_ACCEL)
robot.set_cartesian_pose(at_z(place, Z_APPROACH), speed=MOVE_SPEED, acceleration=MOVE_ACCEL)
robot.set_cartesian_pose(place, speed=MOVE_SPEED, acceleration=MOVE_ACCEL)
gripper.move(position=GRIP_OPEN_FULL_MM, force=GRIP_FORCE_N, asynchronous=False)
robot.set_cartesian_pose(at_z(place, Z_APPROACH), speed=MOVE_SPEED, acceleration=MOVE_ACCEL)
logger.success(f"[{flat_index}] placed")
flat_index += 1
robot.set_cartesian_pose(HOME_POSE, speed=MOVE_SPEED, acceleration=MOVE_ACCEL)
finally:
try:
gripper.disconnect()
except Exception as e:
logger.warning(f"Gripper disconnect failed: {e}")
try:
robot.disconnect()
except Exception as e:
logger.warning(f"Robot disconnect failed: {e}")
