Class ClosedFormIKPtr


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

      • ClosedFormIKPtr

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

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

        public ClosedFormIKPtr​(ClosedFormIK 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 ClosedFormIK deref()
        The pointer stored in the object.
      • __ref__

        public ClosedFormIK __ref__()
        Dereferencing operator.
      • getDeref

        public ClosedFormIK 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
      • make

        public ClosedFormIKPtr make​(Device device,
                                    State state)
        Closed-form IK solver for a device.

        The device must be a serial device with 6 revolute joints described
        by DH parameters.

        The IK solver is currently implemented in terms of PieperSolver. See
        the documentation of PieperSolver for the specific requirements for
        the DH parameters.

        An exception is thrown if closed-form IK for the device is not
        supported, except that all such cases are currently not discovered.
        You should check for yourself that the closed-form IK for the device
        is correct.
      • solve

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

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