palletizing btn
This commit is contained in:
parent
4f1f7bfa16
commit
886a9d0e5a
16
gui/init.py
16
gui/init.py
|
@ -9,6 +9,7 @@ from gui.informer import Informer
|
||||||
from gui.imitator import Imitator
|
from gui.imitator import Imitator
|
||||||
from gui.command import Command
|
from gui.command import Command
|
||||||
from gui.visualize import Visualize
|
from gui.visualize import Visualize
|
||||||
|
from gui.palletizing import Palletizing
|
||||||
from gui.observable import Observable
|
from gui.observable import Observable
|
||||||
from logger import logger
|
from logger import logger
|
||||||
|
|
||||||
|
@ -56,15 +57,19 @@ class MainContentComponent(QWidget):
|
||||||
|
|
||||||
commandArgs = kwargs.get("commandPanel", {})
|
commandArgs = kwargs.get("commandPanel", {})
|
||||||
self.commandPanel = Command(**commandArgs)
|
self.commandPanel = Command(**commandArgs)
|
||||||
|
|
||||||
|
palletizingArgs = kwargs.get("palletizingPanel", {})
|
||||||
|
self.palletizingPanel = Palletizing(**palletizingArgs)
|
||||||
|
|
||||||
self.rightPanel = MyPanel(
|
self.rightPanel = MyPanel(
|
||||||
panels=[
|
panels=[
|
||||||
self.statusPanel,
|
# self.statusPanel,
|
||||||
self.robotPanel,
|
self.robotPanel,
|
||||||
self.informerPanel,
|
self.informerPanel,
|
||||||
self.filenamePanel,
|
# self.filenamePanel,
|
||||||
self.imitatorPanel,
|
# self.imitatorPanel,
|
||||||
self.commandPanel,
|
# self.commandPanel,
|
||||||
|
self.palletizingPanel,
|
||||||
],
|
],
|
||||||
color=(169, 169, 169),
|
color=(169, 169, 169),
|
||||||
)
|
)
|
||||||
|
@ -102,7 +107,8 @@ class MainContentComponent(QWidget):
|
||||||
self.informerPanel,
|
self.informerPanel,
|
||||||
self.filenamePanel,
|
self.filenamePanel,
|
||||||
self.imitatorPanel,
|
self.imitatorPanel,
|
||||||
self.commandPanel
|
self.commandPanel,
|
||||||
|
self.palletizingPanel,
|
||||||
]
|
]
|
||||||
for p in panels:
|
for p in panels:
|
||||||
if new_value == "not_connected":
|
if new_value == "not_connected":
|
||||||
|
|
|
@ -0,0 +1,33 @@
|
||||||
|
from PyQt6.QtWidgets import QWidget, QVBoxLayout, QPushButton, QLabel
|
||||||
|
from PyQt6.QtCore import Qt, QTimer
|
||||||
|
|
||||||
|
from logger import logger
|
||||||
|
|
||||||
|
|
||||||
|
class Palletizing(QWidget):
|
||||||
|
def __init__(self, load_palletizing):
|
||||||
|
super().__init__()
|
||||||
|
self.load_palletizing = load_palletizing
|
||||||
|
self.initUI()
|
||||||
|
|
||||||
|
def initUI(self):
|
||||||
|
self.layout = QVBoxLayout()
|
||||||
|
|
||||||
|
self.robotsLabel = QLabel("Паллетирование")
|
||||||
|
self.layout.addWidget(self.robotsLabel)
|
||||||
|
|
||||||
|
self.palletButton = QPushButton("Визуализировать")
|
||||||
|
self.palletButton.clicked.connect(self.startPalletzing)
|
||||||
|
self.layout.addWidget(self.palletButton)
|
||||||
|
|
||||||
|
self.setLayout(self.layout)
|
||||||
|
|
||||||
|
def startPalletzing(self):
|
||||||
|
logger.info("start palletizing")
|
||||||
|
self.load_palletizing()
|
||||||
|
|
||||||
|
def paintEvent(self, event):
|
||||||
|
p = self.palette()
|
||||||
|
p.setColor(self.backgroundRole(), Qt.GlobalColor.lightGray)
|
||||||
|
self.setPalette(p)
|
||||||
|
super().paintEvent(event)
|
7
main.py
7
main.py
|
@ -71,6 +71,9 @@ class MyApp:
|
||||||
"getFilename": self.get_filename,
|
"getFilename": self.get_filename,
|
||||||
"setFilename": self.set_filename,
|
"setFilename": self.set_filename,
|
||||||
},
|
},
|
||||||
|
palletizingPanel={
|
||||||
|
"load_palletizing": self.load_palletizing,
|
||||||
|
},
|
||||||
)
|
)
|
||||||
mainWindow.setWindowTitle("ROBOT GUI")
|
mainWindow.setWindowTitle("ROBOT GUI")
|
||||||
self.window = mainWindow
|
self.window = mainWindow
|
||||||
|
@ -175,6 +178,10 @@ class MyApp:
|
||||||
def set_filename(self, filename):
|
def set_filename(self, filename):
|
||||||
self.robot_app.filename = filename
|
self.robot_app.filename = filename
|
||||||
|
|
||||||
|
@check_robot_app
|
||||||
|
def load_palletizing(self):
|
||||||
|
return self.robot_app.load_palletizing()
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
parser = argparse.ArgumentParser(description="MyApp Command Line Interface")
|
parser = argparse.ArgumentParser(description="MyApp Command Line Interface")
|
||||||
|
|
|
@ -71,6 +71,9 @@ class SocketRobotArm:
|
||||||
def load_models(self):
|
def load_models(self):
|
||||||
self.urdf_manager.load_models()
|
self.urdf_manager.load_models()
|
||||||
self.body_id = self.urdf_manager.body_id
|
self.body_id = self.urdf_manager.body_id
|
||||||
|
|
||||||
|
def load_palletizing(self):
|
||||||
|
self.urdf_manager.load_palletizing()
|
||||||
|
|
||||||
def get_pybullet_image(self):
|
def get_pybullet_image(self):
|
||||||
return self.urdf_manager.get_pybullet_image()
|
return self.urdf_manager.get_pybullet_image()
|
||||||
|
|
|
@ -34,19 +34,23 @@ class UrdfManager:
|
||||||
def run_pybullet(self, type="DIRECT"):
|
def run_pybullet(self, type="DIRECT"):
|
||||||
self.physics_client = p.connect(getattr(p, type))
|
self.physics_client = p.connect(getattr(p, type))
|
||||||
logger.info(f"Connect to {self.physics_client} by {type}")
|
logger.info(f"Connect to {self.physics_client} by {type}")
|
||||||
|
|
||||||
def create_cube(self, size, position):
|
def create_cube(self, size, position):
|
||||||
# Создание формы коллизии для куба
|
# Создание формы коллизии для куба
|
||||||
collision_shape_id = p.createCollisionShape(
|
collision_shape_id = p.createCollisionShape(
|
||||||
shapeType=p.GEOM_BOX,
|
shapeType=p.GEOM_BOX,
|
||||||
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0] # halfExtents задаются радиусами по осям x, y и z
|
halfExtents=[
|
||||||
|
size[0] / 2.0,
|
||||||
|
size[1] / 2.0,
|
||||||
|
size[2] / 2.0,
|
||||||
|
], # halfExtents задаются радиусами по осям x, y и z
|
||||||
)
|
)
|
||||||
|
|
||||||
# Создание визуальной формы для куба
|
# Создание визуальной формы для куба
|
||||||
visual_shape_id = p.createVisualShape(
|
visual_shape_id = p.createVisualShape(
|
||||||
shapeType=p.GEOM_BOX,
|
shapeType=p.GEOM_BOX,
|
||||||
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0],
|
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0],
|
||||||
rgbaColor=[0, 0, 1, 1] # Синий цвет
|
rgbaColor=[0, 0, 1, 1], # Синий цвет
|
||||||
)
|
)
|
||||||
|
|
||||||
# Создание многосоставного тела с формой коллизии и визуальной формой
|
# Создание многосоставного тела с формой коллизии и визуальной формой
|
||||||
|
@ -54,21 +58,21 @@ class UrdfManager:
|
||||||
baseMass=1.0, # Масса тела
|
baseMass=1.0, # Масса тела
|
||||||
baseCollisionShapeIndex=collision_shape_id,
|
baseCollisionShapeIndex=collision_shape_id,
|
||||||
baseVisualShapeIndex=visual_shape_id,
|
baseVisualShapeIndex=visual_shape_id,
|
||||||
basePosition=position
|
basePosition=position,
|
||||||
)
|
)
|
||||||
|
|
||||||
return body_id
|
return body_id
|
||||||
|
|
||||||
def create_conveyor(self, size, position):
|
def create_conveyor(self, size, position):
|
||||||
collision_shape_id = p.createCollisionShape(
|
collision_shape_id = p.createCollisionShape(
|
||||||
shapeType=p.GEOM_BOX,
|
shapeType=p.GEOM_BOX,
|
||||||
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0]
|
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0],
|
||||||
)
|
)
|
||||||
# Создание визуальной формы для конвейера
|
# Создание визуальной формы для конвейера
|
||||||
visual_shape_id = p.createVisualShape(
|
visual_shape_id = p.createVisualShape(
|
||||||
shapeType=p.GEOM_BOX,
|
shapeType=p.GEOM_BOX,
|
||||||
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0],
|
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0],
|
||||||
rgbaColor=[0.5, 0.5, 0.5, 1] # Серый цвет для конвейера
|
rgbaColor=[0.5, 0.5, 0.5, 1], # Серый цвет для конвейера
|
||||||
)
|
)
|
||||||
|
|
||||||
# Создание тела для конвейера (можно без массы, если оно не должно взаимодействовать с другими объектами)
|
# Создание тела для конвейера (можно без массы, если оно не должно взаимодействовать с другими объектами)
|
||||||
|
@ -76,7 +80,7 @@ class UrdfManager:
|
||||||
baseMass=0.0, # Это статичный объект, поэтому масса 0
|
baseMass=0.0, # Это статичный объект, поэтому масса 0
|
||||||
baseCollisionShapeIndex=collision_shape_id,
|
baseCollisionShapeIndex=collision_shape_id,
|
||||||
baseVisualShapeIndex=visual_shape_id,
|
baseVisualShapeIndex=visual_shape_id,
|
||||||
basePosition=position
|
basePosition=position,
|
||||||
)
|
)
|
||||||
|
|
||||||
return conveyor_id
|
return conveyor_id
|
||||||
|
@ -90,28 +94,32 @@ class UrdfManager:
|
||||||
self.body_id = p.loadURDF(
|
self.body_id = p.loadURDF(
|
||||||
urdf_path, self.robot_start_position, useFixedBase=True
|
urdf_path, self.robot_start_position, useFixedBase=True
|
||||||
)
|
)
|
||||||
|
|
||||||
|
def load_palletizing(self):
|
||||||
# Путь к URDF модели палеты
|
# Путь к URDF модели палеты
|
||||||
urdf_path_pallet = os.path.join(
|
urdf_path_pallet = os.path.join(
|
||||||
self.application_path, "urdf", "europallet.urdf" # Убедитесь, что имя файла соответствует
|
self.application_path,
|
||||||
|
"urdf",
|
||||||
|
"europallet.urdf", # Убедитесь, что имя файла соответствует
|
||||||
)
|
)
|
||||||
|
|
||||||
# Загрузка палеты рядом с роботом
|
# Загрузка палеты рядом с роботом
|
||||||
# Предположим, что вы хотите расположить палету на расстоянии от робота
|
# Предположим, что вы хотите расположить палету на расстоянии от робота
|
||||||
pallet_offset_x = 1.5 # Расстояние в метрах по оси X
|
pallet_offset_x = 1.5 # Расстояние в метрах по оси X
|
||||||
pallet_offset_y = 0.0 # Расстояние по оси Y
|
pallet_offset_y = 0.0 # Расстояние по оси Y
|
||||||
pallet_height = 0.145 # Высота палеты (подгонка под высоту робота)
|
pallet_height = 0.145 # Высота палеты (подгонка под высоту робота)
|
||||||
|
|
||||||
pallet_position = [
|
pallet_position = [
|
||||||
self.robot_start_position[0] + pallet_offset_x,
|
self.robot_start_position[0] + pallet_offset_x,
|
||||||
self.robot_start_position[1] + pallet_offset_y,
|
self.robot_start_position[1] + pallet_offset_y,
|
||||||
pallet_height / 2.0 # Разместите палету выше, чтобы она не находилась на земле
|
pallet_height
|
||||||
|
/ 2.0, # Разместите палету выше, чтобы она не находилась на земле
|
||||||
]
|
]
|
||||||
pallet_orientation = p.getQuaternionFromEuler([0, 0, np.deg2rad(90)])
|
pallet_orientation = p.getQuaternionFromEuler([0, 0, np.deg2rad(90)])
|
||||||
self.pallet_id = p.loadURDF(
|
self.pallet_id = p.loadURDF(
|
||||||
urdf_path_pallet, pallet_position, pallet_orientation, useFixedBase=True
|
urdf_path_pallet, pallet_position, pallet_orientation, useFixedBase=True
|
||||||
)
|
)
|
||||||
|
|
||||||
# Создание коробок на палете
|
# Создание коробок на палете
|
||||||
box_size = [0.2, 0.2, 0.2] # Размеры коробки: [ширина, высота, глубина]
|
box_size = [0.2, 0.2, 0.2] # Размеры коробки: [ширина, высота, глубина]
|
||||||
boxes_per_row = 3
|
boxes_per_row = 3
|
||||||
|
@ -124,19 +132,27 @@ class UrdfManager:
|
||||||
box_z_position = pallet_height + (box_size[2] / 2)
|
box_z_position = pallet_height + (box_size[2] / 2)
|
||||||
|
|
||||||
box_position = [
|
box_position = [
|
||||||
pallet_position[0] + box_x_offset - (boxes_per_row * (box_size[0] + 0.05) / 2),
|
pallet_position[0]
|
||||||
pallet_position[1] + box_y_offset - (boxes_per_column * (box_size[1] + 0.05) / 2),
|
+ box_x_offset
|
||||||
box_z_position
|
- (boxes_per_row * (box_size[0] + 0.05) / 2),
|
||||||
|
pallet_position[1]
|
||||||
|
+ box_y_offset
|
||||||
|
- (boxes_per_column * (box_size[1] + 0.05) / 2),
|
||||||
|
box_z_position,
|
||||||
]
|
]
|
||||||
|
|
||||||
# Создаем кубик
|
# Создаем кубик
|
||||||
self.create_cube(box_size, box_position)
|
self.create_cube(box_size, box_position)
|
||||||
|
|
||||||
# Создание конвейера
|
# Создание конвейера
|
||||||
conveyor_size = [3.0, 0.5, 0.1] # Длина, ширина и высота
|
conveyor_size = [3.0, 0.5, 0.1] # Длина, ширина и высота
|
||||||
conveyor_position = [0.5, 1.5, 0.5] # Позиция в пространстве (выше уровня земли)
|
conveyor_position = [
|
||||||
|
0.5,
|
||||||
|
1.5,
|
||||||
|
0.5,
|
||||||
|
] # Позиция в пространстве (выше уровня земли)
|
||||||
self.conveyor_id = self.create_conveyor(conveyor_size, conveyor_position)
|
self.conveyor_id = self.create_conveyor(conveyor_size, conveyor_position)
|
||||||
|
|
||||||
time.sleep(1)
|
time.sleep(1)
|
||||||
|
|
||||||
def get_pybullet_image(self):
|
def get_pybullet_image(self):
|
||||||
|
|
Loading…
Reference in New Issue