kinematics-dynamics
Loading...
Searching...
No Matches
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
14namespace roboticslab
15{
16
26{
27public:
29 using JointConfig = std::vector<double>;
30
32 using Solutions = std::vector<JointConfig>;
33
35 virtual ~ScrewTheoryIkSubproblem() = default;
36
75 virtual bool solve(const KDL::Frame & rhs, const KDL::Frame & pointTransform, const JointConfig & reference, Solutions & solutions) const = 0;
76
77 bool solve(const KDL::Frame & rhs, const KDL::Frame & pointTransform, Solutions & _solutions)
78 {
79 return solve(rhs, pointTransform, JointConfig(solutions()), _solutions);
80 }
81
83 virtual int solutions() const = 0;
84
86 virtual const char * describe() const = 0;
87};
88
99{
100public:
102 using JointIdsToSubproblem = std::pair<std::vector<int>, const ScrewTheoryIkSubproblem *>;
103
105 using Steps = std::vector<JointIdsToSubproblem>;
106
108 using Solutions = std::vector<KDL::JntArray>;
109
112
113 // disable these, avoid issues related to dynamic alloc
115 ScrewTheoryIkProblem & operator=(const ScrewTheoryIkProblem &) = delete;
116
127 std::vector<bool> solve(const KDL::Frame & H_S_T, const KDL::JntArray & reference, Solutions & solutions);
128
129 std::vector<bool> solve(const KDL::Frame & H_S_T, Solutions & solutions)
130 {
131 return solve(H_S_T, KDL::JntArray(poe.size()), solutions);
132 }
133
135 int solutions() const
136 { return soln; }
137
139 const Steps & getSteps() const
140 { return steps; }
141
143 bool isReversed() const
144 { return reversed; }
145
155 static ScrewTheoryIkProblem * create(const PoeExpression & poe, const Steps & steps, bool reversed = false);
156
157private:
158 enum poe_term
159 {
160 EXP_KNOWN,
161 EXP_COMPUTED,
162 EXP_UNKNOWN
163 };
164
165 using Frames = std::vector<KDL::Frame>;
166 using PoeTerms = std::vector<poe_term>;
167
168 // disable instantiation, force users to call builder class
169 ScrewTheoryIkProblem(const PoeExpression & poe, const Steps & steps, bool reversed);
170
171 void recalculateFrames(const Solutions & solutions, Frames & frames, PoeTerms & poeTerms);
172 bool recalculateFrames(const Solutions & solutions, Frames & frames, PoeTerms & poeTerms, bool backwards);
173
174 KDL::Frame transformPoint(const KDL::JntArray & jointValues, const PoeTerms & poeTerms);
175
176 const PoeExpression poe;
177
178 // we own these, resources freed in destructor
179 const Steps steps;
180
181 PoeTerms poeTerms;
182 Frames rhsFrames;
183 std::vector<bool> reachability;
184
185 const bool reversed;
186 const int soln;
187};
188
200{
201public:
203 struct PoeTerm
204 {
205 PoeTerm() : known(false), simplified(false) {}
206 bool known, simplified;
207 };
208
215
222
223private:
224 static std::vector<KDL::Vector> searchPoints(const PoeExpression & poe);
225
226 ScrewTheoryIkProblem::Steps searchSolutions();
227
228 void refreshSimplificationState();
229
230 void simplify(int depth);
231 void simplifyWithPadenKahanOne(const KDL::Vector & point);
232 void simplifyWithPadenKahanThree(const KDL::Vector & point);
233 void simplifyWithPardosOne();
234
236
237 PoeExpression poe;
238
239 std::vector<KDL::Vector> points;
240 std::vector<KDL::Vector> testPoints;
241
242 std::vector<PoeTerm> poeTerms;
243
244 static const int MAX_SIMPLIFICATION_DEPTH = 2;
245};
246
247} // namespace roboticslab
248
249#endif // __SCREW_THEORY_IK_PROBLEM_HPP__
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