3#ifndef __SCREW_THEORY_IK_PROBLEM_HPP__
4#define __SCREW_THEORY_IK_PROBLEM_HPP__
9#include <kdl/frames.hpp>
10#include <kdl/jntarray.hpp>
12#include "ProductOfExponentials.hpp"
77 bool solve(
const KDL::Frame & rhs,
const KDL::Frame & pointTransform,
Solutions & _solutions)
105 using Steps = std::vector<JointIdsToSubproblem>;
165 using Frames = std::vector<KDL::Frame>;
166 using PoeTerms = std::vector<poe_term>;
169 ScrewTheoryIkProblem(
const PoeExpression & poe,
const Steps & steps,
bool reversed);
171 void recalculateFrames(
const Solutions &
solutions, Frames & frames, PoeTerms & poeTerms);
172 bool recalculateFrames(
const Solutions &
solutions, Frames & frames, PoeTerms & poeTerms,
bool backwards);
174 KDL::Frame transformPoint(
const KDL::JntArray & jointValues,
const PoeTerms & poeTerms);
176 const PoeExpression poe;
183 std::vector<bool> reachability;
205 PoeTerm() : known(
false), simplified(
false) {}
206 bool known, simplified;
224 static std::vector<KDL::Vector> searchPoints(
const PoeExpression & poe);
228 void refreshSimplificationState();
230 void simplify(
int depth);
231 void simplifyWithPadenKahanOne(
const KDL::Vector & point);
232 void simplifyWithPadenKahanThree(
const KDL::Vector & point);
233 void simplifyWithPardosOne();
239 std::vector<KDL::Vector> points;
240 std::vector<KDL::Vector> testPoints;
242 std::vector<PoeTerm> poeTerms;
244 static const int MAX_SIMPLIFICATION_DEPTH = 2;
Abstraction of a product of exponentials (POE) formula.
Definition ProductOfExponentials.hpp:28
int size() const
Size of this POE.
Definition ProductOfExponentials.hpp:76
Automated IK solution finder.
Definition ScrewTheoryIkProblem.hpp:200
ScrewTheoryIkProblem * build()
Finds a valid sequence of geometric subproblems that solve a global IK problem.
Definition ScrewTheoryIkProblemBuilder.cpp:231
Proxy IK problem solver class that iterates over a sequence of subproblems.
Definition ScrewTheoryIkProblem.hpp:99
static ScrewTheoryIkProblem * create(const PoeExpression &poe, const Steps &steps, bool reversed=false)
Creates an IK solver instance given a sequence of known subproblems.
Definition ScrewTheoryIkProblem.cpp:290
std::vector< KDL::JntArray > Solutions
Collection of global IK solutions.
Definition ScrewTheoryIkProblem.hpp:108
~ScrewTheoryIkProblem()
Destructor.
Definition ScrewTheoryIkProblem.cpp:70
std::pair< std::vector< int >, const ScrewTheoryIkSubproblem * > JointIdsToSubproblem
Pair of joint ids and an their associated local IK subproblem.
Definition ScrewTheoryIkProblem.hpp:102
const Steps & getSteps() const
Solution of the IK problem (if available)
Definition ScrewTheoryIkProblem.hpp:139
std::vector< bool > solve(const KDL::Frame &H_S_T, const KDL::JntArray &reference, Solutions &solutions)
Find all available solutions.
Definition ScrewTheoryIkProblem.cpp:80
bool isReversed() const
Whether the computed solution is reversed.
Definition ScrewTheoryIkProblem.hpp:143
std::vector< JointIdsToSubproblem > Steps
Ordered sequence of IK subproblems that solve a global IK problem.
Definition ScrewTheoryIkProblem.hpp:105
int solutions() const
Number of global IK solutions.
Definition ScrewTheoryIkProblem.hpp:135
Interface shared by all IK subproblems found in Screw Theory applied to Robotics.
Definition ScrewTheoryIkProblem.hpp:26
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.
virtual const char * describe() const =0
Return a human-readable description of this IK subproblem.
virtual int solutions() const =0
Number of local IK solutions.
virtual ~ScrewTheoryIkSubproblem()=default
Destructor.
std::vector< double > JointConfig
Joint configurations.
Definition ScrewTheoryIkProblem.hpp:29
std::vector< JointConfig > Solutions
Collection of local IK solutions.
Definition ScrewTheoryIkProblem.hpp:32
The main, catch-all namespace for Robotics Lab UC3M.
Definition groups.dox:6
Helper structure that holds the state of a POE term.
Definition ScrewTheoryIkProblem.hpp:204