pycram.pose_generator_and_validator#

Classes#

PoseGenerator

Creates pose candidates from a given costmap.

Functions#

visibility_validator(→ bool)

This method validates if the robot can see the target position from a given

reachability_validator(...)

This method validates if a target position is reachable for the robot.

pose_sequence_reachability_validator(→ bool)

This method validates if a target sequence, if traversed in order, is reachable for the robot.

collision_check(robot, allowed_collision)

This method checks if a given robot collides with any object within the world

Module Contents#

class pycram.pose_generator_and_validator.PoseGenerator(costmap: pycram.costmaps.Costmap, number_of_samples=100, orientation_generator=None)#

Bases: typing_extensions.Iterable[pycram.datastructures.pose.PoseStamped]

Creates pose candidates from a given costmap. The generator selects the highest values, amount is given by number_of_sample, and returns the corresponding positions. Orientations are calculated such that the Robot faces the center of the costmap.

current_orientation_generator = None#

If no orientation generator is given, this generator is used to generate the orientation of the robot.

override_orientation_generator = None#

Override the orientation generator with a custom generator, which will be used regardless of the current_orientation_generator.

costmap#
number_of_samples = 100#
orientation_generator = None#
__iter__() typing_extensions.Iterator[pycram.datastructures.pose.PoseStamped]#

A generator that crates pose candidates from a given costmap. The generator selects the highest 100 values and returns the corresponding positions. Orientations are calculated such that the Robot faces the center of the costmap.

Yield:

A tuple of position and orientation

static height_generator() float#
static generate_orientation(position: typing_extensions.List[float], origin: pycram.datastructures.pose.PoseStamped) typing_extensions.List[float]#

This method generates the orientation for a given position in a costmap. The orientation is calculated such that the robot faces the origin of the costmap. This generation is done by simply calculating the arctan between the position, in the costmap, and the origin of the costmap.

Parameters:
  • position – The position in the costmap. This position is already converted to the world coordinate frame.

  • origin – The origin of the costmap. This is also the point which the robot should face.

Returns:

A quaternion of the calculated orientation

pycram.pose_generator_and_validator.visibility_validator(robot: pycram.world_concepts.world_object.Object, object_or_pose: typing_extensions.Union[pycram.world_concepts.world_object.Object, pycram.datastructures.pose.PoseStamped]) bool#

This method validates if the robot can see the target position from a given pose candidate. The target position can either be a position, in world coordinate system, or an object in the World. The validation is done by shooting a ray from the camera to the target position and checking that it does not collide with anything else.

Parameters:
  • robot – The robot object for which this should be validated

  • object_or_pose – The target position or object for which the pose candidate should be validated.

Returns:

True if the target is visible for the robot, None in any other case.

pycram.pose_generator_and_validator.reachability_validator(robot: pycram.world_concepts.world_object.Object, target_pose: pycram.datastructures.pose.PoseStamped, arm: pycram.datastructures.enums.Arms, allowed_collision: typing_extensions.Dict[pycram.world_concepts.world_object.Object, typing_extensions.List] = None) typing_extensions.Optional[typing_extensions.Dict[str, float]]#

This method validates if a target position is reachable for the robot. This is done by asking the ik solver if there is a valid solution if the robot stands at the position of the pose candidate. if there is a solution the validator returns True and False in any other case.

Parameters:
  • robot – The robot object in the World for which the reachability should be validated.

  • target_pose – The target pose for which the reachability should be validated.

  • arm – The arm that should be checked for reachability.

  • allowed_collision – dict of objects with which the robot is allowed to collide each object correlates to a list of links of which this object consists

Returns:

The final joint states of the robot if the target pose is reachable without collision, None in any other case.

pycram.pose_generator_and_validator.pose_sequence_reachability_validator(robot: pycram.world_concepts.world_object.Object, target_sequence: typing_extensions.List[pycram.datastructures.pose.PoseStamped], arm: pycram.datastructures.enums.Arms, allowed_collision: typing_extensions.Dict[pycram.world_concepts.world_object.Object, typing_extensions.List] = None) bool#

This method validates if a target sequence, if traversed in order, is reachable for the robot. This is done by asking the ik solver if there is a valid solution if the robot stands at the position of the pose candidate. If there is a solution the validator returns The arm that can reach the target position and None in any other case.

Parameters:
  • robot – The robot object in the World for which the reachability should be validated.

  • target_sequence – The target sequence of poses for which the reachability should be validated.

  • arm – The arm that should be checked for reachability.

  • allowed_collision – dict of objects with which the robot is allowed to collide each object correlates to a list of links of which this object consists

Returns:

The arm that can reach the target position and None in any other case.

pycram.pose_generator_and_validator.collision_check(robot: pycram.world_concepts.world_object.Object, allowed_collision: typing_extensions.Dict[pycram.world_concepts.world_object.Object, typing_extensions.List])#

This method checks if a given robot collides with any object within the world which it is not allowed to collide with. This is done checking iterating over every object within the world and checking if the robot collides with it. Careful the floor will be ignored. If there is a collision with an object that was not within the allowed collision list the function will raise a RobotInCollision exception.

Parameters:
  • robot – The robot object in the (Bullet)World where it should be checked if it collides with something

  • allowed_collision – dict of objects with which the robot is allowed to collide each object correlates to a list of links of which this object consists

Raises:

RobotInCollision if the robot collides with an object it is not allowed to collide with.