pycram.external_interfaces.ik#
Functions#
|
Generates an ik request message for the kdl_ik_service. The message is |
|
Sends a request to the kdl_ik_service and returns the solution. |
Checks if the robot can reach a given position with a specific grasp orientation. |
|
Applies the orientation of a grasp to a given pose. This is done by using the grasp orientation |
|
|
Tries to reach a given position with a given robot. This is done by calculating the inverse kinematics. |
|
Top-level method to request ik solution for a given pose. This method will check if the giskard node is running |
|
Top-level method to request ik solution for a given pose. Before calling the ik service the links directly before |
|
Calls giskard in projection mode and queries the ik solution for a full body ik solution. This method will |
|
Calls the pinocchio ik solver to calculate the ik solution for a given target link and pose. |
Module Contents#
- pycram.external_interfaces.ik._make_request_msg(root_link: str, tip_link: str, target_pose: pycram.datastructures.pose.PoseStamped, robot_object: pycram.world_concepts.world_object.Object, joints: typing_extensions.List[str]) moveit_msgs.msg.PositionIKRequest#
Generates an ik request message for the kdl_ik_service. The message is of the type moveit_msgs/PositionIKRequest and contains all information contained in the parameter.
- Parameters:
root_link – The first link of the chain of joints to be altered
tip_link – The last link of the chain of joints to be altered
target_pose – Target pose for which the message should be created
robot_object – The robot for which the ik should be generated
joints – A list of joint names between the root_link and tip_link that should be altered.
- Returns:
A moveit_msgs/PositionIKRequest message containing all the information from the parameter
- pycram.external_interfaces.ik.call_ik(root_link: str, tip_link: str, target_pose: pycram.datastructures.pose.PoseStamped, robot_object: pycram.world_concepts.world_object.Object, joints: typing_extensions.List[str]) typing_extensions.List[float]#
Sends a request to the kdl_ik_service and returns the solution. Note that the robot in robot_object should be identical to the robot description uploaded to the parameter server. Furthermore, note that the root_link and tip_link are the links attached to the first and last joints in the joints list.
- Parameters:
root_link – The first link of the chain of joints to be altered
tip_link – The last link in the chain of joints to be altered
target_pose – The target pose in frame of root link second is the orientation as quaternion in world coordinate frame
robot_object – The robot object for which the ik solution should be generated
joints – A list of joint name that should be altered
- Returns:
The solution that was generated as a list of joint values corresponding to the order of joints given
- pycram.external_interfaces.ik.try_to_reach_with_grasp(pose_or_object: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, pycram.world_concepts.world_object.Object], prospection_robot: pycram.world_concepts.world_object.Object, gripper_name: str, grasp_quaternion: typing_extensions.List[float]) typing_extensions.Union[pycram.datastructures.pose.PoseStamped, None]#
Checks if the robot can reach a given position with a specific grasp orientation. To determine this the inverse kinematics are calculated and applied.
- Parameters:
pose_or_object – The position and rotation or Object for which reachability should be checked or an Object
prospection_robot – The robot that should reach for the position
gripper_name – The name of the end effector
grasp_quaternion – The orientation of the grasp
- pycram.external_interfaces.ik.apply_grasp_orientation_to_pose(grasp_orientation: typing_extensions.List[float], pose: pycram.datastructures.pose.PoseStamped) pycram.datastructures.pose.PoseStamped#
Applies the orientation of a grasp to a given pose. This is done by using the grasp orientation of the given grasp and applying it to the given pose.
- Parameters:
grasp_orientation – The orientation of the grasp
pose – The pose to which the grasp orientation should be applied
- pycram.external_interfaces.ik.try_to_reach(pose_or_object: typing_extensions.Union[pycram.datastructures.pose.PoseStamped, pycram.world_concepts.world_object.Object], prospection_robot: pycram.world_concepts.world_object.Object, gripper_name: str) typing_extensions.Union[pycram.datastructures.pose.PoseStamped, None]#
Tries to reach a given position with a given robot. This is done by calculating the inverse kinematics.
- Parameters:
pose_or_object – The position and rotation or Object for which reachability should be checked.
prospection_robot – The robot that should be used to check for reachability, should be the one in the prospection world
gripper_name – Name of the gripper tool frame
- Returns:
The pose at which the robot should stand or None if the target is not reachable
- pycram.external_interfaces.ik.request_ik(target_pose: pycram.datastructures.pose.PoseStamped, robot: pycram.world_concepts.world_object.Object, joints: typing_extensions.List[str], gripper: str) typing_extensions.Tuple[pycram.datastructures.pose.PoseStamped, typing_extensions.Dict[str, float]]#
Top-level method to request ik solution for a given pose. This method will check if the giskard node is running and if so will call the giskard service. If the giskard node is not running the kdl_ik_service will be called.
- Parameters:
target_pose – Pose of the end-effector for which an ik solution should be found
robot – The robot object which should be used
joints – A list of joints that should be used in computation, this is only relevant for the kdl_ik_service
gripper – Name of the tool frame which should grasp, this should be at the end of the given joint chain
- Returns:
A Pose at which the robt should stand as well as a dictionary of joint values
- pycram.external_interfaces.ik.request_kdl_ik(target_pose: pycram.datastructures.pose.PoseStamped, robot: pycram.world_concepts.world_object.Object, joints: typing_extensions.List[str], gripper: str) typing_extensions.Dict[str, float]#
Top-level method to request ik solution for a given pose. Before calling the ik service the links directly before and after the joint chain will be queried and the target_pose will be transformed into the frame of the root_link. Afterward, the offset between the tip_link and end effector will be calculated and taken into account. Lastly the ik service is called and the result returned
- Parameters:
target_pose – Pose for which an ik solution should be found
robot – Robot object which should be used
joints – List of joints that should be used in computation
gripper – Name of the gripper which should grasp, this should be at the end of the given joint chain
- Returns:
A list of joint values
- pycram.external_interfaces.ik.request_giskard_ik(target_pose: pycram.datastructures.pose.PoseStamped, robot: pycram.world_concepts.world_object.Object, gripper: str) typing_extensions.Tuple[pycram.datastructures.pose.PoseStamped, typing_extensions.Dict[str, float]]#
Calls giskard in projection mode and queries the ik solution for a full body ik solution. This method will try to drive the robot directly to a pose from which the target_pose is reachable for the end effector. If there are obstacles in the way this method will fail. In this case please use the GiskardLocation designator.
- Parameters:
target_pose – Pose at which the end effector should be moved.
robot – Robot object which should be used.
gripper – Name of the tool frame which should grasp, this should be at the end of the given joint chain.
- Returns:
A list of joint values.
- pycram.external_interfaces.ik.request_pinocchio_ik(target_pose: pycram.datastructures.pose.PoseStamped, robot: pycram.world_concepts.world_object.Object, target_link: str, joints: typing_extensions.List[str]) typing_extensions.Dict[str, float]#
Calls the pinocchio ik solver to calculate the ik solution for a given target link and pose.
- Parameters:
target_link – The target link for which the ik solution should be calculated
target_pose – The target pose for which the ik solution should be calculated
robot – The robot object for which the ik solution should be calculated
joints – The joints that should be used in the calculation
- Returns:
A dictionary containing the joint names and joint values