pycram.external_interfaces.pinocchio_ik
=======================================

.. py:module:: pycram.external_interfaces.pinocchio_ik


Functions
---------

.. autoapisummary::

   pycram.external_interfaces.pinocchio_ik.create_joint_configuration
   pycram.external_interfaces.pinocchio_ik.compute_ik
   pycram.external_interfaces.pinocchio_ik.inverse_kinematics_logarithmic
   pycram.external_interfaces.pinocchio_ik.inverse_kinematics_translation
   pycram.external_interfaces.pinocchio_ik.parse_configuration_vector_to_joint_positions
   pycram.external_interfaces.pinocchio_ik.clip_joints_to_limits


Module Contents
---------------

.. py:function:: create_joint_configuration(robot: pycram.world_concepts.world_object.Object, model) -> numpy.ndarray[float]

   Create a joint configuration vector (q) from the current joint positions of the robot.

   :param robot: The robot object.
   :param model: The Pinocchio model.
   :return: The joint configuration vector.


.. py:function:: compute_ik(target_link: str, target_pose: pycram.datastructures.pose.PoseStamped, robot: pycram.world_concepts.world_object.Object) -> typing_extensions.Dict[str, float]

   Compute the inverse kinematics for a given target link and pose.

   :param target_link: The target link.
   :param target_pose: The target pose.
   :param robot: The robot object.
   :return: The joint configuration as a dictionary with joint names and joint values.


.. py:function:: inverse_kinematics_logarithmic(model, configuration, data, target_joint_id, target_transformation, eps=0.0001, max_iter=1000, dt=0.1, damp=1e-12) -> typing_extensions.Tuple[numpy.ndarray[float], bool]

   Compute the inverse kinematics for a given target transformation. Using a logarithmic error metric.

   :param model: The Pinocchio model.
   :param configuration: The initial joint configuration.
   :param data: The Pinocchio data.
   :param target_joint_id: The target joint ID.
   :param target_transformation: The target transformation.
   :param eps: The error threshold.
   :param max_iter: The maximum number of iterations.
   :param dt: The time step.
   :param damp: The damping factor.
   :return: The final joint configuration and a boolean indicating if the computation was successful.


.. py:function:: inverse_kinematics_translation(model, configuration, data, target_joint_id, target_transformation, eps=0.0001, max_iter=1000, dt=0.1, damp=1e-12) -> typing_extensions.Tuple[numpy.ndarray[float], bool]

   Compute the inverse kinematics for a given target transformation. Using the distance of the translation as error metric.

   :param model: The Pinocchio model.
   :param configuration: The initial joint configuration.
   :param data: The Pinocchio data.
   :param target_joint_id: The target joint ID.
   :param target_transformation: The target transformation.
   :param eps: The error threshold.
   :param max_iter: The maximum number of iterations.
   :param dt: The time step.
   :param damp: The damping factor.
   :return: The final joint configuration and a boolean indicating if the computation was successful.


.. py:function:: parse_configuration_vector_to_joint_positions(configuration: numpy.ndarray[float], model) -> typing_extensions.Dict[str, float]

   Takes the configuration vector from pinocchio and the robot model and returns a dictionary with joint names and
   joint values.

   :param configuration: The configuration vector.
   :param model: The robot model.
   :return: The joint configuration as a dictionary with joint names and joint values.


.. py:function:: clip_joints_to_limits(joint_positions: typing_extensions.List[float], lower_limits: typing_extensions.List[float], upper_limits: typing_extensions.List[float]) -> numpy.ndarray[float]

   Clip the joint positions to the joint limits.

   :param joint_positions: The joint positions to clip.
   :param lower_limits: A List of lower joint limits.
   :param upper_limits: A List of upper joint limits.
   :return: The clipped joint positions.


