pycram.external_interfaces.giskard#

Attributes#

Functions#

thread_safe(→ typing_extensions.Callable)

Adds thread safety to a function via a decorator. This uses the giskard_lock

init_giskard_interface(→ typing_extensions.Callable)

Checks if the ROS messages are available and if giskard is running, if that is the case the interface will be

initial_adding_objects(→ None)

Adds object that are loaded in the World to the Giskard belief state, if they are not present at the moment.

removing_of_objects(→ None)

Removes objects that are present in the Giskard belief state but not in the World from the Giskard belief state.

sync_worlds(→ None)

Synchronizes the World and the Giskard belief state, this includes adding and removing objects to the Giskard

update_pose(→ UpdateWorldResponse)

Sends an update message to giskard to update the object position. Might not work when working on the real robot just

spawn_object(→ None)

Spawns a World Object in the giskard belief state.

remove_object(→ UpdateWorldResponse)

Removes an object from the giskard belief state.

spawn_urdf(→ UpdateWorldResponse)

Spawns an URDF in giskard's belief state.

spawn_mesh(→ UpdateWorldResponse)

Spawns a mesh into giskard's belief state

_manage_par_motion_goals(...)

Manages multiple goals that should be executed in parallel. The current sequence of motion goals is saved and the

achieve_joint_goal(→ MoveResult)

Takes a dictionary of joint position that should be achieved, the keys in the dictionary are the joint names and

set_joint_goal(→ None)

Takes a dictionary of joint position that should be achieved, the keys in the dictionary are the joint names and

achieve_cartesian_goal(→ MoveResult)

Takes a cartesian position and tries to move the tip_link to this position using the chain defined by

achieve_straight_cartesian_goal(→ MoveResult)

Takes a cartesian position and tries to move the tip_link to this position in a straight line, using the chain

achieve_translation_goal(→ MoveResult)

Tries to move the tip_link to the position defined by goal_point using the chain defined by root_link and

achieve_straight_translation_goal(→ MoveResult)

Tries to move the tip_link to the position defined by goal_point in a straight line, using the chain defined by

achieve_rotation_goal(→ MoveResult)

Tries to bring the tip link into the rotation defined by quat using the chain defined by root_link and

achieve_align_planes_goal(→ MoveResult)

Tries to align the plane defined by tip normal with goal_normal using the chain between root_link and

achieve_open_container_goal(→ MoveResult)

Tries to open a container in an environment, this only works if the container was added as a URDF. This goal assumes

achieve_close_container_goal(→ MoveResult)

Tries to close a container, this only works if the container was added as a URDF. Assumes that the handle of the

achieve_cartesian_waypoints_goal(→ MoveResult)

Tries to achieve each waypoint in the given sequence of waypoints.

projection_cartesian_goal(→ MoveResult)

Tries to move the tip_link to the position defined by goal_pose using the chain defined by tip_link and root_link.

projection_cartesian_goal_with_approach(→ MoveResult)

Tries to achieve the goal_pose using the chain defined by tip_link and root_link. The approach_pose is used to drive

projection_joint_goal(→ MoveResult)

Tries to achieve the joint goal defined by goal_poses, the goal_poses are projected to the closest point on the

allow_gripper_collision(→ None)

Allows the specified gripper to collide with anything.

get_gripper_group_names(→ typing_extensions.List[str])

add_gripper_groups(→ None)

Add the gripper links as a group for collision avoidance.

avoid_all_collisions(→ None)

Will avoid all collision for the next goal.

allow_self_collision(→ None)

Will allow the robot collision with itself.

avoid_collisions(→ None)

Will avoid collision between the two objects for the next goal.

make_world_body(→ WorldBody)

Create a WorldBody message for a World Object. The WorldBody will contain the URDF of the World Object

make_point_stamped(→ PointStamped)

Creates a PointStamped message for the given position in world coordinate frame.

make_quaternion_stamped(→ QuaternionStamped)

Creates a QuaternionStamped message for the given quaternion.

make_vector_stamped(→ Vector3Stamped)

Creates a Vector3Stamped message, this is similar to PointStamped but represents a vector instead of a point.

Module Contents#

pycram.external_interfaces.giskard.giskard_wrapper = None#
pycram.external_interfaces.giskard.giskard_update_service = None#
pycram.external_interfaces.giskard.is_init = False#
pycram.external_interfaces.giskard.number_of_par_goals = 0#
pycram.external_interfaces.giskard.giskard_lock#
pycram.external_interfaces.giskard.giskard_rlock#
pycram.external_interfaces.giskard.par_threads#
pycram.external_interfaces.giskard.thread_safe(func: typing_extensions.Callable) typing_extensions.Callable#

Adds thread safety to a function via a decorator. This uses the giskard_lock

Parameters:

func – Function that should be thread safe

Returns:

A function with thread safety

pycram.external_interfaces.giskard.init_giskard_interface(func: typing_extensions.Callable) typing_extensions.Callable#

Checks if the ROS messages are available and if giskard is running, if that is the case the interface will be initialized.

Parameters:

func – Function this decorator should be wrapping

Returns:

A callable function which initializes the interface and then calls the wrapped function

pycram.external_interfaces.giskard.initial_adding_objects() None#

Adds object that are loaded in the World to the Giskard belief state, if they are not present at the moment.

pycram.external_interfaces.giskard.removing_of_objects() None#

Removes objects that are present in the Giskard belief state but not in the World from the Giskard belief state.

pycram.external_interfaces.giskard.sync_worlds(projection: bool = False) None#

Synchronizes the World and the Giskard belief state, this includes adding and removing objects to the Giskard belief state such that it matches the objects present in the World and moving the robot to the position it is currently at in the World.

Parameters:

projection – Whether the sync in projection mode or reality.

pycram.external_interfaces.giskard.update_pose(object: pycram.world_concepts.world_object.Object) UpdateWorldResponse#

Sends an update message to giskard to update the object position. Might not work when working on the real robot just in standalone mode.

Parameters:

object – Object that should be updated

Returns:

An UpdateWorldResponse

pycram.external_interfaces.giskard.spawn_object(object: pycram.world_concepts.world_object.Object) None#

Spawns a World Object in the giskard belief state.

Parameters:

object – World object that should be spawned

pycram.external_interfaces.giskard.remove_object(object: pycram.world_concepts.world_object.Object) UpdateWorldResponse#

Removes an object from the giskard belief state.

Parameters:

object – The World Object that should be removed

pycram.external_interfaces.giskard.spawn_urdf(name: str, urdf_path: str, pose: pycram.datastructures.pose.PoseStamped) UpdateWorldResponse#

Spawns an URDF in giskard’s belief state.

Parameters:
  • name – Name of the URDF

  • urdf_path – Path to the URDF file

  • pose – Pose in which the URDF should be spawned

Returns:

An UpdateWorldResponse message

pycram.external_interfaces.giskard.spawn_mesh(name: str, path: str, pose: pycram.datastructures.pose.PoseStamped) UpdateWorldResponse#

Spawns a mesh into giskard’s belief state

Parameters:
  • name – Name of the mesh

  • path – Path to the mesh file

  • pose – Pose in which the mesh should be spawned

Returns:

An UpdateWorldResponse message

pycram.external_interfaces.giskard._manage_par_motion_goals(goal_func, *args) typing_extensions.Optional[MoveResult]#

Manages multiple goals that should be executed in parallel. The current sequence of motion goals is saved and the parallel motion goal is loaded if there is one, then the new motion goal given by goal_func is added to the parallel motion goal. If this was the last motion goal for the parallel motion goal it is then executed.

Parameters:
  • goal_func – Function which adds a new motion goal to the giskard_wrapper

  • args – Arguments for the goal_func function

Returns:

MoveResult of the execution if there was an execution, True if a new motion goal was added to the giskard_wrapper and None in any other case

pycram.external_interfaces.giskard.achieve_joint_goal(goal_poses: typing_extensions.Dict[str, float]) MoveResult#

Takes a dictionary of joint position that should be achieved, the keys in the dictionary are the joint names and values are the goal joint positions.

Parameters:

goal_poses – Dictionary with joint names and position goals

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.set_joint_goal(goal_poses: typing_extensions.Dict[str, float]) None#

Takes a dictionary of joint position that should be achieved, the keys in the dictionary are the joint names and values are the goal joint positions.

Parameters:

goal_poses – Dictionary with joint names and position goals

pycram.external_interfaces.giskard.achieve_cartesian_goal(goal_pose: pycram.datastructures.pose.PoseStamped, tip_link: str, root_link: str, position_threshold: float = 0.02, orientation_threshold: float = 0.02, use_monitor: bool = True, grippers_that_can_collide: typing_extensions.Optional[pycram.datastructures.enums.Arms] = None) MoveResult#

Takes a cartesian position and tries to move the tip_link to this position using the chain defined by tip_link and root_link.

Parameters:
  • goal_pose – The position which should be achieved with tip_link

  • tip_link – The end link of the chain as well as the link which should achieve the goal_pose

  • root_link – The starting link of the chain which should be used to achieve this goal

  • position_threshold – Position distance at which the goal is successfully reached

  • orientation_threshold – Orientation distance at which the goal is successfully reached

  • use_monitor – Whether to use a monitor for this goal or not.

  • grippers_that_can_collide – The gripper(s) that should be allowed to collide.

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.achieve_straight_cartesian_goal(goal_pose: pycram.datastructures.pose.PoseStamped, tip_link: str, root_link: str, grippers_that_can_collide: typing_extensions.Optional[pycram.datastructures.enums.Arms] = None) MoveResult#

Takes a cartesian position and tries to move the tip_link to this position in a straight line, using the chain defined by tip_link and root_link.

Parameters:
  • goal_pose – The position which should be achieved with tip_link

  • tip_link – The end link of the chain as well as the link which should achieve the goal_pose

  • root_link – The starting link of the chain which should be used to achieve this goal

  • grippers_that_can_collide – The gripper(s) that should be allowed to collide.

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.achieve_translation_goal(goal_point: typing_extensions.List[float], tip_link: str, root_link: str) MoveResult#

Tries to move the tip_link to the position defined by goal_point using the chain defined by root_link and tip_link. Since goal_point only defines the position but no rotation, rotation is not taken into account.

Parameters:
  • goal_point – The goal position of the tip_link

  • tip_link – The link which should be moved to goal_point as well as the end of the used chain

  • root_link – The start link of the chain

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.achieve_straight_translation_goal(goal_point: typing_extensions.List[float], tip_link: str, root_link: str) MoveResult#

Tries to move the tip_link to the position defined by goal_point in a straight line, using the chain defined by root_link and tip_link. Since goal_point only defines the position but no rotation, rotation is not taken into account.

Parameters:
  • goal_point – The goal position of the tip_link

  • tip_link – The link which should be moved to goal_point as well as the end of the used chain

  • root_link – The start link of the chain

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.achieve_rotation_goal(quat: typing_extensions.List[float], tip_link: str, root_link: str) MoveResult#

Tries to bring the tip link into the rotation defined by quat using the chain defined by root_link and tip_link.

Parameters:
  • quat – The rotation that should be achieved, given as a quaternion

  • tip_link – The link that should be in the rotation defined by quat

  • root_link – The start link of the chain

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.achieve_align_planes_goal(goal_normal: typing_extensions.List[float], tip_link: str, tip_normal: typing_extensions.List[float], root_link: str) MoveResult#

Tries to align the plane defined by tip normal with goal_normal using the chain between root_link and tip_link.

Parameters:
  • goal_normal – The goal plane, given as a list of XYZ

  • tip_link – The end link of the chain that should be used.

  • tip_normal – The plane that should be aligned with goal_normal, given as a list of XYZ

  • root_link – The starting link of the chain that should be used.

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.achieve_open_container_goal(tip_link: str, environment_link: str) MoveResult#

Tries to open a container in an environment, this only works if the container was added as a URDF. This goal assumes that the handle was already grasped. Can only handle container with 1 DOF

Parameters:
  • tip_link – The End effector that should open the container

  • environment_link – The name of the handle for this container.

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.achieve_close_container_goal(tip_link: str, environment_link: str) MoveResult#

Tries to close a container, this only works if the container was added as a URDF. Assumes that the handle of the container was already grasped. Can only handle container with 1 DOF.

Parameters:
  • tip_link – Link name that should be used to close the container.

  • environment_link – Name of the handle

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.achieve_cartesian_waypoints_goal(waypoints: typing_extensions.List[pycram.datastructures.pose.PoseStamped], tip_link: str, root_link: str, enforce_final_orientation: bool = True) MoveResult#

Tries to achieve each waypoint in the given sequence of waypoints. If :param enforce_final_orientation is False, each waypoint needs a corresponding orientation. If it is True only the last waypoint needs to have an orientation.

Parameters:
  • waypoints – The sequence of waypoints as poses to achieve.

  • tip_link – The endeffector link of the chain that should be used.

  • root_link – The root link of the chain that should be used.

  • enforce_final_orientation – If true, only achieve the orientation of the last waypoint. If false, achieve the orientation of each waypoint.

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.projection_cartesian_goal(goal_pose: pycram.datastructures.pose.PoseStamped, tip_link: str, root_link: str) MoveResult#

Tries to move the tip_link to the position defined by goal_pose using the chain defined by tip_link and root_link. The goal_pose is projected to the closest point on the robot’s workspace.

Parameters:
  • goal_pose – The position which should be achieved with tip_link

  • tip_link – The end link of the chain as well as the link which should achieve the goal_pose

  • root_link – The starting link of the chain which should be used to achieve this goal

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.projection_cartesian_goal_with_approach(approach_pose: pycram.datastructures.pose.PoseStamped, goal_pose: pycram.datastructures.pose.PoseStamped, tip_link: str, root_link: str, robot_base_link: str) MoveResult#

Tries to achieve the goal_pose using the chain defined by tip_link and root_link. The approach_pose is used to drive the robot to a pose close the actual goal pose, the robot_base_link is used to define the base link of the robot.

Parameters:
  • approach_pose – Pose near the goal_pose

  • goal_pose – Pose to which the tip_link should be moved

  • tip_link – The link which should be moved to goal_pose, usually the tool frame

  • root_link – The start of the link chain which should be used for planning

  • robot_base_link – The base link of the robot

Returns:

A trajectory calculated to move the tip_link to the goal_pose

pycram.external_interfaces.giskard.projection_joint_goal(goal_poses: typing_extensions.Dict[str, float], allow_collisions: bool = False) MoveResult#

Tries to achieve the joint goal defined by goal_poses, the goal_poses are projected to the closest point on the robot’s workspace.

Parameters:
  • goal_poses – Dictionary with joint names and position goals

  • allow_collisions – If all collisions should be allowed for this goal

Returns:

MoveResult message for this goal

pycram.external_interfaces.giskard.allow_gripper_collision(gripper: pycram.datastructures.enums.Arms, at_goal: bool = False) None#

Allows the specified gripper to collide with anything.

Parameters:
  • gripper – The gripper which can collide, either ‘Arms.RIGHT’, ‘Arms.LEFT’ or ‘Arms.BOTH’

  • at_goal – If the collision should be allowed only for this motion goal.

pycram.external_interfaces.giskard.get_gripper_group_names() typing_extensions.List[str]#
Returns:

The list of groups that are registered in giskard which have ‘gripper’ in their name.

pycram.external_interfaces.giskard.add_gripper_groups() None#

Add the gripper links as a group for collision avoidance.

Returns:

Response of the RegisterGroup Service

pycram.external_interfaces.giskard.avoid_all_collisions() None#

Will avoid all collision for the next goal.

pycram.external_interfaces.giskard.allow_self_collision() None#

Will allow the robot collision with itself.

pycram.external_interfaces.giskard.avoid_collisions(object1: pycram.world_concepts.world_object.Object, object2: pycram.world_concepts.world_object.Object) None#

Will avoid collision between the two objects for the next goal.

Parameters:
  • object1 – The first World Object

  • object2 – The second World Object

pycram.external_interfaces.giskard.make_world_body(object: pycram.world_concepts.world_object.Object) WorldBody#

Create a WorldBody message for a World Object. The WorldBody will contain the URDF of the World Object

Parameters:

object – The World Object

Returns:

A WorldBody message for the World Object

pycram.external_interfaces.giskard.make_point_stamped(point: typing_extensions.List[float]) PointStamped#

Creates a PointStamped message for the given position in world coordinate frame.

Parameters:

point – XYZ coordinates of the point

Returns:

A PointStamped message

pycram.external_interfaces.giskard.make_quaternion_stamped(quaternion: typing_extensions.List[float]) QuaternionStamped#

Creates a QuaternionStamped message for the given quaternion.

Parameters:

quaternion – The quaternion as a list of xyzw

Returns:

A QuaternionStamped message

pycram.external_interfaces.giskard.make_vector_stamped(vector: typing_extensions.List[float]) Vector3Stamped#

Creates a Vector3Stamped message, this is similar to PointStamped but represents a vector instead of a point.

Parameters:

vector – The vector given as xyz in world frame

Returns:

A Vector3Stamped message