1 /*
2 * Copyright (c) 2011-2021, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33 #include "dart/dynamics/HierarchicalIK.hpp"
34 #include "dart/dynamics/BodyNode.hpp"
35 #include "dart/dynamics/DegreeOfFreedom.hpp"
36 #include "dart/dynamics/EndEffector.hpp"
37 #include "dart/dynamics/Skeleton.hpp"
38 #include "dart/optimizer/GradientDescentSolver.hpp"
39
40 namespace dart {
41 namespace dynamics {
42
43 //==============================================================================
solve(bool applySolution)44 bool HierarchicalIK::solve(bool applySolution)
45 {
46 if (applySolution)
47 {
48 return solveAndApply(true);
49 }
50 else
51 {
52 Eigen::VectorXd positions;
53 return findSolution(positions);
54 }
55 }
56
57 //==============================================================================
solve(Eigen::VectorXd & positions,bool applySolution)58 bool HierarchicalIK::solve(Eigen::VectorXd& positions, bool applySolution)
59 {
60 if (applySolution)
61 return solveAndApply(positions, true);
62 else
63 return findSolution(positions);
64 }
65
66 //==============================================================================
findSolution(Eigen::VectorXd & positions)67 bool HierarchicalIK::findSolution(Eigen::VectorXd& positions)
68 {
69 if (nullptr == mSolver)
70 {
71 dtwarn << "[HierarchicalIK::findSolution] The Solver for a HierarchicalIK "
72 << "module associated with [" << mSkeleton.lock()->getName()
73 << "] is a nullptr. You must reset the module's Solver before you "
74 << "can use it.\n";
75 return false;
76 }
77
78 if (nullptr == mProblem)
79 {
80 dtwarn << "[HierarchicalIK::findSolution] The Problem for a HierarchicalIK "
81 << "module associated with [" << mSkeleton.lock()->getName()
82 << "] is a nullptr. You must reset the module's Problem before you "
83 << "can use it.\n";
84 return false;
85 }
86
87 const SkeletonPtr& skel = getSkeleton();
88
89 if (nullptr == skel)
90 {
91 dtwarn << "[HierarchicalIK::findSolution] Calling a HierarchicalIK module "
92 << "which is associated with a Skeleton that no longer exists.\n";
93 return false;
94 }
95
96 const std::size_t nDofs = skel->getNumDofs();
97 mProblem->setDimension(nDofs);
98
99 mProblem->setInitialGuess(skel->getPositions());
100
101 Eigen::VectorXd bounds(nDofs);
102 for (std::size_t i = 0; i < nDofs; ++i)
103 bounds[i] = skel->getDof(i)->getPositionLowerLimit();
104 mProblem->setLowerBounds(bounds);
105
106 for (std::size_t i = 0; i < nDofs; ++i)
107 bounds[i] = skel->getDof(i)->getPositionUpperLimit();
108 mProblem->setUpperBounds(bounds);
109
110 refreshIKHierarchy();
111
112 // Many GradientMethod implementations use Joint::integratePositions, so we
113 // need to clear out any velocities that might be in the Skeleton and then
114 // reset those velocities later. This has been opened as issue #699.
115 const Eigen::VectorXd originalVelocities = skel->getVelocities();
116 skel->resetVelocities();
117
118 const Eigen::VectorXd originalPositions = skel->getPositions();
119 const bool wasSolved = mSolver->solve();
120
121 positions = mProblem->getOptimalSolution();
122
123 setPositions(originalPositions);
124 skel->setVelocities(originalVelocities);
125 return wasSolved;
126 }
127
128 //==============================================================================
solveAndApply(bool allowIncompleteResult)129 bool HierarchicalIK::solveAndApply(bool allowIncompleteResult)
130 {
131 Eigen::VectorXd solution;
132 const auto wasSolved = findSolution(solution);
133 if (wasSolved || allowIncompleteResult)
134 setPositions(solution);
135 return wasSolved;
136 }
137
138 //==============================================================================
solveAndApply(Eigen::VectorXd & positions,bool allowIncompleteResult)139 bool HierarchicalIK::solveAndApply(
140 Eigen::VectorXd& positions, bool allowIncompleteResult)
141 {
142 const auto wasSolved = findSolution(positions);
143 if (wasSolved || allowIncompleteResult)
144 setPositions(positions);
145 return wasSolved;
146 }
147
148 //==============================================================================
setObjective(const std::shared_ptr<optimizer::Function> & _objective)149 void HierarchicalIK::setObjective(
150 const std::shared_ptr<optimizer::Function>& _objective)
151 {
152 mObjective = _objective;
153 }
154
155 //==============================================================================
getObjective()156 const std::shared_ptr<optimizer::Function>& HierarchicalIK::getObjective()
157 {
158 return mObjective;
159 }
160
161 //==============================================================================
getObjective() const162 std::shared_ptr<const optimizer::Function> HierarchicalIK::getObjective() const
163 {
164 return mObjective;
165 }
166
167 //==============================================================================
setNullSpaceObjective(const std::shared_ptr<optimizer::Function> & _nsObjective)168 void HierarchicalIK::setNullSpaceObjective(
169 const std::shared_ptr<optimizer::Function>& _nsObjective)
170 {
171 mNullSpaceObjective = _nsObjective;
172 }
173
174 //==============================================================================
175 const std::shared_ptr<optimizer::Function>&
getNullSpaceObjective()176 HierarchicalIK::getNullSpaceObjective()
177 {
178 return mNullSpaceObjective;
179 }
180
181 //==============================================================================
182 std::shared_ptr<const optimizer::Function>
getNullSpaceObjective() const183 HierarchicalIK::getNullSpaceObjective() const
184 {
185 return mNullSpaceObjective;
186 }
187
188 //==============================================================================
hasNullSpaceObjective() const189 bool HierarchicalIK::hasNullSpaceObjective() const
190 {
191 return (nullptr != mNullSpaceObjective);
192 }
193
194 //==============================================================================
getProblem()195 const std::shared_ptr<optimizer::Problem>& HierarchicalIK::getProblem()
196 {
197 return mProblem;
198 }
199
200 //==============================================================================
getProblem() const201 std::shared_ptr<const optimizer::Problem> HierarchicalIK::getProblem() const
202 {
203 return mProblem;
204 }
205
206 //==============================================================================
resetProblem(bool _clearSeeds)207 void HierarchicalIK::resetProblem(bool _clearSeeds)
208 {
209 mProblem->removeAllEqConstraints();
210 mProblem->removeAllIneqConstraints();
211
212 if (_clearSeeds)
213 mProblem->clearAllSeeds();
214
215 mProblem->setObjective(std::make_shared<Objective>(mPtr.lock()));
216 mProblem->addEqConstraint(std::make_shared<Constraint>(mPtr.lock()));
217
218 mProblem->setDimension(mSkeleton.lock()->getNumDofs());
219 }
220
221 //==============================================================================
setSolver(const std::shared_ptr<optimizer::Solver> & _newSolver)222 void HierarchicalIK::setSolver(
223 const std::shared_ptr<optimizer::Solver>& _newSolver)
224 {
225 mSolver = _newSolver;
226 if (nullptr == mSolver)
227 return;
228
229 mSolver->setProblem(mProblem);
230 }
231
232 //==============================================================================
getSolver()233 const std::shared_ptr<optimizer::Solver>& HierarchicalIK::getSolver()
234 {
235 return mSolver;
236 }
237
238 //==============================================================================
getSolver() const239 std::shared_ptr<const optimizer::Solver> HierarchicalIK::getSolver() const
240 {
241 return mSolver;
242 }
243
244 //==============================================================================
getIKHierarchy() const245 const IKHierarchy& HierarchicalIK::getIKHierarchy() const
246 {
247 return mHierarchy;
248 }
249
250 //==============================================================================
computeNullSpaces() const251 const std::vector<Eigen::MatrixXd>& HierarchicalIK::computeNullSpaces() const
252 {
253 bool recompute = false;
254 const ConstSkeletonPtr& skel = getSkeleton();
255 const std::size_t nDofs = skel->getNumDofs();
256 if (static_cast<std::size_t>(mLastPositions.size()) != nDofs)
257 {
258 recompute = true;
259 }
260 else
261 {
262 for (std::size_t i = 0; i < nDofs; ++i)
263 {
264 if (mLastPositions[i] != skel->getDof(i)->getPosition())
265 {
266 recompute = true;
267 break;
268 }
269 }
270 }
271
272 // TODO(MXG): When deciding whether we need to recompute, we should also check
273 // the "version" of the Skeleton, as soon as the Skeleton versioning features
274 // are available. The version should account for information about changes in
275 // indexing and changes in Joint / BodyNode properties.
276
277 if (!recompute)
278 return mNullSpaceCache;
279
280 const IKHierarchy& hierarchy = getIKHierarchy();
281
282 mNullSpaceCache.resize(hierarchy.size());
283 bool zeroedNullSpace = false;
284 for (std::size_t i = 0; i < hierarchy.size(); ++i)
285 {
286 const std::vector<std::shared_ptr<InverseKinematics> >& level
287 = hierarchy[i];
288
289 Eigen::MatrixXd& NS = mNullSpaceCache[i];
290 if (i == 0)
291 {
292 // Start with an identity null space
293 NS = Eigen::MatrixXd::Identity(nDofs, nDofs);
294 }
295 else if (zeroedNullSpace)
296 {
297 // If the null space has been zeroed out, just keep propogating the zeroes
298 NS.setZero(nDofs, nDofs);
299 continue;
300 }
301 else
302 {
303 // Otherwise, we will just build on the last level's null space
304 NS = mNullSpaceCache[i - 1];
305 }
306
307 mJacCache.resize(6, nDofs);
308 for (std::size_t j = 0; j < level.size(); ++j)
309 {
310 const std::shared_ptr<InverseKinematics>& ik = level[j];
311
312 if (!ik->isActive())
313 continue;
314
315 const math::Jacobian& J = ik->computeJacobian();
316 const std::vector<std::size_t>& dofs = ik->getDofs();
317
318 mJacCache.setZero();
319 for (std::size_t d = 0; d < dofs.size(); ++d)
320 {
321 std::size_t k = dofs[d];
322 mJacCache.block<6, 1>(0, k) = J.block<6, 1>(0, d);
323 }
324
325 mSVDCache.compute(mJacCache, Eigen::ComputeFullV);
326 math::extractNullSpace(mSVDCache, mPartialNullspaceCache);
327
328 if (mPartialNullspaceCache.rows() > 0
329 && mPartialNullspaceCache.cols() > 0)
330 {
331 NS *= mPartialNullspaceCache * mPartialNullspaceCache.transpose();
332 }
333 else
334 {
335 // There no longer exists a null space for this or any lower level
336 NS.setZero();
337 zeroedNullSpace = true;
338 break;
339 }
340 }
341 }
342
343 return mNullSpaceCache;
344 }
345
346 //==============================================================================
getPositions() const347 Eigen::VectorXd HierarchicalIK::getPositions() const
348 {
349 const SkeletonPtr& skel = mSkeleton.lock();
350 if (skel)
351 return skel->getPositions();
352
353 return Eigen::VectorXd();
354 }
355
356 //==============================================================================
setPositions(const Eigen::VectorXd & _q)357 void HierarchicalIK::setPositions(const Eigen::VectorXd& _q)
358 {
359 const SkeletonPtr& skel = mSkeleton.lock();
360 if (skel)
361 skel->setPositions(_q);
362 }
363
364 //==============================================================================
getSkeleton()365 SkeletonPtr HierarchicalIK::getSkeleton()
366 {
367 return getAffiliation();
368 }
369
370 //==============================================================================
getSkeleton() const371 ConstSkeletonPtr HierarchicalIK::getSkeleton() const
372 {
373 return getAffiliation();
374 }
375
376 //==============================================================================
getAffiliation()377 SkeletonPtr HierarchicalIK::getAffiliation()
378 {
379 return mSkeleton.lock();
380 }
381
382 //==============================================================================
getAffiliation() const383 ConstSkeletonPtr HierarchicalIK::getAffiliation() const
384 {
385 return mSkeleton.lock();
386 }
387
388 //==============================================================================
clearCaches()389 void HierarchicalIK::clearCaches()
390 {
391 mLastPositions.resize(0);
392 }
393
394 //==============================================================================
Objective(const std::shared_ptr<HierarchicalIK> & _ik)395 HierarchicalIK::Objective::Objective(const std::shared_ptr<HierarchicalIK>& _ik)
396 : mIK(_ik)
397 {
398 // Do nothing
399 }
400
401 //==============================================================================
clone(const std::shared_ptr<HierarchicalIK> & _newIK) const402 optimizer::FunctionPtr HierarchicalIK::Objective::clone(
403 const std::shared_ptr<HierarchicalIK>& _newIK) const
404 {
405 return std::make_shared<Objective>(_newIK);
406 }
407
408 //==============================================================================
eval(const Eigen::VectorXd & _x)409 double HierarchicalIK::Objective::eval(const Eigen::VectorXd& _x)
410 {
411 const std::shared_ptr<HierarchicalIK>& hik = mIK.lock();
412
413 if (nullptr == hik)
414 {
415 dterr << "[HierarchicalIK::Objective::eval] Attempting to use an Objective "
416 << "function of an expired HierarchicalIK module!\n";
417 assert(false);
418 return 0;
419 }
420
421 double cost = 0.0;
422
423 if (hik->mObjective)
424 cost += hik->mObjective->eval(_x);
425
426 if (hik->mNullSpaceObjective)
427 cost += hik->mNullSpaceObjective->eval(_x);
428
429 return cost;
430 }
431
432 //==============================================================================
evalGradient(const Eigen::VectorXd & _x,Eigen::Map<Eigen::VectorXd> _grad)433 void HierarchicalIK::Objective::evalGradient(
434 const Eigen::VectorXd& _x, Eigen::Map<Eigen::VectorXd> _grad)
435 {
436 const std::shared_ptr<HierarchicalIK>& hik = mIK.lock();
437
438 if (nullptr == hik)
439 {
440 dterr << "[HierarchicalIK::Objective::evalGradient] Attempting to use an "
441 << "Objective function of an expired HierarchicalIK module!\n";
442 assert(false);
443 return;
444 }
445
446 if (hik->mObjective)
447 hik->mObjective->evalGradient(_x, _grad);
448 else
449 _grad.setZero();
450
451 if (hik->mNullSpaceObjective)
452 {
453 mGradCache.resize(_grad.size());
454 Eigen::Map<Eigen::VectorXd> gradMap(mGradCache.data(), _grad.size());
455 hik->mNullSpaceObjective->evalGradient(_x, gradMap);
456
457 hik->setPositions(_x);
458
459 const std::vector<Eigen::MatrixXd>& nullspaces = hik->computeNullSpaces();
460 if (nullspaces.size() > 0)
461 {
462 // Project through the deepest null space
463 mGradCache = nullspaces.back() * mGradCache;
464 }
465
466 _grad += mGradCache;
467 }
468 }
469
470 //==============================================================================
Constraint(const std::shared_ptr<HierarchicalIK> & _ik)471 HierarchicalIK::Constraint::Constraint(
472 const std::shared_ptr<HierarchicalIK>& _ik)
473 : mIK(_ik)
474 {
475 // Do nothing
476 }
477
478 //==============================================================================
clone(const std::shared_ptr<HierarchicalIK> & _newIK) const479 optimizer::FunctionPtr HierarchicalIK::Constraint::clone(
480 const std::shared_ptr<HierarchicalIK>& _newIK) const
481 {
482 return std::make_shared<Constraint>(_newIK);
483 }
484
485 //==============================================================================
eval(const Eigen::VectorXd & _x)486 double HierarchicalIK::Constraint::eval(const Eigen::VectorXd& _x)
487 {
488 const std::shared_ptr<HierarchicalIK>& hik = mIK.lock();
489 if (nullptr == hik)
490 {
491 dterr << "[HierarchicalIK::Constraint::eval] Attempting to use a "
492 << "Constraint function of an expired HierarchicalIK module!\n";
493 assert(false);
494 return 0.0;
495 }
496
497 const IKHierarchy& hierarchy = hik->getIKHierarchy();
498
499 double cost = 0.0;
500 for (std::size_t i = 0; i < hierarchy.size(); ++i)
501 {
502 const std::vector<std::shared_ptr<InverseKinematics> >& level
503 = hierarchy[i];
504
505 for (std::size_t j = 0; j < level.size(); ++j)
506 {
507 const std::shared_ptr<InverseKinematics>& ik = level[j];
508
509 if (!ik->isActive())
510 continue;
511
512 const std::vector<std::size_t>& dofs = ik->getDofs();
513 Eigen::VectorXd q(dofs.size());
514 for (std::size_t k = 0; k < dofs.size(); ++k)
515 q[k] = _x[dofs[k]];
516
517 InverseKinematics::ErrorMethod& method = ik->getErrorMethod();
518 const Eigen::Vector6d& error = method.evalError(q);
519
520 cost += error.dot(error);
521 }
522 }
523
524 return std::sqrt(cost);
525 }
526
527 //==============================================================================
evalGradient(const Eigen::VectorXd & _x,Eigen::Map<Eigen::VectorXd> _grad)528 void HierarchicalIK::Constraint::evalGradient(
529 const Eigen::VectorXd& _x, Eigen::Map<Eigen::VectorXd> _grad)
530 {
531 const std::shared_ptr<HierarchicalIK>& hik = mIK.lock();
532
533 const IKHierarchy& hierarchy = hik->getIKHierarchy();
534 const SkeletonPtr& skel = hik->getSkeleton();
535 const std::size_t nDofs = skel->getNumDofs();
536 const std::vector<Eigen::MatrixXd>& nullspaces = hik->computeNullSpaces();
537
538 _grad.setZero();
539 for (std::size_t i = 0; i < hierarchy.size(); ++i)
540 {
541 const std::vector<std::shared_ptr<InverseKinematics> >& level
542 = hierarchy[i];
543
544 mLevelGradCache.setZero(nDofs);
545 for (std::size_t j = 0; j < level.size(); ++j)
546 {
547 const std::shared_ptr<InverseKinematics>& ik = level[j];
548
549 if (!ik->isActive())
550 continue;
551
552 // Grab only the dependent coordinates from q
553 const std::vector<std::size_t>& dofs = ik->getDofs();
554 Eigen::VectorXd q(dofs.size());
555 for (std::size_t k = 0; k < dofs.size(); ++k)
556 q[k] = _x[dofs[k]];
557
558 // Compute the gradient of this specific error term
559 mTempGradCache.setZero(dofs.size());
560 Eigen::Map<Eigen::VectorXd> gradMap(
561 mTempGradCache.data(), mTempGradCache.size());
562
563 InverseKinematics::GradientMethod& method = ik->getGradientMethod();
564 method.evalGradient(q, gradMap);
565
566 // Add the components of this gradient into the gradient of this level
567 for (std::size_t k = 0; k < dofs.size(); ++k)
568 mLevelGradCache[dofs[k]] += mTempGradCache[k];
569 }
570
571 // Project this level's gradient through the null spaces of the levels with
572 // higher precedence, then add it to the overall gradient
573 if (i > 0)
574 _grad += nullspaces[i - 1] * mLevelGradCache;
575 else
576 _grad += mLevelGradCache;
577 }
578 }
579
580 //==============================================================================
HierarchicalIK(const SkeletonPtr & _skeleton)581 HierarchicalIK::HierarchicalIK(const SkeletonPtr& _skeleton)
582 : mSkeleton(_skeleton)
583 {
584 // initialize MUST be called immediately after the construction of any
585 // directly inheriting classes.
586 }
587
588 //==============================================================================
initialize(const std::shared_ptr<HierarchicalIK> & my_ptr)589 void HierarchicalIK::initialize(const std::shared_ptr<HierarchicalIK>& my_ptr)
590 {
591 mPtr = my_ptr;
592
593 setObjective(nullptr);
594 setNullSpaceObjective(nullptr);
595
596 mProblem = std::make_shared<optimizer::Problem>();
597 resetProblem();
598
599 std::shared_ptr<optimizer::GradientDescentSolver> solver
600 = std::make_shared<optimizer::GradientDescentSolver>(mProblem);
601 solver->setStepSize(1.0);
602 mSolver = solver;
603 }
604
605 //==============================================================================
cloneIkFunc(const std::shared_ptr<optimizer::Function> & _function,const std::shared_ptr<HierarchicalIK> & _ik)606 static std::shared_ptr<optimizer::Function> cloneIkFunc(
607 const std::shared_ptr<optimizer::Function>& _function,
608 const std::shared_ptr<HierarchicalIK>& _ik)
609 {
610 std::shared_ptr<HierarchicalIK::Function> ikFunc
611 = std::dynamic_pointer_cast<HierarchicalIK::Function>(_function);
612
613 if (ikFunc)
614 return ikFunc->clone(_ik);
615
616 return _function;
617 }
618
619 //==============================================================================
copyOverSetup(const std::shared_ptr<HierarchicalIK> & _otherIK) const620 void HierarchicalIK::copyOverSetup(
621 const std::shared_ptr<HierarchicalIK>& _otherIK) const
622 {
623 _otherIK->setSolver(mSolver->clone());
624
625 const std::shared_ptr<optimizer::Problem>& newProblem
626 = _otherIK->getProblem();
627 newProblem->setObjective(cloneIkFunc(mProblem->getObjective(), _otherIK));
628
629 newProblem->removeAllEqConstraints();
630 for (std::size_t i = 0; i < mProblem->getNumEqConstraints(); ++i)
631 newProblem->addEqConstraint(
632 cloneIkFunc(mProblem->getEqConstraint(i), _otherIK));
633
634 newProblem->removeAllIneqConstraints();
635 for (std::size_t i = 0; i < mProblem->getNumIneqConstraints(); ++i)
636 newProblem->addIneqConstraint(
637 cloneIkFunc(mProblem->getIneqConstraint(i), _otherIK));
638
639 newProblem->getSeeds() = mProblem->getSeeds();
640 }
641
642 //==============================================================================
create(const SkeletonPtr & _skel)643 std::shared_ptr<CompositeIK> CompositeIK::create(const SkeletonPtr& _skel)
644 {
645 std::shared_ptr<CompositeIK> ik(new CompositeIK(_skel));
646 ik->initialize(ik);
647 return ik;
648 }
649
650 //==============================================================================
clone(const SkeletonPtr & _newSkel) const651 std::shared_ptr<HierarchicalIK> CompositeIK::clone(
652 const SkeletonPtr& _newSkel) const
653 {
654 return cloneCompositeIK(_newSkel);
655 }
656
657 //==============================================================================
cloneCompositeIK(const SkeletonPtr & _newSkel) const658 std::shared_ptr<CompositeIK> CompositeIK::cloneCompositeIK(
659 const SkeletonPtr& _newSkel) const
660 {
661 std::shared_ptr<CompositeIK> newComposite = create(_newSkel);
662 copyOverSetup(newComposite);
663
664 for (const std::shared_ptr<InverseKinematics>& ik : mModuleSet)
665 {
666 JacobianNode* node = nullptr;
667 JacobianNode* oldNode = ik->getNode();
668
669 if (dynamic_cast<BodyNode*>(oldNode))
670 {
671 node = _newSkel->getBodyNode(oldNode->getName());
672 }
673 else if (dynamic_cast<EndEffector*>(oldNode))
674 {
675 node = _newSkel->getEndEffector(oldNode->getName());
676 }
677
678 if (node)
679 {
680 newComposite->addModule(ik->clone(node));
681 }
682 }
683
684 return newComposite;
685 }
686
687 //==============================================================================
addModule(const std::shared_ptr<InverseKinematics> & _ik)688 bool CompositeIK::addModule(const std::shared_ptr<InverseKinematics>& _ik)
689 {
690 if (_ik->getNode()->getSkeleton() != mSkeleton.lock())
691 return false; // Should we print a warning message here, or is the return
692 // value sufficient?
693
694 ModuleSet::iterator it = mModuleSet.find(_ik);
695
696 // We already have this module
697 if (it != mModuleSet.end())
698 return true;
699
700 mModuleSet.insert(_ik);
701
702 return true;
703 }
704
705 //==============================================================================
getModuleSet()706 const CompositeIK::ModuleSet& CompositeIK::getModuleSet()
707 {
708 return mModuleSet;
709 }
710
711 //==============================================================================
getModuleSet() const712 CompositeIK::ConstModuleSet CompositeIK::getModuleSet() const
713 {
714 ConstModuleSet modules;
715 for (const std::shared_ptr<InverseKinematics>& module : mModuleSet)
716 modules.insert(module);
717
718 return modules;
719 }
720
721 //==============================================================================
refreshIKHierarchy()722 void CompositeIK::refreshIKHierarchy()
723 {
724 if (mModuleSet.size() == 0)
725 {
726 mHierarchy.clear();
727 return;
728 }
729
730 int highestLevel = -1;
731 for (const std::shared_ptr<InverseKinematics>& module : mModuleSet)
732 {
733 highestLevel
734 = std::max(static_cast<int>(module->getHierarchyLevel()), highestLevel);
735 }
736
737 assert(highestLevel >= 0);
738
739 mHierarchy.resize(highestLevel + 1);
740 for (auto& level : mHierarchy)
741 level.clear();
742
743 for (const std::shared_ptr<InverseKinematics>& module : mModuleSet)
744 mHierarchy[module->getHierarchyLevel()].push_back(module);
745 }
746
747 //==============================================================================
CompositeIK(const SkeletonPtr & _skel)748 CompositeIK::CompositeIK(const SkeletonPtr& _skel) : HierarchicalIK(_skel)
749 {
750 // Do nothing
751 }
752
753 //==============================================================================
create(const SkeletonPtr & _skel)754 std::shared_ptr<WholeBodyIK> WholeBodyIK::create(const SkeletonPtr& _skel)
755 {
756 std::shared_ptr<WholeBodyIK> ik(new WholeBodyIK(_skel));
757 ik->initialize(ik);
758 return ik;
759 }
760
761 //==============================================================================
clone(const SkeletonPtr & _newSkel) const762 std::shared_ptr<HierarchicalIK> WholeBodyIK::clone(
763 const SkeletonPtr& _newSkel) const
764 {
765 return cloneWholeBodyIK(_newSkel);
766 }
767
768 //==============================================================================
cloneWholeBodyIK(const SkeletonPtr & _newSkel) const769 std::shared_ptr<WholeBodyIK> WholeBodyIK::cloneWholeBodyIK(
770 const SkeletonPtr& _newSkel) const
771 {
772 std::shared_ptr<WholeBodyIK> newIK = create(_newSkel);
773 copyOverSetup(newIK);
774 return newIK;
775 }
776
777 //==============================================================================
refreshIKHierarchy()778 void WholeBodyIK::refreshIKHierarchy()
779 {
780 const SkeletonPtr& skel = mSkeleton.lock();
781
782 // TODO(MXG): Consider giving Skeletons a list of all the JacobianNodes that
783 // they contain, so that we can make this extensible to user-defined
784 // JacobianNode types, and also make the code more DRY.
785
786 int highestLevel = -1;
787 for (std::size_t i = 0; i < skel->getNumBodyNodes(); ++i)
788 {
789 BodyNode* bn = skel->getBodyNode(i);
790 const std::shared_ptr<InverseKinematics>& ik = bn->getIK();
791
792 if (ik)
793 {
794 highestLevel
795 = std::max(static_cast<int>(ik->getHierarchyLevel()), highestLevel);
796 }
797 }
798
799 for (std::size_t i = 0; i < skel->getNumEndEffectors(); ++i)
800 {
801 EndEffector* ee = skel->getEndEffector(i);
802 const std::shared_ptr<InverseKinematics>& ik = ee->getIK();
803
804 if (ik)
805 {
806 highestLevel
807 = std::max(static_cast<int>(ik->getHierarchyLevel()), highestLevel);
808 }
809 }
810
811 if (-1 == highestLevel)
812 {
813 // There were no IK modules present in this Skeleton
814 mHierarchy.clear();
815 return;
816 }
817
818 mHierarchy.resize(highestLevel + 1);
819 for (auto& level : mHierarchy)
820 level.clear();
821
822 for (std::size_t i = 0; i < skel->getNumBodyNodes(); ++i)
823 {
824 BodyNode* bn = skel->getBodyNode(i);
825 const std::shared_ptr<InverseKinematics>& ik = bn->getIK();
826
827 if (ik)
828 mHierarchy[ik->getHierarchyLevel()].push_back(ik);
829 }
830
831 for (std::size_t i = 0; i < skel->getNumEndEffectors(); ++i)
832 {
833 EndEffector* ee = skel->getEndEffector(i);
834 const std::shared_ptr<InverseKinematics>& ik = ee->getIK();
835
836 if (ik)
837 mHierarchy[ik->getHierarchyLevel()].push_back(ik);
838 }
839 }
840
841 //==============================================================================
WholeBodyIK(const SkeletonPtr & _skel)842 WholeBodyIK::WholeBodyIK(const SkeletonPtr& _skel) : HierarchicalIK(_skel)
843 {
844 // Do nothing
845 }
846
847 } // namespace dynamics
848 } // namespace dart
849