pycram.external_interfaces.ik
Module Contents
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 |
|
|
|
|
Top-level method to request ik solution for a given pose. Before calling the ik service the links directly before |
- pycram.external_interfaces.ik._make_request_msg(root_link: str, tip_link: str, target_pose: pycram.datastructures.pose.Pose, 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.Pose, 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.Pose, pycram.world_concepts.world_object.Object], prospection_robot: pycram.world_concepts.world_object.Object, gripper_name: str, grasp: str) typing_extensions.Union[pycram.datastructures.pose.Pose, 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 – The grasp type with which the object should be grasped
- pycram.external_interfaces.ik.apply_grasp_orientation_to_pose(grasp: str, pose: pycram.datastructures.pose.Pose) pycram.datastructures.pose.Pose
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 – The name 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.Pose, pycram.world_concepts.world_object.Object], prospection_robot: pycram.world_concepts.world_object.Object, gripper_name: str) typing_extensions.Union[pycram.datastructures.pose.Pose, None]
- pycram.external_interfaces.ik.request_ik(target_pose: pycram.datastructures.pose.Pose, robot: pycram.world_concepts.world_object.Object, joints: typing_extensions.List[str], gripper: str) typing_extensions.List[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