Class ClosedFormIKSolverKukaIIWA


  • public class ClosedFormIKSolverKukaIIWA
    extends ClosedFormIK

    Analytical inverse solver for the Kuka LBR IIWA 7 R800 robot.

    Notice that this is a 7 DOF robot and that there is an infinite number of solutions.
    The extra DOF means that the middle joint of the robot is able to move in a circle.
    This solver will choose a point on this circle randomly and return up to 8 possible
    solutions.
    • Constructor Detail

      • ClosedFormIKSolverKukaIIWA

        public ClosedFormIKSolverKukaIIWA​(long cPtr,
                                          boolean cMemoryOwn)
      • ClosedFormIKSolverKukaIIWA

        public ClosedFormIKSolverKukaIIWA​(SerialDeviceCPtr device,
                                          State state)
        Construct new closed form solver for a Kuka 7 DOF IIWA robot.
        Parameters:
        device - [in] the device.
        state - [in] the state to get the frame structure and extract the dimensions from.
    • Method Detail

      • solve

        public VectorQ solve​(Transform3D baseTend,
                             State state)
        Description copied from class: InvKinSolver
        Calculates the inverse kinematics

        Given a desired \robabx{}{desired}{\mathbf{T}}
        and the current state, the method solves the inverse kinematics
        problem.

        If the algorithm is able to identify multiple solutions (e.g. elbow
        up and down) it will return all of these. Before returning a solution,
        they may be checked to be within the bounds of the configuration space.
        (See setCheckJointLimits(bool) )

        Overrides:
        solve in class InvKinSolver
        Parameters:
        baseTend - [in] Desired base to end transformation \robabx{}{desired}{\mathbf{T}}

        state - [in] State of the device from which to start the
        iterations

        Returns:
        List of solutions. Notice that the list may be empty.

        Note: The targets baseTend must be defined relative to the base of the
        robot/device.
      • solve

        public VectorQ solve​(Transform3D baseTend,
                             State state,
                             Vector3D dir4)
        Find inverse kinematic solutions deterministically by pulling joint 4 as much in
        the given direction as possible.
        Parameters:
        baseTend - [in] Desired base to end transformation
        \robabx{}{desired}{\mathbf{T}}.
        state - [in] State of the device from which to start the iterations.
        dir4 - [in] unit vector giving the direction to pull joint 4 in (given in base
        coordinate system).
        Returns:
        List of up to 8 solutions. Notice that the list may be empty.
      • setCheckJointLimits

        public void setCheckJointLimits​(boolean check)
        Description copied from class: InvKinSolver
        Specifies whether to check joint limits before returning a solution.

        Overrides:
        setCheckJointLimits in class InvKinSolver
        Parameters:
        check - [in] If true the method should perform a check that joints are within
        bounds.
      • getTCP

        public FrameCPtr getTCP()
        Description copied from class: InvKinSolver
        Returns the Tool Center Point (TCP) used when solving the IK problem.

        Overrides:
        getTCP in class InvKinSolver
        Returns:
        The TCP Frame used when solving the IK.