Class JacobianIKSolverPtr


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

      • JacobianIKSolverPtr

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

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

        public JacobianIKSolverPtr​(JacobianIKSolver ptr)
        Do not take ownership of ptr.

        ptr can be null.

        The constructor is implicit on purpose.
    • Method Detail

      • delete

        public void delete()
      • 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
      • setInterpolatorStep

        public void setInterpolatorStep​(double interpolatorStep)
        sets the maximal step length that is allowed on the
        local search towards the solution.
        Parameters:
        interpolatorStep - [in] the interpolation step.
      • setEnableInterpolation

        public void setEnableInterpolation​(boolean enableInterpolation)
        the solver may fail or be very slow if the the solution is too far from the
        initial configuration. This function enables the use of via points generated using
        an interpolation from initial end effector configuration to the goal target.
        Parameters:
        enableInterpolation - [in] set true to enable interpolation, false otherwise
      • solveLocal

        public boolean solveLocal​(Transform3D bTed,
                                  double maxError,
                                  State state,
                                  int maxIter)
        performs a local search toward 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
      • setClampToBounds

        public void setClampToBounds​(boolean enableClamping)
        enables clamping of the solution such that solution always is within joint limits
        Parameters:
        enableClamping - [in] true to enable clamping, false otherwise
      • setSolverType

        public void setSolverType​(JacobianIKSolver.JacobianSolverType type)
        set the type of solver to use for stepping toward a solution
        Parameters:
        type - [in] the type of jacobian solver
      • setWeightVector

        public void setWeightVector​(SWIGTYPE_p_Eigen__VectorXd weights)
        setWeightVector sets the weight vector used for solver type "Weighted"
        Parameters:
        weights - a vector of weights for each degree of freedom, ie weights.size() == DOF
      • setWeightVector

        public void setWeightVector​(vector_d weights)
        setWeightVector sets the weight vector used for solver type "Weighted"
        Parameters:
        weights - a vector of weights for each degree of freedom, ie weights.size() == DOF
      • setJointLimitTolerance

        public void setJointLimitTolerance​(double tolerance)
        setJointLimitTolerance set the tolerance used for bound-checking the solution
        Parameters:
        tolerance - for joint bounds checking
      • setCheckJointLimits

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