From 44bf3a2639109ed6b2194bdea7bee373f2aef29c Mon Sep 17 00:00:00 2001 From: Kseninia Mikhaylova Date: Thu, 12 Dec 2024 12:32:45 +0300 Subject: [PATCH] load pallete pos --- robot/urdf_manager.py | 40 +++++++++++----------------------------- 1 file changed, 11 insertions(+), 29 deletions(-) diff --git a/robot/urdf_manager.py b/robot/urdf_manager.py index ab83f7a..572d8f7 100644 --- a/robot/urdf_manager.py +++ b/robot/urdf_manager.py @@ -41,42 +41,24 @@ class UrdfManager: self.body_id = p.loadURDF( urdf_path, self.robot_start_position, - useFixedBase=True + useFixedBase=True, ) p.setGravity(0, 0, -9.81, physicsClientId=self.physics_client) def load_palletizing(self): - # Путь к URDF модели палеты + pallet_position = [1.5, -1, 0.1] urdf_path_pallet = os.path.join( - self.application_path, - "urdf", - "europallet.urdf", # Убедитесь, что имя файла соответствует + self.application_path, "urdf", "europallet.urdf" ) + self.pallet_id = p.loadURDF(urdf_path_pallet, pallet_position) - # Загрузка палеты рядом с роботом - # Предположим, что вы хотите расположить палету на расстоянии от робота - pallet_offset_x = 1.5 # Расстояние в метрах по оси X - pallet_offset_y = 0.0 # Расстояние по оси Y - pallet_height = 0.145 # Высота палеты (подгонка под высоту робота) - - pallet_position = [ - self.robot_start_position[0] + pallet_offset_x, - self.robot_start_position[1] + pallet_offset_y, - pallet_height - / 2.0, # Разместите палету выше, чтобы она не находилась на земле - ] - pallet_orientation = p.getQuaternionFromEuler([0, 0, np.deg2rad(90)]) - # self.pallet_id = p.loadURDF( - # urdf_path_pallet, pallet_position, pallet_orientation, useFixedBase=True - # ) - - conveyor_size = [3.0, 0.5, 0.1] - conveyor_position = [0.5, 1.5, 0.5] - box_size = [0.2, 0.2, 0.2] - box_spacing = 0.2 - box_speed = 0.1 # Скорость движения коробок - - ConveyorBelt(conveyor_size, conveyor_position, box_size, box_spacing, box_speed) + ConveyorBelt( + [3.0, 0.5, 0.1], + [-1.5, -1, 0.5], + [0.2, 0.2, 0.2], + 0.2, + 0.1, + ) time.sleep(1)