RobWorkProject  23.9.11-
Public Member Functions | List of all members
IKQPSolver Class Reference

Iterative inverse kinematics solved based on the QPController. More...

#include <IKQPSolver.hpp>

Inherits IterativeIK.

Public Member Functions

 IKQPSolver (rw::models::SerialDevice *device, const rw::kinematics::State &state)
 Constructs IKQPSolver for device. More...
 
std::vector< rw::math::Qsolve (const rw::math::Transform3D<> &baseTend, const rw::kinematics::State &state) const
 Calculates the inverse kinematics. More...
 
void setCheckJointLimits (bool limit)
 Specifies whether to check joint limits before returning a solution. More...
 
- Public Member Functions inherited from IterativeIK
virtual ~IterativeIK ()
 Destructor.
 
virtual void setMaxError (double maxError)
 Sets the maximal error for a solution. More...
 
virtual double getMaxError () const
 Returns the maximal error for a solution. More...
 
virtual void setMaxIterations (int maxIterations)
 Sets the maximal number of iterations allowed. More...
 
virtual int getMaxIterations () const
 Returns the maximal number of iterations.
 
virtual rw::core::PropertyMapgetProperties ()
 Returns the PropertyMap. More...
 
virtual const rw::core::PropertyMapgetProperties () const
 Returns the PropertyMap return Reference to the PropertyMap.
 
- Public Member Functions inherited from InvKinSolver
virtual ~InvKinSolver ()
 destructor
 
virtual std::vector< math::Qsolve (const rw::math::Transform3D< double > &baseTend, const rw::kinematics::State &state) const =0
 Calculates the inverse kinematics. More...
 
virtual rw::core::Ptr< const rw::kinematics::FramegetTCP () const =0
 Returns the Tool Center Point (TCP) used when solving the IK problem. More...
 

Additional Inherited Members

- Public Types inherited from IterativeIK
typedef rw::core::Ptr< IterativeIKPtr
 smart pointer type to this class
 
typedef rw::core::Ptr< const IterativeIKCPtr
 smart pointer type to this const class
 
- Public Types inherited from InvKinSolver
typedef rw::core::Ptr< InvKinSolverPtr
 smart pointer type to this class
 
typedef rw::core::Ptr< const InvKinSolverCPtr
 smart pointer type to this const class
 
- Static Public Member Functions inherited from IterativeIK
static IterativeIK::Ptr makeDefault (rw::core::Ptr< rw::models::Device > device, const rw::kinematics::State &state)
 Default iterative inverse kinematics solver for a device and state. More...
 
- Protected Member Functions inherited from IterativeIK
 IterativeIK ()
 Constructor.
 

Detailed Description

Iterative inverse kinematics solved based on the QPController.

The IKQPSolver works very similar to the SimpleSolver. However, instead of using a simple inverse Jacobian it uses the rw::algorithms::QPController making it robust to singularities and ensuring joint limits.

Usually the IKQPSolver runs order of magnitudes slower than the standard SimpleSolver. Solutions returned by the IKQPSolver might not be exact solutions, but are least square fits. Given a target outside the robot workspace the IKQPSolver will, given enough iterations, return the least square solution.

Notice that the IKQPSolver is a local method. It there is thus no guarantee that the solution returned will be the global least square.

Constructor & Destructor Documentation

◆ IKQPSolver()

IKQPSolver ( rw::models::SerialDevice device,
const rw::kinematics::State state 
)

Constructs IKQPSolver for device.

It is required that the device has correct joint position, velocity and acceleration limits.

Parameters
device[in] Device to solve for *
state[in] State of the workcell

Member Function Documentation

◆ setCheckJointLimits()

void setCheckJointLimits ( bool  check)
inlinevirtual

Specifies whether to check joint limits before returning a solution.

Parameters
check[in] If true the method should perform a check that joints are within bounds.

Implements InvKinSolver.

◆ solve()

std::vector<rw::math::Q> solve ( const rw::math::Transform3D<> &  baseTend,
const rw::kinematics::State state 
) const

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) )

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.
Note
The targets baseTend must be defined relative to the base of the robot/device.

The documentation for this class was generated from the following file: