Class CCDSolver


  • public class CCDSolver
    extends IterativeIK
    This inverse kinematics method is a heuristic search technique called
    the Cyclic-Coordinate Descent method. The method attempts to minimize position
    and orientation errors by varying individual joints at a time.

    Notice that the CCDSolver only work on devices with 1-dof joints.
    • Constructor Detail

      • CCDSolver

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

      • getCPtr

        public static long getCPtr​(CCDSolver obj)
      • setMaxLocalStep

        public void setMaxLocalStep​(double quatlength)
        Sets the maximal size of a local step
        Parameters:
        quatlength - [in] Maximal length for quartenion
      • solve

        public VectorQ solve​(Transform3D baseTend,
                             State state)


        Example:

        CCDAlgorithm r;

        r.inverseKinematics(device, Ttarget);
        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.
      • solveLocal

        public boolean solveLocal​(Transform3D bTed,
                                  double maxError,
                                  State state,
                                  int maxIter)
        performs a local search toward the the target bTed. No via points
        are generated to support the convergence and robustness.
        Parameters:
        bTed - [in] the target end pose
        maxError - [in] the maximal allowed error
        state - [in/out] the starting position for the search. The end position will
        also be saved in this state.
        maxIter - [in] max number of iterations
        Returns:
        true if error is below max error
        Note: the result will be saved in state
      • 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.