RobWorkProject
24.12.4-
|
Interface for inverse kinematics algorithms. More...
#include <InvKinSolver.hpp>
Inherited by AmbiguityResolver, ClosedFormIK, and IterativeIK.
Public Types | |
typedef rw::core::Ptr< InvKinSolver > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< const InvKinSolver > | CPtr |
smart pointer type to this const class | |
Public Member Functions | |
virtual | ~InvKinSolver () |
destructor | |
virtual std::vector< math::Q > | solve (const rw::math::Transform3D< double > &baseTend, const rw::kinematics::State &state) const =0 |
Calculates the inverse kinematics. More... | |
virtual void | setCheckJointLimits (bool check)=0 |
Specifies whether to check joint limits before returning a solution. More... | |
virtual rw::core::Ptr< const rw::kinematics::Frame > | getTCP () const =0 |
Returns the Tool Center Point (TCP) used when solving the IK problem. More... | |
Interface for inverse kinematics algorithms.
The InvKinSolver 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.
|
pure virtual |
Returns the Tool Center Point (TCP) used when solving the IK problem.
Implemented in PieperSolver, ParallelIKSolver, JacobianIKSolver, IKMetaSolver, ClosedFormIKSolverUR, ClosedFormIKSolverKukaIIWA, CCDSolver, and AmbiguityResolver.
|
pure virtual |
Specifies whether to check joint limits before returning a solution.
check | [in] If true the method should perform a check that joints are within bounds. |
Implemented in IKQPSolver, PieperSolver, ParallelIKSolver, JacobianIKSolver, IKMetaSolver, ClosedFormIKSolverUR, ClosedFormIKSolverKukaIIWA, CCDSolver, and AmbiguityResolver.
|
pure virtual |
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) )
baseTend | [in] Desired base to end transformation \( \robabx{}{desired}{\mathbf{T}}\) |
state | [in] State of the device from which to start the iterations |
Implemented in PieperSolver, JacobianIKSolver, IKMetaSolver, ClosedFormIKSolverUR, ClosedFormIKSolverKukaIIWA, CCDSolver, and ParallelIKSolver.