mani_skill.agents.controllers.utils.kinematics ============================================== .. py:module:: mani_skill.agents.controllers.utils.kinematics .. autoapi-nested-parse:: Code for kinematics utilities on CPU/GPU Classes ------- .. autoapisummary:: mani_skill.agents.controllers.utils.kinematics.Kinematics Module Contents --------------- .. py:class:: Kinematics(urdf_path, end_link_name, articulation, active_joint_indices) .. py:method:: _setup_cpu() setup the kinematics solvers on the CPU .. py:method:: _setup_gpu() setup the kinematics solvers on the GPU .. py:method:: compute_ik(pose, q0, is_delta_pose = False, current_pose = None, solver_config = dict(type='levenberg_marquardt', solver_iterations=1, alpha=1.0)) 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. :param pose: target pose in the world frame. Note this is not relative to the robot base frame! :type pose: Pose :param q0: initial joint positions of each active joint in the articulation. Note that this function will mask out the joints that are not kinematically relevant. :type q0: torch.Tensor :param is_delta_pose: 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. :type is_delta_pose: bool :param current_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. :type current_pose: Optional[Pose] :param solver_config: 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. :type solver_config: dict .. py:attribute:: _kinematic_chain_joint_names .. py:attribute:: _kinematic_chain_link_names .. py:attribute:: active_ancestor_joints .. py:attribute:: active_joint_indices .. py:attribute:: articulation .. py:attribute:: device .. py:attribute:: end_link .. py:attribute:: urdf_path