AmbiguityResolver |
Wraps a InvKinSolver and searches for ambiguities due to joint able to rotate
2 \ pi or more.
For each solution \mathbf{q} the method tries to see if a j exists s.t.
\mathbf{q}(i)=\mathbf{q}(i)+j * 2 \ pi is a valid solution.
The AmbiguityResolver always tests for joint limits.
|
CCDSolver |
This inverse kinematics method is a heuristic search technique called
the Cyclic-Coordinate Descent method.
|
ClosedFormIK |
Interface for closed form inverse kinematics algorithms.
The ClosedFormIK interface provides an interface for calculating the
inverse kinematics of a device.
|
ClosedFormIKCPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
ClosedFormIKPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
ClosedFormIKSolverKukaIIWA |
Analytical inverse solver for the Kuka LBR IIWA 7 R800 robot.
Notice that this is a 7 DOF robot and that there is an infinite number of solutions.
The extra DOF means that the middle joint of the robot is able to move in a circle.
This solver will choose a point on this circle randomly and return up to 8 possible
solutions.
|
ClosedFormIKSolverKukaIIWACPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
ClosedFormIKSolverKukaIIWAPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
ClosedFormIKSolverUR |
Analytical inverse kinematics solver to the kinematics of a Universal Robots.
|
ClosedFormIKSolverURCPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
ClosedFormIKSolverURPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
IKMetaSolver |
Solve the inverse kinematics problem with respect to joint limits and
collisions.
Given an arbitrary iterative inverse kinematics solver, the IKMetaSolver
attempts to find a collision free solution satisfying joint limits.
|
IKMetaSolverCPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
IKMetaSolverPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
InvKinSolver |
Interface for inverse kinematics algorithms
The InvKinSolver interface provides an interface for calculating
the inverse kinematics of a device.
|
InvKinSolverPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
IterativeIK |
Interface for iterative inverse kinematics algorithms
The IterativeIK interface provides an interface for calculating
the inverse kinematics of a device.
|
IterativeIKCPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
IterativeIKPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
IterativeMultiIK |
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.
|
JacobianIKSolver |
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.
|
JacobianIKSolver.JacobianSolverType |
the type of jacobian solver
|
JacobianIKSolverCPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
JacobianIKSolverM |
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.
|
JacobianIKSolverM.JacobianSolverType |
the type of Jacobian solver
|
JacobianIKSolverPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
ParallelIKSolver |
Inverse kinematics method for parallel devices.
The method is based on solving for two simultaneous constraints.
First, the junctions defined in the ParallelDevice must remain connected.
Second, the target(s) given by the user should be fulfilled.
A stacked Jacobian is used to form an equation system that includes these objectives.
The Singular Value Decomposition is used to find the solution for the joint values
in this equation system.
|
ParallelIKSolver.Target |
A target definition used in the multi-target solve function.
|
PieperSolver |
Calculates the closed form inverse kinematics of
a device using Piepers method
To use Piepers method it is required that the device has
6 DOF revolute joints, and that last three axis intersects.
In this implementation it will be assumed that the that
rotation of these last three axis are equivalent to an
Euler ZYZ or Z(-Y)Z rotation.
See Introduction to Robotics Mechanics and Control, by
John J.
|
PieperSolverCPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
PieperSolverPtr |
Ptr stores a pointer and optionally takes ownership of the value.
|
sdurw_invkin |
|
sdurw_invkinJNI |
|
SWIGTYPE_p_Eigen__VectorXd |
|
SWIGTYPE_p_rw__core__PtrT_rw__pathplanning__QConstraint_t |
|
SWIGTYPE_p_rw__core__PtrT_rw__proximity__CollisionDetector_t |
|
SWIGTYPE_p_rw__math__VectorNDT_6_bool_t |
|
SWIGTYPE_p_std__vectorT_rw__invkin__ParallelIKSolver__Target_t |
|
SWIGTYPE_p_std__vectorT_rw__math__Transform3DT_double_t_t |
|