Proxy IK problem solver class that iterates over a sequence of subproblems.
More...
#include <ScrewTheoryIkProblem.hpp>
|
using | JointIdsToSubproblem = std::pair< std::vector< int >, const ScrewTheoryIkSubproblem * > |
| Pair of joint ids and an their associated local IK subproblem.
|
|
using | Steps = std::vector< JointIdsToSubproblem > |
| Ordered sequence of IK subproblems that solve a global IK problem.
|
|
using | Solutions = std::vector< KDL::JntArray > |
| Collection of global IK solutions.
|
|
|
| ~ScrewTheoryIkProblem () |
| Destructor.
|
|
| ScrewTheoryIkProblem (const ScrewTheoryIkProblem &)=delete |
|
ScrewTheoryIkProblem & | operator= (const ScrewTheoryIkProblem &)=delete |
|
std::vector< bool > | solve (const KDL::Frame &H_S_T, const KDL::JntArray &reference, Solutions &solutions) |
| Find all available solutions.
|
|
std::vector< bool > | solve (const KDL::Frame &H_S_T, Solutions &solutions) |
|
int | solutions () const |
| Number of global IK solutions.
|
|
const Steps & | getSteps () const |
| Solution of the IK problem (if available)
|
|
bool | isReversed () const |
| Whether the computed solution is reversed.
|
|
|
enum | poe_term { EXP_KNOWN
, EXP_COMPUTED
, EXP_UNKNOWN
} |
|
using | Frames = std::vector< KDL::Frame > |
|
using | PoeTerms = std::vector< poe_term > |
|
|
| ScrewTheoryIkProblem (const PoeExpression &poe, const Steps &steps, bool reversed) |
|
void | recalculateFrames (const Solutions &solutions, Frames &frames, PoeTerms &poeTerms) |
|
bool | recalculateFrames (const Solutions &solutions, Frames &frames, PoeTerms &poeTerms, bool backwards) |
|
KDL::Frame | transformPoint (const KDL::JntArray &jointValues, const PoeTerms &poeTerms) |
|
|
const PoeExpression | poe |
|
const Steps | steps |
|
PoeTerms | poeTerms |
|
Frames | rhsFrames |
|
std::vector< bool > | reachability |
|
const bool | reversed |
|
const int | soln |
|
This class is immutable. Instantiation is allowed by means of a static builder method.
- See also
- ScrewTheoryIkProblemBuilder
◆ create()
- Parameters
-
poe | A product of exponentials (POE) formula. |
steps | Collection of subproblems that solve this particular IK problem. |
reversed | True if the POE has been reversed (in order to find a valid solution). |
- Returns
- An instance of an IK problem solver.
◆ solve()
std::vector< bool > ScrewTheoryIkProblem::solve |
( |
const KDL::Frame & |
H_S_T, |
|
|
const KDL::JntArray & |
reference, |
|
|
Solutions & |
solutions |
|
) |
| |
- Parameters
-
H_S_T | Target pose in cartesian space. |
reference | Known nearby solutions to be used as reference in case a singularity is found. |
solutions | Output vector of solutions stored as joint arrays. |
- Returns
- Vector of Booleans indicating whether the associated solution is reachable.
The documentation for this class was generated from the following files: