RobWorkProject  23.9.11-
Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
IterativeIK Class Reference

Interface for iterative inverse kinematics algorithms. More...

#include <IterativeIK.hpp>

Inherits InvKinSolver.

Inherited by CCDSolver, IKMetaSolver, JacobianIKSolver, ParallelIKSolver, and IKQPSolver.

Public Types

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
 

Public Member Functions

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 void setCheckJointLimits (bool check)=0
 Specifies whether to check joint limits before returning a solution. More...
 
virtual rw::core::Ptr< const rw::kinematics::FramegetTCP () const =0
 Returns the Tool Center Point (TCP) used when solving the IK problem. More...
 

Static Public Member Functions

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

 IterativeIK ()
 Constructor.
 

Detailed Description

Interface for iterative inverse kinematics algorithms.

The IterativeIK 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.

Member Function Documentation

◆ getMaxError()

virtual double getMaxError ( ) const
virtual

Returns the maximal error for a solution.

Returns
Maximal error

◆ getProperties()

virtual rw::core::PropertyMap& getProperties ( )
virtual

Returns the PropertyMap.

Returns
Reference to the PropertyMap

◆ makeDefault()

static IterativeIK::Ptr makeDefault ( rw::core::Ptr< rw::models::Device device,
const rw::kinematics::State state 
)
static

Default iterative inverse kinematics solver for a device and state.

Parameters
device[in] Device for which to solve IK.
state[in] Fixed state for which IK is solved.

◆ setMaxError()

virtual void setMaxError ( double  maxError)
virtual

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

◆ setMaxIterations()

virtual void setMaxIterations ( int  maxIterations)
virtual

Sets the maximal number of iterations allowed.

Parameters
maxIterations[in] maximal number of iterations

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