Class ParallelDeviceCPtr


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

      • ParallelDeviceCPtr

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

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

        public ParallelDeviceCPtr​(ParallelDevice 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 ParallelDevice deref()
        The pointer stored in the object.
      • 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
      • setQ

        public void setQ​(Q q,
                         State state)


        The configuration q is the configuration for the actuated joints
        of the parallel device. Based on the value of q the setQ() method
        automatically computes the values for the unactuated (passive)
        joints.
      • setQ

        public void setQ​(Q q,
                         vector_b enabled,
                         State state)
        Set only some of the actuated joints.

        This version of setQ will only set a subset of the actuated joints.
        Based on the value of
        q, the function will compute the values for the
        unactuated (passive) joints, and the remaining actuated joints.

        This is mainly useful for parallel devices that have more controlled joints
        than strictly required to make the kinematics determined.

        Parameters:
        q - [in] the configuration of the actuated joints
        (the only considered elements are the ones where the corresponding elements of enabled
        is true).
        enabled - [in] vector of same size as q, specifying which values to solve for.
        state - [in/out] the state with all active and passive joint values.
        The input state is expected to contain a valid and consistent configuration of the
        device.
      • getJunctions

        public VectorParallelDeviceLeg getJunctions()
        Get the junctions of the device.
        Returns:
        a vector of junctions. Each junction is given by a two or more legs.
      • getActiveJoints

        public VectorJoint_p getActiveJoints()
        The active joints of the parallel device.
      • getAllJoints

        public VectorJoint_p getAllJoints()
        Get all joints (both active and passive).
        Returns:
        a vector of all the joints.
      • getFullDOF

        public long getFullDOF()
        Get the total degrees of freedom for all (active and passive) joints in the
        device.
        Returns:
        the total degrees of freedom.
      • getAllBounds

        public PairQ getAllBounds()
        Get bounds for all joints (includes both active and passive joints).
        Returns:
        a pair with the lower and upper limits.
      • getFullQ

        public Q getFullQ​(State state)
        Get the full configuration vector of the device. This gives the complete state of
        the parallel device.
        Parameters:
        state - [in] the state that contains the full configuration.
        Returns:
        the configuration vector with the joint values for both active and passive
        joints.
      • setFullQ

        public void setFullQ​(Q q,
                             State state)
        Set the full configuration of the device.
        This sets the joint values directly, and there is no checks or guarantees that the device
        will be in a valid connected configuration afterwards.
        Parameters:
        q - [in] the configuration vector to set.
        state - [in/out] the state to update with a new configuration.
      • getJoints

        public VectorJoint_p getJoints()
        Get all joints of this device
        Returns:
        all joints
      • getQ

        public Q getQ​(State state)
      • getDOF

        public long getDOF()
      • getBounds

        public PairQ getBounds()
      • getVelocityLimits

        public Q getVelocityLimits()
      • getAccelerationLimits

        public Q getAccelerationLimits()
      • getName

        public java.lang.String getName()
        Returns the name of the device
        Returns:
        name of the device
      • baseTframe

        public Transform3D baseTframe​(FrameCPtr f,
                                      State state)
        Calculates the homogeneous transform from base to a frame f
        \robabx{b}{f}{\mathbf{T}}
        Returns:
        the homogeneous transform \robabx{b}{f}{\mathbf{T}}
      • baseTend

        public Transform3D baseTend​(State state)
        Calculates the homogeneous transform from base to the end frame
        \robabx{base}{end}{\mathbf{T}}
        Returns:
        the homogeneous transform \robabx{base}{end}{\mathbf{T}}
      • worldTbase

        public Transform3D worldTbase​(State state)
        Calculates the homogeneous transform from world to base \robabx{w}{b}{\mathbf{T}}

        Returns:
        the homogeneous transform \robabx{w}{b}{\mathbf{T}}
      • baseJframes

        public Jacobian baseJframes​(FrameVector frames,
                                    State state)
        The Jacobian for a sequence of frames.

        A Jacobian is computed for each of the frames and the Jacobians are
        stacked on top of eachother.
        Parameters:
        frames - [in] the frames to calculate the frames from
        state - [in] the state to calculate in
        Returns:
        the jacobian
      • baseJCend

        public JacobianCalculatorPtr baseJCend​(State state)
        DeviceJacobian for the end frame.

        By default this method forwards to baseDJframe().
      • baseJCframe

        public JacobianCalculatorPtr baseJCframe​(FrameCPtr frame,
                                                 State state)
        DeviceJacobian for a particular frame.

        By default this method forwards to baseDJframes().