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

Solve the inverse kinematics problem with respect to joint limits and collisions. More...

#include <IKMetaSolver.hpp>

Inherits IterativeIK.

Public Types

typedef rw::core::Ptr< IKMetaSolverPtr
 smart pointer type to this class
 
- 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
 

Public Member Functions

 IKMetaSolver (rw::core::Ptr< rw::invkin::IterativeIK > iksolver, const rw::core::Ptr< class rw::models::Device > device, rw::core::Ptr< rw::proximity::CollisionDetector > collisionDetector=NULL)
 Constructs IKMetaSolver. More...
 
 IKMetaSolver (rw::core::Ptr< rw::invkin::IterativeIK > iksolver, const rw::core::Ptr< class rw::models::Device > device, rw::core::Ptr< rw::pathplanning::QConstraint > constraint)
 Constructs IKMetaSolver. More...
 
virtual ~IKMetaSolver ()
 Descrutor.
 
std::vector< rw::math::Qsolve (const rw::math::Transform3D< double > &baseTend, const rw::kinematics::State &state) const
 Calculates the inverse kinematics. More...
 
void setMaxAttempts (size_t maxAttempts)
 Sets up the maximal number of attempts. More...
 
void setStopAtFirst (bool stopAtFirst)
 Sets whether to stop searching after the first solution. More...
 
void setProximityLimit (double limit)
 Sets the distance for which two solutions are considered the same. More...
 
void setCheckJointLimits (bool check)
 Specifies whether to check joint limits before returning a solution. More...
 
std::vector< rw::math::Qsolve (const rw::math::Transform3D< double > &baseTend, const rw::kinematics::State &state, size_t cnt, bool stopatfirst) const
 Solves the inverse kinematics problem. 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 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
 

Additional Inherited Members

- 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

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. It repeatingly calls the iterative solver with new random start configurations until either a solution is found or a specified max attempts has been reached.

Usage example:

// create a inverse kinematics solver for your dvs. here we use ResolvedRateSolver
ResolvedRateSolver iksolver(&myDevice); // takes a pointer to your device
// if we want colision free ik results then create or get the collisiondetector
CollisionDetector *detector = NULL; // here we don't care about collisions
// now create the meta solver
IKMetaSolver mSolver(&iksolver, &myDevice, detector);
// the pose that you want the endeffector to be in
Transform3D<> pose(Vector3D<>(0,0,1),RPY<>(1,0,0));
// and use it to generate joint configurations
std::vector<Q> result;
result = mSolver.solve( pose , state, 200, true );
IKMetaSolver(rw::core::Ptr< rw::invkin::IterativeIK > iksolver, const rw::core::Ptr< class rw::models::Device > device, rw::core::Ptr< rw::proximity::CollisionDetector > collisionDetector=NULL)
Constructs IKMetaSolver.

Constructor & Destructor Documentation

◆ IKMetaSolver() [1/2]

IKMetaSolver ( rw::core::Ptr< rw::invkin::IterativeIK iksolver,
const rw::core::Ptr< class rw::models::Device device,
rw::core::Ptr< rw::proximity::CollisionDetector collisionDetector = NULL 
)

Constructs IKMetaSolver.

The IKMetaSolver takes ownership of the iksolver. The IKMetaSolver does NOT take ownership of the collisionDetector. To skip testing for collision use null as collision detector

Parameters
iksolver[in] The basic iksolver to use. Ownership is taken
device[in] Device to solve for
collisionDetector[in] CollisionDetector to use. If null no collision detection used.

◆ IKMetaSolver() [2/2]

Constructs IKMetaSolver.

The IKMetaSolver takes ownership of the iksolver. To skip testing for feasibility set constraint to NULL.

Parameters
iksolver[in] The basic iksolver to use. Ownership is taken
device[in] Device to solve for
constraint[in] QConstraint pointer to use. If null no constraints is applied

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.

◆ setMaxAttempts()

void setMaxAttempts ( size_t  maxAttempts)

Sets up the maximal number of attempts.

Parameters
maxAttempts[in] Maximal number of attempts

◆ setProximityLimit()

void setProximityLimit ( double  limit)

Sets the distance for which two solutions are considered the same.

For distance measure an infinite norm is used. Default value is set to 1e-5.

Set limit < 0 to allow doublets in the solution.

Parameters
limit[in] The proximity limit.

◆ setStopAtFirst()

void setStopAtFirst ( bool  stopAtFirst)

Sets whether to stop searching after the first solution.

Parameters
stopAtFirst[in] True to stop after first solution has been found

◆ 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.

Searches for a valid solution using the parameters set in the IKMetaSolver

Implements InvKinSolver.

◆ solve() [2/2]

std::vector<rw::math::Q> solve ( const rw::math::Transform3D< double > &  baseTend,
const rw::kinematics::State state,
size_t  cnt,
bool  stopatfirst 
) const

Solves the inverse kinematics problem.

Tries to solve the inverse kinematics problem using the iterative inverse kinematics solver provided in the constructor. It tries at most cnt times and can either be stopped after the first solution is found or continue to search for solutions. If multiple solutions are returned there might be duplicates in the list.

Parameters
baseTend[in] Desired base to end transform
state[in] State of the workcell
cnt[in] Maximal number of attempts
stopatfirst[in] If true the method will return after the first solution is found. If false it will continue searching for more solution until the maximal number of attemps is met.

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