Package org.robwork.sdurw_invkin
Class IterativeIK
- java.lang.Object
-
- org.robwork.sdurw_invkin.InvKinSolver
-
- org.robwork.sdurw_invkin.IterativeIK
-
- Direct Known Subclasses:
CCDSolver
,IKMetaSolver
,JacobianIKSolver
,ParallelIKSolver
public class IterativeIK extends InvKinSolver
Interface for iterative inverse kinematics algorithms
The IterativeIK interface provides an interface for calculating
the inverse kinematics of a device. That is to calculate
\mathbf{q} such that \robabx{base}{end}{\mathbf{T}}(\mathbf{q})= \robabx{}{desired}{\mathbf{T}}.
By default it solves the problem beginning at the robot base and
ending with the frame defined as the end of the devices, and which is
accessible through the Device::getEnd() method.
-
-
Constructor Summary
Constructors Constructor Description IterativeIK(long cPtr, boolean cMemoryOwn)
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description void
delete()
static long
getCPtr(IterativeIK obj)
double
getMaxError()
Returns the maximal error for a solution
int
getMaxIterations()
Returns the maximal number of iterationsPropertyMap
getProperties()
Returns the PropertyMapstatic IterativeIKPtr
makeDefault(DevicePtr device, State state)
Default iterative inverse kinematics solver for a device and
state.
void
setMaxError(double maxError)
Sets the maximal error for a solution
The error between two transformations is defined as the maximum of infinite-norm
of the positional error and the angular error encoded as EAA.
void
setMaxIterations(int maxIterations)
Sets the maximal number of iterations allowed
-
Methods inherited from class org.robwork.sdurw_invkin.InvKinSolver
getCPtr, getTCP, setCheckJointLimits, solve
-
-
-
-
Method Detail
-
getCPtr
public static long getCPtr(IterativeIK obj)
-
delete
public void delete()
- Overrides:
delete
in classInvKinSolver
-
setMaxError
public void setMaxError(double maxError)
Sets the maximal error for a solution
The error between two transformations is defined as the maximum of infinite-norm
of the positional error and the angular error encoded as EAA.
- Parameters:
maxError
- [in] the maxError. It will be assumed that maxError > 0
-
getMaxError
public double getMaxError()
Returns the maximal error for a solution
- Returns:
- Maximal error
-
setMaxIterations
public void setMaxIterations(int maxIterations)
Sets the maximal number of iterations allowed
- Parameters:
maxIterations
- [in] maximal number of iterations
-
getMaxIterations
public int getMaxIterations()
Returns the maximal number of iterations
-
getProperties
public PropertyMap getProperties()
Returns the PropertyMap- Returns:
- Reference to the PropertyMap
-
makeDefault
public static IterativeIKPtr makeDefault(DevicePtr device, State state)
Default iterative inverse kinematics solver for a device and
state.
- Parameters:
device
- [in] Device for which to solve IK.state
- [in] Fixed state for which IK is solved.
-
-