pycram.designators.location_designator

Contents

pycram.designators.location_designator#

Attributes#

Classes#

Location

Default location designator which only wraps a pose.

CostmapLocation

Uses Costmaps to create locations for complex constrains

AccessingLocation

Location designator which describes poses used for opening drawers

SemanticCostmapLocation

Locations over semantic entities, like a table surface

ProbabilisticSemanticLocation

Location designator which samples poses from a semantic costmap with a probability distribution.

ProbabilisticCostmapLocation

Uses Costmaps to create locations for complex constrains.

Functions#

_create_target_sequence(...)

Creates the sequence of poses that need to be reachable for the robot to grasp the target.

Module Contents#

pycram.designators.location_designator.logger#
class pycram.designators.location_designator.Location(pose: pycram.datastructures.pose.PoseStamped)#

Bases: pycram.designator.LocationDesignatorDescription

Default location designator which only wraps a pose.

pose: pycram.datastructures.pose.PoseStamped#
ground() pycram.datastructures.pose.PoseStamped#

Default specialized_designators which returns a resolved designator which contains the pose given in init.

Returns:

A resolved designator

pycram.designators.location_designator._create_target_sequence(grasp_description: pycram.datastructures.grasp.GraspDescription, target: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, semantic_digital_twin.world_description.world_entity.Body], robot: semantic_digital_twin.robots.abstract_robot.AbstractRobot, object_in_hand: semantic_digital_twin.world_description.world_entity.Body, reachable_arm: pycram.datastructures.enums.Arms, world: semantic_digital_twin.world.World, rotation_agnostic: bool = False) typing_extensions.List[pycram.datastructures.pose.PoseStamped]#

Creates the sequence of poses that need to be reachable for the robot to grasp the target. For pickup this would be retract pose, target pose and lift pose. For place this would be lift pose, target pose and retract pose.

Parameters:
  • grasp_description – Grasp description to be used for grasping

  • target – The target of reachability, either a pose or an object

  • robot – The robot that should be checked for reachability

  • object_in_hand – An object that is held if any

  • reachable_arm – The arm which should be checked for reachability

Returns:

A list of poses that need to be reachable in this order

class pycram.designators.location_designator.CostmapLocation(target: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, semantic_digital_twin.world_description.world_entity.Body], reachable_for: semantic_digital_twin.robots.abstract_robot.AbstractRobot = None, visible_for: semantic_digital_twin.robots.abstract_robot.AbstractRobot = None, reachable_arm: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[pycram.datastructures.enums.Arms], pycram.datastructures.enums.Arms]] = None, ignore_collision_with: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[semantic_digital_twin.world_description.world_entity.Body], semantic_digital_twin.world_description.world_entity.Body]] = None, grasp_descriptions: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[pycram.datastructures.grasp.GraspDescription], pycram.datastructures.grasp.GraspDescription]] = None, rotation_agnostic: bool = False)#

Bases: pycram.designator.LocationDesignatorDescription

Uses Costmaps to create locations for complex constrains

target: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, semantic_digital_twin.world_description.world_entity.Body]#
reachable_for: semantic_digital_twin.robots.abstract_robot.AbstractRobot = None#
visible_for: semantic_digital_twin.robots.abstract_robot.AbstractRobot = None#
reachable_arm: typing_extensions.Optional[pycram.datastructures.enums.Arms] = None#
ignore_collision_with = None#
grasps: typing_extensions.List[typing_extensions.Optional[pycram.datastructures.enums.Grasp]] = None#
ground() pycram.datastructures.pose.PoseStamped#

Default specialized_designators which returns the first result from the iterator of this instance.

Returns:

A resolved location

setup_costmaps(target: pycram.datastructures.pose.PoseStamped, visible_for, reachable_for) pycram.costmaps.Costmap#

Sets up the costmaps for the given target and robot. The costmaps are merged and stored in the final_map

__iter__() typing_extensions.Iterator[pycram.datastructures.pose.PoseStamped]#

Generates positions for a given set of constrains from a costmap and returns them. The generation is based of a costmap which itself is the product of merging costmaps, each for a different purpose. In any case an occupancy costmap is used as the base, then according to the given constrains a visibility or gaussian costmap is also merged with this. Once the costmaps are merged, a generator generates pose candidates from the costmap. Each pose candidate is then validated against the constraints given by the designator if all validators pass the pose is considered valid and yielded.

yield:

An instance of CostmapLocation.Location with a valid position that satisfies the given constraints

class pycram.designators.location_designator.AccessingLocation(handle: typing_extensions.Union[semantic_digital_twin.world_description.world_entity.Body, typing_extensions.Iterable[semantic_digital_twin.world_description.world_entity.Body]], robot_desig: typing_extensions.Union[semantic_digital_twin.robots.abstract_robot.AbstractRobot, typing_extensions.Iterable[semantic_digital_twin.robots.abstract_robot.AbstractRobot]], arm: typing_extensions.Union[typing_extensions.List[pycram.datastructures.enums.Arms], pycram.datastructures.enums.Arms] = None, prepose_distance: float = ActionConfig.grasping_prepose_distance)#

Bases: pycram.designator.LocationDesignatorDescription

Location designator which describes poses used for opening drawers

handle: semantic_digital_twin.world_description.world_entity.Body#
robot: semantic_digital_twin.robots.abstract_robot.AbstractRobot#
prepose_distance#
arm = None#
ground() pycram.datastructures.pose.PoseStamped#

Default specialized_designators for this location designator, just returns the first element from the iteration

Returns:

A location designator for a pose from which the drawer can be opened

static adjust_map_for_drawer_opening(cost_map: pycram.costmaps.Costmap, init_pose: pycram.datastructures.pose.PoseStamped, goal_pose: pycram.datastructures.pose.PoseStamped, width: float = 0.2)#

Adjust the cost map for opening a drawer. This is done by removing all locations between the initial and final pose of the drawer/container.

Parameters:
  • cost_map – Costmap that should be adjusted.

  • init_pose – Pose of the drawer/container when it is fully closed.

  • goal_pose – Pose of the drawer/container when it is fully opened.

  • width – Width of the drawer/container.

setup_costmaps(handle: semantic_digital_twin.world_description.world_entity.Body) pycram.costmaps.Costmap#

Sets up the costmaps for the given handle and robot. The costmaps are merged and stored in the final_map.

create_target_sequence(params_box: box.Box, final_map: pycram.costmaps.Costmap) typing_extensions.List[pycram.datastructures.pose.PoseStamped]#

Creates the sequence of target poses

Parameters:
  • params_box

  • final_map

Returns:

__iter__() typing_extensions.Iterator[pycram.datastructures.pose.PoseStamped]#

Creates poses from which the robot can open the drawer specified by the ObjectPart designator describing the handle. Poses are validated by checking if the robot can grasp the handle while the drawer is closed and if the handle can be grasped if the drawer is open.

Yield:

A location designator containing the pose and the arms that can be used.

class pycram.designators.location_designator.SemanticCostmapLocation(body, for_object: semantic_digital_twin.world_description.world_entity.Body = None, edges_only: bool = False, horizontal_edges_only: bool = False, edge_size_in_meters: float = 0.06, height_offset: float = 0.0)#

Bases: pycram.designator.LocationDesignatorDescription

Locations over semantic entities, like a table surface

body: semantic_digital_twin.world_description.world_entity.Body#
for_object: typing_extensions.Optional[semantic_digital_twin.world_description.world_entity.Body] = None#
edges_only: bool = False#
horizontal_edges_only: bool = False#
edge_size_in_meters: float = 0.06#
sem_costmap: typing_extensions.Optional[pycram.costmaps.SemanticCostmap] = None#
ground() pycram.datastructures.pose.PoseStamped#

Default specialized_designators which returns the first element of the iterator of this instance.

Returns:

A resolved location

__iter__() typing_extensions.Iterator[pycram.datastructures.pose.PoseStamped]#

Creates a costmap on top of a link of an Object and creates positions from it. If there is a specific Object for which the position should be found, a height offset will be calculated which ensures that the bottom of the Object is at the position in the Costmap and not the origin of the Object which is usually in the centre of the Object.

Yield:

An instance of SemanticCostmapLocation.Location with the found valid position of the Costmap.

class pycram.designators.location_designator.ProbabilisticSemanticLocation(bodies: typing_extensions.List[semantic_digital_twin.world_description.world_entity.Body], for_object: semantic_digital_twin.world_description.world_entity.Body = None, link_is_center_link: bool = False, number_of_samples: int = 1000, sort_sampels: bool = False, uniform_sampling: bool = False, highlight_used_surfaces: bool = False)#

Bases: pycram.designator.LocationDesignatorDescription

Location designator which samples poses from a semantic costmap with a probability distribution. The construction of the probabilistic circuit can be quite time-consuming, but the majority of the computational load is done during the first iteration only. In this case the exact time is highly dependent on the number of links in the world, and the number of links we are sampling from.

surface_x#

Variable representing the x coordinate on a surface

surface_y#

Variable representing the y coordinate on a surface

sort_samples = False#
uniform_sampling = False#
number_of_samples = 1000#
bodies: typing_extensions.List[semantic_digital_twin.world_description.world_entity.Body]#
for_object: typing_extensions.Optional[semantic_digital_twin.world_description.world_entity.Body] = None#
highlight_used_surfaces: bool = False#
ground() pycram.datastructures.pose.PoseStamped#

Default specialized_designators which returns the first element of the iterator of this instance.

Returns:

A resolved location

Creates a probabilistic circuit that samples navigation poses on a surface defined by the given surface samples. The circuit will sample poses that are close to the surface samples and have the given link id as true. The circuit will also sample the x and y coordinates of the poses from a Gaussian distribution centered around the surface samples with a scale of 1.0.

Parameters:

surface_samples – A list of surface samples, each sample is a tuple of (x, y) coordinates.

Returns:

A ProbabilisticCircuit that samples navigation poses on the surface defined by the surface samples.

static _create_surface_event(body: semantic_digital_twin.world_description.world_entity.Body, search_space: semantic_digital_twin.world_description.shape_collection.BoundingBoxCollection, wall_bloat: float) typing_extensions.Optional[random_events.product_algebra.Event]#

Creates an event that describes the surface of the link we want to sample from. The surface event is constructed from the bounding box of the link, and the walls and doors are cut out to ensure that the target poses are not too close to walls or doors.

Parameters:
  • body – The link for which the surface event should be created.

  • search_space – The search space in which the surface event should be created.

  • wall_bloat – The amount by which the walls should be bloated to ensure the target poses are not too close

to walls or doors.

Returns:

An Event that describes the surface of the link, or None if the surface event is empty.

_create_navigation_space_event(free_space: semantic_digital_twin.world_description.graph_of_convex_sets.GraphOfConvexSets, body: semantic_digital_twin.world_description.world_entity.Body) typing_extensions.Optional[random_events.product_algebra.Event]#

Creates an event that describes the navigation space for the link we want to sample from. The navigation space is the free space around the link, which is used to sample navigation poses. The navigation space is constructed from the free space graph, which is a subgraph of the free space that is reachable from the target node, which is the node in the free space graph that is above the link.

Parameters:
  • free_space – The free space graph that is used to sample navigation poses.

  • body – The link for which the navigation space event should be created.

Returns:

An Event that describes the navigation space for the link, or None if the navigation space event is empty.

Creates a distribution for the given link, which is a probabilistic circuit that samples navigation poses on the surface of the link. The distribution is conditioned on the navigation space event, which is the free space around the link, and the surface event, which is the surface of the link we want to sample from.

Parameters:

body – The link for which the distribution should be created.

Returns:

A tuple containing the conditioned link circuit and the probability of the condition.

static _calculate_surface_z_coord(test_robot: semantic_digital_twin.robots.abstract_robot.AbstractRobot, surface_coords: typing_extensions.Tuple[float, float]) typing_extensions.Optional[float]#

Calculates the z-coordinate of the surface at the given surface coordinates on the link.

Parameters:
  • test_robot – The robot that is used to test the surface coordinates.

  • surface_coords – The coordinates on the surface where the z-coordinate should be calculated.

Returns:

The z-coordinate of the surface at the given surface coordinates, or None if the link is not hit.

__iter__() typing_extensions.Iterator[pycram.datastructures.pose.PoseStamped]#

Creates a costmap on top of a link of an Object and creates positions from it. If there is a specific Object for which the position should be found, a height offset will be calculated which ensures that the bottom of the Object is at the position in the Costmap and not the origin of the Object which is usually in the centre of the Object.

Yield:

A PoseStamped with the found valid position of the Costmap.

class pycram.designators.location_designator.ProbabilisticCostmapLocation(target: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, semantic_digital_twin.world_description.world_entity.Body], reachable_for: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[semantic_digital_twin.robots.abstract_robot.AbstractRobot], semantic_digital_twin.robots.abstract_robot.AbstractRobot]] = None, visible_for: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[semantic_digital_twin.robots.abstract_robot.AbstractRobot], semantic_digital_twin.robots.abstract_robot.AbstractRobot]] = None, reachable_arm: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[pycram.datastructures.enums.Arms], pycram.datastructures.enums.Arms]] = None, ignore_collision_with: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[semantic_digital_twin.world_description.world_entity.Body], semantic_digital_twin.world_description.world_entity.Body]] = None, grasp_descriptions: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[pycram.datastructures.grasp.GraspDescription], pycram.datastructures.grasp.GraspDescription]] = None, object_in_hand: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[semantic_digital_twin.world_description.world_entity.Body], semantic_digital_twin.world_description.world_entity.Body]] = None, rotation_agnostic: bool = False, number_of_samples: int = 300, costmap_resolution: float = 0.1)#

Bases: pycram.designator.LocationDesignatorDescription

Uses Costmaps to create locations for complex constrains. The construction of the probabilistic circuit can be quite time-consuming, but the majority of the computational load is done during the first iteration only. In this case the exact time is highly dependent on the number of links in the world.

target_x#

Variable representing the x coordinate of the target pose

target_y#

Variable representing the y coordinate of the target pose

number_of_samples = 300#
costmap_resolution = 0.05#
target: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, semantic_digital_twin.world_description.world_entity.Body]#
reachable_for: semantic_digital_twin.robots.abstract_robot.AbstractRobot = None#
visible_for: semantic_digital_twin.robots.abstract_robot.AbstractRobot = None#
reachable_arm: typing_extensions.Optional[pycram.datastructures.enums.Arms] = None#
ignore_collision_with = None#
grasps: typing_extensions.List[typing_extensions.Optional[pycram.datastructures.enums.Grasp]] = None#
ground() pycram.datastructures.pose.PoseStamped#

Default specialized_designators which returns the first element of the iterator of this instance.

Returns:

A resolved location

static _calculate_room_event(world: semantic_digital_twin.world.World, free_space_graph: semantic_digital_twin.world_description.graph_of_convex_sets.GraphOfConvexSets, target_position: pycram.datastructures.pose.Vector3) random_events.product_algebra.Event#

Calculates an event for the free space inside the room around the target position is located in, in 2d.

Parameters:
  • world – The current world

  • free_space_graph – The free space graph that is used as basis for the room calculation

  • target_position – The position of the target in the world

Returns:

An Event that describes the room around the target position in 2d

_create_free_space_conditions(world: semantic_digital_twin.world.World, target_position: pycram.datastructures.pose.Vector3, search_distance: float = 1.5) typing_extensions.Tuple[random_events.product_algebra.Event, random_events.product_algebra.Event, random_events.product_algebra.Event]#

Creates the conditions for the free space around the target position. 1. reachable_space_condition: The condition that describes the reachable space around the target position in 3d 2. navigation_space_condition: The condition that describes the navigation space around the target position in 2d 3. room_condition: The condition that describes the room around the target position in 2d

Parameters:
  • world – The current world

  • target_position – The position of the target in the world

  • search_distance – The distance around the target position to search for free space, defaults to 1.5 meters

Returns:

A tuple containing the reachable space condition, navigation space condition and room condition

_create_navigation_circuit(target_position: pycram.datastructures.pose.Vector3) probabilistic_model.probabilistic_circuit.rx.probabilistic_circuit.ProbabilisticCircuit#

Creates a probabilistic circuit that samples navigation poses around the target position.

__iter__() typing_extensions.Iterator[pycram.datastructures.pose.PoseStamped]#

Creates a costmap on top of a link of an Object and creates positions from it. If there is a specific Object for which the position should be found, a height offset will be calculated which ensures that the bottom of the Object is at the position in the Costmap and not the origin of the Object which is usually in the centre of the Object.

Yield:

An instance of ProbabilisticSemanticLocation.Location with the found valid position of the Costmap.