Class TreeDeviceCPtr


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

      • TreeDeviceCPtr

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

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

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

        public TreeDevice __ref__()
        Dereferencing operator.
      • getDeref

        public TreeDevice getDeref()
        Member access operator.
      • equals

        public boolean equals​(TreeDevice p)
      • 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
      • baseJends

        public Jacobian baseJends​(State state)
        like Device::baseJend() but with a Jacobian calculated for all
        end effectors.
      • getEnds

        public FrameVector getEnds()
        The end-effectors of the tree device.
      • frames

        public FrameVector frames()
        Frames of the device.

        This method is being used when displaying the kinematic structure of
        devices in RobWorkStudio. The method really isn't of much use for
        everyday programming.
      • getJoints

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

        public void setQ​(Q q,
                         State state)
      • 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}}
      • baseJframe

        public Jacobian baseJframe​(FrameCPtr frame,
                                   State state)
        Calculates the jacobian matrix of a frame f described in the
        robot base frame ^{base}_{frame}\mathbf{J}_{\mathbf{q}}(\mathbf{q})

        Parameters:
        frame - [in] Frame for which to calculate the Jacobian
        state - [in] State for which to calculate the Jacobian

        Returns:
        the 6*ndof jacobian matrix: {^{base}_{frame}}\mathbf{J}_{\mathbf{q}}(\mathbf{q})

        This method calculates the jacobian relating joint velocities ( \mathbf{\dot{q}} ) to the frame f velocity seen from base-frame
        ( \nu^{base}_{frame} )

        \nu^{base}_{frame} = {^{base}_{frame}}\mathbf{J}_\mathbf{q}(\mathbf{q})\mathbf{\dot{q}}


        The jacobian matrix {^{base}_n}\mathbf{J}_{\mathbf{q}}(\mathbf{q})
        is defined as:

        {^{base}_n}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) = \frac{\partial ^{base}\mathbf{x}_n}{\partial \mathbf{q}}

        By default the method forwards to baseJframes().
      • 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().