kinematics-dynamics
Loading...
Searching...
No Matches
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 JointConfig = std::vector< double >
 Joint configurations.
 
using Solutions = std::vector< JointConfig >
 Collection of local IK solutions.
 

Public Member Functions

virtual ~ScrewTheoryIkSubproblem ()=default
 Destructor.
 
virtual bool solve (const KDL::Frame &rhs, const KDL::Frame &pointTransform, const JointConfig &reference, Solutions &solutions) const =0
 Finds a closed geometric solution for this IK subproblem.
 
bool solve (const KDL::Frame &rhs, const KDL::Frame &pointTransform, Solutions &_solutions)
 
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

◆ describe()

virtual const char * roboticslab::ScrewTheoryIkSubproblem::describe ( ) const
pure virtual

◆ solutions()

virtual int roboticslab::ScrewTheoryIkSubproblem::solutions ( ) const
pure virtual

◆ solve()

virtual bool roboticslab::ScrewTheoryIkSubproblem::solve ( const KDL::Frame &  rhs,
const KDL::Frame &  pointTransform,
const JointConfig reference,
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.
referenceKnown nearby solutions to be used as reference in case a singularity is found.
solutionsOutput vector of local solutions.
Returns
True if all solutions are reachable, false otherwise.

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


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