Package org.robwork.sdurw_models
Class TreeDevicePtr
- java.lang.Object
-
- org.robwork.sdurw_models.TreeDevicePtr
-
public class TreeDevicePtr extends java.lang.Object
Ptr stores a pointer and optionally takes ownership of the value.
-
-
Constructor Summary
Constructors Constructor Description TreeDevicePtr()
Default constructor yielding a NULL-pointer.TreeDevicePtr(long cPtr, boolean cMemoryOwn)
TreeDevicePtr(TreeDevice 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 TreeDevice
__ref__()
Dereferencing operator.JacobianCalculatorPtr
baseJCend(State state)
DeviceJacobian for the end frame.
By default this method forwards to baseDJframe().JacobianCalculatorPtr
baseJCframe(FrameCPtr frame, State state)
DeviceJacobian for a particular frame.
By default this method forwards to baseDJframes().JacobianCalculatorPtr
baseJCframes(FrameVector frames, State state)
Jacobian
baseJend(State state)
Jacobian
baseJends(State state)
like Device::baseJend() but with a Jacobian calculated for all
end effectors.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})
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.Transform3D
baseTend(State state)
Calculates the homogeneous transform from base to the end frame
\robabx{base}{end}{\mathbf{T}}Transform3D
baseTframe(FrameCPtr f, State state)
Calculates the homogeneous transform from base to a frame f
\robabx{b}{f}{\mathbf{T}}TreeDeviceCPtr
cptr()
void
delete()
TreeDevice
deref()
The pointer stored in the object.boolean
equals(TreeDevice p)
FrameVector
frames()
Frames of the device.
This method is being used when displaying the kinematic structure of
devices in RobWorkStudio.Q
getAccelerationLimits()
Frame
getBase()
PairQ
getBounds()
static long
getCPtr(TreeDevicePtr obj)
TreeDevice
getDeref()
Member access operator.long
getDOF()
Frame
getEnd()
FrameVector
getEnds()
The end-effectors of the tree device.VectorJoint_p
getJoints()
Get all joints of this devicejava.lang.String
getName()
Returns the name of the devicePropertyMap
getPropertyMap()
Q
getQ(State state)
StateStructurePtr
getStateStructure()
Get the state structure.Q
getVelocityLimits()
boolean
isNull()
checks if the pointer is nullboolean
isRegistered()
Check if object has registered its state.boolean
isShared()
check if this Ptr has shared ownership or none
ownershipvoid
registerIn(State state)
initialize this stateless data to a specific statevoid
registerIn(StateStructurePtr state)
register this stateless object in a statestructure.void
setAccelerationLimits(Q acclimits)
void
setBounds(PairQ bounds)
void
setName(java.lang.String name)
Sets the name of the Devicevoid
setQ(Q q, State state)
void
setVelocityLimits(Q vellimits)
java.lang.String
toString()
void
unregister()
unregisters all state data of this stateless objectTransform3D
worldTbase(State state)
Calculates the homogeneous transform from world to base \robabx{w}{b}{\mathbf{T}}
-
-
-
Constructor Detail
-
TreeDevicePtr
public TreeDevicePtr(long cPtr, boolean cMemoryOwn)
-
TreeDevicePtr
public TreeDevicePtr()
Default constructor yielding a NULL-pointer.
-
TreeDevicePtr
public TreeDevicePtr(TreeDevice ptr)
Do not take ownership of ptr.
ptr can be null.
The constructor is implicit on purpose.
-
-
Method Detail
-
getCPtr
public static long getCPtr(TreeDevicePtr obj)
-
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
-
cptr
public TreeDeviceCPtr cptr()
-
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.
-
getEnd
public Frame getEnd()
-
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
-
getDOF
public long getDOF()
-
getBounds
public PairQ getBounds()
-
setBounds
public void setBounds(PairQ bounds)
-
getVelocityLimits
public Q getVelocityLimits()
-
setVelocityLimits
public void setVelocityLimits(Q vellimits)
-
getAccelerationLimits
public Q getAccelerationLimits()
-
setAccelerationLimits
public void setAccelerationLimits(Q acclimits)
-
baseJCframes
public JacobianCalculatorPtr baseJCframes(FrameVector frames, State state)
-
getBase
public Frame getBase()
-
getName
public java.lang.String getName()
Returns the name of the device- Returns:
- name of the device
-
setName
public void setName(java.lang.String name)
Sets the name of the Device- Parameters:
name
- [in] the new name of the frame
-
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 Jacobianstate
- [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 fromstate
- [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().
-
getPropertyMap
public PropertyMap getPropertyMap()
-
toString
public java.lang.String toString()
- Overrides:
toString
in classjava.lang.Object
-
registerIn
public void registerIn(State state)
initialize this stateless data to a specific state- Parameters:
state
- [in] the state in which to register the data.
Note: the data will be registered in the state structure of the state
and any copies or other instances of the state will therefore also
contain the added states.
-
registerIn
public void registerIn(StateStructurePtr state)
register this stateless object in a statestructure.
-
unregister
public void unregister()
unregisters all state data of this stateless object
-
getStateStructure
public StateStructurePtr getStateStructure()
Get the state structure.- Returns:
- the state structure.
-
isRegistered
public boolean isRegistered()
Check if object has registered its state.- Returns:
- true if registered, false otherwise.
-
-