Skip to content

Commit

Permalink
[MultiverseActions] merged new dev changes and fixed issues.
Browse files Browse the repository at this point in the history
  • Loading branch information
AbdelrhmanBassiouny committed Aug 21, 2024
1 parent 097ecb7 commit 1285227
Show file tree
Hide file tree
Showing 7 changed files with 16 additions and 16 deletions.
6 changes: 3 additions & 3 deletions src/pycram/world_concepts/world_object.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class Object(WorldEntity):
"""

def __init__(self, name: str, obj_type: ObjectType, path: str,
description: Type[ObjectDescription] = URDFObject,
description: Optional[ObjectDescription] = None,
pose: Optional[Pose] = None,
world: Optional[World] = None,
color: Color = Color(),
Expand Down Expand Up @@ -68,7 +68,7 @@ def __init__(self, name: str, obj_type: ObjectType, path: str,
self.path: Optional[str] = path
self.obj_type: ObjectType = obj_type
self.color: Color = color
self.description = description()
self.description = description if description is not None else URDFObject()
self.cache_manager = self.world.cache_manager

self.local_transformer = LocalTransformer()
Expand Down Expand Up @@ -1347,7 +1347,7 @@ def copy_to_world(self, world: World) -> Object:
:param world: The world to which the object should be copied.
:return: The copied object in the given world.
"""
obj = Object(self.name, self.obj_type, self.path, type(self.description), self.get_pose(),
obj = Object(self.name, self.obj_type, self.path, self.description, self.get_pose(),
world, self.color)
return obj

Expand Down
6 changes: 3 additions & 3 deletions src/pycram/worlds/bullet_world.py
Original file line number Diff line number Diff line change
Expand Up @@ -78,15 +78,15 @@ def load_generic_object_and_get_id(self, description: GenericObjectDescription)
"""
# Create visual shape
vis_shape = p.createVisualShape(p.GEOM_BOX, halfExtents=description.shape_data,
rgbaColor=description.color.get_rgba())
rgbaColor=description.color.get_rgba(), physicsClientId=self.id)

# Create collision shape
col_shape = p.createCollisionShape(p.GEOM_BOX, halfExtents=description.shape_data)
col_shape = p.createCollisionShape(p.GEOM_BOX, halfExtents=description.shape_data, physicsClientId=self.id)

# Create MultiBody with both visual and collision shapes
obj_id = p.createMultiBody(baseMass=1.0, baseCollisionShapeIndex=col_shape, baseVisualShapeIndex=vis_shape,
basePosition=description.origin.position_as_list(),
baseOrientation=description.origin.orientation_as_list())
baseOrientation=description.origin.orientation_as_list(), physicsClientId=self.id)

# Assuming you have a list to keep track of created objects
return obj_id
Expand Down
2 changes: 1 addition & 1 deletion test/bullet_world_testcase.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def setUpClass(cls):
RobotDescription.current_robot_description.name + cls.extension)
cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + cls.extension)
cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl",
ObjectDescription, pose=Pose([1.3, 0.7, 0.95]))
pose=Pose([1.3, 0.7, 0.95]))
ProcessModule.execution_delay = False
cls.viz_marker_publisher = VizMarkerPublisher()
OntologyManager(SOMA_ONTOLOGY_IRI)
Expand Down
3 changes: 1 addition & 2 deletions test/test_bullet_world.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,7 @@ def test_remove_object(self):
self.assertTrue(milk_id in [obj.id for obj in self.world.objects])
self.world.remove_object(self.milk)
self.assertTrue(milk_id not in [obj.id for obj in self.world.objects])
BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl",
ObjectDescription, pose=Pose([1.3, 1, 0.9]))
BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9]))

def test_remove_robot(self):
robot_id = self.robot.id
Expand Down
4 changes: 2 additions & 2 deletions test/test_failure_handling.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ class FailureHandlingTest(unittest.TestCase):
@classmethod
def setUpClass(cls):
cls.world = BulletWorld(WorldMode.DIRECT)
cls.robot = Object(RobotDescription.current_robot_description.name, ObjectType.ROBOT, RobotDescription.current_robot_description.name + extension,
ObjectDescription)
cls.robot = Object(RobotDescription.current_robot_description.name, ObjectType.ROBOT,
RobotDescription.current_robot_description.name + extension)
ProcessModule.execution_delay = True

def setUp(self):
Expand Down
5 changes: 3 additions & 2 deletions test/test_object.py
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,7 @@ def test_object_equal(self):
class GenericObjectTestCase(BulletWorldTestCase):

def test_init_generic_object(self):
gen_obj_desc = lambda: GenericObjectDescription("robokudo_object", [0,0,0], [0.1, 0.1, 0.1])
gen_obj_desc = GenericObjectDescription("robokudo_object", [0,0,0], [0.1, 0.1, 0.1])
obj = Object("robokudo_object", ObjectType.MILK, None, gen_obj_desc)
self.assertTrue(True)
pose = obj.get_pose()
self.assertTrue(isinstance(pose, Pose))
6 changes: 3 additions & 3 deletions test/test_robot_description.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from pycram.robot_description import RobotDescription, KinematicChainDescription, EndEffectorDescription, \
CameraDescription, RobotDescriptionManager
from pycram.datastructures.enums import Arms, GripperState
from pycram.object_descriptors.urdf import ObjectDescription as URDFObject
from pycram.object_descriptors.urdf import ObjectDescription as URDF


class TestRobotDescription(unittest.TestCase):
Expand All @@ -12,15 +12,15 @@ class TestRobotDescription(unittest.TestCase):
def setUpClass(cls):
cls.path = str(pathlib.Path(__file__).parent.resolve()) + '/../resources/robots/' + "pr2" + '.urdf'
cls.path_turtlebot = str(pathlib.Path(__file__).parent.resolve()) + '/../resources/robots/' + "turtlebot" + '.urdf'
cls.urdf_obj = URDFObject(cls.path)
cls.urdf_obj = URDF(cls.path)

def test_robot_description_construct(self):
robot_description = RobotDescription("pr2", "base_link", "torso_lift_link", "torso_lift_joint", self.path)
self.assertEqual(robot_description.name, "pr2")
self.assertEqual(robot_description.base_link, "base_link")
self.assertEqual(robot_description.torso_link, "torso_lift_link")
self.assertEqual(robot_description.torso_joint, "torso_lift_joint")
self.assertTrue(type(robot_description.urdf_object) is URDFObject)
self.assertTrue(type(robot_description.urdf_object) is URDF)
self.assertEqual(len(robot_description.links), 88)
self.assertEqual(len(robot_description.joints), 87)

Expand Down

0 comments on commit 1285227

Please sign in to comment.