Package org.robwork.sdurw_invkin
Class JacobianIKSolver
- java.lang.Object
-
- org.robwork.sdurw_invkin.InvKinSolver
-
- org.robwork.sdurw_invkin.IterativeIK
-
- org.robwork.sdurw_invkin.JacobianIKSolver
-
public class JacobianIKSolver extends IterativeIK
A Jacobian based iterative inverse kinematics algorithm for devices with a single end
effector.
This algorithm does implicitly handle joint limits, however it is possible to force the
solution within joint limits using clamping in each iterative step. If joint clamping is not
enabled then this algorithm might contain joint values that are out of bounds.
The method uses an Newton-Raphson iterative approach and is based on using the inverse of
the device Jacobian to compute each local solution in each iteration. Several methods for
calculating/approximating the inverse Jacobian are available, where the SVD method currently
is the most stable, see the JacobianSolverType option for additional options.
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
JacobianIKSolver.JacobianSolverType
the type of jacobian solver
-
Constructor Summary
Constructors Constructor Description JacobianIKSolver(long cPtr, boolean cMemoryOwn)
JacobianIKSolver(DeviceCPtr device, FrameCPtr foi, State state)
Constructs JacobianIKSolver for device, where the frame foi will
be used as end effector.JacobianIKSolver(DeviceCPtr device, State state)
Constructs JacobianIKSolver for device device.
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description void
delete()
static long
getCPtr(JacobianIKSolver 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.
void
setClampToBounds(boolean enableClamping)
enables clamping of the solution such that solution always is within joint limitsvoid
setEnableInterpolation(boolean enableInterpolation)
the solver may fail or be very slow if the the solution is too far from the
initial configuration.void
setInterpolatorStep(double interpolatorStep)
sets the maximal step length that is allowed on the
local search towards the solution.void
setJointLimitTolerance(double tolerance)
setJointLimitTolerance set the tolerance used for bound-checking the solutionvoid
setSolverType(JacobianIKSolver.JacobianSolverType type)
set the type of solver to use for stepping toward a solutionvoid
setWeightVector(vector_d weights)
setWeightVector sets the weight vector used for solver type "Weighted"void
setWeightVector(SWIGTYPE_p_Eigen__VectorXd weights)
setWeightVector sets the weight vector used for solver type "Weighted"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.boolean
solveLocal(Transform3D bTed, double maxError, State state, int maxIter)
performs a local search toward the target bTed.-
Methods inherited from class org.robwork.sdurw_invkin.IterativeIK
getCPtr, getMaxError, getMaxIterations, getProperties, makeDefault, setMaxError, setMaxIterations
-
Methods inherited from class org.robwork.sdurw_invkin.InvKinSolver
getCPtr
-
-
-
-
Constructor Detail
-
JacobianIKSolver
public JacobianIKSolver(long cPtr, boolean cMemoryOwn)
-
JacobianIKSolver
public JacobianIKSolver(DeviceCPtr device, State state)
Constructs JacobianIKSolver for device device.- Parameters:
device
- [in] the device to do inverse kinematics for.state
- [in] the initial state.
-
JacobianIKSolver
public JacobianIKSolver(DeviceCPtr device, FrameCPtr foi, State state)
Constructs JacobianIKSolver for device, where the frame foi will
be used as end effector.- Parameters:
device
- [in] the device to do inverse kinematics for.foi
- [in] end effector frame.state
- [in] the initial state.
-
-
Method Detail
-
getCPtr
public static long getCPtr(JacobianIKSolver obj)
-
delete
public void delete()
- Overrides:
delete
in classIterativeIK
-
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.
-
setInterpolatorStep
public void setInterpolatorStep(double interpolatorStep)
sets the maximal step length that is allowed on the
local search towards the solution.- Parameters:
interpolatorStep
- [in] the interpolation step.
-
setEnableInterpolation
public void setEnableInterpolation(boolean enableInterpolation)
the solver may fail or be very slow if the the solution is too far from the
initial configuration. This function enables the use of via points generated using
an interpolation from initial end effector configuration to the goal target.- Parameters:
enableInterpolation
- [in] set true to enable interpolation, false otherwise
-
solveLocal
public boolean solveLocal(Transform3D bTed, double maxError, State state, int maxIter)
performs a local search toward the target bTed. No via points
are generated to support the convergence and robustness.- Parameters:
bTed
- [in] the target end posemaxError
- [in] the maximal allowed errorstate
- [in/out] the starting position for the search. The end position will
also be saved in this state.maxIter
- [in] max number of iterations- Returns:
- true if error is below max error
Note: the result will be saved in state
-
setClampToBounds
public void setClampToBounds(boolean enableClamping)
enables clamping of the solution such that solution always is within joint limits- Parameters:
enableClamping
- [in] true to enable clamping, false otherwise
-
setSolverType
public void setSolverType(JacobianIKSolver.JacobianSolverType type)
set the type of solver to use for stepping toward a solution- Parameters:
type
- [in] the type of jacobian solver
-
setWeightVector
public void setWeightVector(SWIGTYPE_p_Eigen__VectorXd weights)
setWeightVector sets the weight vector used for solver type "Weighted"- Parameters:
weights
- a vector of weights for each degree of freedom, ie weights.size() == DOF
-
setWeightVector
public void setWeightVector(vector_d weights)
setWeightVector sets the weight vector used for solver type "Weighted"- Parameters:
weights
- a vector of weights for each degree of freedom, ie weights.size() == DOF
-
setJointLimitTolerance
public void setJointLimitTolerance(double tolerance)
setJointLimitTolerance set the tolerance used for bound-checking the solution- Parameters:
tolerance
- for joint bounds checking
-
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.
-
-