pycram.designators.location_designator
======================================

.. py:module:: pycram.designators.location_designator


Classes
-------

.. autoapisummary::

   pycram.designators.location_designator.Location
   pycram.designators.location_designator.CostmapLocation
   pycram.designators.location_designator.AccessingLocation
   pycram.designators.location_designator.SemanticCostmapLocation


Module Contents
---------------

.. py:class:: Location(pose: pycram.datastructures.pose.PoseStamped)

   Bases: :py:obj:`pycram.designator.LocationDesignatorDescription`


   Default location designator which only wraps a pose.


   .. py:attribute:: pose
      :type:  pycram.datastructures.pose.PoseStamped


   .. py:method:: ground() -> pycram.datastructures.pose.PoseStamped

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

      :return: A resolved designator



.. py:class:: CostmapLocation(target: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, pycram.world_concepts.world_object.Object], reachable_for: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[pycram.world_concepts.world_object.Object], pycram.world_concepts.world_object.Object]] = None, visible_for: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[pycram.world_concepts.world_object.Object], pycram.world_concepts.world_object.Object]] = 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[pycram.world_concepts.world_object.Object], pycram.world_concepts.world_object.Object]] = None, grasp_descriptions: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[pycram.datastructures.pose.GraspDescription], pycram.datastructures.pose.GraspDescription]] = None, object_in_hand: typing_extensions.Optional[typing_extensions.Union[typing_extensions.Iterable[pycram.world_concepts.world_object.Object], pycram.world_concepts.world_object.Object]] = None)

   Bases: :py:obj:`pycram.designator.LocationDesignatorDescription`


   Uses Costmaps to create locations for complex constrains


   .. py:attribute:: target
      :type:  typing_extensions.Union[pycram.datastructures.pose.PoseStamped, pycram.world_concepts.world_object.Object]


   .. py:attribute:: reachable_for
      :type:  pycram.world_concepts.world_object.Object
      :value: None



   .. py:attribute:: visible_for
      :type:  pycram.world_concepts.world_object.Object
      :value: None



   .. py:attribute:: reachable_arm
      :type:  typing_extensions.Optional[pycram.datastructures.enums.Arms]
      :value: None



   .. py:attribute:: ignore_collision_with
      :value: None



   .. py:attribute:: grasps
      :type:  typing_extensions.List[typing_extensions.Optional[pycram.datastructures.enums.Grasp]]
      :value: None



   .. py:method:: ground() -> pycram.datastructures.pose.PoseStamped

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

      :return: A resolved location



   .. py:method:: setup_costmaps(target: pycram.datastructures.pose.PoseStamped, robot: pycram.world_concepts.world_object.Object, visible_for, reachable_for) -> pycram.costmaps.Costmap
      :staticmethod:


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





   .. py:method:: create_target_sequence(grasp_description: pycram.datastructures.pose.GraspDescription, target: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, pycram.world_concepts.world_object.Object], robot: pycram.world_concepts.world_object.Object, object_in_hand: pycram.world_concepts.world_object.Object, reachable_arm: pycram.datastructures.enums.Arms) -> typing_extensions.List[pycram.datastructures.pose.PoseStamped]
      :staticmethod:


      Creates a sequence of poses which need to be reachable in this order

      :param grasp_description: Grasp description to be used for grasping
      :param target: The target of reachability, either a pose or an object
      :param robot: The robot that should be checked for reachability
      :param object_in_hand: An object that is held if any
      :param reachable_arm: The arm which should be checked for reachability
      :return: A list of poses that need to be reachable in this order



   .. py:method:: create_allowed_collisions(ignore_collision_with: typing_extensions.List[pycram.world_concepts.world_object.Object], object_in_hand: pycram.world_concepts.world_object.Object) -> typing_extensions.Dict[pycram.world_concepts.world_object.Object, str]
      :staticmethod:


      Creates a dict of object which are allowed to collide with the robot without impacting reachability

      :param ignore_collision_with: List of objects for which collision should be ignored
      :param object_in_hand: An object that the robot might hold
      :return: A dict of objects that link to their names



   .. py:method:: __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
         



.. py:class:: AccessingLocation(handle: typing_extensions.Union[pycram.object_descriptors.urdf.ObjectDescription.Link, typing_extensions.Iterable[pycram.object_descriptors.urdf.ObjectDescription.Link]], robot_desig: typing_extensions.Union[pycram.world_concepts.world_object.Object, typing_extensions.Iterable[pycram.world_concepts.world_object.Object]], arm: typing_extensions.Union[typing_extensions.List[pycram.datastructures.enums.Arms], pycram.datastructures.enums.Arms] = None, prepose_distance: float = ActionConfig.grasping_prepose_distance)

   Bases: :py:obj:`pycram.designator.LocationDesignatorDescription`


   Location designator which describes poses used for opening drawers


   .. py:attribute:: handle
      :type:  pycram.object_descriptors.urdf.ObjectDescription.Link


   .. py:attribute:: robot
      :type:  pycram.world_concepts.world_object.Object


   .. py:attribute:: prepose_distance


   .. py:attribute:: arm
      :value: None



   .. py:method:: ground() -> pycram.datastructures.pose.PoseStamped

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

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



   .. py:method:: 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)
      :staticmethod:


      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.

      :param cost_map: Costmap that should be adjusted.
      :param init_pose: Pose of the drawer/container when it is fully closed.
      :param goal_pose: Pose of the drawer/container when it is fully opened.
      :param width: Width of the drawer/container.



   .. py:method:: setup_costmaps(handle: pycram.world_concepts.world_object.Link) -> pycram.costmaps.Costmap

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



   .. py:method:: 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

      :param params_box:
      :param final_map:
      :return:



   .. py:method:: __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.



.. py:class:: SemanticCostmapLocation(link_name, part_of, for_object=None, edges_only: bool = False, horizontal_edges_only: bool = False, edge_size_in_meters: float = 0.06, height_offset: float = 0.0)

   Bases: :py:obj:`pycram.designator.LocationDesignatorDescription`


   Locations over semantic entities, like a table surface


   .. py:attribute:: link_name
      :type:  str


   .. py:attribute:: part_of
      :type:  pycram.world_concepts.world_object.Object


   .. py:attribute:: for_object
      :type:  typing_extensions.Optional[pycram.world_concepts.world_object.Object]
      :value: None



   .. py:attribute:: edges_only
      :type:  bool
      :value: False



   .. py:attribute:: horizontal_edges_only
      :type:  bool
      :value: False



   .. py:attribute:: edge_size_in_meters
      :type:  float
      :value: 0.06



   .. py:attribute:: sem_costmap
      :type:  typing_extensions.Optional[pycram.costmaps.SemanticCostmap]
      :value: None



   .. py:method:: ground() -> pycram.datastructures.pose.PoseStamped

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

      :return: A resolved location



   .. py:method:: __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.



