This commit is contained in:
Kseninia Mikhaylova 2024-12-16 13:13:19 +03:00
parent b00e8d46b2
commit 410f22e5ba
3 changed files with 44 additions and 10 deletions

View File

@ -9,7 +9,7 @@ class PalletPacker:
self.pallet_height = pallet.get("y", 0.8) self.pallet_height = pallet.get("y", 0.8)
self.pallet_depth = pallet.get("z", 0.144) self.pallet_depth = pallet.get("z", 0.144)
gap = 0.2 gap = 0
self.box_width = box.get("x", 0.2) + gap self.box_width = box.get("x", 0.2) + gap
self.box_height = box.get("y", 0.2) + gap self.box_height = box.get("y", 0.2) + gap
self.box_depth = box.get("z", 0.2) self.box_depth = box.get("z", 0.2)

View File

@ -216,10 +216,18 @@ class SocketRobotArm:
pallet_position = self.urdf_manager.packing[ pallet_position = self.urdf_manager.packing[
counter % len(self.urdf_manager.packing) counter % len(self.urdf_manager.packing)
] ]
logger.info(counter) logger.info(f"pallete {pallet_position}")
logger.info(pallet_position)
base1_position = pallet_position[:]
base1_position[0] -= 0.2
base1_position[2] += 0.2
base_position = pallet_position[:] base_position = pallet_position[:]
base_position[2] += 1.0 base_position[0] -= 0.2
drop_position = pallet_position[:]
drop_position[0] -= 0.4
drop_position[2] += 0.4
json_res = [] json_res = []
tool_pos = [0, 0, 0] tool_pos = [0, 0, 0]
@ -228,14 +236,19 @@ class SocketRobotArm:
{"type": "move", "coordinates": near_position}, {"type": "move", "coordinates": near_position},
{"type": "move", "coordinates": object_position}, {"type": "move", "coordinates": object_position},
{"type": "create_constraint"}, {"type": "create_constraint"},
{"type": "move", "coordinates": base1_position},
{"type": "move", "coordinates": base_position},
{"type": "move", "coordinates": pallet_position}, {"type": "move", "coordinates": pallet_position},
{"type": "remove_constraint"}, {"type": "remove_constraint"},
{"type": "move", "coordinates": base_position}, {"type": "move", "coordinates": base_position},
{"type": "move", "coordinates": base1_position},
{"type": "move", "coordinates": drop_position},
] ]
constraint_id = None constraint_id = None
for step in steps: for step in steps:
if step["type"] == "move": if step["type"] == "move":
# logger.info(step["coordinates"])
jointPoses = self.convert_to_joint_base( jointPoses = self.convert_to_joint_base(
step["coordinates"], step["coordinates"],
np.radians(tool_pos), np.radians(tool_pos),
@ -246,7 +259,10 @@ class SocketRobotArm:
) )
) )
self.motionFund(jointPoses) self.motionFund(jointPoses)
# time.sleep(2)
if step["type"] == "create_constraint": if step["type"] == "create_constraint":
link_state = p.getLinkState(self.body_id, self.num_joints - 1)
orientation = link_state[1]
constraint_id = p.createConstraint( constraint_id = p.createConstraint(
parentBodyUniqueId=self.body_id, parentBodyUniqueId=self.body_id,
parentLinkIndex=self.num_joints - 1, parentLinkIndex=self.num_joints - 1,
@ -259,12 +275,18 @@ class SocketRobotArm:
parentFrameOrientation=p.getQuaternionFromEuler( parentFrameOrientation=p.getQuaternionFromEuler(
np.radians([0, 0, 90]) np.radians([0, 0, 90])
), ),
childFrameOrientation=p.getQuaternionFromEuler( childFrameOrientation=orientation,
np.radians([0, 0, 0])
),
) )
if step["type"] == "remove_constraint": if step["type"] == "remove_constraint":
time.sleep(0.5)
p.removeConstraint(constraint_id) p.removeConstraint(constraint_id)
# time.sleep(0.5)
# p.resetBasePositionAndOrientation(
# box_id,
# pallet_position,
# p.getQuaternionFromEuler(np.radians([0, 0, 0])),
# )
with open(f"data/palletizing.json", "w") as myfile: with open(f"data/palletizing.json", "w") as myfile:
myfile.write(json.dumps(json_res)) myfile.write(json.dumps(json_res))

View File

@ -99,10 +99,22 @@ class UrdfManager:
"z": self.box_size[2], "z": self.box_size[2],
}, },
).pack() ).pack()
logger.info(self.packing) self.packing = sorted(self.packing, key=lambda x: (x[0], x[1]))
for p in self.packing: for p in self.packing:
# logger.info(p)
for i in range(len(self.box_size)): for i in range(len(self.box_size)):
p[i] = (self.pallet_position[i] - self.pallet_size[i] * 0.5) + self.box_size[i] * 0.5 - p[i] p[i] = (
self.pallet_target[i]
- p[i]
- self.box_size[i] * 0.5
)
dir_wall = (self.conv_direction + 1) % (3 - 1)
p[dir_wall] -= self.box_size[dir_wall]
p[self.conv_direction] -= self.box_size[self.conv_direction] * 0.5
p[2] += self.pallet_size[2]
# logger.info(f"{self.packing[0]} {self.pallet_target}")
time.sleep(1) time.sleep(1)