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/InverseKinematics.hpp"
34 #include "dart/dynamics/BodyNode.hpp"
35 #include "dart/dynamics/DegreeOfFreedom.hpp"
36 #include "dart/dynamics/SimpleFrame.hpp"
37 #include "dart/optimizer/GradientDescentSolver.hpp"
38 
39 namespace dart {
40 namespace dynamics {
41 
42 //==============================================================================
create(JacobianNode * _node)43 InverseKinematicsPtr InverseKinematics::create(JacobianNode* _node)
44 {
45   return InverseKinematicsPtr(
46       std::shared_ptr<InverseKinematics>(new InverseKinematics(_node)));
47 }
48 
49 //==============================================================================
~InverseKinematics()50 InverseKinematics::~InverseKinematics()
51 {
52   mTargetConnection.disconnect();
53   mNodeConnection.disconnect();
54 }
55 
56 //==============================================================================
solve(bool applySolution)57 bool InverseKinematics::solve(bool applySolution)
58 {
59   if (applySolution)
60   {
61     return solveAndApply(true);
62   }
63   else
64   {
65     Eigen::VectorXd positions;
66     return findSolution(positions);
67   }
68 }
69 
70 //==============================================================================
solve(Eigen::VectorXd & positions,bool applySolution)71 bool InverseKinematics::solve(Eigen::VectorXd& positions, bool applySolution)
72 {
73   if (applySolution)
74     return solveAndApply(positions, true);
75   else
76     return findSolution(positions);
77 }
78 
79 //==============================================================================
findSolution(Eigen::VectorXd & positions)80 bool InverseKinematics::findSolution(Eigen::VectorXd& positions)
81 {
82   if (nullptr == mSolver)
83   {
84     dtwarn << "[InverseKinematics::findSolution] The Solver for an "
85            << "InverseKinematics module associated with [" << mNode->getName()
86            << "] is a nullptr. You must reset the module's Solver before you "
87            << "can use it.\n";
88     return false;
89   }
90 
91   if (nullptr == mProblem)
92   {
93     dtwarn << "[InverseKinematics::findSolution] The Problem for an "
94            << "InverseKinematics module associated with [" << mNode->getName()
95            << "] is a nullptr. You must reset the module's Problem before you "
96            << "can use it.\n";
97     return false;
98   }
99 
100   mProblem->setDimension(mDofs.size());
101 
102   mProblem->setInitialGuess(getPositions());
103 
104   const SkeletonPtr& skel = getNode()->getSkeleton();
105 
106   Eigen::VectorXd bounds(mDofs.size());
107   for (std::size_t i = 0; i < mDofs.size(); ++i)
108     bounds[i] = skel->getDof(mDofs[i])->getPositionLowerLimit();
109   mProblem->setLowerBounds(bounds);
110 
111   for (std::size_t i = 0; i < mDofs.size(); ++i)
112     bounds[i] = skel->getDof(mDofs[i])->getPositionUpperLimit();
113   mProblem->setUpperBounds(bounds);
114 
115   // Many GradientMethod implementations use Joint::integratePositions, so we
116   // need to clear out any velocities that might be in the Skeleton and then
117   // reset those velocities later. This has been opened as issue #699.
118   const Eigen::VectorXd originalVelocities = skel->getVelocities();
119   skel->resetVelocities();
120 
121   const Eigen::VectorXd originalPositions = getPositions();
122   const bool wasSolved = mSolver->solve();
123 
124   positions = mProblem->getOptimalSolution();
125 
126   setPositions(originalPositions);
127   skel->setVelocities(originalVelocities);
128   return wasSolved;
129 }
130 
131 //==============================================================================
solveAndApply(bool allowIncompleteResult)132 bool InverseKinematics::solveAndApply(bool allowIncompleteResult)
133 {
134   Eigen::VectorXd solution;
135   const auto wasSolved = findSolution(solution);
136   if (wasSolved || allowIncompleteResult)
137     setPositions(solution);
138   return wasSolved;
139 }
140 
141 //==============================================================================
solveAndApply(Eigen::VectorXd & positions,bool allowIncompleteResult)142 bool InverseKinematics::solveAndApply(
143     Eigen::VectorXd& positions, bool allowIncompleteResult)
144 {
145   const auto wasSolved = findSolution(positions);
146   if (wasSolved || allowIncompleteResult)
147     setPositions(positions);
148   return wasSolved;
149 }
150 
151 //==============================================================================
cloneIkFunc(const std::shared_ptr<optimizer::Function> & _function,InverseKinematics * _ik)152 static std::shared_ptr<optimizer::Function> cloneIkFunc(
153     const std::shared_ptr<optimizer::Function>& _function,
154     InverseKinematics* _ik)
155 {
156   std::shared_ptr<InverseKinematics::Function> ikFunc
157       = std::dynamic_pointer_cast<InverseKinematics::Function>(_function);
158 
159   if (ikFunc)
160     return ikFunc->clone(_ik);
161 
162   return _function;
163 }
164 
165 //==============================================================================
clone(JacobianNode * _newNode) const166 InverseKinematicsPtr InverseKinematics::clone(JacobianNode* _newNode) const
167 {
168   std::shared_ptr<InverseKinematics> newIK(new InverseKinematics(_newNode));
169   newIK->setActive(isActive());
170   newIK->setHierarchyLevel(getHierarchyLevel());
171   newIK->setDofs(getDofs());
172   newIK->setOffset(mOffset);
173   newIK->setTarget(mTarget);
174 
175   newIK->setObjective(cloneIkFunc(mObjective, newIK.get()));
176   newIK->setNullSpaceObjective(cloneIkFunc(mNullSpaceObjective, newIK.get()));
177 
178   // When an Analytical IK method is created, it adjusts the properties of the
179   // ErrorMethod so that error computations aren't clamped, because clamping
180   // the error is useful for iterative methods but not for analytical methods.
181   // To ensure that the original IK module's properties are copied exactly, we
182   // clone the analytical method first so that it cannot override the properties
183   // of the error method.
184   newIK->mGradientMethod = mGradientMethod->clone(newIK.get());
185   newIK->mAnalytical = dynamic_cast<Analytical*>(newIK->mGradientMethod.get());
186   if (nullptr != newIK->mAnalytical)
187     newIK->mAnalytical->constructDofMap();
188 
189   newIK->mErrorMethod = mErrorMethod->clone(newIK.get());
190 
191   newIK->setSolver(mSolver->clone());
192 
193   const std::shared_ptr<optimizer::Problem>& newProblem = newIK->getProblem();
194   newProblem->setObjective(cloneIkFunc(mProblem->getObjective(), newIK.get()));
195 
196   newProblem->removeAllEqConstraints();
197   for (std::size_t i = 0; i < mProblem->getNumEqConstraints(); ++i)
198     newProblem->addEqConstraint(
199         cloneIkFunc(mProblem->getEqConstraint(i), newIK.get()));
200 
201   newProblem->removeAllIneqConstraints();
202   for (std::size_t i = 0; i < mProblem->getNumIneqConstraints(); ++i)
203     newProblem->addIneqConstraint(
204         cloneIkFunc(mProblem->getIneqConstraint(i), newIK.get()));
205 
206   newProblem->getSeeds() = mProblem->getSeeds();
207 
208   return newIK;
209 }
210 
211 //==============================================================================
Properties(const Bounds & _bounds,double _errorClamp,const Eigen::Vector6d & _errorWeights)212 InverseKinematics::ErrorMethod::Properties::Properties(
213     const Bounds& _bounds,
214     double _errorClamp,
215     const Eigen::Vector6d& _errorWeights)
216   : mBounds(_bounds),
217     mErrorLengthClamp(_errorClamp),
218     mErrorWeights(_errorWeights)
219 {
220   // Do nothing
221 }
222 
223 //==============================================================================
ErrorMethod(InverseKinematics * _ik,const std::string & _methodName,const dart::dynamics::InverseKinematics::ErrorMethod::Properties & _properties)224 InverseKinematics::ErrorMethod::ErrorMethod(
225     InverseKinematics* _ik,
226     const std::string& _methodName,
227     const dart::dynamics::InverseKinematics::ErrorMethod::Properties&
228         _properties)
229   : mIK(_ik),
230     mMethodName(_methodName),
231     mLastError(Eigen::Vector6d::Constant(std::nan(""))),
232     mErrorP(_properties)
233 {
234   // Do nothing
235 }
236 
237 //==============================================================================
computeDesiredTransform(const Eigen::Isometry3d &,const Eigen::Vector6d &)238 Eigen::Isometry3d InverseKinematics::ErrorMethod::computeDesiredTransform(
239     const Eigen::Isometry3d& /*_currentTf*/, const Eigen::Vector6d& /*_error*/)
240 {
241   return mIK->getTarget()->getTransform();
242 }
243 
244 //==============================================================================
evalError(const Eigen::VectorXd & _q)245 const Eigen::Vector6d& InverseKinematics::ErrorMethod::evalError(
246     const Eigen::VectorXd& _q)
247 {
248   if (_q.size() != static_cast<int>(mIK->getDofs().size()))
249   {
250     dterr << "[InverseKinematics::ErrorMethod::evalError] Mismatch between "
251           << "joint positions size [" << _q.size() << "] and the available "
252           << "degrees of freedom [" << mIK->getDofs().size() << "]."
253           << "\nSkeleton name: " << mIK->getNode()->getSkeleton()->getName()
254           << "\nBody name: " << mIK->getNode()->getName()
255           << "\nMethod name: " << mMethodName << "\n";
256     mLastError.setZero();
257     return mLastError;
258   }
259 
260   if (_q.size() == 0)
261   {
262     mLastError.setZero();
263     return mLastError;
264   }
265 
266   if (_q.size() == mLastPositions.size())
267   {
268     bool repeat = true;
269     for (int i = 0; i < mLastPositions.size(); ++i)
270     {
271       if (_q[i] != mLastPositions[i])
272       {
273         repeat = false;
274         break;
275       }
276     }
277 
278     if (repeat)
279       return mLastError;
280   }
281 
282   mIK->setPositions(_q);
283   mLastPositions = _q;
284 
285   mLastError = computeError();
286   return mLastError;
287 }
288 
289 //==============================================================================
getMethodName() const290 const std::string& InverseKinematics::ErrorMethod::getMethodName() const
291 {
292   return mMethodName;
293 }
294 
295 //==============================================================================
setBounds(const Eigen::Vector6d & _lower,const Eigen::Vector6d & _upper)296 void InverseKinematics::ErrorMethod::setBounds(
297     const Eigen::Vector6d& _lower, const Eigen::Vector6d& _upper)
298 {
299   mErrorP.mBounds.first = _lower;
300   mErrorP.mBounds.second = _upper;
301   clearCache();
302 }
303 
304 //==============================================================================
setBounds(const std::pair<Eigen::Vector6d,Eigen::Vector6d> & _bounds)305 void InverseKinematics::ErrorMethod::setBounds(
306     const std::pair<Eigen::Vector6d, Eigen::Vector6d>& _bounds)
307 {
308   mErrorP.mBounds = _bounds;
309   clearCache();
310 }
311 
312 //==============================================================================
313 const std::pair<Eigen::Vector6d, Eigen::Vector6d>&
getBounds() const314 InverseKinematics::ErrorMethod::getBounds() const
315 {
316   return mErrorP.mBounds;
317 }
318 
319 //==============================================================================
setAngularBounds(const Eigen::Vector3d & _lower,const Eigen::Vector3d & _upper)320 void InverseKinematics::ErrorMethod::setAngularBounds(
321     const Eigen::Vector3d& _lower, const Eigen::Vector3d& _upper)
322 {
323   mErrorP.mBounds.first.head<3>() = _lower;
324   mErrorP.mBounds.second.head<3>() = _upper;
325   clearCache();
326 }
327 
328 //==============================================================================
setAngularBounds(const std::pair<Eigen::Vector3d,Eigen::Vector3d> & _bounds)329 void InverseKinematics::ErrorMethod::setAngularBounds(
330     const std::pair<Eigen::Vector3d, Eigen::Vector3d>& _bounds)
331 {
332   setAngularBounds(_bounds.first, _bounds.second);
333 }
334 
335 //==============================================================================
336 std::pair<Eigen::Vector3d, Eigen::Vector3d>
getAngularBounds() const337 InverseKinematics::ErrorMethod::getAngularBounds() const
338 {
339   return std::pair<Eigen::Vector3d, Eigen::Vector3d>(
340       mErrorP.mBounds.first.head<3>(), mErrorP.mBounds.second.head<3>());
341 }
342 
343 //==============================================================================
setLinearBounds(const Eigen::Vector3d & _lower,const Eigen::Vector3d & _upper)344 void InverseKinematics::ErrorMethod::setLinearBounds(
345     const Eigen::Vector3d& _lower, const Eigen::Vector3d& _upper)
346 {
347   mErrorP.mBounds.first.tail<3>() = _lower;
348   mErrorP.mBounds.second.tail<3>() = _upper;
349   clearCache();
350 }
351 
352 //==============================================================================
setLinearBounds(const std::pair<Eigen::Vector3d,Eigen::Vector3d> & _bounds)353 void InverseKinematics::ErrorMethod::setLinearBounds(
354     const std::pair<Eigen::Vector3d, Eigen::Vector3d>& _bounds)
355 {
356   setLinearBounds(_bounds.first, _bounds.second);
357 }
358 
359 //==============================================================================
360 std::pair<Eigen::Vector3d, Eigen::Vector3d>
getLinearBounds() const361 InverseKinematics::ErrorMethod::getLinearBounds() const
362 {
363   return std::pair<Eigen::Vector3d, Eigen::Vector3d>(
364       mErrorP.mBounds.first.tail<3>(), mErrorP.mBounds.second.tail<3>());
365 }
366 
367 //==============================================================================
setErrorLengthClamp(double _clampSize)368 void InverseKinematics::ErrorMethod::setErrorLengthClamp(double _clampSize)
369 {
370   mErrorP.mErrorLengthClamp = _clampSize;
371   clearCache();
372 }
373 
374 //==============================================================================
getErrorLengthClamp() const375 double InverseKinematics::ErrorMethod::getErrorLengthClamp() const
376 {
377   return mErrorP.mErrorLengthClamp;
378 }
379 
380 //==============================================================================
setErrorWeights(const Eigen::Vector6d & _weights)381 void InverseKinematics::ErrorMethod::setErrorWeights(
382     const Eigen::Vector6d& _weights)
383 {
384   mErrorP.mErrorWeights = _weights;
385   clearCache();
386 }
387 
388 //==============================================================================
getErrorWeights() const389 const Eigen::Vector6d& InverseKinematics::ErrorMethod::getErrorWeights() const
390 {
391   return mErrorP.mErrorWeights;
392 }
393 
394 //==============================================================================
setAngularErrorWeights(const Eigen::Vector3d & _weights)395 void InverseKinematics::ErrorMethod::setAngularErrorWeights(
396     const Eigen::Vector3d& _weights)
397 {
398   mErrorP.mErrorWeights.head<3>() = _weights;
399   clearCache();
400 }
401 
402 //==============================================================================
getAngularErrorWeights() const403 Eigen::Vector3d InverseKinematics::ErrorMethod::getAngularErrorWeights() const
404 {
405   return mErrorP.mErrorWeights.head<3>();
406 }
407 
408 //==============================================================================
setLinearErrorWeights(const Eigen::Vector3d & _weights)409 void InverseKinematics::ErrorMethod::setLinearErrorWeights(
410     const Eigen::Vector3d& _weights)
411 {
412   mErrorP.mErrorWeights.tail<3>() = _weights;
413   clearCache();
414 }
415 
416 //==============================================================================
getLinearErrorWeights() const417 Eigen::Vector3d InverseKinematics::ErrorMethod::getLinearErrorWeights() const
418 {
419   return mErrorP.mErrorWeights.tail<3>();
420 }
421 
422 //==============================================================================
423 InverseKinematics::ErrorMethod::Properties
getErrorMethodProperties() const424 InverseKinematics::ErrorMethod::getErrorMethodProperties() const
425 {
426   return mErrorP;
427 }
428 
429 //==============================================================================
clearCache()430 void InverseKinematics::ErrorMethod::clearCache()
431 {
432   // This will force the error to be recomputed the next time computeError is
433   // called
434   mLastPositions.resize(0);
435 }
436 
437 //==============================================================================
UniqueProperties(bool computeErrorFromCenter,SimpleFramePtr referenceFrame)438 InverseKinematics::TaskSpaceRegion::UniqueProperties::UniqueProperties(
439     bool computeErrorFromCenter, SimpleFramePtr referenceFrame)
440   : mComputeErrorFromCenter(computeErrorFromCenter),
441     mReferenceFrame(std::move(referenceFrame))
442 {
443   // Do nothing
444 }
445 
446 //==============================================================================
Properties(const ErrorMethod::Properties & errorProperties,const UniqueProperties & taskSpaceProperties)447 InverseKinematics::TaskSpaceRegion::Properties::Properties(
448     const ErrorMethod::Properties& errorProperties,
449     const UniqueProperties& taskSpaceProperties)
450   : ErrorMethod::Properties(errorProperties),
451     UniqueProperties(taskSpaceProperties)
452 {
453   // Do nothing
454 }
455 
456 //==============================================================================
TaskSpaceRegion(InverseKinematics * _ik,const Properties & _properties)457 InverseKinematics::TaskSpaceRegion::TaskSpaceRegion(
458     InverseKinematics* _ik, const Properties& _properties)
459   : ErrorMethod(_ik, "TaskSpaceRegion", _properties), mTaskSpaceP(_properties)
460 {
461   // Do nothing
462 }
463 
464 //==============================================================================
465 std::unique_ptr<InverseKinematics::ErrorMethod>
clone(InverseKinematics * _newIK) const466 InverseKinematics::TaskSpaceRegion::clone(InverseKinematics* _newIK) const
467 {
468   return std::make_unique<TaskSpaceRegion>(
469       _newIK, getTaskSpaceRegionProperties());
470 }
471 
472 //==============================================================================
computeDesiredTransform(const Eigen::Isometry3d & _currentTf,const Eigen::Vector6d & _error)473 Eigen::Isometry3d InverseKinematics::TaskSpaceRegion::computeDesiredTransform(
474     const Eigen::Isometry3d& _currentTf, const Eigen::Vector6d& _error)
475 {
476   Eigen::Isometry3d tf(Eigen::Isometry3d::Identity());
477 
478   tf.rotate(_currentTf.linear());
479   for (std::size_t i = 0; i < 3; ++i)
480   {
481     const double angle = _error[i];
482     Eigen::Vector3d axis(Eigen::Vector3d::Zero());
483     axis[i] = 1.0;
484     tf.prerotate(Eigen::AngleAxisd(-angle, axis));
485   }
486 
487   tf.pretranslate(_currentTf.translation());
488   tf.pretranslate(-_error.tail<3>());
489 
490   return tf;
491 }
492 
493 //==============================================================================
computeError()494 Eigen::Vector6d InverseKinematics::TaskSpaceRegion::computeError()
495 {
496   // This is a slightly modified implementation of the Berenson et al Task Space
497   // Region method found in "Task Space Regions: A Framework for
498   // Pose-Constrained Manipulation Planning".
499   //
500   // The modification is that we handle the computation of translational error
501   // independently from the computation of rotational error, whereas the work of
502   // Berenson computes them simultaneously using homogeneous transform matrices.
503   // Handling them in terms of their homogeneous matrices results in less direct
504   // paths while performing gradient descent, because it produces a pseudo-error
505   // in translation whenever rotational error exists.
506   //
507   // Also, we offer the option of always computing the error from the center of
508   // the Task Space Region, which will often allow the end effector to enter the
509   // valid constraint manifold faster than computing it from the edge of the
510   // Task Space Region.
511 
512   const Frame* referenceFrame = mTaskSpaceP.mReferenceFrame.get();
513   if (referenceFrame == nullptr)
514     referenceFrame = mIK->getTarget()->getParentFrame();
515   assert(referenceFrame != nullptr);
516 
517   // Use the target's transform with respect to its reference frame
518   const Eigen::Isometry3d targetTf
519       = mIK->getTarget()->getTransform(referenceFrame);
520   // Use the actual transform with respect to the target's reference frame
521   const Eigen::Isometry3d actualTf
522       = mIK->getNode()->getTransform(referenceFrame);
523 
524   // ^ This scheme makes it so that the bounds are expressed in the reference
525   // frame of the target
526 
527   Eigen::Vector3d p_error = actualTf.translation() - targetTf.translation();
528   if (mIK->hasOffset())
529     p_error += actualTf.linear() * mIK->getOffset();
530 
531   const Eigen::Matrix3d R_error
532       = actualTf.linear() * targetTf.linear().transpose();
533 
534   Eigen::Vector6d displacement;
535   displacement << math::matrixToEulerXYZ(R_error), p_error;
536 
537   Eigen::Vector6d error;
538   const Eigen::Vector6d& min = mErrorP.mBounds.first;
539   const Eigen::Vector6d& max = mErrorP.mBounds.second;
540   double tolerance = mIK->getSolver()->getTolerance();
541   for (int i = 0; i < 6; ++i)
542   {
543     if (displacement[i] < min[i])
544     {
545       if (mTaskSpaceP.mComputeErrorFromCenter)
546       {
547         if (std::isfinite(max[i]))
548           error[i] = displacement[i] - (min[i] + max[i]) / 2.0;
549         else
550           error[i] = displacement[i] - (min[i] + tolerance);
551       }
552       else
553       {
554         error[i] = displacement[i] - min[i];
555       }
556     }
557     else if (max[i] < displacement[i])
558     {
559       if (mTaskSpaceP.mComputeErrorFromCenter)
560       {
561         if (std::isfinite(min[i]))
562           error[i] = displacement[i] - (min[i] + max[i]) / 2.0;
563         else
564           error[i] = displacement[i] - (max[i] - tolerance);
565       }
566       else
567       {
568         error[i] = displacement[i] - max[i];
569       }
570     }
571     else
572       error[i] = 0.0;
573   }
574 
575   error = error.cwiseProduct(mErrorP.mErrorWeights);
576 
577   if (error.norm() > mErrorP.mErrorLengthClamp)
578     error = error.normalized() * mErrorP.mErrorLengthClamp;
579 
580   if (!referenceFrame->isWorld())
581   {
582     // Transform the error term into the world frame if it's not already
583     const Eigen::Isometry3d& R = referenceFrame->getWorldTransform();
584     error.head<3>() = R.linear() * error.head<3>();
585     error.tail<3>() = R.linear() * error.tail<3>();
586   }
587 
588   return error;
589 }
590 
591 //==============================================================================
setComputeFromCenter(bool computeFromCenter)592 void InverseKinematics::TaskSpaceRegion::setComputeFromCenter(
593     bool computeFromCenter)
594 {
595   mTaskSpaceP.mComputeErrorFromCenter = computeFromCenter;
596 }
597 
598 //==============================================================================
isComputingFromCenter() const599 bool InverseKinematics::TaskSpaceRegion::isComputingFromCenter() const
600 {
601   return mTaskSpaceP.mComputeErrorFromCenter;
602 }
603 
604 //==============================================================================
setReferenceFrame(SimpleFramePtr referenceFrame)605 void InverseKinematics::TaskSpaceRegion::setReferenceFrame(
606     SimpleFramePtr referenceFrame)
607 {
608   mTaskSpaceP.mReferenceFrame = std::move(referenceFrame);
609 }
610 
611 //==============================================================================
getReferenceFrame() const612 ConstSimpleFramePtr InverseKinematics::TaskSpaceRegion::getReferenceFrame()
613     const
614 {
615   return mTaskSpaceP.mReferenceFrame;
616 }
617 
618 //==============================================================================
619 InverseKinematics::TaskSpaceRegion::Properties
getTaskSpaceRegionProperties() const620 InverseKinematics::TaskSpaceRegion::getTaskSpaceRegionProperties() const
621 {
622   return Properties(getErrorMethodProperties(), mTaskSpaceP);
623 }
624 
625 //==============================================================================
Properties(double clamp,const Eigen::VectorXd & weights)626 InverseKinematics::GradientMethod::Properties::Properties(
627     double clamp, const Eigen::VectorXd& weights)
628   : mComponentWiseClamp(clamp), mComponentWeights(weights)
629 {
630   // Do nothing
631 }
632 
633 //==============================================================================
GradientMethod(InverseKinematics * _ik,const std::string & _methodName,const Properties & _properties)634 InverseKinematics::GradientMethod::GradientMethod(
635     InverseKinematics* _ik,
636     const std::string& _methodName,
637     const Properties& _properties)
638   : mIK(_ik), mMethodName(_methodName), mGradientP(_properties)
639 {
640   // Do nothing
641 }
642 
643 //==============================================================================
evalGradient(const Eigen::VectorXd & _q,Eigen::Map<Eigen::VectorXd> _grad)644 void InverseKinematics::GradientMethod::evalGradient(
645     const Eigen::VectorXd& _q, Eigen::Map<Eigen::VectorXd> _grad)
646 {
647   if (_q.size() != static_cast<int>(mIK->getDofs().size()))
648   {
649     dterr << "[InverseKinematics::GradientMethod::evalGradient] Mismatch "
650           << "between joint positions size [" << _q.size() << "] and the "
651           << "available degrees of freedom [" << mIK->getDofs().size() << "]."
652           << "\nSkeleton name: " << mIK->getNode()->getSkeleton()->getName()
653           << "\nBody name: " << mIK->getNode()->getName()
654           << "\nMethod name: " << mMethodName << "\n";
655     assert(false);
656     mLastGradient.resize(_q.size());
657     mLastGradient.setZero();
658     _grad = mLastGradient;
659     return;
660   }
661 
662   if (_q.size() == 0)
663   {
664     _grad.setZero();
665     return;
666   }
667 
668   if (_q.size() == mLastPositions.size())
669   {
670     bool repeat = true;
671     for (int i = 0; i < mLastPositions.size(); ++i)
672     {
673       if (_q[i] != mLastPositions[i])
674       {
675         repeat = false;
676         break;
677       }
678     }
679 
680     if (repeat)
681     {
682       _grad = mLastGradient;
683       return;
684     }
685   }
686 
687   const Eigen::Vector6d& error = mIK->getErrorMethod().evalError(_q);
688   mIK->setPositions(_q);
689   mLastGradient.resize(_grad.size());
690   computeGradient(error, mLastGradient);
691   _grad = mLastGradient;
692 }
693 
694 //==============================================================================
getMethodName() const695 const std::string& InverseKinematics::GradientMethod::getMethodName() const
696 {
697   return mMethodName;
698 }
699 
700 //==============================================================================
clampGradient(Eigen::VectorXd & _grad) const701 void InverseKinematics::GradientMethod::clampGradient(
702     Eigen::VectorXd& _grad) const
703 {
704   for (int i = 0; i < _grad.size(); ++i)
705   {
706     if (std::abs(_grad[i]) > mGradientP.mComponentWiseClamp)
707       _grad[i] = _grad[i] > 0 ? mGradientP.mComponentWiseClamp
708                               : -mGradientP.mComponentWiseClamp;
709   }
710 }
711 
712 //==============================================================================
setComponentWiseClamp(double _clamp)713 void InverseKinematics::GradientMethod::setComponentWiseClamp(double _clamp)
714 {
715   mGradientP.mComponentWiseClamp = std::abs(_clamp);
716 }
717 
718 //==============================================================================
getComponentWiseClamp() const719 double InverseKinematics::GradientMethod::getComponentWiseClamp() const
720 {
721   return mGradientP.mComponentWiseClamp;
722 }
723 
724 //==============================================================================
applyWeights(Eigen::VectorXd & _grad) const725 void InverseKinematics::GradientMethod::applyWeights(
726     Eigen::VectorXd& _grad) const
727 {
728   std::size_t numComponents
729       = std::min(_grad.size(), mGradientP.mComponentWeights.size());
730   for (std::size_t i = 0; i < numComponents; ++i)
731     _grad[i] = mGradientP.mComponentWeights[i] * _grad[i];
732 }
733 
734 //==============================================================================
setComponentWeights(const Eigen::VectorXd & _weights)735 void InverseKinematics::GradientMethod::setComponentWeights(
736     const Eigen::VectorXd& _weights)
737 {
738   mGradientP.mComponentWeights = _weights;
739 }
740 
741 //==============================================================================
getComponentWeights() const742 const Eigen::VectorXd& InverseKinematics::GradientMethod::getComponentWeights()
743     const
744 {
745   return mGradientP.mComponentWeights;
746 }
747 
748 //==============================================================================
convertJacobianMethodOutputToGradient(Eigen::VectorXd & grad,const std::vector<std::size_t> & dofs)749 void InverseKinematics::GradientMethod::convertJacobianMethodOutputToGradient(
750     Eigen::VectorXd& grad, const std::vector<std::size_t>& dofs)
751 {
752   const SkeletonPtr& skel = mIK->getNode()->getSkeleton();
753   mInitialPositionsCache = skel->getPositions(dofs);
754 
755   for (std::size_t i = 0; i < dofs.size(); ++i)
756     skel->getDof(dofs[i])->setVelocity(grad[i]);
757   // Velocities of unused DOFs should already be set to zero.
758 
759   for (std::size_t i = 0; i < dofs.size(); ++i)
760   {
761     Joint* joint = skel->getDof(dofs[i])->getJoint();
762     joint->integratePositions(1.0);
763 
764     // Reset this joint's velocities to zero to avoid double-integrating
765     const std::size_t numJointDofs = joint->getNumDofs();
766     for (std::size_t j = 0; j < numJointDofs; ++j)
767       joint->setVelocity(j, 0.0);
768   }
769 
770   grad = skel->getPositions(dofs);
771   grad -= mInitialPositionsCache;
772 }
773 
774 //==============================================================================
775 InverseKinematics::GradientMethod::Properties
getGradientMethodProperties() const776 InverseKinematics::GradientMethod::getGradientMethodProperties() const
777 {
778   return mGradientP;
779 }
780 
781 //==============================================================================
clearCache()782 void InverseKinematics::GradientMethod::clearCache()
783 {
784   // This will force the gradient to be recomputed the next time computeGradient
785   // is called
786   mLastPositions.resize(0);
787 }
788 
789 //==============================================================================
getIK()790 InverseKinematics* InverseKinematics::GradientMethod::getIK()
791 {
792   return mIK;
793 }
794 
795 //==============================================================================
getIK() const796 const InverseKinematics* InverseKinematics::GradientMethod::getIK() const
797 {
798   return mIK;
799 }
800 
801 //==============================================================================
UniqueProperties(double damping)802 InverseKinematics::JacobianDLS::UniqueProperties::UniqueProperties(
803     double damping)
804   : mDamping(damping)
805 {
806   // Do nothing
807 }
808 
809 //==============================================================================
Properties(const GradientMethod::Properties & gradientProperties,const UniqueProperties & dlsProperties)810 InverseKinematics::JacobianDLS::Properties::Properties(
811     const GradientMethod::Properties& gradientProperties,
812     const UniqueProperties& dlsProperties)
813   : GradientMethod::Properties(gradientProperties),
814     UniqueProperties(dlsProperties)
815 {
816   // Do nothing
817 }
818 
819 //==============================================================================
JacobianDLS(InverseKinematics * _ik,const Properties & properties)820 InverseKinematics::JacobianDLS::JacobianDLS(
821     InverseKinematics* _ik, const Properties& properties)
822   : GradientMethod(_ik, "JacobianDLS", properties), mDLSProperties(properties)
823 {
824   // Do nothing
825 }
826 
827 //==============================================================================
828 std::unique_ptr<InverseKinematics::GradientMethod>
clone(InverseKinematics * _newIK) const829 InverseKinematics::JacobianDLS::clone(InverseKinematics* _newIK) const
830 {
831   return std::make_unique<JacobianDLS>(_newIK, getJacobianDLSProperties());
832 }
833 
834 //==============================================================================
computeGradient(const Eigen::Vector6d & _error,Eigen::VectorXd & _grad)835 void InverseKinematics::JacobianDLS::computeGradient(
836     const Eigen::Vector6d& _error, Eigen::VectorXd& _grad)
837 {
838   const math::Jacobian& J = mIK->computeJacobian();
839 
840   const double& damping = mDLSProperties.mDamping;
841   int rows = J.rows(), cols = J.cols();
842   if (rows <= cols)
843   {
844     _grad = J.transpose()
845             * (pow(damping, 2) * Eigen::MatrixXd::Identity(rows, rows)
846                + J * J.transpose())
847                   .inverse()
848             * _error;
849   }
850   else
851   {
852     _grad = (pow(damping, 2) * Eigen::MatrixXd::Identity(cols, cols)
853              + J.transpose() * J)
854                 .inverse()
855             * J.transpose() * _error;
856   }
857 
858   convertJacobianMethodOutputToGradient(_grad, mIK->getDofs());
859   applyWeights(_grad);
860   clampGradient(_grad);
861 }
862 
863 //==============================================================================
setDampingCoefficient(double _damping)864 void InverseKinematics::JacobianDLS::setDampingCoefficient(double _damping)
865 {
866   mDLSProperties.mDamping = _damping;
867 }
868 
869 //==============================================================================
getDampingCoefficient() const870 double InverseKinematics::JacobianDLS::getDampingCoefficient() const
871 {
872   return mDLSProperties.mDamping;
873 }
874 
875 //==============================================================================
876 InverseKinematics::JacobianDLS::Properties
getJacobianDLSProperties() const877 InverseKinematics::JacobianDLS::getJacobianDLSProperties() const
878 {
879   return Properties(mGradientP, mDLSProperties);
880 }
881 
882 //==============================================================================
JacobianTranspose(InverseKinematics * _ik,const Properties & properties)883 InverseKinematics::JacobianTranspose::JacobianTranspose(
884     InverseKinematics* _ik, const Properties& properties)
885   : GradientMethod(_ik, "JacobianTranspose", properties)
886 {
887   // Do nothing
888 }
889 
890 //==============================================================================
891 std::unique_ptr<InverseKinematics::GradientMethod>
clone(InverseKinematics * _newIK) const892 InverseKinematics::JacobianTranspose::clone(InverseKinematics* _newIK) const
893 {
894   return std::make_unique<JacobianTranspose>(
895       _newIK, getGradientMethodProperties());
896 }
897 
898 //==============================================================================
computeGradient(const Eigen::Vector6d & _error,Eigen::VectorXd & _grad)899 void InverseKinematics::JacobianTranspose::computeGradient(
900     const Eigen::Vector6d& _error, Eigen::VectorXd& _grad)
901 {
902   const math::Jacobian& J = mIK->computeJacobian();
903   _grad = J.transpose() * _error;
904 
905   convertJacobianMethodOutputToGradient(_grad, mIK->getDofs());
906   applyWeights(_grad);
907   clampGradient(_grad);
908 }
909 
910 //==============================================================================
Solution(const Eigen::VectorXd & _config,int _validity)911 InverseKinematics::Analytical::Solution::Solution(
912     const Eigen::VectorXd& _config, int _validity)
913   : mConfig(_config), mValidity(_validity)
914 {
915   // Do nothing
916 }
917 
918 //==============================================================================
UniqueProperties(ExtraDofUtilization extraDofUtilization,double extraErrorLengthClamp)919 InverseKinematics::Analytical::UniqueProperties::UniqueProperties(
920     ExtraDofUtilization extraDofUtilization, double extraErrorLengthClamp)
921   : mExtraDofUtilization(extraDofUtilization),
922     mExtraErrorLengthClamp(extraErrorLengthClamp)
923 {
924   resetQualityComparisonFunction();
925 }
926 
927 //==============================================================================
UniqueProperties(ExtraDofUtilization extraDofUtilization,double extraErrorLengthClamp,QualityComparison qualityComparator)928 InverseKinematics::Analytical::UniqueProperties::UniqueProperties(
929     ExtraDofUtilization extraDofUtilization,
930     double extraErrorLengthClamp,
931     QualityComparison qualityComparator)
932   : mExtraDofUtilization(extraDofUtilization),
933     mExtraErrorLengthClamp(extraErrorLengthClamp),
934     mQualityComparator(qualityComparator)
935 {
936   // Do nothing
937 }
938 
939 //==============================================================================
940 void InverseKinematics::Analytical::UniqueProperties::
resetQualityComparisonFunction()941     resetQualityComparisonFunction()
942 {
943   // This function prefers the configuration whose highest joint velocity is
944   // smaller than the highest joint velocity of the other configuration.
945   mQualityComparator = [=](const Eigen::VectorXd& better,
946                            const Eigen::VectorXd& worse,
947                            const InverseKinematics* ik) {
948     const std::vector<std::size_t>& dofs = ik->getAnalytical()->getDofs();
949     double biggestJump = 0.0;
950     bool isBetter = true;
951     for (std::size_t i = 0; i < dofs.size(); ++i)
952     {
953       double q = ik->getNode()->getSkeleton()->getPosition(dofs[i]);
954       const double& testBetter = std::abs(q - better[i]);
955       if (testBetter > biggestJump)
956       {
957         biggestJump = testBetter;
958         isBetter = false;
959       }
960 
961       const double& testWorse = std::abs(q - worse[i]);
962       if (testWorse > biggestJump)
963       {
964         biggestJump = testWorse;
965         isBetter = true;
966       }
967     }
968 
969     return isBetter;
970   };
971 }
972 
973 //==============================================================================
Properties(const GradientMethod::Properties & gradientProperties,const UniqueProperties & analyticalProperties)974 InverseKinematics::Analytical::Properties::Properties(
975     const GradientMethod::Properties& gradientProperties,
976     const UniqueProperties& analyticalProperties)
977   : GradientMethod::Properties(gradientProperties),
978     UniqueProperties(analyticalProperties)
979 {
980   // Do nothing
981 }
982 
983 //==============================================================================
Properties(const UniqueProperties & analyticalProperties)984 InverseKinematics::Analytical::Properties::Properties(
985     const UniqueProperties& analyticalProperties)
986   : UniqueProperties(analyticalProperties)
987 {
988   // Do nothing
989 }
990 
991 //==============================================================================
Analytical(InverseKinematics * _ik,const std::string & _methodName,const Properties & _properties)992 InverseKinematics::Analytical::Analytical(
993     InverseKinematics* _ik,
994     const std::string& _methodName,
995     const Properties& _properties)
996   : GradientMethod(_ik, _methodName, _properties), mAnalyticalP(_properties)
997 {
998   // During the cloning process, the GradientMethod gets created before the
999   // ErrorMethod, so we need to check that an ErrorMethod exists before
1000   // attempting to use it.
1001   if (InverseKinematics::ErrorMethod* error = mIK->mErrorMethod.get())
1002   {
1003     // We override the clamping and the weights of the error method, because
1004     // clamping and weighing are useful for iterative methods, but they are
1005     // harmful to analytical methods.
1006     error->setErrorLengthClamp(std::numeric_limits<double>::infinity());
1007     error->setErrorWeights(Eigen::Vector6d::Constant(1.0));
1008   }
1009 }
1010 
1011 //==============================================================================
getSolutions()1012 const std::vector<IK::Analytical::Solution>& IK::Analytical::getSolutions()
1013 {
1014   const Eigen::Isometry3d& currentTf = mIK->getNode()->getWorldTransform();
1015   const Eigen::Vector6d& error = mIK->getErrorMethod().computeError();
1016 
1017   const Eigen::Isometry3d& _desiredTf
1018       = mIK->getErrorMethod().computeDesiredTransform(currentTf, error);
1019 
1020   return getSolutions(_desiredTf);
1021 }
1022 
1023 //==============================================================================
getSolutions(const Eigen::Isometry3d & _desiredTf)1024 const std::vector<IK::Analytical::Solution>& IK::Analytical::getSolutions(
1025     const Eigen::Isometry3d& _desiredTf)
1026 {
1027   mRestoreConfigCache = getPositions();
1028 
1029   computeSolutions(_desiredTf);
1030 
1031   mValidSolutionsCache.clear();
1032   mValidSolutionsCache.reserve(mSolutions.size());
1033 
1034   mOutOfReachCache.clear();
1035   mOutOfReachCache.reserve(mSolutions.size());
1036 
1037   mLimitViolationCache.clear();
1038   mLimitViolationCache.reserve(mSolutions.size());
1039 
1040   for (std::size_t i = 0; i < mSolutions.size(); ++i)
1041   {
1042     const Solution& s = mSolutions[i];
1043     if (s.mValidity == VALID)
1044       mValidSolutionsCache.push_back(s);
1045     else if ((s.mValidity & LIMIT_VIOLATED) == LIMIT_VIOLATED)
1046       mLimitViolationCache.push_back(s);
1047     else
1048       mOutOfReachCache.push_back(s);
1049   }
1050 
1051   auto comparator = [=](const Solution& s1, const Solution& s2) {
1052     return mAnalyticalP.mQualityComparator(s1.mConfig, s2.mConfig, mIK);
1053   };
1054 
1055   std::sort(
1056       mValidSolutionsCache.begin(), mValidSolutionsCache.end(), comparator);
1057 
1058   std::sort(mOutOfReachCache.begin(), mOutOfReachCache.end(), comparator);
1059 
1060   std::sort(
1061       mLimitViolationCache.begin(), mLimitViolationCache.end(), comparator);
1062 
1063   mSolutions.clear();
1064   mSolutions.insert(
1065       mSolutions.end(),
1066       mValidSolutionsCache.begin(),
1067       mValidSolutionsCache.end());
1068 
1069   mSolutions.insert(
1070       mSolutions.end(), mOutOfReachCache.begin(), mOutOfReachCache.end());
1071 
1072   mSolutions.insert(
1073       mSolutions.end(),
1074       mLimitViolationCache.begin(),
1075       mLimitViolationCache.end());
1076 
1077   setPositions(mRestoreConfigCache);
1078 
1079   return mSolutions;
1080 }
1081 
1082 //==============================================================================
addExtraDofGradient(Eigen::VectorXd & grad,const Eigen::Vector6d & error,ExtraDofUtilization)1083 void InverseKinematics::Analytical::addExtraDofGradient(
1084     Eigen::VectorXd& grad,
1085     const Eigen::Vector6d& error,
1086     ExtraDofUtilization /*utilization*/)
1087 {
1088   mExtraDofGradCache.resize(mExtraDofs.size());
1089   const math::Jacobian& J = mIK->computeJacobian();
1090   const std::vector<int>& gradMap = mIK->getDofMap();
1091 
1092   for (std::size_t i = 0; i < mExtraDofs.size(); ++i)
1093   {
1094     std::size_t depIndex = mExtraDofs[i];
1095     int gradIndex = gradMap[depIndex];
1096     if (gradIndex == -1)
1097       continue;
1098 
1099     mExtraDofGradCache[i] = J.col(gradIndex).transpose() * error;
1100   }
1101 
1102   convertJacobianMethodOutputToGradient(mExtraDofGradCache, mExtraDofs);
1103 
1104   for (std::size_t i = 0; i < mExtraDofs.size(); ++i)
1105   {
1106     std::size_t depIndex = mExtraDofs[i];
1107     int gradIndex = gradMap[depIndex];
1108     if (gradIndex == -1)
1109       continue;
1110 
1111     double weight = mGradientP.mComponentWeights.size() > gradIndex
1112                         ? mGradientP.mComponentWeights[gradIndex]
1113                         : 1.0;
1114 
1115     double dq = weight * mExtraDofGradCache[i];
1116 
1117     if (std::abs(dq) > mGradientP.mComponentWiseClamp)
1118     {
1119       dq = dq < 0 ? -mGradientP.mComponentWiseClamp
1120                   : mGradientP.mComponentWiseClamp;
1121     }
1122 
1123     grad[gradIndex] = dq;
1124   }
1125 }
1126 
1127 //==============================================================================
computeGradient(const Eigen::Vector6d & _error,Eigen::VectorXd & _grad)1128 void InverseKinematics::Analytical::computeGradient(
1129     const Eigen::Vector6d& _error, Eigen::VectorXd& _grad)
1130 {
1131   _grad.setZero();
1132   if (Eigen::Vector6d::Zero() == _error)
1133     return;
1134 
1135   const Eigen::Isometry3d& desiredTf
1136       = mIK->getErrorMethod().computeDesiredTransform(
1137           mIK->getNode()->getWorldTransform(), _error);
1138 
1139   if ((PRE_ANALYTICAL == mAnalyticalP.mExtraDofUtilization
1140        || PRE_AND_POST_ANALYTICAL == mAnalyticalP.mExtraDofUtilization)
1141       && mExtraDofs.size() > 0)
1142   {
1143     const double norm = _error.norm();
1144     const Eigen::Vector6d& error
1145         = norm > mAnalyticalP.mExtraErrorLengthClamp
1146               ? mAnalyticalP.mExtraErrorLengthClamp * _error / norm
1147               : _error;
1148 
1149     addExtraDofGradient(_grad, error, PRE_ANALYTICAL);
1150 
1151     const std::vector<int>& gradMap = mIK->getDofMap();
1152     for (std::size_t i = 0; i < mExtraDofs.size(); ++i)
1153     {
1154       const std::size_t depIndex = mExtraDofs[i];
1155       DegreeOfFreedom* dof = mIK->getNode()->getDependentDof(depIndex);
1156 
1157       const std::size_t gradIndex = gradMap[depIndex];
1158       dof->setPosition(dof->getPosition() - _grad[gradIndex]);
1159     }
1160   }
1161 
1162   getSolutions(desiredTf);
1163 
1164   if (mSolutions.empty())
1165     return;
1166 
1167   if (mSolutions[0].mValidity != VALID)
1168     return;
1169 
1170   const Eigen::VectorXd& bestSolution = mSolutions[0].mConfig;
1171   mConfigCache = getPositions();
1172 
1173   const std::vector<int>& analyticalToDependent = mDofMap;
1174   const std::vector<int>& dependentToGradient = mIK->getDofMap();
1175 
1176   for (std::size_t i = 0; i < analyticalToDependent.size(); ++i)
1177   {
1178     if (analyticalToDependent[i] == -1)
1179       continue;
1180 
1181     int index = dependentToGradient[analyticalToDependent[i]];
1182     if (index == -1)
1183       continue;
1184 
1185     _grad[index] = mConfigCache[i] - bestSolution[i];
1186   }
1187 
1188   if ((POST_ANALYTICAL == mAnalyticalP.mExtraDofUtilization
1189        || PRE_AND_POST_ANALYTICAL == mAnalyticalP.mExtraDofUtilization)
1190       && mExtraDofs.size() > 0)
1191   {
1192     setPositions(bestSolution);
1193 
1194     const Eigen::Isometry3d& postTf = mIK->getNode()->getWorldTransform();
1195     Eigen::Vector6d postError;
1196     postError.tail<3>() = postTf.translation() - desiredTf.translation();
1197     Eigen::AngleAxisd aaError(postTf.linear() * desiredTf.linear().transpose());
1198     postError.head<3>() = aaError.angle() * aaError.axis();
1199 
1200     double norm = postError.norm();
1201     if (norm > mAnalyticalP.mExtraErrorLengthClamp)
1202       postError = mAnalyticalP.mExtraErrorLengthClamp * postError / norm;
1203 
1204     addExtraDofGradient(_grad, postError, POST_ANALYTICAL);
1205   }
1206 }
1207 
1208 //==============================================================================
setPositions(const Eigen::VectorXd & _config)1209 void InverseKinematics::Analytical::setPositions(const Eigen::VectorXd& _config)
1210 {
1211   mIK->getNode()->getSkeleton()->setPositions(getDofs(), _config);
1212 }
1213 
1214 //==============================================================================
getPositions() const1215 Eigen::VectorXd InverseKinematics::Analytical::getPositions() const
1216 {
1217   return mIK->getNode()->getSkeleton()->getPositions(getDofs());
1218 }
1219 
1220 //==============================================================================
setExtraDofUtilization(ExtraDofUtilization _utilization)1221 void InverseKinematics::Analytical::setExtraDofUtilization(
1222     ExtraDofUtilization _utilization)
1223 {
1224   mAnalyticalP.mExtraDofUtilization = _utilization;
1225 }
1226 
1227 //==============================================================================
getExtraDofUtilization() const1228 IK::Analytical::ExtraDofUtilization IK::Analytical::getExtraDofUtilization()
1229     const
1230 {
1231   return mAnalyticalP.mExtraDofUtilization;
1232 }
1233 
1234 //==============================================================================
setExtraErrorLengthClamp(double _clamp)1235 void IK::Analytical::setExtraErrorLengthClamp(double _clamp)
1236 {
1237   mAnalyticalP.mExtraErrorLengthClamp = _clamp;
1238 }
1239 
1240 //==============================================================================
getExtraErrorLengthClamp() const1241 double IK::Analytical::getExtraErrorLengthClamp() const
1242 {
1243   return mAnalyticalP.mExtraErrorLengthClamp;
1244 }
1245 
1246 //==============================================================================
setQualityComparisonFunction(const QualityComparison & _func)1247 void InverseKinematics::Analytical::setQualityComparisonFunction(
1248     const QualityComparison& _func)
1249 {
1250   mAnalyticalP.mQualityComparator = _func;
1251 }
1252 
1253 //==============================================================================
resetQualityComparisonFunction()1254 void InverseKinematics::Analytical::resetQualityComparisonFunction()
1255 {
1256   mAnalyticalP.resetQualityComparisonFunction();
1257 }
1258 
1259 //==============================================================================
1260 InverseKinematics::Analytical::Properties
getAnalyticalProperties() const1261 InverseKinematics::Analytical::getAnalyticalProperties() const
1262 {
1263   return Properties(getGradientMethodProperties(), mAnalyticalP);
1264 }
1265 
1266 //==============================================================================
constructDofMap()1267 void InverseKinematics::Analytical::constructDofMap()
1268 {
1269   const std::vector<std::size_t>& analyticalDofs = getDofs();
1270   const std::vector<std::size_t>& nodeDofs
1271       = mIK->getNode()->getDependentGenCoordIndices();
1272 
1273   mDofMap.clear();
1274   mDofMap.resize(analyticalDofs.size());
1275 
1276   std::vector<bool> isExtraDof;
1277   isExtraDof.resize(nodeDofs.size(), true);
1278 
1279   for (std::size_t i = 0; i < analyticalDofs.size(); ++i)
1280   {
1281     mDofMap[i] = -1;
1282     for (std::size_t j = 0; j < nodeDofs.size(); ++j)
1283     {
1284       if (analyticalDofs[i] == nodeDofs[j])
1285       {
1286         mDofMap[i] = j;
1287         isExtraDof[j] = false;
1288       }
1289     }
1290 
1291     if (mDofMap[i] == -1)
1292     {
1293       DegreeOfFreedom* dof
1294           = mIK->getNode()->getSkeleton()->getDof(analyticalDofs[i]);
1295       std::string name
1296           = (dof == nullptr) ? std::string("nonexistent") : dof->getName();
1297       dtwarn << "[InverseKinematics::Analytical::constructDofMap] Your "
1298              << "analytical IK solver includes a DegreeOfFreedom ("
1299              << analyticalDofs[i] << ") [" << name << "] which is not a "
1300              << "dependent DOF of the JacobianNode ["
1301              << mIK->getNode()->getName() << "]. This might result in "
1302              << "undesirable behavior, such as that DOF being ignored\n";
1303     }
1304   }
1305 
1306   mExtraDofs.clear();
1307   mExtraDofs.reserve(isExtraDof.size());
1308 
1309   const std::vector<int>& gradDofMap = mIK->getDofMap();
1310   for (std::size_t i = 0; i < isExtraDof.size(); ++i)
1311   {
1312     if (isExtraDof[i] && (gradDofMap[i] > -1))
1313       mExtraDofs.push_back(i);
1314   }
1315 }
1316 
1317 //==============================================================================
checkSolutionJointLimits()1318 void InverseKinematics::Analytical::checkSolutionJointLimits()
1319 {
1320   const std::vector<std::size_t>& dofs = getDofs();
1321   for (std::size_t i = 0; i < mSolutions.size(); ++i)
1322   {
1323     Solution& s = mSolutions[i];
1324     const Eigen::VectorXd& q = s.mConfig;
1325 
1326     for (std::size_t j = 0; j < dofs.size(); ++j)
1327     {
1328       DegreeOfFreedom* dof = mIK->getNode()->getSkeleton()->getDof(dofs[j]);
1329       if (q[j] < dof->getPositionLowerLimit()
1330           || dof->getPositionUpperLimit() < q[j])
1331       {
1332         s.mValidity |= LIMIT_VIOLATED;
1333         break;
1334       }
1335     }
1336   }
1337 }
1338 
1339 //==============================================================================
setActive(bool _active)1340 void InverseKinematics::setActive(bool _active)
1341 {
1342   mActive = _active;
1343 }
1344 
1345 //==============================================================================
setInactive()1346 void InverseKinematics::setInactive()
1347 {
1348   mActive = false;
1349 }
1350 
1351 //==============================================================================
isActive() const1352 bool InverseKinematics::isActive() const
1353 {
1354   return mActive;
1355 }
1356 
1357 //==============================================================================
setHierarchyLevel(std::size_t _level)1358 void InverseKinematics::setHierarchyLevel(std::size_t _level)
1359 {
1360   mHierarchyLevel = _level;
1361 }
1362 
1363 //==============================================================================
getHierarchyLevel() const1364 std::size_t InverseKinematics::getHierarchyLevel() const
1365 {
1366   return mHierarchyLevel;
1367 }
1368 
1369 //==============================================================================
useChain()1370 void InverseKinematics::useChain()
1371 {
1372   mDofs.clear();
1373 
1374   if (mNode->getNumDependentGenCoords() == 0)
1375   {
1376     setDofs(mDofs);
1377     return;
1378   }
1379 
1380   setDofs(mNode->getChainDofs());
1381 }
1382 
1383 //==============================================================================
useWholeBody()1384 void InverseKinematics::useWholeBody()
1385 {
1386   setDofs(mNode->getDependentGenCoordIndices());
1387 }
1388 
1389 //==============================================================================
setDofs(const std::vector<std::size_t> & _dofs)1390 void InverseKinematics::setDofs(const std::vector<std::size_t>& _dofs)
1391 {
1392   mDofs = _dofs;
1393   const std::vector<std::size_t>& entityDependencies
1394       = mNode->getDependentGenCoordIndices();
1395 
1396   mDofMap.resize(entityDependencies.size());
1397   for (std::size_t i = 0; i < mDofMap.size(); ++i)
1398   {
1399     mDofMap[i] = -1;
1400     for (std::size_t j = 0; j < mDofs.size(); ++j)
1401     {
1402       if (mDofs[j] == entityDependencies[i])
1403       {
1404         mDofMap[i] = j;
1405       }
1406     }
1407   }
1408 
1409   mProblem->setDimension(mDofs.size());
1410 
1411   if (mAnalytical)
1412     mAnalytical->constructDofMap();
1413 }
1414 
1415 //==============================================================================
getDofs() const1416 const std::vector<std::size_t>& InverseKinematics::getDofs() const
1417 {
1418   return mDofs;
1419 }
1420 
1421 //==============================================================================
getDofMap() const1422 const std::vector<int>& InverseKinematics::getDofMap() const
1423 {
1424   return mDofMap;
1425 }
1426 
1427 //==============================================================================
setObjective(const std::shared_ptr<optimizer::Function> & _objective)1428 void InverseKinematics::setObjective(
1429     const std::shared_ptr<optimizer::Function>& _objective)
1430 {
1431   mObjective = _objective;
1432 }
1433 
1434 //==============================================================================
getObjective()1435 const std::shared_ptr<optimizer::Function>& InverseKinematics::getObjective()
1436 {
1437   return mObjective;
1438 }
1439 
1440 //==============================================================================
getObjective() const1441 std::shared_ptr<const optimizer::Function> InverseKinematics::getObjective()
1442     const
1443 {
1444   return mObjective;
1445 }
1446 
1447 //==============================================================================
setNullSpaceObjective(const std::shared_ptr<optimizer::Function> & _nsObjective)1448 void InverseKinematics::setNullSpaceObjective(
1449     const std::shared_ptr<optimizer::Function>& _nsObjective)
1450 {
1451   mNullSpaceObjective = _nsObjective;
1452 }
1453 
1454 //==============================================================================
1455 const std::shared_ptr<optimizer::Function>&
getNullSpaceObjective()1456 InverseKinematics::getNullSpaceObjective()
1457 {
1458   return mNullSpaceObjective;
1459 }
1460 
1461 //==============================================================================
1462 std::shared_ptr<const optimizer::Function>
getNullSpaceObjective() const1463 InverseKinematics::getNullSpaceObjective() const
1464 {
1465   return mNullSpaceObjective;
1466 }
1467 
1468 //==============================================================================
hasNullSpaceObjective() const1469 bool InverseKinematics::hasNullSpaceObjective() const
1470 {
1471   return (nullptr != mNullSpaceObjective);
1472 }
1473 
1474 //==============================================================================
getErrorMethod()1475 InverseKinematics::ErrorMethod& InverseKinematics::getErrorMethod()
1476 {
1477   return *mErrorMethod;
1478 }
1479 
1480 //==============================================================================
getErrorMethod() const1481 const InverseKinematics::ErrorMethod& InverseKinematics::getErrorMethod() const
1482 {
1483   return *mErrorMethod;
1484 }
1485 
1486 //==============================================================================
getGradientMethod()1487 InverseKinematics::GradientMethod& InverseKinematics::getGradientMethod()
1488 {
1489   return *mGradientMethod;
1490 }
1491 
1492 //==============================================================================
getGradientMethod() const1493 const InverseKinematics::GradientMethod& InverseKinematics::getGradientMethod()
1494     const
1495 {
1496   return *mGradientMethod;
1497 }
1498 
1499 //==============================================================================
getAnalytical()1500 InverseKinematics::Analytical* InverseKinematics::getAnalytical()
1501 {
1502   return mAnalytical;
1503 }
1504 
1505 //==============================================================================
getAnalytical() const1506 const InverseKinematics::Analytical* InverseKinematics::getAnalytical() const
1507 {
1508   return mAnalytical;
1509 }
1510 
1511 //==============================================================================
getProblem()1512 const std::shared_ptr<optimizer::Problem>& InverseKinematics::getProblem()
1513 {
1514   return mProblem;
1515 }
1516 
1517 //==============================================================================
getProblem() const1518 std::shared_ptr<const optimizer::Problem> InverseKinematics::getProblem() const
1519 {
1520   return mProblem;
1521 }
1522 
1523 //==============================================================================
resetProblem(bool _clearSeeds)1524 void InverseKinematics::resetProblem(bool _clearSeeds)
1525 {
1526   mProblem->removeAllEqConstraints();
1527   mProblem->removeAllIneqConstraints();
1528 
1529   if (_clearSeeds)
1530     mProblem->clearAllSeeds();
1531 
1532   mProblem->setObjective(Objective::createShared(this));
1533   mProblem->addEqConstraint(std::make_shared<Constraint>(this));
1534 
1535   mProblem->setDimension(mDofs.size());
1536 }
1537 
1538 //==============================================================================
setSolver(const std::shared_ptr<optimizer::Solver> & _newSolver)1539 void InverseKinematics::setSolver(
1540     const std::shared_ptr<optimizer::Solver>& _newSolver)
1541 {
1542   mSolver = _newSolver;
1543   if (nullptr == mSolver)
1544     return;
1545 
1546   mSolver->setProblem(getProblem());
1547 }
1548 
1549 //==============================================================================
getSolver()1550 const std::shared_ptr<optimizer::Solver>& InverseKinematics::getSolver()
1551 {
1552   return mSolver;
1553 }
1554 
1555 //==============================================================================
getSolver() const1556 std::shared_ptr<const optimizer::Solver> InverseKinematics::getSolver() const
1557 {
1558   return mSolver;
1559 }
1560 
1561 //==============================================================================
setOffset(const Eigen::Vector3d & _offset)1562 void InverseKinematics::setOffset(const Eigen::Vector3d& _offset)
1563 {
1564   if (Eigen::Vector3d::Zero() == _offset)
1565     mHasOffset = false;
1566   else
1567     mHasOffset = true;
1568 
1569   clearCaches();
1570   mOffset = _offset;
1571 }
1572 
1573 //==============================================================================
getOffset() const1574 const Eigen::Vector3d& InverseKinematics::getOffset() const
1575 {
1576   return mOffset;
1577 }
1578 
1579 //==============================================================================
hasOffset() const1580 bool InverseKinematics::hasOffset() const
1581 {
1582   return mHasOffset;
1583 }
1584 
1585 //==============================================================================
setTarget(std::shared_ptr<SimpleFrame> _newTarget)1586 void InverseKinematics::setTarget(std::shared_ptr<SimpleFrame> _newTarget)
1587 {
1588   if (nullptr == _newTarget)
1589   {
1590     _newTarget = SimpleFramePtr(new SimpleFrame(
1591         Frame::World(),
1592         mNode->getName() + "_target",
1593         mNode->getWorldTransform()));
1594   }
1595 
1596   mTarget = _newTarget;
1597   resetTargetConnection();
1598 }
1599 
1600 //==============================================================================
getTarget()1601 std::shared_ptr<SimpleFrame> InverseKinematics::getTarget()
1602 {
1603   return mTarget;
1604 }
1605 
1606 //==============================================================================
getTarget() const1607 std::shared_ptr<const SimpleFrame> InverseKinematics::getTarget() const
1608 {
1609   return mTarget;
1610 }
1611 
1612 //==============================================================================
getNode()1613 JacobianNode* InverseKinematics::getNode()
1614 {
1615   return getAffiliation();
1616 }
1617 
1618 //==============================================================================
getNode() const1619 const JacobianNode* InverseKinematics::getNode() const
1620 {
1621   return getAffiliation();
1622 }
1623 
1624 //==============================================================================
getAffiliation()1625 JacobianNode* InverseKinematics::getAffiliation()
1626 {
1627   return mNode;
1628 }
1629 
1630 //==============================================================================
getAffiliation() const1631 const JacobianNode* InverseKinematics::getAffiliation() const
1632 {
1633   return mNode;
1634 }
1635 
1636 //==============================================================================
computeJacobian() const1637 const math::Jacobian& InverseKinematics::computeJacobian() const
1638 {
1639   // TODO(MXG): Test whether we can safely use a const reference here instead of
1640   // just a regular const
1641   const math::Jacobian fullJacobian = hasOffset()
1642                                           ? getNode()->getWorldJacobian(mOffset)
1643                                           : getNode()->getWorldJacobian();
1644 
1645   mJacobian.setZero(6, getDofs().size());
1646 
1647   for (int i = 0; i < static_cast<int>(getDofMap().size()); ++i)
1648   {
1649     int j = getDofMap()[i];
1650     if (j >= 0)
1651       mJacobian.block<6, 1>(0, j) = fullJacobian.block<6, 1>(0, i);
1652   }
1653 
1654   return mJacobian;
1655 }
1656 
1657 //==============================================================================
getPositions() const1658 Eigen::VectorXd InverseKinematics::getPositions() const
1659 {
1660   return mNode->getSkeleton()->getPositions(mDofs);
1661 }
1662 
1663 //==============================================================================
setPositions(const Eigen::VectorXd & _q)1664 void InverseKinematics::setPositions(const Eigen::VectorXd& _q)
1665 {
1666   if (_q.size() != static_cast<int>(mDofs.size()))
1667   {
1668     dterr << "[InverseKinematics::setPositions] Mismatch between joint "
1669           << "positions size [" << _q.size() << "] and number of available "
1670           << "degrees of freedom [" << mDofs.size() << "]\n";
1671     return;
1672   }
1673 
1674   const dart::dynamics::SkeletonPtr& skel = getNode()->getSkeleton();
1675   skel->setPositions(mDofs, _q);
1676 }
1677 
1678 //==============================================================================
clearCaches()1679 void InverseKinematics::clearCaches()
1680 {
1681   mErrorMethod->clearCache();
1682   mGradientMethod->clearCache();
1683 }
1684 
1685 //==============================================================================
Objective(InverseKinematics * _ik)1686 InverseKinematics::Objective::Objective(InverseKinematics* _ik) : mIK(_ik)
1687 {
1688   // Do nothing
1689 }
1690 
1691 //==============================================================================
clone(InverseKinematics * _newIK) const1692 optimizer::FunctionPtr InverseKinematics::Objective::clone(
1693     InverseKinematics* _newIK) const
1694 {
1695   return std::make_shared<Objective>(_newIK);
1696 }
1697 
1698 //==============================================================================
eval(const Eigen::VectorXd & _x)1699 double InverseKinematics::Objective::eval(const Eigen::VectorXd& _x)
1700 {
1701   if (nullptr == mIK)
1702   {
1703     dterr << "[InverseKinematics::Objective::eval] Attempting to use an "
1704           << "Objective function of an expired InverseKinematics module!\n";
1705     assert(false);
1706     return 0;
1707   }
1708 
1709   double cost = 0.0;
1710 
1711   if (mIK->mObjective)
1712     cost += mIK->mObjective->eval(_x);
1713 
1714   if (mIK->mNullSpaceObjective)
1715     cost += mIK->mNullSpaceObjective->eval(_x);
1716 
1717   return cost;
1718 }
1719 
1720 //==============================================================================
evalGradient(const Eigen::VectorXd & _x,Eigen::Map<Eigen::VectorXd> _grad)1721 void InverseKinematics::Objective::evalGradient(
1722     const Eigen::VectorXd& _x, Eigen::Map<Eigen::VectorXd> _grad)
1723 {
1724   if (nullptr == mIK)
1725   {
1726     dterr << "[InverseKinematics::Objective::evalGradient] Attempting to use "
1727           << "an Objective function of an expired InverseKinematics module!\n";
1728     assert(false);
1729     return;
1730   }
1731 
1732   if (mIK->mObjective)
1733     mIK->mObjective->evalGradient(_x, _grad);
1734   else
1735     _grad.setZero();
1736 
1737   if (mIK->mNullSpaceObjective)
1738   {
1739     mGradCache.resize(_grad.size());
1740     Eigen::Map<Eigen::VectorXd> gradMap(mGradCache.data(), _grad.size());
1741     mIK->mNullSpaceObjective->evalGradient(_x, gradMap);
1742 
1743     mIK->setPositions(_x);
1744 
1745     const math::Jacobian& J = mIK->computeJacobian();
1746     mSVDCache.compute(J, Eigen::ComputeFullV);
1747     math::extractNullSpace(mSVDCache, mNullSpaceCache);
1748     _grad += mNullSpaceCache * mNullSpaceCache.transpose() * mGradCache;
1749   }
1750 }
1751 
1752 //==============================================================================
Constraint(InverseKinematics * _ik)1753 InverseKinematics::Constraint::Constraint(InverseKinematics* _ik) : mIK(_ik)
1754 {
1755   // Do nothing
1756 }
1757 
1758 //==============================================================================
clone(InverseKinematics * _newIK) const1759 optimizer::FunctionPtr InverseKinematics::Constraint::clone(
1760     InverseKinematics* _newIK) const
1761 {
1762   return std::make_shared<Constraint>(_newIK);
1763 }
1764 
1765 //==============================================================================
eval(const Eigen::VectorXd & _x)1766 double InverseKinematics::Constraint::eval(const Eigen::VectorXd& _x)
1767 {
1768   if (nullptr == mIK)
1769   {
1770     dterr << "[InverseKinematics::Constraint::eval] Attempting to use a "
1771           << "Constraint function of an expired InverseKinematics module!\n";
1772     assert(false);
1773     return 0;
1774   }
1775 
1776   return mIK->getErrorMethod().evalError(_x).norm();
1777 }
1778 
1779 //==============================================================================
evalGradient(const Eigen::VectorXd & _x,Eigen::Map<Eigen::VectorXd> _grad)1780 void InverseKinematics::Constraint::evalGradient(
1781     const Eigen::VectorXd& _x, Eigen::Map<Eigen::VectorXd> _grad)
1782 {
1783   if (nullptr == mIK)
1784   {
1785     dterr << "[InverseKinematics::Constraint::evalGradient] Attempting to use "
1786           << "a Constraint function of an expired InverseKinematics module!\n";
1787     assert(false);
1788     return;
1789   }
1790 
1791   mIK->getGradientMethod().evalGradient(_x, _grad);
1792 }
1793 
1794 //==============================================================================
InverseKinematics(JacobianNode * _node)1795 InverseKinematics::InverseKinematics(JacobianNode* _node)
1796   : mActive(true),
1797     mHierarchyLevel(0),
1798     mOffset(Eigen::Vector3d::Zero()),
1799     mHasOffset(false),
1800     mNode(_node)
1801 {
1802   initialize();
1803 }
1804 
1805 //==============================================================================
initialize()1806 void InverseKinematics::initialize()
1807 {
1808   // Default to having no objectives
1809   setObjective(nullptr);
1810   setNullSpaceObjective(nullptr);
1811 
1812   mProblem = std::make_shared<optimizer::Problem>();
1813   resetProblem();
1814 
1815   // The default error method is the one based on Task Space Regions
1816   setErrorMethod<TaskSpaceRegion>();
1817 
1818   // The default gradient method is damped least squares Jacobian
1819   setGradientMethod<JacobianDLS>();
1820 
1821   // Create the default target for this IK module
1822   setTarget(nullptr);
1823 
1824   // Set up the cache clearing connections. These connections will ensure that
1825   // any time an outsider alters the transform of the object's transform or the
1826   // target's transform, our saved caches will be cleared so that the error and
1827   // gradient will be recomputed the next time they are polled.
1828   resetTargetConnection();
1829   resetNodeConnection();
1830 
1831   // By default, we use the linkage when performing IK
1832   useChain();
1833 
1834   // Default to the native DART gradient descent solver
1835   std::shared_ptr<optimizer::GradientDescentSolver> solver
1836       = std::make_shared<optimizer::GradientDescentSolver>(mProblem);
1837   solver->setStepSize(1.0);
1838   mSolver = solver;
1839 }
1840 
1841 //==============================================================================
resetTargetConnection()1842 void InverseKinematics::resetTargetConnection()
1843 {
1844   mTargetConnection.disconnect();
1845   mTargetConnection = mTarget->onTransformUpdated.connect(
1846       [=](const Entity*) { this->clearCaches(); });
1847   clearCaches();
1848 }
1849 
1850 //==============================================================================
resetNodeConnection()1851 void InverseKinematics::resetNodeConnection()
1852 {
1853   mNodeConnection.disconnect();
1854   mNodeConnection = mNode->onTransformUpdated.connect(
1855       [=](const Entity*) { this->clearCaches(); });
1856   clearCaches();
1857 }
1858 
1859 } // namespace dynamics
1860 } // namespace dart
1861