kinematics-dynamics
|
Second Pardos-Gotor subproblem. More...
#include <ScrewTheoryIkSubproblems.hpp>
Public Member Functions | |
PardosGotorTwo (int id1, int id2, const MatrixExponential &exp1, const MatrixExponential &exp2, const KDL::Vector &p) | |
Constructor. More... | |
bool | solve (const KDL::Frame &rhs, const KDL::Frame &pointTransform, Solutions &solutions) const override |
Finds a closed geometric solution for this IK subproblem. More... | |
int | solutions () const override |
Number of local IK solutions. | |
const char * | describe () const override |
Return a human-readable description of this IK subproblem. | |
Public Member Functions inherited from roboticslab::ScrewTheoryIkSubproblem | |
virtual | ~ScrewTheoryIkSubproblem ()=default |
Destructor. | |
Private Attributes | |
const int | id1 |
const int | id2 |
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 | 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. | |
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]).
PardosGotorTwo::PardosGotorTwo | ( | int | id1, |
int | id2, | ||
const MatrixExponential & | exp1, | ||
const MatrixExponential & | exp2, | ||
const KDL::Vector & | p | ||
) |
id1 | Zero-based joint id of the first product of exponentials (POE) term. |
id2 | Zero-based joint id of the second POE term. |
exp1 | First POE term. |
exp2 | Second POE term. |
p | Characteristic point. |
|
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 \) .
rhs | Right-hand side of the POE formula prior to being applied to the right-hand side of this subproblem. |
pointTransform | Transformation frame applied to the first (and perhaps only) characteristic point of this subproblem. |
solutions | Output vector of local solutions. |
Implements roboticslab::ScrewTheoryIkSubproblem.