inverse.cpp
Go to the documentation of this file.
1/* *********************
2 * @file inverse.cpp
3 *
4 * @author Stefan Ulbrich
5 * @date 2013-2014
6 *
7 * @brief This file contains the implementation the methods of the KBM::Models::KBM class related to subdivision and the global IK algorithms.
8 * *********************/
9
10#include <assert.h>
11
12#include <cmath>
13#include <queue>
14
15#include <boost/multi_array.hpp>
16
19
20#include "kbm.h"
21
23{
24
25 /* Removec can be evaluated with subdivide(center,Eigen3::VectorXf::Constant(x,y)
26 * void KBM::subdivide(const Vector &center, Real newSpreadAngle){
27 Vector newSpreadAngles = Vector::Constant(this->nDoF,newSpreadAngle);
28 return this->subdivide(center,newSpreadAngles);
29 }*/
30
31 void
32 KBM::subdivide(const Vector& center, const Vector& newSpreadAngles)
33 {
34 this->getSubdivisedNet(center, newSpreadAngles, this->controlNet);
35 this->spreadAngles = newSpreadAngles;
36 this->center = center;
37 }
38
39 void
40 KBM::getSubdivisedNet(unsigned int subdividedDoF,
41 Real newCenter,
42 Real newSpreadAngle,
43 Matrix& resultingControlNet) const
44 {
45 Matrix SLE = Matrix::Constant(nControlPoints, nControlPoints, 1.0);
46 using CacheType = boost::multi_array<Real, 3>;
47 CacheType cache(boost::extents[this->nDoF][3][3]);
48
49 for (int iDoF = 0; iDoF < this->nDoF; iDoF++)
50 {
51 for (int idx = 0; idx < 3; idx++)
52 for (int idx2 = 0; idx2 < 3; idx2++)
53 {
54 assert(iDoF >= 0);
55 if (static_cast<unsigned int>(iDoF) != subdividedDoF)
56 {
57 if (idx != idx2)
58 {
59 cache[iDoF][idx][idx2] = 0.0f;
60 }
61 else
62 {
63 cache[iDoF][idx][idx2] = 1.0f;
64 }
65 }
66 else
67 {
68 Real a1, a2;
69
70 switch (idx2)
71 {
72 case 0:
73 a1 = (newCenter - this->center(iDoF)) - newSpreadAngle;
74 a2 = (newCenter - this->center(iDoF)) - newSpreadAngle;
75 break;
76
77 case 1:
78 a1 = (newCenter - this->center(iDoF)) - newSpreadAngle;
79 a2 = (newCenter - this->center(iDoF)) + newSpreadAngle;
80 break;
81
82 case 2:
83 a1 = (newCenter - this->center(iDoF)) + newSpreadAngle;
84 a2 = (newCenter - this->center(iDoF)) + newSpreadAngle;
85 break;
86 }
87
88 Real t1 =
89 std::tan(a1 / 2.0) / tan(this->spreadAngles[iDoF] / 2.0) / 2.0 + 0.5;
90 Real t2 =
91 std::tan(a2 / 2.0) / tan(this->spreadAngles[iDoF] / 2.0) / 2.0 + 0.5;
92
93 //ARMARX_DEBUG_S << idx2 << "," << iDoF<< ": " << a1 << "," << a2 << "," << t1 << ","<< t2<<std::endl;
94 switch (idx)
95 {
96 case 0:
97 cache[iDoF][idx][idx2] = (1 - t1) * (1 - t2);
98 break;
99
100 case 1:
101 cache[iDoF][idx][idx2] = ((1 - t1) * t2 + (1 - t2) * t1) *
102 std::cos(this->spreadAngles[iDoF]);
103 break;
104
105 case 2:
106 cache[iDoF][idx][idx2] = t1 * t2;
107 break;
108 }
109 }
110
111 //ARMARX_DEBUG_S << iDoF << "," << idx << "," << idx2 << "," << cache[iDoF][idx][idx2] <<std::endl;
112 }
113 }
114
115 for (int iSamples = 0; iSamples < nControlPoints; iSamples++)
116 {
117 Real weight = 0;
118
119 for (int iControlPoints = 0; iControlPoints < nControlPoints; iControlPoints++)
120 {
121 // SLE(iControlPoints,iSamples)=1.0;
122 // ARMARX_DEBUG_S << SLE;
123 for (int iDoF = 0; iDoF < this->nDoF; iDoF++)
124 {
125 int idx = this->index(iControlPoints, iDoF);
126 int idx2 = this->index(iSamples, iDoF);
127
128 SLE(iControlPoints, iSamples) *= cache[iDoF][idx][idx2];
129 }
130
131 // ARMARX_DEBUG_S << SLE << std::endl;
132 weight += SLE(iControlPoints, iSamples);
133 }
134
135 for (int iControlPoints = 0; iControlPoints < nControlPoints; iControlPoints++)
136 {
137 SLE(iControlPoints, iSamples) /= weight;
138 }
139 }
140
141 // ARMARX_DEBUG_S << std::endl << SLE <<std::endl;
142 resultingControlNet = this->controlNet * SLE;
143 // ARMARX_DEBUG_S << this->controlNet << std::endl;
144 }
145
146 void
148 Vector newSpreadAngles,
149 Matrix& resultingControlNet) const
150 {
151
152 Matrix SLE = Matrix::Constant(nControlPoints, nControlPoints, 1.0);
153
154 using CacheType = boost::multi_array<Real, 3>;
155 CacheType cache(boost::extents[this->nDoF][3][3]);
156
157 for (int iDoF = 0; iDoF < this->nDoF; iDoF++)
158 {
159 for (int idx = 0; idx < 3; idx++)
160 for (int idx2 = 0; idx2 < 3; idx2++)
161 {
162 Real a1, a2;
163
164 switch (idx2)
165 {
166 case 0:
167 a1 = (newCenter(iDoF) - this->center(iDoF)) - newSpreadAngles[iDoF];
168 a2 = (newCenter(iDoF) - this->center(iDoF)) - newSpreadAngles[iDoF];
169 break;
170
171 case 1:
172 a1 = (newCenter(iDoF) - this->center(iDoF)) - newSpreadAngles[iDoF];
173 a2 = (newCenter(iDoF) - this->center(iDoF)) + newSpreadAngles[iDoF];
174 break;
175
176 case 2:
177 a1 = (newCenter(iDoF) - this->center(iDoF)) + newSpreadAngles[iDoF];
178 a2 = (newCenter(iDoF) - this->center(iDoF)) + newSpreadAngles[iDoF];
179 break;
180 }
181
182 Real t1 = std::tan(a1 / 2.0) / tan(this->spreadAngles[iDoF] / 2.0) / 2.0 + 0.5;
183 Real t2 = std::tan(a2 / 2.0) / tan(this->spreadAngles[iDoF] / 2.0) / 2.0 + 0.5;
184
185 //ARMARX_DEBUG_S << idx2 << "," << iDoF<< ": " << a1 << "," << a2 << "," << t1 << ","<< t2<<std::endl;
186 switch (idx)
187 {
188 case 0:
189 cache[iDoF][idx][idx2] = (1 - t1) * (1 - t2);
190 break;
191
192 case 1:
193 cache[iDoF][idx][idx2] = ((1 - t1) * t2 + (1 - t2) * t1) *
194 std::cos(this->spreadAngles[iDoF]);
195 break;
196
197 case 2:
198 cache[iDoF][idx][idx2] = t1 * t2;
199 break;
200 }
201 }
202 }
203
204
205 for (int iSamples = 0; iSamples < nControlPoints; iSamples++)
206 {
207 Real weight = 0;
208
209 for (int iControlPoints = 0; iControlPoints < nControlPoints; iControlPoints++)
210 {
211 // SLE(iControlPoints,iSamples)=1.0;
212 // ARMARX_DEBUG_S << SLE;
213 for (int iDoF = 0; iDoF < this->nDoF; iDoF++)
214 {
215 int idx = this->index(iControlPoints, iDoF);
216 int idx2 = this->index(iSamples, iDoF);
217 SLE(iControlPoints, iSamples) *= cache[iDoF][idx][idx2];
218 }
219
220 //ARMARX_DEBUG_S << SLE;
221 weight += SLE(iControlPoints, iSamples);
222 }
223
224 for (int iControlPoints = 0; iControlPoints < nControlPoints; iControlPoints++)
225 {
226 SLE(iControlPoints, iSamples) /= weight;
227 }
228 }
229
230 // ARMARX_DEBUG_S << std::endl << SLE <<std::endl;
231 resultingControlNet = this->controlNet * SLE;
232 // ARMARX_DEBUG_S << this->controlNet << std::endl;
233 }
234
235 /*Removed -- can be emulated by checkBBox(point,point)
236 * bool KBM::checkBBox(const Vector &point) const
237 {
238 return KBM::checkBBoxes(point,this->controlNet);
239 }*/
240
242 KBM::checkBBox(const Vector& lower, const Vector& upper, Real tolerance) const
243 {
244 return KBM::checkBBoxes(lower, upper, this->controlNet, tolerance);
245 }
246
249 const Vector& upper,
250 const Matrix& controlNet,
251 Real tolerance)
252 {
253 Vector BBlower, BBupper;
254 KBM::getBBox(BBlower, BBupper, controlNet);
255 //ARMARX_DEBUG_S << "lower: " << BBlower.transpose() << ", upper: " << BBupper.transpose() << std::endl << controlNet << std::endl
256 // << "Target lower: " << lower.transpose() << ", uppder: " << upper.transpose() << std::endl;
257 bool covered = true;
258 bool included = true;
259
260 for (int i = 0; i < lower.size(); i++)
261 {
262 if ((BBlower(i) > (upper(i)) + tolerance) || BBupper(i) <= (lower(i) - tolerance))
263 {
264 return KBM::DISJOINT;
265 }
266
267 if ((BBlower(i) < lower(i)) || (BBupper(i) > upper(i)))
268 {
269 covered = false;
270 }
271
272 if ((BBlower(i) > lower(i)) || (BBupper(i) < upper(i)))
273 {
274 included = false;
275 }
276 }
277
278 if (covered)
279 {
280 return KBM::COVERED;
281 }
282
283 if (included)
284 {
285 return KBM::INCLUDED;
286 }
287
288 return KBM::OVERLAPPING;
289 }
290
291 /*Removed -- can be emulated by checkBBoxes(point,point)
292 bool KBM::checkBBoxes(const Vector &point, const Matrix &controlNet)
293 {
294 return KBM::checkBBoxes(point,point,controlNet);
295 }*/
296
297 void
298 KBM::getBBox(Vector& lower, Vector& upper, const Matrix& controlNet)
299 {
300 lower = controlNet.rowwise().minCoeff();
301 upper = controlNet.rowwise().maxCoeff();
302 }
303
304 void
305 KBM::getBBox(Vector& lower, Vector& upper)
306 {
307 getBBox(lower, upper, this->controlNet);
308 }
309
310 Real
312 {
313 Vector lower, upper;
314 this->getBBox(lower, upper);
315 Vector size = upper - lower;
316 return size.prod();
317 }
318
319 Real
320 KBM::getOverlappingVolumeRatio(const Vector& lower, const Vector& upper, Real targetVolume)
321 {
322 Real volume = this->getOverlappingVolume(lower, upper);
323 return volume / targetVolume;
324 }
325
326 Real
327 KBM::getOverlappingVolume(const Vector& lower, const Vector& upper)
328 {
329 Vector BBlower, BBupper;
330 this->getBBox(BBlower, BBupper);
331 Real volume = 1.0;
332
333 for (int i = 0; i < lower.size(); i++)
334 {
335 volume *= std::min(upper(i), BBupper(i)) - std::max(lower(i), BBlower(i));
336
337 if (volume <= 0.0f)
338 {
339 return 0.0f;
340 }
341 }
342
343 return volume;
344 }
345
346} // namespace memoryx::KBM::Models
347
348//int KBM::predictInverse(const Vector &shape, int nSubdivisions, unsigned int dim)
349//{
350// KBM childA(*this), childB(*this);
351// // TODO: Check if solution lies in control net (this->controlNet.[min|max]Coefficient) [>|<] shape
352// // return 0 if not
353// // Todo compute the new centers and spread angles for the children
354// Vector centerA,centerB;
355// std::vector<Real> spreadAnglesA, spreadAnglesB;
356// childA.subdivide(centerA,spreadAnglesA);
357// childB.subdivide(centerB,spreadAnglesB);
358// return childA.predictInverse(shape,nSubdivisions,dim+1) + childB.predictInverse(shape,nSubdivisions,dim+1);
359//}
360
362{
363 // Recursive search
364 void
365 solveGlobalIK(unsigned int recursion,
366 int side,
367 SolutionSet& solutionSet,
368 Models::KBM_ptr kbm,
369 const Vector& lower,
370 const Vector& upper,
371 Real resolution,
372 Vector spreadAngles,
373 Vector center)
374 {
375
376 // 1. Check if target is in BBox. Else stop
377 Matrix controlNet;
378 kbm->getSubdivisedNet(center, spreadAngles, controlNet);
379
380 KBM::Models::KBM::BBCheckType check = Models::KBM::checkBBoxes(lower, upper, controlNet);
381
382 // <for ARMARX_DEBUG_S>
383 Vector BBlower, BBupper;
384 Models::KBM::getBBox(BBlower, BBupper, controlNet);
385 // <for ARMARX_DEBUG_S/>
386 Solution solution(center, spreadAngles, BBupper, BBlower, check);
387
388 // if completely disjoint stop search in this interval.
389 if (check ==
390 KBM::Models::KBM::DISJOINT) //The tolerance should be implemented by upper lower.
391 {
392 solutionSet.push_back(solution);
393 ARMARX_DEBUG_S << "Disjoint: " << std::string(recursion * 2, '-') << recursion << ":"
394 << side << std::endl; /*
395 << "lower: " << lower.transpose() << ", upper: " << upper.transpose() << std::endl
396 << "BB-lower: " << BBlower.transpose() << ", BB-upper: " << BBupper.transpose() << std::endl;*/
397 return;
398 }
399
400
401 // if the interval covers the bounding box, a solution has been found.
402 if (check == KBM::Models::KBM::COVERED)
403 {
404 solutionSet.push_back(solution);
406 << "Covered: " << std::string(recursion * 2, '-') << recursion << ":" << side
407 << std::
408 endl; /* << "center: " << center.transpose() << ", max. angle: " << spreadAngles.maxCoeff()
409 << ", lower: " << lower.transpose() << ", upper: " << upper.transpose()
410 << ", BB-lower: " << BBlower << ", BB-upper: " << BBupper << std::endl;*/
411 return;
412 }
413
414 // 2. Now check if resolution has been reached.
415 if (spreadAngles.maxCoeff() <= resolution)
416 {
417 // Include those solutions as well?
418 if (check == KBM::Models::KBM::INCLUDED)
419 {
420 ARMARX_DEBUG_S << "Max Res: " << std::string(recursion * 2, '-') << recursion
421 << ":" << side << std::endl
422 << "center: " << center.transpose()
423 << ", max. angle: " << spreadAngles.maxCoeff()
424 << ", lower: " << lower.transpose()
425 << ", upper: " << upper.transpose()
426 << ", BB-lower: " << BBlower.transpose()
427 << ", BB-upper: " << BBupper.transpose() << std::endl;
428 }
429
430
431 solutionSet.push_back(solution);
432
433 //ARMARX_DEBUG_Sging stuff
435 << "Max Res: " << std::string(recursion * 2, '-') << recursion << ":" << side
436 << std::
437 endl; /* <<"center: " << center.transpose() << ", max. angle: " << spreadAngles.maxCoeff()
438 << ", lower: " << lower.transpose() << ", upper: " << upper.transpose()
439 << ", BB-lower: " << BBlower.transpose() << ", BB-upper: " << BBupper.transpose() << std::endl;
440 */
441 }
442 // subdivide the input interval
443 else
444 {
445
446 ARMARX_DEBUG_S << "Subdivide: " << std::string(recursion * 2, '-') << recursion << ":"
447 << side << std::endl;
448 Vector center1 = center;
449 Vector center2 = center;
450
451 unsigned int dof = recursion % kbm->getNDoF();
452 center1(dof) = center(dof) + spreadAngles[dof] / 2.0f;
453 center2(dof) = center(dof) - spreadAngles[dof] / 2.0f;
454 spreadAngles[dof] /= 2.0f;
455 solveGlobalIK(recursion + 1,
456 1,
457 solutionSet,
458 kbm,
459 lower,
460 upper,
461 resolution,
462 spreadAngles,
463 center1);
464 solveGlobalIK(recursion + 1,
465 2,
466 solutionSet,
467 kbm,
468 lower,
469 upper,
470 resolution,
471 spreadAngles,
472 center2);
473 }
474 }
475
476 SolutionSet
477 solveGlobalIK(Models::KBM_ptr kbm, const Vector& lower, const Vector& upper, Real resolution)
478 {
479 SolutionSet solution;
481 0,
482 solution,
483 kbm,
484 lower,
485 upper,
486 resolution,
487 kbm->getSpreadAngles(),
488 kbm->getCenter());
489 return solution;
490 }
491
492 SolutionSet
493 solveGlobalIK(Models::KBM_ptr kbm, const Vector& target, Real resolution)
494 {
495 SolutionSet solution;
497 0,
498 solution,
499 kbm,
500 target,
501 target,
502 resolution,
503 kbm->getSpreadAngles(),
504 kbm->getCenter());
505 return solution;
506 }
507
508 void
510 const Vector lower,
511 const Vector upper,
513 {
514 this->targetLower = lower;
515 this->targetUpper = upper;
516 this->resolution = resolution;
517 this->recurse(0, kbm);
518 }
519
522 {
523 Vector center;
524 Vector spreadAngles;
525 this->subdivideAngles(side, recursion, kbm, center, spreadAngles);
526 Matrix controlNet;
527#if 1
528 unsigned int dof = recursion % kbm->getNDoF();
529 kbm->getSubdivisedNet(dof, center[dof], spreadAngles[dof], controlNet);
530#else
531 Matrix controlNet2;
532 kbm->getSubdivisedNet(center, spreadAngles, controlNet2);
533 ARMARX_DEBUG_S << "Similarity of Dof " << dof << ": " << controlNet.isApprox(controlNet2)
534 << std::endl;
535#endif
536
537
539 kbm->getNDoF(), kbm->getNDim(), center, spreadAngles, controlNet);
540 }
541
542 void
544 unsigned int recursion,
545 Models::KBM_ptr kbm,
546 Vector& center,
547 Vector& spreadAngles)
548 {
549 unsigned int dof = recursion % kbm->getNDoF();
550 center = kbm->getCenter();
551 spreadAngles = kbm->getSpreadAngles();
552
553 if (side == GlobalIKBase::LOWER)
554 {
555 center(dof) = center(dof) - spreadAngles[dof] / 2.0f;
556 }
557 else
558 {
559 center(dof) = center(dof) + spreadAngles[dof] / 2.0f;
560 }
561
562 spreadAngles[dof] /= 2.0f;
563 }
564
565 unsigned int
567 {
568 KBM::Models::KBM::BBCheckType check = kbm->checkBBox(this->targetLower, this->targetUpper);
569 // <for ARMARX_DEBUG_S/>
570 Vector BBupper, BBlower;
571 kbm->getBBox(BBupper, BBlower);
572 Solution solution(kbm->getCenter(), kbm->getSpreadAngles(), BBupper, BBlower, check);
573
574 // 1. Definitively a Solution or no definitively solution
575 if (check == KBM::Models::KBM::DISJOINT)
576 {
577 solutions.push_back(solution);
578 return 0;
579 }
580
581 if (check == KBM::Models::KBM::COVERED)
582 {
583 solutions.push_back(solution);
584 return 1;
585 }
586
587 // 2. Now check if resolution has been reached.
588 if (kbm->getSpreadAngles().maxCoeff() <= resolution)
589 {
590 solutions.push_back(solution);
591 return 0;
592 }
593 else
594 {
595 //solutions.push_back(solution);
596
598 int n = this->recurse(level + 1, sub);
599 sub = this->subdivideKBM(GlobalIKBase::UPPER, level, kbm);
600 kbm.reset();
601 n += this->recurse(level + 1, sub);
602 return n;
603 }
604
605 return 0;
606 }
607
608 unsigned int
610 {
611 this->targetVolume = (this->targetUpper - this->targetLower).prod();
612 Real overlap = kbm->getOverlappingVolumeRatio(
613 this->targetLower, this->targetUpper, this->targetVolume);
614
615 KBM::Models::KBM::BBCheckType check = kbm->checkBBox(this->targetLower, this->targetUpper);
616 // <for ARMARX_DEBUG_S/>
617 Solution solution(kbm, check);
618 bool breadth = kbm->getSpreadAngles().maxCoeff() > this->semiBreadthRecursion;
619
620 if (breadth)
621 {
622 ARMARX_DEBUG_S << "breadth " << std::string(level * 2, '-') << level << std::endl;
623 }
624 else
625 {
626 ARMARX_DEBUG_S << "depth " << std::string(level * 2, '-') << level << ": "
627 << kbm->getSpreadAngles().maxCoeff() / M_PI * 180.0f << std::endl;
628 }
629
630 // 1. Definitively a Solution or no definitively solution
631 if (check == KBM::Models::KBM::DISJOINT)
632 {
633 if (breadth && (check & solutionSelect))
634 {
635 solutions.push_back(solution);
636 }
637
638 ARMARX_DEBUG_S << "Dead End: " << overlap << std::endl;
639 assert(overlap == 0.0f);
640 return 0;
641 }
642
643 if (check == KBM::Models::KBM::COVERED)
644 {
645 ARMARX_DEBUG_S << "Solution found: " << overlap << std::endl;
646 solutions.push_back(solution);
647 Real overlap = kbm->getOverlappingVolumeRatio(
648 this->targetLower, this->targetUpper, kbm->getVolume());
649 ARMARX_CHECK_EXPRESSION(overlap == 1.0f);
650 return 1;
651 }
652
653 // 2. Now check if resolution has been reached.
654 if (kbm->getSpreadAngles().maxCoeff() <= resolution)
655 {
656 ARMARX_DEBUG_S << "Max recursion, target overlap " << overlap * 100.f << ", "
657 << kbm->getOverlappingVolumeRatio(
658 this->targetLower, this->targetUpper, kbm->getVolume())
659 << "%" << std::endl;
660 misses++;
661 return 0;
662 }
663 else
664 {
665 if (!breadth && (check & solutionSelect))
666
667 {
668 solutions.push_back(solution);
669 }
670
671
672 if (!breadth)
673 {
674 Real ratio = kbm->getOverlappingVolumeRatio(
675 this->targetLower, this->targetUpper, kbm->getVolume());
676 GraphNode initial(kbm, ratio, level, kbm->getVolume());
677 SolutionSet s = this->runDijkstra(initial);
678 solutions.insert(solutions.end(), s.begin(), s.end());
679 return s.size();
680 }
681 else
682 {
683 Models::KBM_ptr sub1 = this->subdivideKBM(GlobalIKBase::LOWER, level, kbm);
684 Models::KBM_ptr sub2 = this->subdivideKBM(GlobalIKBase::UPPER, level, kbm);
685 Real ratio1 = sub1->getOverlappingVolumeRatio(
686 this->targetLower, this->targetUpper, this->targetVolume);
687 Real ratio2 = sub2->getOverlappingVolumeRatio(
688 this->targetLower, this->targetUpper, this->targetVolume);
689 //Real ratio1 = sub1->getOverlappingVolumeRatio(this->targetLower,this->targetUpper, kbm->getVolume());
690 //Real ratio2 = sub2->getOverlappingVolumeRatio(this->targetLower,this->targetUpper, kbm->getVolume());
691 ARMARX_DEBUG_S << "Reduction by subdivision: "
692 << 100.f * sub1->getVolume() / kbm->getVolume() << "%, "
693 << sub2->getVolume() / kbm->getVolume() * 100.f << "%" << std::endl;
694 ARMARX_DEBUG_S << "Target overlapping: " << ratio1 * 100.f << "%, "
695 << ratio2 * 100.f << "%, " << this->targetVolume << std::endl;
696 kbm.reset();
697
698 //if (std::max(ratio1,ratio2)<0.75){
699 // ARMARX_DEBUG_S << "Not enough overlap\n";
700 // return 0;
701 // }
702 int n;
703
704 if (ratio1 > ratio2)
705 {
706 n = this->recurse(level + 1, sub1);
707 }
708 else
709 {
710 n = this->recurse(level + 1, sub2);
711 }
712
713 if (breadth || n == 0)
714 {
715 //sub = this->subdivideKBM(GlobalIKBase::UPPER,level,kbm);
716 //kbm.reset();
717 if (ratio1 > ratio2)
718 {
719 n += this->recurse(level + 1, sub2);
720 }
721 else
722 {
723 n += this->recurse(level + 1, sub1);
724 }
725 }
726
727 return n;
728 }
729 }
730
731 assert(0);
732 return 0;
733 }
734
735 // ReachabilityTree Klasse anlegen!
736
737 // Reuse GraphNode for extensive search too
738
739 bool
740 operator<(const GraphNode& left, const GraphNode& right)
741 {
742 if (left.ratio != right.ratio)
743 {
744 return left.ratio < right.ratio;
745 }
746
747 return false;
748 }
749
750 GlobalIKBase::SolutionSet
752 {
753 SolutionSet s;
754 std::priority_queue<GraphNode> priority_queue;
755 //priority_queue.push(GraphNode(model,this->targetLower,this->targetUpper,this->targetVolume));
756 priority_queue.push(initial);
757 int counter = 0;
758
759 while (!priority_queue.empty())
760 {
761 GraphNode topNode = priority_queue.top();
762 ARMARX_DEBUG_S << topNode.ratio << ", ";
763 priority_queue.pop();
764
765 if (topNode.ratio == 1.0)
766 {
767 s.push_back(Solution(topNode.model, Models::KBM::COVERED));
768 return s;
769 }
770
771 if (topNode.model->getSpreadAngles().maxCoeff() >= resolution)
772 for (unsigned int side = GlobalIKBase::LOWER; side != GlobalIKBase::END; side++)
773 {
774 Models::KBM_ptr child = this->subdivideKBM(
775 (GlobalIKBase::Side)side, topNode.level + 1, topNode.model);
776 Real volume = child->getVolume();
777 Real ratio = child->getOverlappingVolumeRatio(
778 this->targetLower, this->targetUpper, volume);
779
780 if (ratio != 0.0f)
781 {
782 counter++;
783 priority_queue.push(GraphNode(child, ratio, topNode.level + 1, volume));
784 std::cout << side + 1 << ". Ratio: " << ratio << " ("
785 << ratio / topNode.ratio * 100.0f
786 << "%), Vol.: " << volume / topNode.volume * 100.f << "%, ";
787 }
788 else
789 {
790 std::cout << "0 ";
791 }
792 }
793 else
794 {
795 std::cout << "Resolution: " << topNode.model->getSpreadAngles().maxCoeff();
796 }
797
798 std::cout << ", " << topNode.model->getSpreadAngles().maxCoeff() / M_PI * 180.0f << "("
799 << resolution / M_PI * 180.0f << ")"
800 << ", Level: " << topNode.level << std::endl;
801 }
802
803 ARMARX_DEBUG_S << counter << std::endl;
804 return s;
805 }
806
807 GlobalIKSemiBreadth::GlobalIKSemiBreadth(Real _semiBreadthRecursion, int _solutionSelect) :
808 semiBreadthRecursion(_semiBreadthRecursion), solutionSelect(_solutionSelect)
809 {
810 this->misses = 0;
811 }
812} // namespace memoryx::KBM::Inverse
#define M_PI
Definition MathTools.h:17
virtual unsigned int recurse(unsigned int level, Models::KBM_ptr kbm)=0
void subdivideAngles(Side side, unsigned int recursion, Models::KBM_ptr kbm, Vector &center, Vector &spreadAngles)
Subdivides the joint angles only. Can be used to select in which direction to subdivise first.
Definition inverse.cpp:543
Models::KBM_ptr subdivideKBM(GlobalIKBase::Side side, unsigned int recursion, Models::KBM_ptr kbm)
Subdivides the kbm and creates new KBM. Calls GlobalIKBase::subdivideAngles().
Definition inverse.cpp:521
void solve(Models::KBM_ptr kbm, const Vector lower, const Vector upper, Real resolution=2.0f *M_PI/180.0f)
Definition inverse.cpp:509
std::vector< Solution > SolutionSet
Definition kbm.h:338
unsigned int recurse(unsigned int level, Models::KBM_ptr kbm) override
Definition inverse.cpp:566
unsigned int recurse(unsigned int level, Models::KBM_ptr kbm) override
Definition inverse.cpp:609
GlobalIKSemiBreadth(Real _semiBreadthRecursion, int _solutionSelect=Models::KBM::COVERED)
Definition inverse.cpp:807
GlobalIKBase::SolutionSet runDijkstra(KBM::Inverse::GraphNode initial)
Definition inverse.cpp:751
Real getOverlappingVolumeRatio(const Vector &lower, const Vector &upper, Real targetVolume)
Definition inverse.cpp:320
static BBCheckType checkBBoxes(const Vector &lower, const Vector &upper, const Matrix &controlNet, Real tolerance=0.0f)
Check whether an interval overlaps the the bounding box of a given control net.
Definition inverse.cpp:248
void getSubdivisedNet(const Vector newCenter, Vector newSpreadAngles, Matrix &resultingControlNet) const
Work in progress This method computes the control net of a subdivised KBM instance.
Definition inverse.cpp:147
static KBM_ptr createKBM(int nDoF, int dim, const Vector &center, const Vector &spreadAngles, const Matrix &controlNet)
Factory methods.
Definition kbm.cpp:455
BBCheckType
Cases for the check of bounding boxes (i.e., an interval ) and an interval ( )both in Cartesian coor...
Definition kbm.h:95
@ DISJOINT
The bounding box and interval are disjoint .
Definition kbm.h:101
@ OVERLAPPING
The interval and bounding box are partially overlapping (if none of the above applies).
Definition kbm.h:103
@ INCLUDED
The interval is included in the bounding box .
Definition kbm.h:97
@ COVERED
The bounding box is covered by the interval (most interesting case for inverse kinematics).
Definition kbm.h:99
static void getBBox(Vector &lower, Vector &upper, const Matrix &controlNet)
Helper function that extracts the bounding box of a control net.
Definition inverse.cpp:298
Real getOverlappingVolume(const Vector &lower, const Vector &upper)
Definition inverse.cpp:327
void subdivide(const Vector &center, const Vector &newSpreadAngles)
Work in progress This method subdivides the KBM representation.
Definition inverse.cpp:32
BBCheckType checkBBox(const Vector &lower, const Vector &upper, Real tolerance=0.0f) const
Check whether an interval overlaps the the bounding box of the control points.
Definition inverse.cpp:242
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_DEBUG_S
The logging level for output that is only interesting while debugging.
Definition Logging.h:205
Namespace for algorithms related to solving the inverse kinematics.
Definition inverse.cpp:362
bool operator<(const GraphNode &left, const GraphNode &right)
Definition inverse.cpp:740
std::vector< Solution > SolutionSet
Return type of the global inverse kinematics solvers.
Definition kbm.h:434
void solveGlobalIK(unsigned int recursion, int side, SolutionSet &solutionSet, Models::KBM_ptr kbm, const Vector &lower, const Vector &upper, Real resolution, Vector spreadAngles, Vector center)
Definition inverse.cpp:365
Where the model representation for a Body Schema (especially the Kinematic B“ezier Maps) reside.
Definition inverse.cpp:23
std::shared_ptr< KBM > KBM_ptr
Definition kbm.h:71
Eigen::MatrixXd Matrix
Definition kbm.h:40
Eigen::VectorXd Vector
Definition kbm.h:41
double Real
Type definition of the underlying Realing point type.
Definition kbm.h:39
Point sub(const Point &x, const Point &y)
Definition point.hpp:46
Models::KBM_ptr model
Definition kbm.h:381