pycram.world_reasoning

Module Contents

Functions

stable(→ bool)

Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating

contact(→ typing_extensions.Union[bool, ...)

Checks if two objects are in contact or not. If the links should be returned then the output will also contain a

get_visible_objects(...)

Returns a segmentation mask of the objects that are visible from the given camera pose and the front facing axis.

visible(→ bool)

Checks if an object is visible from a given position. This will be achieved by rendering the object

occluding(...)

Lists all objects which are occluding the given object. This works similar to 'visible'.

reachable(→ bool)

Checks if the robot can reach a given position. To determine this the inverse kinematics are

blocking(...)

Checks if any objects are blocking another object when a robot tries to pick it. This works

supporting(→ bool)

Checks if one object is supporting another object. An object supports another object if they are in

link_pose_for_joint_config(...)

Returns the pose a link would be in if the given joint configuration would be applied to the object.

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]]

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.get_visible_objects(camera_pose: pycram.datastructures.pose.Pose, front_facing_axis: typing_extensions.Optional[typing_extensions.List[float]] = None) typing_extensions.Tuple[numpy.ndarray, pycram.datastructures.pose.Pose]

Returns 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

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.Pose, front_facing_axis: typing_extensions.Optional[typing_extensions.List[float]] = None, threshold: float = 0.8) 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.

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.Pose, front_facing_axis: typing_extensions.Optional[typing_extensions.List[float]] = None) 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

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.Pose], 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.Pose], robot: pycram.world_concepts.world_object.Object, gripper_name: str, grasp: str = 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_name – The name of the end effector of the robot

  • 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

Returns 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