pycram.world_reasoning#
Functions#
|
Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating |
|
Checks if two objects are in contact or not. If the links should be returned then the output will also contain a |
|
Check if the robot collides with any object in the world at the given pose. |
|
Check if the object is picked by the robot. |
|
Return a segmentation mask of the objects that are visible from the given camera pose and the front facing axis. |
|
Checks if an object is visible from a given position. This will be achieved by rendering the object |
|
Lists all objects which are occluding the given object. This works similar to 'visible'. |
|
Checks if the robot can reach a given position. To determine this the inverse kinematics are |
|
Checks if any objects are blocking another object when a robot tries to pick it. This works |
|
Checks if one object is supporting another object. An object supports another object if they are in |
Get the pose a link would be in if the given joint configuration would be applied to the object. |
|
Move all objects away from the robot to create an empty space for the robot to look at the target location. |
|
|
Generate a virtual object at the target location. |
|
Cast a ray from the camera to the target position. |
|
Check if the gripper has grasped the body by checking if the gripper fingers are in contact with the body. |
|
Check if the body is between the fingers of the gripper. |
Check if there is empty space between the fingers of the gripper. |
|
|
Get the intersection between the body and the empty space between the fingers. |
|
Check if the body is in the given region. |
Module Contents#
- pycram.world_reasoning.stable(obj: pycram.world_concepts.world_object.Object) bool#
Checks if an object is stable in the world. Stable meaning that it’s position will not change after simulating physics in the World. This will be done by simulating the world for 10 seconds and compare the previous coordinates with the coordinates after the simulation.
- Parameters:
obj – The object which should be checked
- Returns:
True if the given object is stable in the world False else
- pycram.world_reasoning.contact(object1: pycram.world_concepts.world_object.Object, object2: pycram.world_concepts.world_object.Object, return_links: bool = False) typing_extensions.Union[bool, typing_extensions.Tuple[bool, typing_extensions.List[typing_extensions.Tuple[pycram.world_concepts.world_object.Link, pycram.world_concepts.world_object.Link]]]]#
Checks if two objects are in contact or not. If the links should be returned then the output will also contain a list of tuples where the first element is the link name of ‘object1’ and the second element is the link name of ‘object2’.
- Parameters:
object1 – The first object
object2 – The second object
return_links – If the respective links on the objects that are in contact should be returned.
- Returns:
True if the two objects are in contact False else. If links should be returned a list of links in contact
- pycram.world_reasoning.prospect_robot_contact(robot: pycram.world_concepts.world_object.Object, ignore_collision_with: typing_extensions.Optional[typing_extensions.List[pycram.world_concepts.world_object.Object]] = None) bool#
Check if the robot collides with any object in the world at the given pose.
- Parameters:
robot – The robot object
pose – The pose to check for collision
ignore_collision_with – A list of objects to ignore collision with
- Returns:
True if the robot collides with any object, False otherwise
- pycram.world_reasoning.is_held_object(robot: pycram.world_concepts.world_object.Object, obj: pycram.world_concepts.world_object.Object, robot_contact_links: typing_extensions.List[pycram.world_concepts.world_object.Link]) bool#
Check if the object is picked by the robot.
- Parameters:
robot – The robot object
obj – The object to check if it is picked
robot_contact_links – The links of the robot that are in contact with the object
- Returns:
True if the object is picked by the robot, False otherwise
- pycram.world_reasoning.get_visible_objects(camera_pose: pycram.datastructures.pose.PoseStamped, front_facing_axis: typing_extensions.Optional[typing_extensions.List[float]] = None, plot_segmentation_mask: bool = False) typing_extensions.Tuple[numpy.ndarray, pycram.datastructures.pose.PoseStamped]#
Return a segmentation mask of the objects that are visible from the given camera pose and the front facing axis.
- Parameters:
camera_pose – The pose of the camera in world coordinate frame.
front_facing_axis – The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz
plot_segmentation_mask – If the segmentation mask should be plotted
- Returns:
A segmentation mask of the objects that are visible and the pose of the point at exactly 2 meters in front of the camera in the direction of the front facing axis with respect to the world coordinate frame.
- pycram.world_reasoning.visible(obj: pycram.world_concepts.world_object.Object, camera_pose: pycram.datastructures.pose.PoseStamped, front_facing_axis: typing_extensions.Optional[typing_extensions.List[float]] = None, threshold: float = 0.8, plot_segmentation_mask: bool = False) bool#
Checks if an object is visible from a given position. This will be achieved by rendering the object alone and counting the visible pixel, then rendering the complete scene and compare the visible pixels with the absolut count of pixels.
- Parameters:
obj – The object for which the visibility should be checked
camera_pose – The pose of the camera in map frame
front_facing_axis – The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz
threshold – The minimum percentage of the object that needs to be visible for this method to return true.
plot_segmentation_mask – If the segmentation mask should be plotted.
- Returns:
True if the object is visible from the camera_position False if not
- pycram.world_reasoning.occluding(obj: pycram.world_concepts.world_object.Object, camera_pose: pycram.datastructures.pose.PoseStamped, front_facing_axis: typing_extensions.Optional[typing_extensions.List[float]] = None, plot_segmentation_mask: bool = False) typing_extensions.List[pycram.world_concepts.world_object.Object]#
Lists all objects which are occluding the given object. This works similar to ‘visible’. First the object alone will be rendered and the position of the pixels of the object in the picture will be saved. After that the complete scene will be rendered and the previous saved pixel positions will be compared to the actual pixels, if in one pixel another object is visible ot will be saved as occluding.
- Parameters:
obj – The object for which occlusion should be checked
camera_pose – The pose of the camera in world coordinate frame
front_facing_axis – The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz
plot_segmentation_mask – If the segmentation mask should be plotted
- Returns:
A list of occluding objects
- pycram.world_reasoning.reachable(pose_or_object: typing_extensions.Union[pycram.world_concepts.world_object.Object, pycram.datastructures.pose.PoseStamped], robot: pycram.world_concepts.world_object.Object, gripper_name: str, threshold: float = 0.01) bool#
Checks if the robot can reach a given position. To determine this the inverse kinematics are calculated and applied. Afterward the distance between the position and the given end effector is calculated, if it is smaller than the threshold the reasoning query returns True, if not it returns False.
- Parameters:
pose_or_object – The position and rotation or Object for which reachability should be checked or an Object
robot – The robot that should reach for the position
gripper_name – The name of the end effector
threshold – The threshold between the end effector and the position.
- Returns:
True if the end effector is closer than the threshold to the target position, False in every other case
- pycram.world_reasoning.blocking(pose_or_object: typing_extensions.Union[pycram.world_concepts.world_object.Object, pycram.datastructures.pose.PoseStamped], robot: pycram.world_concepts.world_object.Object, gripper_chain: pycram.robot_description.KinematicChainDescription, grasp: pycram.datastructures.enums.Grasp = None) typing_extensions.Union[typing_extensions.List[pycram.world_concepts.world_object.Object], None]#
Checks if any objects are blocking another object when a robot tries to pick it. This works similar to the reachable predicate. First the inverse kinematics between the robot and the object will be calculated and applied. Then it will be checked if the robot is in contact with any object except the given one. If the given pose or Object is not reachable None will be returned
- Parameters:
pose_or_object – The object or pose for which blocking objects should be found
robot – The robot Object who reaches for the object
gripper_chain – The kinematic chain of the used gripper
grasp – The grasp type with which the object should be grasped
- Returns:
A list of objects the robot is in collision with when reaching for the specified object or None if the pose or object is not reachable.
- pycram.world_reasoning.supporting(object1: pycram.world_concepts.world_object.Object, object2: pycram.world_concepts.world_object.Object) bool#
Checks if one object is supporting another object. An object supports another object if they are in contact and the second object is above the first one. (e.g. a Bottle will be supported by a table)
- Parameters:
object1 – Object that is supported
object2 – Object that supports the first object
- Returns:
True if the second object is in contact with the first one and the second is above the first else False
- pycram.world_reasoning.link_pose_for_joint_config(obj: pycram.world_concepts.world_object.Object, joint_config: typing_extensions.Dict[str, float], link_name: str) pycram.datastructures.pose.PoseStamped#
Get the pose a link would be in if the given joint configuration would be applied to the object. This is done by using the respective object in the prospection world and applying the joint configuration to this one. After applying the joint configuration the link position is taken from there.
- Parameters:
obj – Object of which the link is a part
joint_config – Dict with the goal joint configuration
link_name – Name of the link for which the pose should be returned
- Returns:
The pose of the link after applying the joint configuration
- pycram.world_reasoning.move_away_all_objects_to_create_empty_space(exclude_objects: typing_extensions.List[str] = None)#
Move all objects away from the robot to create an empty space for the robot to look at the target location.
- Parameters:
exclude_objects – The objects that should not be moved away.
- pycram.world_reasoning.generate_object_at_target(target_location: typing_extensions.List[float], size: typing_extensions.Tuple[float, Ellipsis] = (0.2, 0.2, 0.2), name: str = 'target') pycram.world_concepts.world_object.Object#
Generate a virtual object at the target location.
- Parameters:
target_location – The target location at which the object should be generated.
size – The size of the object.
name – The name of the object.
- pycram.world_reasoning.cast_a_ray_from_camera(max_distance: float = 10)#
Cast a ray from the camera to the target position.
- Parameters:
max_distance – The maximum distance the ray should be cast if no object is found.
- pycram.world_reasoning.has_gripper_grasped_body(arm: pycram.datastructures.enums.Arms, body: pycram.datastructures.world_entity.PhysicalBody) bool#
Check if the gripper has grasped the body by checking if the gripper fingers are in contact with the body. else it will check if the gripper links are in contact with the body. Note: This is different from
pycram.world_reasoning.is_held_object()as it only checks if the gripper is incontact with the body, not if it is attached to the gripper.
- Parameters:
arm – The arm for which the grasping should be checked.
body – The body for which the grasping should be checked.
- Returns:
True if the gripper has grasped the body, False otherwise.
- pycram.world_reasoning.is_body_between_fingers(body: pycram.datastructures.world_entity.PhysicalBody, fingers_link_names: typing_extensions.List[str], method: pycram.datastructures.enums.FindBodyInRegionMethod = FindBodyInRegionMethod.FingerToCentroid) bool#
Check if the body is between the fingers of the gripper.
- Parameters:
body – The body for which the check should be done.
fingers_link_names – The names of the links that represent the fingers of the gripper.
method – The method to use to find the body in the region.
- pycram.world_reasoning.get_empty_space_between_fingers(fingers_link_names: typing_extensions.List[str]) typing_extensions.Optional[trimesh.Trimesh]#
Check if there is empty space between the fingers of the gripper.
- Parameters:
fingers_link_names – The names of the links that represent the fingers of the gripper.
- Returns:
The empty space between the fingers.
- pycram.world_reasoning.get_intersection_between_body_bounding_box_and_empty_space(body: pycram.datastructures.world_entity.PhysicalBody, empty_space: trimesh.Trimesh) typing_extensions.Optional[trimesh.Trimesh]#
Get the intersection between the body and the empty space between the fingers.
- Parameters:
body – The body for which the intersection should be calculated.
empty_space – The empty space between the fingers.
- Returns:
The intersection between the body and the empty space between the fingers.
- pycram.world_reasoning.is_body_in_region(body: pycram.datastructures.world_entity.PhysicalBody, region: trimesh.Trimesh, step_size_in_meters: float = 0.01, method: pycram.datastructures.enums.FindBodyInRegionMethod = FindBodyInRegionMethod.Centroid) bool#
Check if the body is in the given region.
- Parameters:
body – The body for which the check should be done.
region – The region to check if the body is in.
step_size_in_meters – The step size in meters between the rays.
method – The method to use to find the body in the region.