mani_skill.agents.controllers.utils.kinematics#
Code for kinematics utilities on CPU/GPU
Classes#
Module Contents#
- class mani_skill.agents.controllers.utils.kinematics.Kinematics(urdf_path, end_link_name, articulation, active_joint_indices)[source]#
- Parameters:
urdf_path (str) –
end_link_name (str) –
articulation (mani_skill.utils.structs.articulation.Articulation) –
active_joint_indices (torch.Tensor) –
- compute_ik(pose, q0, is_delta_pose=False, current_pose=None, solver_config=dict(type='levenberg_marquardt', solver_iterations=1, alpha=1.0))[source]#
Given a target pose, initial joint positions, this computes the target joint positions that will achieve the target pose. For optimization you can also provide the delta pose instead and specify is_delta_pose=True.
- Parameters:
pose (Pose) – target pose in the world frame. Note this is not relative to the robot base frame!
q0 (torch.Tensor) – initial joint positions of each active joint in the articulation. Note that this function will mask out the joints that are not kinematically relevant.
is_delta_pose (bool) – if True, the pose parameter should be a delta pose. It can also be a tensor of shape (N, 6) with the first 3 channels for translation and the last 3 channels for rotation in the euler angle format.
current_pose (Optional[Pose]) – current pose of the controlled link in the world frame. This is used to optimize the function by avoiding computing the current pose from q0 to compute the delta pose. If is_delta_pose is False, this is not used.
solver_config (dict) – configuration for the IK solver. Default is dict(type=”levenberg_marquardt”, alpha=1.0). type can be one of “levenberg_marquardt” or “pseudo_inverse”. alpha is a scaling term applied to the delta joint positions generated by the solver.