Class InvKinSolver

  • Direct Known Subclasses:
    AmbiguityResolver, ClosedFormIK, IterativeIK

    public class InvKinSolver
    extends java.lang.Object
    Interface for inverse kinematics algorithms

    The InvKinSolver interface provides an interface for calculating
    the inverse kinematics of a device. That is to calculate
    \mathbf{q} such that \robabx{base}{end}{\mathbf{T}}(\mathbf{q})= \robabx{}{desired}{\mathbf{T}}.

    By default it solves the problem beginning at the robot base and
    ending with the frame defined as the end of the devices, and which is
    accessible through the Device::getEnd() method.
    • Constructor Summary

      Constructors 
      Constructor Description
      InvKinSolver​(long cPtr, boolean cMemoryOwn)  
    • Method Summary

      All Methods Static Methods Instance Methods Concrete Methods 
      Modifier and Type Method Description
      void delete()  
      static long getCPtr​(InvKinSolver obj)  
      FrameCPtr getTCP()
      Returns the Tool Center Point (TCP) used when solving the IK problem.

      void setCheckJointLimits​(boolean check)
      Specifies whether to check joint limits before returning a solution.

      VectorQ solve​(Transform3D baseTend, State state)
      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.
      • Methods inherited from class java.lang.Object

        equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
    • Constructor Detail

      • InvKinSolver

        public InvKinSolver​(long cPtr,
                            boolean cMemoryOwn)
    • Method Detail

      • getCPtr

        public static long getCPtr​(InvKinSolver obj)
      • delete

        public void delete()
      • solve

        public VectorQ solve​(Transform3D baseTend,
                             State state)
        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) )

        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.
      • setCheckJointLimits

        public void setCheckJointLimits​(boolean check)
        Specifies whether to check joint limits before returning a solution.

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

        public FrameCPtr getTCP()
        Returns the Tool Center Point (TCP) used when solving the IK problem.

        Returns:
        The TCP Frame used when solving the IK.