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

Analytical inverse solver for the Kuka LBR IIWA 7 R800 robot. More...

#include <ClosedFormIKSolverKukaIIWA.hpp>

Inherits ClosedFormIK.

Public Types

typedef rw::core::Ptr< ClosedFormIKSolverKukaIIWAPtr
 Smart pointer type to ClosedFormIKSolverKukaIIWA.
 
- Public Types inherited from ClosedFormIK
typedef rw::core::Ptr< ClosedFormIKPtr
 smart pointer type to this 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
 

Public Member Functions

 ClosedFormIKSolverKukaIIWA (const rw::core::Ptr< const rw::models::SerialDevice > device, const rw::kinematics::State &state)
 Construct new closed form solver for a Kuka 7 DOF IIWA robot. More...
 
virtual ~ClosedFormIKSolverKukaIIWA ()
 Destructor.
 
std::vector< rw::math::Qsolve (const rw::math::Transform3D< double > &baseTend, const rw::kinematics::State &state) const
 Calculates the inverse kinematics. More...
 
std::vector< rw::math::Qsolve (const rw::math::Transform3D< double > &baseTend, const rw::kinematics::State &state, const rw::math::Vector3D< double > &dir4) const
 Find inverse kinematic solutions deterministically by pulling joint 4 as much in the given direction as possible. More...
 
void setCheckJointLimits (bool check)
 Specifies whether to check joint limits before returning a solution. More...
 
virtual rw::core::Ptr< const rw::kinematics::FramegetTCP () const
 Returns the Tool Center Point (TCP) used when solving the IK problem. More...
 
- Public Member Functions inherited from ClosedFormIK
virtual ~ClosedFormIK ()
 Destructor.
 
- Public Member Functions inherited from InvKinSolver
virtual ~InvKinSolver ()
 destructor
 

Additional Inherited Members

- Static Public Member Functions inherited from ClosedFormIK
static ClosedFormIK::Ptr make (const rw::models::Device &device, const rw::kinematics::State &state)
 Closed-form IK solver for a device. More...
 
- Protected Member Functions inherited from ClosedFormIK
 ClosedFormIK ()
 Constructor.
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ClosedFormIKSolverKukaIIWA()

Construct new closed form solver for a Kuka 7 DOF IIWA robot.

Parameters
device[in] the device.
state[in] the state to get the frame structure and extract the dimensions from.

Member Function Documentation

◆ getTCP()

virtual rw::core::Ptr<const rw::kinematics::Frame> getTCP ( ) const
virtual

Returns the Tool Center Point (TCP) used when solving the IK problem.

Returns
The TCP Frame used when solving the IK.

Implements InvKinSolver.

◆ setCheckJointLimits()

void setCheckJointLimits ( bool  check)
virtual

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() [1/2]

std::vector<rw::math::Q> solve ( const rw::math::Transform3D< double > &  baseTend,
const rw::kinematics::State state 
) const
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) )

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.

Implements InvKinSolver.

◆ solve() [2/2]

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

Find inverse kinematic solutions deterministically by pulling joint 4 as much in the given direction as possible.

Parameters
baseTend[in] Desired base to end transformation \(\robabx{}{desired}{\mathbf{T}}\).
state[in] State of the device from which to start the iterations.
dir4[in] unit vector giving the direction to pull joint 4 in (given in base coordinate system).
Returns
List of up to 8 solutions. Notice that the list may be empty.

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