Class IKMetaSolver


  • public class IKMetaSolver
    extends IterativeIK
    Solve the inverse kinematics problem with respect to joint limits and
    collisions.

    Given an arbitrary iterative inverse kinematics solver, the IKMetaSolver
    attempts to find a collision free solution satisfying joint limits. It
    repeatingly calls the iterative solver with new random start configurations
    until either a solution is found or a specified max attempts has been
    reached.
    • Constructor Detail

      • IKMetaSolver

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

      • getCPtr

        public static long getCPtr​(IKMetaSolver obj)
      • solve

        public VectorQ solve​(Transform3Dd baseTend,
                             State state)
        Calculates the inverse kinematics

        Given a desired transformation
        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.

        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.

        Searches for a valid solution using the parameters set in the IKMetaSolver
      • setMaxAttempts

        public void setMaxAttempts​(long maxAttempts)
        Sets up the maximal number of attempts

        Parameters:
        maxAttempts - [in] Maximal number of attempts
      • setStopAtFirst

        public void setStopAtFirst​(boolean stopAtFirst)
        Sets whether to stop searching after the first solution

        Parameters:
        stopAtFirst - [in] True to stop after first solution has been found
      • setProximityLimit

        public void setProximityLimit​(double limit)
        Sets the distance for which two solutions are considered the same.

        For distance measure an infinite norm is used. Default value is set to 1e-5.

        Set limit < 0 to allow doublets in the solution.

        Parameters:
        limit - [in] The proximity limit.
      • setCheckJointLimits

        public void setCheckJointLimits​(boolean check)
        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.
      • solve

        public VectorQ solve​(Transform3Dd baseTend,
                             State state,
                             long cnt,
                             boolean stopatfirst)
        Solves the inverse kinematics problem

        Tries to solve the inverse kinematics problem using the iterative
        inverse kinematics solver provided in the constructor. It tries at
        most cnt times and can either be stopped after the first solution
        is found or continue to search for solutions. If multiple solutions
        are returned there might be duplicates in the list.

        Parameters:
        baseTend - [in] Desired base to end transform
        state - [in] State of the workcell
        cnt - [in] Maximal number of attempts

        stopatfirst - [in] If true the method will return after the first
        solution is found. If false it will continue searching for more solution
        until the maximal number of attemps is met.