kinematics-dynamics
ScrewTheoryIkProblem.hpp
1 // -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2 
3 #ifndef __SCREW_THEORY_IK_PROBLEM_HPP__
4 #define __SCREW_THEORY_IK_PROBLEM_HPP__
5 
6 #include <utility>
7 #include <vector>
8 
9 #include <kdl/frames.hpp>
10 #include <kdl/jntarray.hpp>
11 
12 #include "ProductOfExponentials.hpp"
13 
14 namespace roboticslab
15 {
16 
26 {
27 public:
29  using JointIdToSolution = std::pair<int, double>;
30 
32  using JointIdsToSolutions = std::vector<JointIdToSolution>;
33 
35  using Solutions = std::vector<JointIdsToSolutions>;
36 
38  virtual ~ScrewTheoryIkSubproblem() = default;
39 
76  virtual bool solve(const KDL::Frame & rhs, const KDL::Frame & pointTransform, Solutions & solutions) const = 0;
77 
79  virtual int solutions() const = 0;
80 
82  virtual const char * describe() const = 0;
83 };
84 
95 {
96 public:
98  using Steps = std::vector<const ScrewTheoryIkSubproblem *>;
99 
101  using Solutions = std::vector<KDL::JntArray>;
102 
105 
106  // disable these, avoid issues related to dynamic alloc
107  ScrewTheoryIkProblem(const ScrewTheoryIkProblem &) = delete;
108  ScrewTheoryIkProblem & operator=(const ScrewTheoryIkProblem &) = delete;
109 
118  bool solve(const KDL::Frame & H_S_T, Solutions & solutions);
119 
121  int solutions() const
122  { return soln; }
123 
125  const Steps & getSteps() const
126  { return steps; }
127 
129  bool isReversed() const
130  { return reversed; }
131 
141  static ScrewTheoryIkProblem * create(const PoeExpression & poe, const Steps & steps, bool reversed = false);
142 
143 private:
144  enum poe_term
145  {
146  EXP_KNOWN,
147  EXP_COMPUTED,
148  EXP_UNKNOWN
149  };
150 
151  using Frames = std::vector<KDL::Frame>;
152  using PoeTerms = std::vector<poe_term>;
153 
154  // disable instantiation, force users to call builder class
155  ScrewTheoryIkProblem(const PoeExpression & poe, const Steps & steps, bool reversed);
156 
157  void recalculateFrames(const Solutions & solutions, Frames & frames, PoeTerms & poeTerms);
158  bool recalculateFrames(const Solutions & solutions, Frames & frames, PoeTerms & poeTerms, bool backwards);
159 
160  KDL::Frame transformPoint(const KDL::JntArray & jointValues, const PoeTerms & poeTerms);
161 
162  const PoeExpression poe;
163 
164  // we own these, resources freed in destructor
165  const Steps steps;
166 
167  const bool reversed;
168 
169  const int soln;
170 };
171 
183 {
184 public:
186  struct PoeTerm
187  {
188  PoeTerm() : known(false), simplified(false) {}
189  bool known, simplified;
190  };
191 
198 
205 
206 private:
207  static std::vector<KDL::Vector> searchPoints(const PoeExpression & poe);
208 
209  ScrewTheoryIkProblem::Steps searchSolutions();
210 
211  void refreshSimplificationState();
212 
213  void simplify(int depth);
214  void simplifyWithPadenKahanOne(const KDL::Vector & point);
215  void simplifyWithPadenKahanThree(const KDL::Vector & point);
216  void simplifyWithPardosOne();
217 
218  ScrewTheoryIkSubproblem * trySolve(int depth);
219 
220  PoeExpression poe;
221 
222  std::vector<KDL::Vector> points;
223  std::vector<KDL::Vector> testPoints;
224 
225  std::vector<PoeTerm> poeTerms;
226 
227  static const int MAX_SIMPLIFICATION_DEPTH = 2;
228 };
229 
230 } // namespace roboticslab
231 
232 #endif // __SCREW_THEORY_IK_PROBLEM_HPP__
Abstraction of a product of exponentials (POE) formula.
Definition: ProductOfExponentials.hpp:28
Automated IK solution finder.
Definition: ScrewTheoryIkProblem.hpp:183
ScrewTheoryIkProblem * build()
Finds a valid sequence of geometric subproblems that solve a global IK problem.
Definition: ScrewTheoryIkProblemBuilder.cpp:231
ScrewTheoryIkProblemBuilder(const PoeExpression &poe)
Constructor.
Definition: ScrewTheoryIkProblemBuilder.cpp:144
Proxy IK problem solver class that iterates over a sequence of subproblems.
Definition: ScrewTheoryIkProblem.hpp:95
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:265
const Steps & getSteps() const
Solution of the IK problem (if available)
Definition: ScrewTheoryIkProblem.hpp:125
bool solve(const KDL::Frame &H_S_T, Solutions &solutions)
Find all available solutions.
Definition: ScrewTheoryIkProblem.cpp:62
std::vector< KDL::JntArray > Solutions
Collection of global IK solutions.
Definition: ScrewTheoryIkProblem.hpp:101
~ScrewTheoryIkProblem()
Destructor.
Definition: ScrewTheoryIkProblem.cpp:52
bool isReversed() const
Whether the computed solution is reversed.
Definition: ScrewTheoryIkProblem.hpp:129
std::vector< const ScrewTheoryIkSubproblem * > Steps
Ordered sequence of IK subproblems needed to solve a IK problem.
Definition: ScrewTheoryIkProblem.hpp:98
int solutions() const
Number of global IK solutions.
Definition: ScrewTheoryIkProblem.hpp:121
Interface shared by all IK subproblems found in Screw Theory applied to Robotics.
Definition: ScrewTheoryIkProblem.hpp:26
std::vector< JointIdsToSolutions > Solutions
Collection of local IK solutions.
Definition: ScrewTheoryIkProblem.hpp:35
std::vector< JointIdToSolution > JointIdsToSolutions
At least one joint-id+value pair per solution.
Definition: ScrewTheoryIkProblem.hpp:32
virtual int solutions() const =0
Number of local IK solutions.
virtual ~ScrewTheoryIkSubproblem()=default
Destructor.
virtual bool solve(const KDL::Frame &rhs, const KDL::Frame &pointTransform, 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.
std::pair< int, double > JointIdToSolution
Maps a joint id to a screw magnitude.
Definition: ScrewTheoryIkProblem.hpp:29
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:187