kinematics-dynamics
Public Types | Public Member Functions | List of all members
roboticslab::ScrewTheoryIkSubproblem Class Referenceabstract

Interface shared by all IK subproblems found in Screw Theory applied to Robotics. More...

#include <ScrewTheoryIkProblem.hpp>

Inheritance diagram for roboticslab::ScrewTheoryIkSubproblem:
roboticslab::PadenKahanOne roboticslab::PadenKahanThree roboticslab::PadenKahanTwo roboticslab::PardosGotorFour roboticslab::PardosGotorOne roboticslab::PardosGotorThree roboticslab::PardosGotorTwo

Public Types

using JointIdToSolution = std::pair< int, double >
 Maps a joint id to a screw magnitude.
 
using JointIdsToSolutions = std::vector< JointIdToSolution >
 At least one joint-id+value pair per solution.
 
using Solutions = std::vector< JointIdsToSolutions >
 Collection of local IK solutions.
 

Public Member Functions

virtual ~ScrewTheoryIkSubproblem ()=default
 Destructor.
 
virtual bool solve (const KDL::Frame &rhs, const KDL::Frame &pointTransform, Solutions &solutions) const =0
 Finds a closed geometric solution for this IK subproblem. More...
 
virtual int solutions () const =0
 Number of local IK solutions.
 
virtual const char * describe () const =0
 Return a human-readable description of this IK subproblem.
 

Detailed Description

Derived classes are considered to be immutable.

Member Function Documentation

◆ solve()

virtual bool roboticslab::ScrewTheoryIkSubproblem::solve ( const KDL::Frame &  rhs,
const KDL::Frame &  pointTransform,
Solutions solutions 
) const
pure virtual

Given the product of exponentials (POE) formula \( \prod_i e\,^{\hat{\xi}_i\,{\theta_i}} \cdot H_{ST}(0) = H_{ST}(\theta) \) , , invariant and known terms are rearranged to the right side (rhs) as follows:

\[ \prod_{i=j}^{j+k} e\,^{\hat{\xi}_i\,{\theta_i}} = \left [ \prod_{i=1}^{j-1} e\,^{\hat{\xi}_i\,{\theta_i}} \right ]^{-1} \cdot H_{ST}(\theta) \cdot \left [ H_{ST}(0) \right ]^{-1} \cdot \left [ \prod_{i=j+k+1}^{N} e\,^{\hat{\xi}_i\,{\theta_i}} \right ]^{-1} \]

where \( j = \{1, 2, ..., N\}, k = \{1, 2, ..., N-1\}, 1 <= j+k <= N \) .

Given \( N \) terms in the POE formula, \( j \) of which are unknowns, any characteristic point \( p \) postmultiplying this expression could be rewritten as \( p' \) per:

\[ \prod_{i=1}^j e\,^{\hat{\xi}_i\,{\theta_i}} \cdot \prod_{i=j+1}^N e\,^{\hat{\xi}_i\,{\theta_i}} \cdot p = \prod_{i=1}^j e\,^{\hat{\xi}_i\,{\theta_i}} \cdot p' \]

where pointTransform is the transformation matrix that produces \( p' \) from \( p \) .

Parameters
rhsRight-hand side of the POE formula prior to being applied to the right-hand side of this subproblem.
pointTransformTransformation frame applied to the first (and perhaps only) characteristic point of this subproblem.
solutionsOutput vector of local solutions.
Returns
True if all solutions are reachable, false otherwise.

Implemented in roboticslab::PardosGotorFour, roboticslab::PardosGotorThree, roboticslab::PardosGotorTwo, roboticslab::PardosGotorOne, roboticslab::PadenKahanThree, roboticslab::PadenKahanTwo, and roboticslab::PadenKahanOne.


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