Package org.robwork.sdurw_invkin
Class JacobianIKSolverM
- java.lang.Object
-
- org.robwork.sdurw_invkin.IterativeMultiIK
-
- org.robwork.sdurw_invkin.JacobianIKSolverM
-
public class JacobianIKSolverM extends IterativeMultiIK
A Jacobian based iterative inverse kinematics algorithm for devices with
multiple end effectors.
This algorithm does not 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
JacobianIKSolverM.JacobianSolverType
the type of Jacobian solver
-
Constructor Summary
Constructors Constructor Description JacobianIKSolverM(long cPtr, boolean cMemoryOwn)
JacobianIKSolverM(JointDevice device, FrameVector foi, State state)
Constructs JacobianIKSolverM for a
JointDevice(SerialDevice and TreeDevice).JacobianIKSolverM(TreeDevice device, State state)
Constructs JacobianIKSolverM for TreeDevice.
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description void
delete()
static long
getCPtr(JacobianIKSolverM obj)
void
setClampToBounds(boolean enableClamping)
enables clamping of the solution such that solution always is within joint limits.void
setEnableInterpolation(boolean enableInterpolation)
the solver may fail or be very slow if the the solution is too far from the
initial configuration.void
setReturnBestFit(boolean returnBestFit)
configures the iterative solver to return the best fit
found, even though error criteria was not met.void
setSolverType(JacobianIKSolverM.JacobianSolverType type)
set the type of solver to use for stepping toward a solutionVectorQ
solve(SWIGTYPE_p_std__vectorT_rw__math__Transform3DT_double_t_t 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.boolean
solveLocal(SWIGTYPE_p_std__vectorT_rw__math__Transform3DT_double_t_t bTed, vector_d maxError, State state, int maxIter)
performs a local search toward the the target bTed.boolean
solveLocal(SWIGTYPE_p_std__vectorT_rw__math__Transform3DT_double_t_t bTed, vector_d maxError, State state, int maxIter, boolean untilSmallChange)
performs a local search toward the the target bTed.-
Methods inherited from class org.robwork.sdurw_invkin.IterativeMultiIK
getCPtr, getMaxError, getMaxIterations, getProperties, setMaxError, setMaxIterations
-
-
-
-
Constructor Detail
-
JacobianIKSolverM
public JacobianIKSolverM(long cPtr, boolean cMemoryOwn)
-
JacobianIKSolverM
public JacobianIKSolverM(TreeDevice device, State state)
Constructs JacobianIKSolverM for TreeDevice. Uses the default
end effectors of the TreeDevice
-
JacobianIKSolverM
public JacobianIKSolverM(JointDevice device, FrameVector foi, State state)
Constructs JacobianIKSolverM for a
JointDevice(SerialDevice and TreeDevice). It does not use
the default end effectors. A list of interest frames are
given instead.
-
-
Method Detail
-
getCPtr
public static long getCPtr(JacobianIKSolverM obj)
-
delete
public void delete()
- Overrides:
delete
in classIterativeMultiIK
-
setReturnBestFit
public void setReturnBestFit(boolean returnBestFit)
configures the iterative solver to return the best fit
found, even though error criteria was not met.- Parameters:
returnBestFit
- [in] set to true if you want best fit returned.
-
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
-
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
-
setSolverType
public void setSolverType(JacobianIKSolverM.JacobianSolverType type)
set the type of solver to use for stepping toward a solution- Parameters:
type
- [in] the type of Jacobian solver
-
solve
public VectorQ solve(SWIGTYPE_p_std__vectorT_rw__math__Transform3DT_double_t_t baseTend, State state)
Description copied from class:IterativeMultiIK
Calculates the inverse kinematics
Given a desired \robabx{}{desired}{\mathbf{T}}
and the current state, the method solves the inverse kinematics
problem. If no solution is found with the required precision and
within the specified number of iterations it will return an empty
list.
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,
it is checked to be within the bounds of the configuration space.
- Overrides:
solve
in classIterativeMultiIK
- 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.
-
solveLocal
public boolean solveLocal(SWIGTYPE_p_std__vectorT_rw__math__Transform3DT_double_t_t bTed, vector_d maxError, State state, int maxIter, boolean untilSmallChange)
performs a local search toward the 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 iterationsuntilSmallChange
- [in] if true the error difference between two
successive iterations need to be smaller than maxError. If false then the
error of a iteration need to be smaller than maxError.- Returns:
- true if error is below max error
Note: the result will be saved in state
-
solveLocal
public boolean solveLocal(SWIGTYPE_p_std__vectorT_rw__math__Transform3DT_double_t_t bTed, vector_d maxError, State state, int maxIter)
performs a local search toward the 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
-
-