Package org.robwork.sdurw_invkin
Class ClosedFormIKSolverUR
- java.lang.Object
-
- org.robwork.sdurw_invkin.InvKinSolver
-
- org.robwork.sdurw_invkin.ClosedFormIK
-
- org.robwork.sdurw_invkin.ClosedFormIKSolverUR
-
public class ClosedFormIKSolverUR extends ClosedFormIK
Analytical inverse kinematics solver to the kinematics of a Universal Robots.
-
-
Constructor Summary
Constructors Constructor Description ClosedFormIKSolverUR(long cPtr, boolean cMemoryOwn)
ClosedFormIKSolverUR(SerialDeviceCPtr device, State state)
Construct new closed form solver for a Universal Robot.
Note: The dimensions will be automatically extracted from the device, using an arbitrary
state.
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description void
delete()
static long
getCPtr(ClosedFormIKSolverUR obj)
FrameCPtr
getTCP()
Returns the Tool Center Point (TCP) used when solving the IK problem.
void
setCheckJointLimits(boolean check)
Specifies whether to check joint limits before returning a solution.
VectorQ
solve(Transform3D baseTend, State state)
Calculates the inverse kinematics
Given a desired \robabx{}{desired}{\mathbf{T}}
and the current state, the method solves the inverse kinematics
problem.
If the algorithm is able to identify multiple solutions (e.g.-
Methods inherited from class org.robwork.sdurw_invkin.ClosedFormIK
getCPtr, make
-
Methods inherited from class org.robwork.sdurw_invkin.InvKinSolver
getCPtr
-
-
-
-
Constructor Detail
-
ClosedFormIKSolverUR
public ClosedFormIKSolverUR(long cPtr, boolean cMemoryOwn)
-
ClosedFormIKSolverUR
public ClosedFormIKSolverUR(SerialDeviceCPtr device, State state)
Construct new closed form solver for a Universal Robot.
Note: The dimensions will be automatically extracted from the device, using an arbitrary
state.- Parameters:
device
- [in] the device.state
- [in] the state to use to extract dimensions.
-
-
Method Detail
-
getCPtr
public static long getCPtr(ClosedFormIKSolverUR obj)
-
delete
public void delete()
- Overrides:
delete
in classClosedFormIK
-
solve
public VectorQ solve(Transform3D baseTend, State state)
Description copied from class:InvKinSolver
Calculates the inverse kinematics
Given a desired \robabx{}{desired}{\mathbf{T}}
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) )
- Overrides:
solve
in classInvKinSolver
- Parameters:
baseTend
- [in] Desired base to end transformation \robabx{}{desired}{\mathbf{T}}
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)
Description copied from class:InvKinSolver
Specifies whether to check joint limits before returning a solution.
- Overrides:
setCheckJointLimits
in classInvKinSolver
- Parameters:
check
- [in] If true the method should perform a check that joints are within
bounds.
-
getTCP
public FrameCPtr getTCP()
Description copied from class:InvKinSolver
Returns the Tool Center Point (TCP) used when solving the IK problem.
- Overrides:
getTCP
in classInvKinSolver
- Returns:
- The TCP Frame used when solving the IK.
-
-