kinematics-dynamics
Loading...
Searching...
No Matches
Public Member Functions | Private Attributes | List of all members
roboticslab::PardosGotorTwo Class Reference

Second Pardos-Gotor subproblem. More...

#include <ScrewTheoryIkSubproblems.hpp>

Inheritance diagram for roboticslab::PardosGotorTwo:
roboticslab::ScrewTheoryIkSubproblem

Public Member Functions

 PardosGotorTwo (const MatrixExponential &exp1, const MatrixExponential &exp2, const KDL::Vector &p)
 Constructor.
 
bool solve (const KDL::Frame &rhs, const KDL::Frame &pointTransform, const JointConfig &reference, Solutions &solutions) const override
 Finds a closed geometric solution for this IK subproblem.
 
int solutions () const override
 Number of local IK solutions.
 
const char * describe () const override
 Return a human-readable description of this IK subproblem.
 
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)
 
- Public Member Functions inherited from roboticslab::ScrewTheoryIkSubproblem
virtual ~ScrewTheoryIkSubproblem ()=default
 Destructor.
 
bool solve (const KDL::Frame &rhs, const KDL::Frame &pointTransform, Solutions &_solutions)
 

Private Attributes

const MatrixExponential exp1
 
const MatrixExponential exp2
 
const KDL::Vector p
 
const KDL::Vector crossPr2
 
const double crossPr2Norm
 

Additional Inherited Members

- Public Types inherited from roboticslab::ScrewTheoryIkSubproblem
using JointConfig = std::vector< double >
 Joint configurations.
 
using Solutions = std::vector< JointConfig >
 Collection of local IK solutions.
 

Detailed Description

Single solution, double prismatic joint geometric IK subproblem given by \( e\,^{\hat{\xi_1}\,{\theta_1}} \cdot e\,^{\hat{\xi_2}\,{\theta_2}} \cdot p = k \) (consecutive translation screws to a point, see [4] [5]).

Constructor & Destructor Documentation

◆ PardosGotorTwo()

PardosGotorTwo::PardosGotorTwo ( const MatrixExponential exp1,
const MatrixExponential exp2,
const KDL::Vector &  p 
)
Parameters
exp1First POE term.
exp2Second POE term.
pCharacteristic point.

Member Function Documentation

◆ describe()

const char * roboticslab::PardosGotorTwo::describe ( ) const
inlineoverridevirtual

◆ solutions()

int roboticslab::PardosGotorTwo::solutions ( ) const
inlineoverridevirtual

◆ solve() [1/2]

bool PardosGotorTwo::solve ( const KDL::Frame &  rhs,
const KDL::Frame &  pointTransform,
const JointConfig reference,
Solutions solutions 
) const
overridevirtual

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.

Implements roboticslab::ScrewTheoryIkSubproblem.

◆ solve() [2/2]

virtual bool roboticslab::ScrewTheoryIkSubproblem::solve ( const KDL::Frame &  rhs,
const KDL::Frame &  pointTransform,
const JointConfig reference,
Solutions solutions 
) const
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.

Implements roboticslab::ScrewTheoryIkSubproblem.


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