Class IKMetaSolverPtr


  • public class IKMetaSolverPtr
    extends java.lang.Object
    Ptr stores a pointer and optionally takes ownership of the value.
    • Constructor Summary

      Constructors 
      Constructor Description
      IKMetaSolverPtr()
      Default constructor yielding a NULL-pointer.
      IKMetaSolverPtr​(long cPtr, boolean cMemoryOwn)  
      IKMetaSolverPtr​(IKMetaSolver ptr)
      Do not take ownership of ptr.

      ptr can be null.

      The constructor is implicit on purpose.
    • Method Summary

      All Methods Static Methods Instance Methods Concrete Methods 
      Modifier and Type Method Description
      IKMetaSolver __ref__()
      Dereferencing operator.
      void delete()  
      IKMetaSolver deref()
      The pointer stored in the object.
      boolean equals​(IKMetaSolver p)  
      static long getCPtr​(IKMetaSolverPtr obj)  
      IKMetaSolver getDeref()
      Member access operator.
      double getMaxError()
      Returns the maximal error for a solution

      int getMaxIterations()
      Returns the maximal number of iterations
      PropertyMap getProperties()
      Returns the PropertyMap

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

      boolean isNull()
      checks if the pointer is null
      boolean isShared()
      check if this Ptr has shared ownership or none
      ownership
      IterativeIKPtr makeDefault​(DevicePtr device, State state)
      Default iterative inverse kinematics solver for a device and
      state.

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

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

      void setMaxError​(double maxError)
      Sets the maximal error for a solution

      The error between two transformations is defined as the maximum of infinite-norm
      of the positional error and the angular error encoded as EAA.

      void setMaxIterations​(int maxIterations)
      Sets the maximal number of iterations allowed

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

      For distance measure an infinite norm is used.
      void setStopAtFirst​(boolean stopAtFirst)
      Sets whether to stop searching after the first solution

      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.
      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.
      • Methods inherited from class java.lang.Object

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

      • IKMetaSolverPtr

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

        public IKMetaSolverPtr()
        Default constructor yielding a NULL-pointer.
      • IKMetaSolverPtr

        public IKMetaSolverPtr​(IKMetaSolver ptr)
        Do not take ownership of ptr.

        ptr can be null.

        The constructor is implicit on purpose.
    • Method Detail

      • delete

        public void delete()
      • deref

        public IKMetaSolver deref()
        The pointer stored in the object.
      • __ref__

        public IKMetaSolver __ref__()
        Dereferencing operator.
      • getDeref

        public IKMetaSolver getDeref()
        Member access operator.
      • isShared

        public boolean isShared()
        check if this Ptr has shared ownership or none
        ownership
        Returns:
        true if Ptr has shared ownership, false if it has no ownership.
      • isNull

        public boolean isNull()
        checks if the pointer is null
        Returns:
        Returns true if the pointer is null
      • 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) )

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

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

        public void setMaxError​(double maxError)
        Sets the maximal error for a solution

        The error between two transformations is defined as the maximum of infinite-norm
        of the positional error and the angular error encoded as EAA.

        Parameters:
        maxError - [in] the maxError. It will be assumed that maxError > 0
      • getMaxError

        public double getMaxError()
        Returns the maximal error for a solution

        Returns:
        Maximal error
      • setMaxIterations

        public void setMaxIterations​(int maxIterations)
        Sets the maximal number of iterations allowed

        Parameters:
        maxIterations - [in] maximal number of iterations
      • getMaxIterations

        public int getMaxIterations()
        Returns the maximal number of iterations
      • getProperties

        public PropertyMap getProperties()
        Returns the PropertyMap

        Returns:
        Reference to the PropertyMap
      • makeDefault

        public IterativeIKPtr makeDefault​(DevicePtr device,
                                          State state)
        Default iterative inverse kinematics solver for a device and
        state.

        Parameters:
        device - [in] Device for which to solve IK.
        state - [in] Fixed state for which IK is solved.
      • 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.