Package org.robwork.sdurw_invkin
Class IterativeMultiIK
- java.lang.Object
-
- org.robwork.sdurw_invkin.IterativeMultiIK
-
- Direct Known Subclasses:
JacobianIKSolverM
public class IterativeMultiIK extends java.lang.Object
Interface for iterative inverse kinematics algorithms for problems
or devices that utilize more than one end-effector.
The IterativeMultiIK interface provides an interface for calculating
the inverse kinematics of a device with multiple end-effectors. 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 IterativeMultiIK(long cPtr, boolean cMemoryOwn)
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description void
delete()
static long
getCPtr(IterativeMultiIK obj)
vector_d
getMaxError()
Returns the maximal error for a solution
int
getMaxIterations()
Returns the maximal number of iterationsPropertyMap
getProperties()
Returns the PropertyMapvoid
setMaxError(vector_d 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
VectorQ
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.
-
-
-
Method Detail
-
getCPtr
public static long getCPtr(IterativeMultiIK obj)
-
delete
public void delete()
-
solve
public VectorQ 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. 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.
- 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.
-
setMaxError
public void setMaxError(vector_d 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 vector_d 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
-
-