This commit is contained in:
Kseninia Mikhaylova 2024-12-13 16:27:27 +03:00
parent fbd148ed31
commit b82ebbd9fb
3 changed files with 43 additions and 17 deletions

View File

@ -39,11 +39,11 @@ class ConveyorBelt:
def create_conveyor(self, size, position):
collision_shape_id = p.createCollisionShape(
shapeType=p.GEOM_BOX,
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0],
halfExtents=[size[i] / 2.0 for i in range(3)],
)
visual_shape_id = p.createVisualShape(
shapeType=p.GEOM_BOX,
halfExtents=[size[0] / 2.0, size[1] / 2.0, size[2] / 2.0],
halfExtents=[size[i] / 2.0 for i in range(3)],
rgbaColor=[0.5, 0.5, 0.5, 1],
)
conveyor_id = p.createMultiBody(
@ -75,19 +75,11 @@ class ConveyorBelt:
def create_box(self, position):
collision_shape_id = p.createCollisionShape(
shapeType=p.GEOM_BOX,
halfExtents=[
self.box_size[0] / 2.0,
self.box_size[1] / 2.0,
self.box_size[2] / 2.0,
],
halfExtents=[self.box_size[i] / 2.0 for i in range(3)],
)
visual_shape_id = p.createVisualShape(
shapeType=p.GEOM_BOX,
halfExtents=[
self.box_size[0] / 2.0,
self.box_size[1] / 2.0,
self.box_size[2] / 2.0,
],
halfExtents=[self.box_size[i] / 2.0 for i in range(3)],
rgbaColor=[1, 0, 0, 1],
)
box_id = p.createMultiBody(

37
robot/pallet.py Normal file
View File

@ -0,0 +1,37 @@
import pybullet as p
class Pallet:
def __init__(
self, target=[1, 1, 0], size=[0.8, 1.2, 0.144], color=[0.6, 0.3, 0.1, 0.5]
):
self.size = size
self.position = [
(target[i] - self.size[i] * 0.5)
for i in range(len(target))
]
self.color = color
self.create_pallet()
def create_pallet(self):
half_size = [s * 0.5 for s in self.size]
# Создаем collision shape для паллеты
collision_shape = p.createCollisionShape(p.GEOM_BOX, halfExtents=half_size)
# Создаем визуальное отображение (shape) для паллеты
visual_shape = p.createVisualShape(
p.GEOM_BOX, halfExtents=half_size, rgbaColor=self.color
)
# Создаем объект паллеты в физическом мире
self.pallet_id = p.createMultiBody(
baseMass=0, # Масса 0, чтобы паллета не взаимодействовала с физикой
baseCollisionShapeIndex=collision_shape,
baseVisualShapeIndex=visual_shape,
basePosition=self.position,
)
# Устанавливаем позицию объекта паллеты в физическом мире
p.resetBasePositionAndOrientation(self.pallet_id, self.position, [0, 0, 0, 1])

View File

@ -7,6 +7,7 @@ import pybullet as p
from logger import logger
from robot.conveyor import ConveyorBelt
from robot.pallet import Pallet
class UrdfManager:
@ -48,11 +49,7 @@ class UrdfManager:
def load_palletizing(self):
# p.resetSimulation()
pallet_position = [1.5, -1.5, 0.1]
urdf_path_pallet = os.path.join(
self.application_path, "urdf", "europallet.urdf"
)
self.pallet_id = p.loadURDF(urdf_path_pallet, pallet_position)
self.pallet_id = Pallet([1.5, 0.5, 0.1])
# положение дальнего угла
self.conv_target = [1.35, -0.75, 0.5]