Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Object dynamic state #234

Merged
merged 49 commits into from
Jan 16, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
49 commits
Select commit Hold shift + click to select a range
c23e502
[SaveWorldState] Corrected the save state functionality and added the…
mohammadkhoshnazarr Oct 10, 2024
b712e8a
[SaveState] Corrected arguments order in save simulator state.
AbdelrhmanBassiouny Oct 11, 2024
75723b3
[MultiverseContact] (WIP) Adding support for multiple contact points.
AbdelrhmanBassiouny Oct 15, 2024
1cb23fb
[MultiverseContact] Multiple contact points with normals now working.
AbdelrhmanBassiouny Oct 16, 2024
8a67ac7
[euROBIN] Added ur5e description and a demo for using it in eurobin.
AbdelrhmanBassiouny Oct 17, 2024
e25d055
[euROBIN] new process_module for gripper, accept grippers as separate…
AbdelrhmanBassiouny Oct 18, 2024
86b714c
[GiskardandRobokudo] Ignore virtual joints when setting joint goal in…
AbdelrhmanBassiouny Nov 5, 2024
8de923d
[MultiverseFallschoolDemo] (WIP) Need to figure out why giskard state…
AbdelrhmanBassiouny Nov 7, 2024
2adf2ba
[MultiverseFallschoolDemo] (WIP) Need to fix multiverse contact, and …
AbdelrhmanBassiouny Nov 8, 2024
217e174
[NavigateAction] Add an option that asks if the joint states should b…
AbdelrhmanBassiouny Nov 11, 2024
aea9593
[ActionDesignator] better prepose and approach technique for picking …
AbdelrhmanBassiouny Nov 12, 2024
aafcf49
[MultiverseFallschoolDemo] The demo works.
AbdelrhmanBassiouny Nov 12, 2024
f9dd053
[MultiverseFallschoolDemo] try and redo actions
AbdelrhmanBassiouny Nov 13, 2024
5bf6ece
[FixORM] added new paramters to orm classes to match actions/motions.
AbdelrhmanBassiouny Nov 20, 2024
e04a49b
[PhysicalObject] Added a physical object class.
AbdelrhmanBassiouny Nov 20, 2024
e734b00
[PhysicalObject] remove contacts, object state has a physical body st…
AbdelrhmanBassiouny Nov 20, 2024
0918965
[PhysicalBody] (WIP) refactoring bullet world to conform with new/cha…
AbdelrhmanBassiouny Nov 21, 2024
26a74b7
[PhysicalBody] (WIP) most tests are passing, there's a problem with t…
AbdelrhmanBassiouny Nov 22, 2024
4a3a731
[PhysicalBody] (WIP) fixed issue with high position tolerance.
AbdelrhmanBassiouny Nov 22, 2024
bd5c87c
[JupyterTests] (WIP) cram_plan_tutorial has problems.
AbdelrhmanBassiouny Nov 27, 2024
93a3072
[MultiverseGetImages] Made use of target pose to adjust camera pose.
AbdelrhmanBassiouny Nov 28, 2024
36733a9
[MultiverseFallschoolDemo] Merged with dev.
AbdelrhmanBassiouny Nov 29, 2024
8097842
[MultiversePycrap] used pycrap in multiverse.
AbdelrhmanBassiouny Nov 30, 2024
e9982a9
[NavigateAction] Add an option that asks if the joint states should b…
AbdelrhmanBassiouny Nov 11, 2024
ef9129c
[PhysicalObject] Added a physical object class.
AbdelrhmanBassiouny Nov 20, 2024
e9401c1
[PhysicalBody] (WIP) refactoring bullet world to conform with new/cha…
AbdelrhmanBassiouny Nov 21, 2024
34e2de0
[PhysicalBody] (WIP) most tests are passing, there's a problem with t…
AbdelrhmanBassiouny Nov 22, 2024
0853f02
[World] rename argument to is_prospection
AbdelrhmanBassiouny Nov 24, 2024
263235e
[VirtualJoint] no need for object.
AbdelrhmanBassiouny Nov 24, 2024
8d39764
[Link] Implement name property as it exists in two parents.
AbdelrhmanBassiouny Nov 24, 2024
0828ef0
[WorldObject] make color None by default instead of white.
AbdelrhmanBassiouny Nov 24, 2024
cff62f1
[LocalTransformer] solved bug where world objects were used instead o…
AbdelrhmanBassiouny Nov 24, 2024
a1a7db8
[Logging] added set log level.
AbdelrhmanBassiouny Nov 24, 2024
aef6fe0
[PhysicalBody] (WIP) Contact points return bodies not links.
AbdelrhmanBassiouny Nov 26, 2024
08e8b38
[PhysicalBody] Everything is a WorldEntity, and they all have parent …
AbdelrhmanBassiouny Nov 27, 2024
e29b493
[PhysicalBody] used pycrap in physical body instead of object.
AbdelrhmanBassiouny Dec 2, 2024
9a3cef6
[Giskard] removed duplicate set_joint_goal.
AbdelrhmanBassiouny Dec 2, 2024
9c37d26
[PhysicalBody] fixed some multiverse bugs.
AbdelrhmanBassiouny Dec 4, 2024
2333eda
[MultiverseFallSchoolDemo] added optional argument grasps to CostmapL…
AbdelrhmanBassiouny Dec 5, 2024
9403bcd
[PhysicalObject] corrections after rebasing on dev.
AbdelrhmanBassiouny Dec 11, 2024
17301e5
[Multiverse] Removed extra lock release in clients.
AbdelrhmanBassiouny Dec 13, 2024
5068e12
[HasConcept] added the has concept as parent to PhysicalBody
AbdelrhmanBassiouny Dec 13, 2024
b7c951a
[MultiverseFallSchoolDemo] merged changes from dev.
AbdelrhmanBassiouny Dec 13, 2024
89c162d
[Multiverse] removed unused dataclasses.
AbdelrhmanBassiouny Dec 13, 2024
497ad03
[Giskard] removed unused import.
AbdelrhmanBassiouny Dec 13, 2024
3f1ee35
[PR2ProcessModules] removed dublicate import.
AbdelrhmanBassiouny Dec 13, 2024
898a42c
[PhysicalBody] removed duplicate method, added a normal property for …
AbdelrhmanBassiouny Dec 15, 2024
3277e0c
[PhysicalBody] Added Supporter type in pycrap.
AbdelrhmanBassiouny Dec 16, 2024
5da450f
[PhysicalBody] minor review changes.
AbdelrhmanBassiouny Dec 19, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion config/world_conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class WorldConfig:
and the world synchronization.
"""

position_tolerance: float = 1e-2
position_tolerance: float = 1e-3
orientation_tolerance: float = 10 * math.pi / 180
prismatic_joint_position_tolerance: float = 1e-2
revolute_joint_position_tolerance: float = 5 * math.pi / 180
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
import pycrap
from pycram.datastructures.enums import GripperState, Arms
from pycram.datastructures.world import UseProspectionWorld
from pycram.process_module import simulated_robot, real_robot
from pycram.datastructures.enums import GripperState
from pycram.process_module import real_robot
from pycram.world_concepts.world_object import Object
from pycram.datastructures.pose import Pose
from pycram.worlds.multiverse import Multiverse
Expand Down Expand Up @@ -30,5 +29,4 @@
with real_robot:
SetGripperAction(robot_arms, [GripperState.CLOSE]).resolve().perform()


world.exit()
1 change: 1 addition & 0 deletions examples/cram_plan_tutorial.md
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ def get_n_random_positions(pose_list, n=4, dist=0.5, random=True):
```

```python
import pycrap
from tf.transformations import quaternion_from_euler
import pycrap
from pycram.costmaps import SemanticCostmap
Expand Down
207 changes: 150 additions & 57 deletions src/pycram/datastructures/dataclasses.py

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion src/pycram/datastructures/mixins.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,4 +19,4 @@ class HasConcept:
"""

def __init__(self):
self.ontology_individual = self.ontology_concept()
self.ontology_individual = self.ontology_concept()
157 changes: 74 additions & 83 deletions src/pycram/datastructures/world.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import numpy as np
from geometry_msgs.msg import Point
from trimesh.parent import Geometry3D
from typing_extensions import List, Optional, Dict, Tuple, Callable, TYPE_CHECKING, Union, Type
from typing_extensions import List, Optional, Dict, Tuple, Callable, TYPE_CHECKING, Union, Type, deprecated

import pycrap
from pycrap import PhysicalObject, Floor, Apartment, Robot
Expand All @@ -24,15 +24,13 @@
ContactPointsList, VirtualMobileBaseJoints, RotatedBoundingBox)
from ..datastructures.enums import JointType, WorldMode, Arms
from ..datastructures.pose import Pose, Transform
from ..datastructures.world_entity import StateEntity
from ..datastructures.world_entity import StateEntity, PhysicalBody, WorldEntity
from ..failures import ProspectionObjectNotFound, WorldObjectNotFound
from ..local_transformer import LocalTransformer
from ..robot_description import RobotDescription
from ..ros.data_types import Time
from ..ros.logging import logwarn
from ..validation.goal_validator import (MultiPoseGoalValidator,
PoseGoalValidator, JointPositionGoalValidator,
MultiJointPositionGoalValidator, GoalValidator,
from ..validation.goal_validator import (GoalValidator,
validate_joint_position, validate_multiple_joint_positions,
validate_object_pose, validate_multiple_object_poses)
from ..world_concepts.constraints import Constraint
Expand All @@ -44,7 +42,7 @@
from ..object_descriptors.generic import ObjectDescription as GenericObjectDescription


class World(StateEntity, ABC):
class World(WorldEntity, ABC):
"""
The World Class represents the physics Simulation and belief state, it is the main interface for reasoning about
the World. This is implemented as a singleton, the current World can be accessed via the static variable
Expand Down Expand Up @@ -80,23 +78,22 @@ class World(StateEntity, ABC):
The ontology of this world.
"""

def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: bool = False,
clear_cache: bool = False):
def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection: bool = False, clear_cache: bool = False,
id_: int = -1):
"""
Create a new simulation, the mode decides if the simulation should be a rendered window or just run in the
background. There can only be one rendered simulation.
The World object also initializes the Events for attachment, detachment and for manipulating the world.

:param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is
"GUI"
:param is_prospection_world: For internal usage, decides if this World should be used as a prospection world.
:param is_prospection: For internal usage, decides if this World should be used as a prospection world.
:param clear_cache: Whether to clear the cache directory.
:param id_: The unique id of the world.
"""

StateEntity.__init__(self)

WorldEntity.__init__(self, id_, self)
self.ontology = pycrap.Ontology()

self.latest_state_id: Optional[int] = None

if clear_cache or (self.conf.clear_cache_at_start and not self.cache_manager.cache_cleared):
Expand All @@ -109,15 +106,12 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo

self.object_lock: threading.Lock = threading.Lock()

self.id: Optional[int] = -1
# This is used to connect to the physics server (allows multiple clients)

self._init_world(mode)

self.objects: List[Object] = []
# List of all Objects in the World

self.is_prospection_world: bool = is_prospection_world
self.is_prospection_world: bool = is_prospection
self._init_and_sync_prospection_world()

self.local_transformer = LocalTransformer()
Expand All @@ -131,27 +125,28 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo

self._current_state: Optional[WorldState] = None

self._init_goal_validators()

self.original_state_id = self.save_state()

self.on_add_object_callbacks: List[Callable[[Object], None]] = []

def get_object_convex_hull(self, obj: Object) -> Geometry3D:
@property
def parent_entity(self) -> Optional[WorldEntity]:
"""
Get the convex hull of an object.

:param obj: The pycram object.
:return: The convex hull of the object as a list of Points.
Return the parent entity of this entity, in this case it is None as the World is the top level entity.
"""
raise NotImplementedError
return None

def get_link_convex_hull(self, link: Link) -> Geometry3D:
@property
def name(self) -> str:
"""
Get the convex hull of a link of an articulated object.
Return the name of the world, which is the name of the implementation class (e.g. BulletWorld).
"""
return self.__class__.__name__

:param link: The link as a AbstractLink object.
:return: The convex hull of the link as a list of Points.
def get_body_convex_hull(self, body: PhysicalBody) -> Geometry3D:
"""
:param body: The body object.
:return: The convex hull of the body as a Geometry3D object.
"""
raise NotImplementedError

Expand Down Expand Up @@ -232,30 +227,6 @@ def robot_joint_actuators(self) -> Dict[str, str]:
"""
return self.robot_description.joint_actuators

def _init_goal_validators(self):
"""
Initialize the goal validators for the World objects' poses, positions, and orientations.
"""

# Objects Pose goal validators
self.pose_goal_validator = PoseGoalValidator(self.get_object_pose, self.conf.get_pose_tolerance(),
self.conf.acceptable_percentage_of_goal)
self.multi_pose_goal_validator = MultiPoseGoalValidator(
lambda x: list(self.get_multiple_object_poses(x).values()),
self.conf.get_pose_tolerance(), self.conf.acceptable_percentage_of_goal)

# Joint Goal validators
self.joint_position_goal_validator = JointPositionGoalValidator(
self.get_joint_position,
acceptable_revolute_joint_position_error=self.conf.revolute_joint_position_tolerance,
acceptable_prismatic_joint_position_error=self.conf.prismatic_joint_position_tolerance,
acceptable_percentage_of_goal_achieved=self.conf.acceptable_percentage_of_goal)
self.multi_joint_position_goal_validator = MultiJointPositionGoalValidator(
lambda x: list(self.get_multiple_joint_positions(x).values()),
acceptable_revolute_joint_position_error=self.conf.revolute_joint_position_tolerance,
acceptable_prismatic_joint_position_error=self.conf.prismatic_joint_position_tolerance,
acceptable_percentage_of_goal_achieved=self.conf.acceptable_percentage_of_goal)

def check_object_exists(self, obj: Object) -> bool:
"""
Check if the object exists in the simulator.
Expand Down Expand Up @@ -302,7 +273,7 @@ def _init_prospection_world(self):
if self.is_prospection_world: # then no need to add another prospection world
self.prospection_world = None
else:
self.prospection_world: World = self.__class__(is_prospection_world=True)
self.prospection_world: World = self.__class__(is_prospection=True)

def _sync_prospection_world(self):
"""
Expand Down Expand Up @@ -470,7 +441,7 @@ def remove_object_from_original_state(self, obj: Object) -> None:
:param obj: The object to be removed.
"""
self.original_state.object_states.pop(obj.name)
self.original_state.simulator_state_id = self.save_physics_simulator_state(use_same_id=True)
self.update_simulator_state_id_in_original_state(use_same_id=True)

def add_object_to_original_state(self, obj: Object) -> None:
"""
Expand Down Expand Up @@ -636,7 +607,7 @@ def simulate(self, seconds: float, real_time: Optional[bool] = False,
curr_time = Time().now()
self.step(func)
for objects, callbacks in self.coll_callbacks.items():
contact_points = self.get_contact_points_between_two_objects(objects[0], objects[1])
contact_points = self.get_contact_points_between_two_bodies(objects[0], objects[1])
if len(contact_points) > 0:
callbacks.on_collision_cb()
elif callbacks.no_collision_cb is not None:
Expand All @@ -645,14 +616,6 @@ def simulate(self, seconds: float, real_time: Optional[bool] = False,
loop_time = Time().now() - curr_time
time_diff = self.simulation_time_step - loop_time.to_sec()
time.sleep(max(0, time_diff))
self.update_all_objects_poses()

def update_all_objects_poses(self) -> None:
"""
Update the positions of all objects in the world.
"""
for obj in self.objects:
obj.update_pose()

@abstractmethod
def get_object_pose(self, obj: Object) -> Pose:
Expand Down Expand Up @@ -737,47 +700,66 @@ def perform_collision_detection(self) -> None:
"""
pass

@abstractmethod
@deprecated("Use get_body_contact_points instead")
AbdelrhmanBassiouny marked this conversation as resolved.
Show resolved Hide resolved
def get_object_contact_points(self, obj: Object) -> ContactPointsList:
"""
Return a list of contact points of this Object with all other Objects.
Same as :meth:`get_body_contact_points` but with objects instead of any type of bodies.
"""
return self.get_body_contact_points(obj)

:param obj: The object.
:return: A list of all contact points with other objects
@abstractmethod
def get_body_contact_points(self, body: PhysicalBody) -> ContactPointsList:
"""
Return the contact points of a body with all other bodies in the world.

:param body: The body.
"""
pass

@abstractmethod
@deprecated("Use get_contact_points_between_two_bodies instead")
def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> ContactPointsList:
"""
Return a list of contact points between obj_a and obj_b.
Same as :meth:`get_contact_points_between_two_bodies` but with objects instead of any type of bodies.
"""
return self.get_contact_points_between_two_bodies(obj1, obj2)

@abstractmethod
def get_contact_points_between_two_bodies(self, body_1: PhysicalBody, body_2: PhysicalBody) -> ContactPointsList:
"""
Return a list of contact points between two bodies.

:param obj1: The first object.
:param obj2: The second object.
:return: A list of all contact points between the two objects.
:param body_1: The first body.
:param body_2: The second body.
:return: A list of all contact points between the two bodies.
"""
pass

def get_object_closest_points(self, obj: Object, max_distance: float) -> ClosestPointsList:
@deprecated("Use get_contact_points_between_two_bodies instead")
def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> ContactPointsList:
"""
Same as :meth:`get_contact_points_between_two_bodies` but with objects instead of any type of bodies.
"""
Return the closest points of this object with all other objects in the world.
return self.get_contact_points_between_two_bodies(obj1, obj2)

:param obj: The object.
:param max_distance: The maximum distance between the points.
def get_body_closest_points(self, body: PhysicalBody, max_distance: float) -> ClosestPointsList:
"""
Return the closest points of this body with all other bodies in the world.

:param body: The body.
:param max_distance: The maximum allowed distance between the points.
:return: A list of the closest points.
"""
all_obj_closest_points = [self.get_closest_points_between_objects(obj, other_obj, max_distance) for other_obj in
self.objects
if other_obj != obj]
all_obj_closest_points = [self.get_closest_points_between_two_bodies(body, other_body, max_distance)
for other_body in self.objects if other_body != body]
return ClosestPointsList([point for closest_points in all_obj_closest_points for point in closest_points])

def get_closest_points_between_objects(self, object_a: Object, object_b: Object, max_distance: float) \
def get_closest_points_between_two_bodies(self, body_a: PhysicalBody, body_b: PhysicalBody, max_distance: float) \
-> ClosestPointsList:
"""
Return the closest points between two objects.

:param object_a: The first object.
:param object_b: The second object.
:param body_a: The first body.
:param body_b: The second body.
:param max_distance: The maximum distance between the points.
:return: A list of the closest points.
"""
Expand Down Expand Up @@ -1299,7 +1281,7 @@ def reset_world(self, remove_saved_states=False) -> None:
self.restore_state(self.original_state_id)
if remove_saved_states:
self.remove_saved_states()
self.original_state_id = self.save_state(use_same_id=True)
self.original_state_id = self.save_state(use_same_id=True)

def remove_saved_states(self) -> None:
"""
Expand Down Expand Up @@ -1684,6 +1666,15 @@ def original_state(self) -> WorldState:
def __del__(self):
self.exit()

def __eq__(self, other: World):
if not isinstance(other, self.__class__):
return False
return (self.is_prospection_world == other.is_prospection_world
and self.id == other.id)

def __hash__(self):
return hash((self.__class__.__name__, self.is_prospection_world, self.id))


class UseProspectionWorld:
"""
Expand Down
Loading