33#ifndef DART_DYNAMICS_INVERSEKINEMATICS_HPP_
34#define DART_DYNAMICS_INVERSEKINEMATICS_HPP_
133 bool solve(
bool _applySolution =
true);
137 bool solve(Eigen::VectorXd& positions,
bool _applySolution =
true);
190 template <
class DegreeOfFreedomT>
191 void setDofs(
const std::vector<DegreeOfFreedomT*>& _dofs);
196 void setDofs(
const std::vector<std::size_t>& _dofs);
199 const std::vector<std::size_t>&
getDofs()
const;
207 const std::vector<int>&
getDofMap()
const;
212 void setObjective(
const std::shared_ptr<optimizer::Function>& _objective);
215 const std::shared_ptr<optimizer::Function>&
getObjective();
218 std::shared_ptr<const optimizer::Function>
getObjective()
const;
229 const std::shared_ptr<optimizer::Function>& _nsObjective);
244 template <
class IKErrorMethod,
typename... Args>
259 template <
class IKGradientMethod,
typename... Args>
281 const std::shared_ptr<optimizer::Problem>&
getProblem();
284 std::shared_ptr<const optimizer::Problem>
getProblem()
const;
296 void setSolver(
const std::shared_ptr<optimizer::Solver>& _newSolver);
299 const std::shared_ptr<optimizer::Solver>&
getSolver();
302 std::shared_ptr<const optimizer::Solver>
getSolver()
const;
309 void setOffset(
const Eigen::Vector3d& _offset = Eigen::Vector3d::Zero());
314 const Eigen::Vector3d&
getOffset()
const;
327 void setTarget(std::shared_ptr<SimpleFrame> _newTarget);
331 std::shared_ptr<SimpleFrame>
getTarget();
335 std::shared_ptr<const SimpleFrame>
getTarget()
const;
481 typedef std::pair<Eigen::Vector6d, Eigen::Vector6d>
Bounds;
500 std::pair<Eigen::Vector6d, Eigen::Vector6d>
mBounds;
515 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
520 const std::string& _methodName,
527 virtual std::unique_ptr<ErrorMethod>
clone(
546 const Eigen::Isometry3d& _currentTf,
const Eigen::Vector6d& _error) = 0;
562 void setBounds(
const std::pair<Eigen::Vector6d, Eigen::Vector6d>& _bounds);
565 const std::pair<Eigen::Vector6d, Eigen::Vector6d>&
getBounds()
const;
569 const Eigen::Vector3d& _lower =
571 const Eigen::Vector3d& _upper =
576 const std::pair<Eigen::Vector3d, Eigen::Vector3d>& _bounds);
583 const Eigen::Vector3d& _lower =
585 const Eigen::Vector3d& _upper =
590 const std::pair<Eigen::Vector3d, Eigen::Vector3d>& _bounds);
614 const Eigen::Vector3d& _weights =
624 const Eigen::Vector3d& _weights =
657 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
704 const Eigen::Isometry3d& _currentTf,
745 const Eigen::VectorXd& weights = Eigen::VectorXd());
750 const std::string& _methodName,
757 virtual std::unique_ptr<GradientMethod>
clone(
776 Eigen::VectorXd& _grad) = 0;
781 Eigen::Map<Eigen::VectorXd> _grad);
821 Eigen::VectorXd& grad,
const std::vector<std::size_t>& dofs);
899 std::unique_ptr<GradientMethod>
clone(
904 Eigen::VectorXd& _grad)
override;
942 std::unique_ptr<GradientMethod>
clone(
947 Eigen::VectorXd& _grad)
override;
1008 Solution(
const Eigen::VectorXd& _config = Eigen::VectorXd(),
1009 int _validity =
VALID);
1020 typedef std::function<bool(
1021 const Eigen::VectorXd& _better,
1022 const Eigen::VectorXd& _worse,
1042 double extraErrorLengthClamp,
1080 const Eigen::Isometry3d& _desiredTf);
1085 Eigen::VectorXd& _grad)
override;
1097 const Eigen::Isometry3d& _desiredBodyTf) = 0;
1104 virtual const std::vector<std::size_t>&
getDofs()
const = 0;
1171 Eigen::VectorXd& grad,
1246 double eval(
const Eigen::VectorXd& _x)
override;
1250 Eigen::Map<Eigen::VectorXd> _grad)
override;
1269 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1294 double eval(
const Eigen::VectorXd& _x)
override;
1298 Eigen::Map<Eigen::VectorXd> _grad)
override;
#define DART_DEFINE_ALIGNED_SHARED_OBJECT_CREATOR(class_name)
Definition Memory.hpp:148
BodyPropPtr properties
Definition SdfParser.cpp:80
class Connection
Definition Signal.hpp:47
The Subject class is a base class for any object that wants to report when it gets destroyed.
Definition Subject.hpp:58
sub_ptr is a pointer to a Subject.
Definition sub_ptr.hpp:47
Analytical is a base class that should be inherited by methods that are made to solve the IK analytic...
Definition InverseKinematics.hpp:965
ExtraDofUtilization getExtraDofUtilization() const
Get how extra DOFs are being utilized by the IK module.
Definition InverseKinematics.cpp:1183
void constructDofMap()
Construct a mapping from the DOFs of getDofs() to their indices within the Node's list of dependent D...
Definition InverseKinematics.cpp:1221
Eigen::VectorXd mRestoreConfigCache
A cache for storing the current configuration so that it can be restored later.
Definition InverseKinematics.hpp:1217
std::vector< Solution > mLimitViolationCache
A cache for solutions that violate joint limits.
Definition InverseKinematics.hpp:1209
Eigen::VectorXd mExtraDofGradCache
A cache for storing the gradient for the extra DOFs.
Definition InverseKinematics.hpp:1220
UniqueProperties mAnalyticalP
Properties for this Analytical IK solver.
Definition InverseKinematics.hpp:1186
std::vector< Solution > mValidSolutionsCache
A cache for the valid solutions.
Definition InverseKinematics.hpp:1203
Validity_t
Bitwise enumerations that are used to describe some properties of each solution produced by the analy...
Definition InverseKinematics.hpp:971
@ VALID
The solution is completely valid and reaches the target.
Definition InverseKinematics.hpp:972
@ LIMIT_VIOLATED
The solution has one or more joint positions that violate the joint limits.
Definition InverseKinematics.hpp:974
@ OUT_OF_REACH
The solution does not reach the target.
Definition InverseKinematics.hpp:973
void checkSolutionJointLimits()
Go through the mSolutions vector and tag entries with LIMIT_VIOLATED if any components of their confi...
Definition InverseKinematics.cpp:1272
void setExtraErrorLengthClamp(double _clamp)
Set how much to clamp the error vector that gets applied to extra DOFs.
Definition InverseKinematics.cpp:1189
Properties getAnalyticalProperties() const
Get the Properties for this Analytical class.
Definition InverseKinematics.cpp:1215
virtual ~Analytical()=default
Virtual destructor.
const std::vector< Solution > & getSolutions()
Get the solutions for this IK module, along with a tag indicating whether each solution is valid.
Definition InverseKinematics.cpp:970
ExtraDofUtilization
If there are extra DOFs in the IK module which your Analytical solver implementation does not make us...
Definition InverseKinematics.hpp:997
@ PRE_AND_POST_ANALYTICAL
Definition InverseKinematics.hpp:1001
@ UNUSED
Definition InverseKinematics.hpp:998
@ POST_ANALYTICAL
Definition InverseKinematics.hpp:1000
@ PRE_ANALYTICAL
Definition InverseKinematics.hpp:999
Eigen::VectorXd mConfigCache
A cache for storing the current configuration.
Definition InverseKinematics.hpp:1212
virtual void addExtraDofGradient(Eigen::VectorXd &grad, const Eigen::Vector6d &error, ExtraDofUtilization utilization)
This function will compute a gradient which utilizes the extra DOFs that go unused by the Analytical ...
Definition InverseKinematics.cpp:1039
virtual const std::vector< Solution > & computeSolutions(const Eigen::Isometry3d &_desiredBodyTf)=0
Use this function to fill the entries of the mSolutions variable.
void computeGradient(const Eigen::Vector6d &_error, Eigen::VectorXd &_grad) override
You should not need to override this function.
Definition InverseKinematics.cpp:1083
void setPositions(const Eigen::VectorXd &_config)
Set the configuration of the DOFs.
Definition InverseKinematics.cpp:1162
virtual const std::vector< std::size_t > & getDofs() const =0
Get a list of the DOFs that will be included in the entries of the solutions returned by getSolutions...
std::vector< Solution > mSolutions
Vector of solutions.
Definition InverseKinematics.hpp:1183
void setExtraDofUtilization(ExtraDofUtilization _utilization)
Set how you want extra DOFs to be utilized by the IK module.
Definition InverseKinematics.cpp:1175
std::vector< std::size_t > mExtraDofs
List of extra DOFs in the module which are not covered by the Analytical IK implementation.
Definition InverseKinematics.hpp:1197
std::vector< Solution > mOutOfReachCache
A cache for the out of reach solutions.
Definition InverseKinematics.hpp:1206
Eigen::VectorXd getPositions() const
Get the configuration of the DOFs.
Definition InverseKinematics.cpp:1169
double getExtraErrorLengthClamp() const
Get how much we will clamp the error vector that gets applied to extra DOFs.
Definition InverseKinematics.cpp:1195
void resetQualityComparisonFunction()
Reset the quality comparison function to the default method.
Definition InverseKinematics.cpp:1208
void setQualityComparisonFunction(const QualityComparison &_func)
Set the function that will be used to compare the qualities of two solutions.
Definition InverseKinematics.cpp:1201
std::function< bool(const Eigen::VectorXd &_better, const Eigen::VectorXd &_worse, const InverseKinematics *_ik)> QualityComparison
Definition InverseKinematics.hpp:1023
std::vector< int > mDofMap
This maps the DOFs provided by getDofs() to their index in the Node's list of dependent DOFs.
Definition InverseKinematics.hpp:1192
The InverseKinematics::Constraint Function is simply meant to be used to merge the ErrorMethod and Gr...
Definition InverseKinematics.hpp:1281
optimizer::FunctionPtr clone(InverseKinematics *_newIK) const override
Enable this function to be cloned to a new IK module.
Definition InverseKinematics.cpp:1713
void evalGradient(const Eigen::VectorXd &_x, Eigen::Map< Eigen::VectorXd > _grad) override
Evaluates and returns the objective function at the point x.
Definition InverseKinematics.cpp:1734
virtual ~Constraint()=default
Virtual constructor.
double eval(const Eigen::VectorXd &_x) override
Evaluates and returns the objective function at the point x.
Definition InverseKinematics.cpp:1720
sub_ptr< InverseKinematics > mIK
Pointer to this Constraint's IK module.
Definition InverseKinematics.hpp:1303
ErrorMethod is a base class for different ways of computing the error of an InverseKinematics module.
Definition InverseKinematics.hpp:478
common::sub_ptr< InverseKinematics > mIK
Pointer to the IK module of this ErrorMethod.
Definition InverseKinematics.hpp:641
virtual ~ErrorMethod()=default
Virtual destructor.
virtual Eigen::Isometry3d computeDesiredTransform(const Eigen::Isometry3d &_currentTf, const Eigen::Vector6d &_error)=0
Override this function with your implementation of computing the desired given the current transform ...
Definition InverseKinematics.cpp:209
void setLinearBounds(const Eigen::Vector3d &_lower=Eigen::Vector3d::Constant(-DefaultIKTolerance), const Eigen::Vector3d &_upper=Eigen::Vector3d::Constant(DefaultIKTolerance))
Set the error bounds for translation.
Definition InverseKinematics.cpp:316
Properties mErrorP
The properties of this ErrorMethod.
Definition InverseKinematics.hpp:653
Eigen::Vector6d mLastError
The last error vector computed by this ErrorMethod.
Definition InverseKinematics.hpp:650
std::pair< Eigen::Vector6d, Eigen::Vector6d > Bounds
Definition InverseKinematics.hpp:481
const std::pair< Eigen::Vector6d, Eigen::Vector6d > & getBounds() const
Get all the error bounds.
Definition InverseKinematics.cpp:285
const std::string & getMethodName() const
Get the name of this ErrorMethod.
Definition InverseKinematics.cpp:261
std::pair< Eigen::Vector3d, Eigen::Vector3d > getAngularBounds() const
Get the error bounds for orientation.
Definition InverseKinematics.cpp:308
const Eigen::Vector6d & evalError(const Eigen::VectorXd &_q)
This function is used to handle caching the error vector.
Definition InverseKinematics.cpp:216
void setErrorWeights(const Eigen::Vector6d &_weights)
Set the weights that will be applied to each component of the error vector.
Definition InverseKinematics.cpp:354
void setAngularBounds(const Eigen::Vector3d &_lower=Eigen::Vector3d::Constant(-DefaultIKTolerance), const Eigen::Vector3d &_upper=Eigen::Vector3d::Constant(DefaultIKTolerance))
Set the error bounds for orientation.
Definition InverseKinematics.cpp:291
void setLinearErrorWeights(const Eigen::Vector3d &_weights=Eigen::Vector3d::Constant(DefaultIKLinearWeight))
Set the weights that will be applied to each linear component of the error vector.
Definition InverseKinematics.cpp:382
double getErrorLengthClamp() const
Set the clamp that will be applied to the length of the error vector each iteration.
Definition InverseKinematics.cpp:348
void setAngularErrorWeights(const Eigen::Vector3d &_weights=Eigen::Vector3d::Constant(DefaultIKAngularWeight))
Set the weights that will be applied to each angular component of the error vector.
Definition InverseKinematics.cpp:368
Eigen::Vector3d getLinearErrorWeights() const
Get the weights that will be applied to each linear component of the error vector.
Definition InverseKinematics.cpp:390
Eigen::VectorXd mLastPositions
The last joint positions passed into this ErrorMethod.
Definition InverseKinematics.hpp:647
virtual Eigen::Vector6d computeError()=0
Override this function with your implementation of the error vector computation.
void setBounds(const Eigen::Vector6d &_lower=Eigen::Vector6d::Constant(-DefaultIKTolerance), const Eigen::Vector6d &_upper=Eigen::Vector6d::Constant(DefaultIKTolerance))
Set all the error bounds.
Definition InverseKinematics.cpp:267
const Eigen::Vector6d & getErrorWeights() const
Get the weights that will be applied to each component of the error vector.
Definition InverseKinematics.cpp:362
std::string mMethodName
Name of this error method.
Definition InverseKinematics.hpp:644
std::pair< Eigen::Vector3d, Eigen::Vector3d > getLinearBounds() const
Get the error bounds for translation.
Definition InverseKinematics.cpp:333
virtual std::unique_ptr< ErrorMethod > clone(InverseKinematics *_newIK) const =0
Enable this ErrorMethod to be cloned to a new IK module.
Properties getErrorMethodProperties() const
Get the Properties of this ErrorMethod.
Definition InverseKinematics.cpp:397
void clearCache()
Clear the cache to force the error to be recomputed.
Definition InverseKinematics.cpp:403
void setErrorLengthClamp(double _clampSize=DefaultIKErrorClamp)
Set the clamp that will be applied to the length of the error vector each iteration.
Definition InverseKinematics.cpp:341
Eigen::Vector3d getAngularErrorWeights() const
Get the weights that will be applied to each angular component of the error vector.
Definition InverseKinematics.cpp:376
This class should be inherited by optimizer::Function classes that have a dependency on the InverseKi...
Definition InverseKinematics.hpp:464
virtual optimizer::FunctionPtr clone(InverseKinematics *_newIK) const =0
Enable this function to be cloned to a new IK module.
virtual ~Function()=default
Virtual destructor.
GradientMethod is a base class for different ways of computing the gradient of an InverseKinematics m...
Definition InverseKinematics.hpp:732
void clampGradient(Eigen::VectorXd &_grad) const
Clamp the gradient based on the clamp settings of this GradientMethod.
Definition InverseKinematics.cpp:659
Eigen::VectorXd mInitialPositionsCache
Cache used by convertJacobianMethodOutputToGradient to avoid reallocating this vector on each iterati...
Definition InverseKinematics.hpp:857
InverseKinematics * getIK()
Returns the IK module that this GradientMethod belongs to.
Definition InverseKinematics.cpp:748
void setComponentWiseClamp(double _clamp=DefaultIKGradientComponentClamp)
Set the component-wise clamp for this GradientMethod.
Definition InverseKinematics.cpp:671
std::string mMethodName
The name of this method.
Definition InverseKinematics.hpp:842
void applyWeights(Eigen::VectorXd &_grad) const
Apply weights to the gradient based on the weight settings of this GradientMethod.
Definition InverseKinematics.cpp:683
const Eigen::VectorXd & getComponentWeights() const
Get the weights of this GradientMethod.
Definition InverseKinematics.cpp:701
const std::string & getMethodName() const
Get the name of this GradientMethod.
Definition InverseKinematics.cpp:653
virtual ~GradientMethod()=default
Virtual destructor.
void clearCache()
Clear the cache to force the gradient to be recomputed.
Definition InverseKinematics.cpp:740
Eigen::VectorXd mLastPositions
The last positions that was passed to this GradientMethod.
Definition InverseKinematics.hpp:845
void setComponentWeights(const Eigen::VectorXd &_weights)
Set the weights that will be applied to each component of the gradient.
Definition InverseKinematics.cpp:693
common::sub_ptr< InverseKinematics > mIK
The IK module that this GradientMethod belongs to.
Definition InverseKinematics.hpp:839
double getComponentWiseClamp() const
Get the component-wise clamp for this GradientMethod.
Definition InverseKinematics.cpp:677
void convertJacobianMethodOutputToGradient(Eigen::VectorXd &grad, const std::vector< std::size_t > &dofs)
Convert the gradient that gets generated by Jacobian methods into a gradient that can be used by a Gr...
Definition InverseKinematics.cpp:707
virtual std::unique_ptr< GradientMethod > clone(InverseKinematics *_newIK) const =0
Enable this GradientMethod to be cloned to a new IK module.
void evalGradient(const Eigen::VectorXd &_q, Eigen::Map< Eigen::VectorXd > _grad)
This function is used to handle caching the gradient vector and interfacing with the solver.
Definition InverseKinematics.cpp:601
Eigen::VectorXd mLastGradient
The last gradient that was computed by this GradientMethod.
Definition InverseKinematics.hpp:848
Properties mGradientP
Properties for this GradientMethod.
Definition InverseKinematics.hpp:851
virtual void computeGradient(const Eigen::Vector6d &_error, Eigen::VectorXd &_grad)=0
Override this function with your implementation of the gradient computation.
Properties getGradientMethodProperties() const
Get the Properties of this GradientMethod.
Definition InverseKinematics.cpp:734
JacobianDLS refers to the Damped Least Squares Jacobian Pseudoinverse (specifically,...
Definition InverseKinematics.hpp:870
UniqueProperties mDLSProperties
Properties of this Damped Least Squares method.
Definition InverseKinematics.hpp:920
std::unique_ptr< GradientMethod > clone(InverseKinematics *_newIK) const override
Enable this GradientMethod to be cloned to a new IK module.
Definition InverseKinematics.cpp:788
double getDampingCoefficient() const
Get the damping coefficient.
Definition InverseKinematics.cpp:825
void computeGradient(const Eigen::Vector6d &_error, Eigen::VectorXd &_grad) override
Override this function with your implementation of the gradient computation.
Definition InverseKinematics.cpp:794
Properties getJacobianDLSProperties() const
Get the Properties of this JacobianDLS.
Definition InverseKinematics.cpp:832
void setDampingCoefficient(double _damping=DefaultIKDLSCoefficient)
Set the damping coefficient.
Definition InverseKinematics.cpp:819
virtual ~JacobianDLS()=default
Virtual destructor.
JacobianTranspose will simply apply the transpose of the Jacobian to the error vector in order to com...
Definition InverseKinematics.hpp:931
virtual ~JacobianTranspose()=default
Virtual destructor.
void computeGradient(const Eigen::Vector6d &_error, Eigen::VectorXd &_grad) override
Override this function with your implementation of the gradient computation.
Definition InverseKinematics.cpp:854
std::unique_ptr< GradientMethod > clone(InverseKinematics *_newIK) const override
Enable this GradientMethod to be cloned to a new IK module.
Definition InverseKinematics.cpp:847
The InverseKinematics::Objective Function is simply used to merge the objective and null space object...
Definition InverseKinematics.hpp:1231
void evalGradient(const Eigen::VectorXd &_x, Eigen::Map< Eigen::VectorXd > _grad) override
Evaluates and returns the objective function at the point x.
Definition InverseKinematics.cpp:1674
Eigen::MatrixXd mNullSpaceCache
Cache for the null space.
Definition InverseKinematics.hpp:1265
virtual ~Objective()=default
Virtual destructor.
double eval(const Eigen::VectorXd &_x) override
Evaluates and returns the objective function at the point x.
Definition InverseKinematics.cpp:1652
Eigen::VectorXd mGradCache
Cache for the gradient of the Objective.
Definition InverseKinematics.hpp:1258
sub_ptr< InverseKinematics > mIK
Pointer to this Objective's IK module.
Definition InverseKinematics.hpp:1255
optimizer::FunctionPtr clone(InverseKinematics *_newIK) const override
Enable this function to be cloned to a new IK module.
Definition InverseKinematics.cpp:1645
Eigen::JacobiSVD< math::Jacobian > mSVDCache
Cache for the null space SVD.
Definition InverseKinematics.hpp:1261
The TaskSpaceRegion is a nicely generalized method for computing the error of an IK Problem.
Definition InverseKinematics.hpp:665
bool isComputingFromCenter() const
Get whether this TaskSpaceRegion is set to compute its error vector from the center of the region.
Definition InverseKinematics.cpp:569
std::unique_ptr< ErrorMethod > clone(InverseKinematics *_newIK) const override
Enable this ErrorMethod to be cloned to a new IK module.
Definition InverseKinematics.cpp:439
Properties getTaskSpaceRegionProperties() const
Get the Properties of this TaskSpaceRegion.
Definition InverseKinematics.cpp:576
Eigen::Vector6d computeError() override
Override this function with your implementation of the error vector computation.
Definition InverseKinematics.cpp:468
Eigen::Isometry3d computeDesiredTransform(const Eigen::Isometry3d &_currentTf, const Eigen::Vector6d &_error) override
Override this function with your implementation of computing the desired given the current transform ...
Definition InverseKinematics.cpp:446
virtual ~TaskSpaceRegion()=default
Virtual destructor.
UniqueProperties mTaskSpaceP
Properties of this TaskSpaceRegion.
Definition InverseKinematics.hpp:724
void setComputeFromCenter(bool computeFromCenter)
Set whether this TaskSpaceRegion should compute its error vector from the center of the region.
Definition InverseKinematics.cpp:562
The InverseKinematics class provides a convenient way of setting up an IK optimization problem.
Definition InverseKinematics.hpp:76
void setActive(bool _active=true)
If this IK module is set to active, then it will be utilized by any HierarchicalIK that has it in its...
Definition InverseKinematics.cpp:1294
std::shared_ptr< SimpleFrame > getTarget()
Get the target that is being used by this IK module.
Definition InverseKinematics.cpp:1554
void clearCaches()
Clear the caches of this IK module.
Definition InverseKinematics.cpp:1631
const std::shared_ptr< optimizer::Solver > & getSolver()
Get the Solver that is being used by this IK module.
Definition InverseKinematics.cpp:1504
const std::shared_ptr< optimizer::Function > & getNullSpaceObjective()
Get the null space objective for this IK module.
Definition InverseKinematics.cpp:1410
void resetNodeConnection()
Reset the signal connection for this IK module's Node.
Definition InverseKinematics.cpp:1806
math::Jacobian mJacobian
Jacobian cache for the IK module.
Definition InverseKinematics.hpp:450
static InverseKinematicsPtr create(JacobianNode *_node)
Create an InverseKinematics module for a specified node.
Definition InverseKinematics.cpp:43
void useWholeBody()
Use all relevant joints on the Skeleton to solve the IK.
Definition InverseKinematics.cpp:1338
void resetProblem(bool _clearSeeds=false)
Reset the Problem that is being maintained by this IK module.
Definition InverseKinematics.cpp:1478
void setPositions(const Eigen::VectorXd &_q)
Set the current joint positions of the Skeleton.
Definition InverseKinematics.cpp:1616
const std::vector< std::size_t > & getDofs() const
Get the indices of the DOFs that this IK module will use when solving.
Definition InverseKinematics.cpp:1370
void useChain()
When solving the IK for this module's Node, use the longest available dynamics::Chain that goes from ...
Definition InverseKinematics.cpp:1324
void setSolver(const std::shared_ptr< optimizer::Solver > &_newSolver)
Set the Solver that should be used by this IK module, and set it up with the Problem that is configur...
Definition InverseKinematics.cpp:1493
void initialize()
Gets called during construction.
Definition InverseKinematics.cpp:1760
bool mHasOffset
True if the offset is non-zero.
Definition InverseKinematics.hpp:441
IKErrorMethod & setErrorMethod(Args &&... args)
Set the ErrorMethod for this IK module.
Definition InverseKinematics.hpp:45
sub_ptr< JacobianNode > mNode
JacobianNode that this IK module is associated with.
Definition InverseKinematics.hpp:447
const std::shared_ptr< optimizer::Function > & getObjective()
Get the objective function for this IK module.
Definition InverseKinematics.cpp:1389
InverseKinematics(const InverseKinematics &)=delete
Copying is not allowed.
void resetTargetConnection()
Reset the signal connection for this IK module's target.
Definition InverseKinematics.cpp:1796
JacobianNode * getAffiliation()
This is the same as getNode().
Definition InverseKinematics.cpp:1578
const Eigen::Vector3d & getOffset() const
Get the offset from the origin of the body frame that will be used when performing inverse kinematics...
Definition InverseKinematics.cpp:1528
IKGradientMethod & setGradientMethod(Args &&... args)
Set the GradientMethod for this IK module.
Definition InverseKinematics.hpp:55
JacobianNode * getNode()
Get the JacobianNode that this IK module operates on.
Definition InverseKinematics.cpp:1566
virtual ~InverseKinematics()
Virtual destructor.
Definition InverseKinematics.cpp:50
bool hasOffset() const
This returns false if the offset for the inverse kinematics is a zero vector.
Definition InverseKinematics.cpp:1534
Analytical * getAnalytical()
Get the Analytical IK method for this module, if one is available.
Definition InverseKinematics.cpp:1454
bool mActive
True if this IK module should be active in its IK hierarcy.
Definition InverseKinematics.hpp:400
void setTarget(std::shared_ptr< SimpleFrame > _newTarget)
Set the target for this IK module.
Definition InverseKinematics.cpp:1540
std::vector< int > mDofMap
Map for the DOFs that are to be used by this IK module.
Definition InverseKinematics.hpp:410
common::Connection mTargetConnection
Connection to the target update.
Definition InverseKinematics.hpp:394
void setNullSpaceObjective(const std::shared_ptr< optimizer::Function > &_nsObjective)
Set an objective function that should be minimized within the null space of the inverse kinematics co...
Definition InverseKinematics.cpp:1402
std::vector< std::size_t > mDofs
A list of the DegreeOfFreedom Skeleton indices that will be used by this IK module.
Definition InverseKinematics.hpp:407
std::shared_ptr< optimizer::Function > mNullSpaceObjective
Null space objective for the IK module.
Definition InverseKinematics.hpp:416
std::size_t mHierarchyLevel
Hierarchy level for this IK module.
Definition InverseKinematics.hpp:403
std::shared_ptr< optimizer::Function > mObjective
Objective for the IK module.
Definition InverseKinematics.hpp:413
bool isActive() const
Returns true if this IK module is allowed to be active in a HierarchicalIK.
Definition InverseKinematics.cpp:1306
common::Connection mNodeConnection
Connection to the node update.
Definition InverseKinematics.hpp:397
bool hasNullSpaceObjective() const
Returns false if the null space objective does nothing.
Definition InverseKinematics.cpp:1423
void setDofs(const std::vector< DegreeOfFreedomT * > &_dofs)
Explicitly set which degrees of freedom should be used to solve the IK for this module.
Definition InverseKinematics.hpp:70
Eigen::Vector3d mOffset
The offset that this IK module should use when computing IK.
Definition InverseKinematics.hpp:438
void setOffset(const Eigen::Vector3d &_offset=Eigen::Vector3d::Zero())
Inverse kinematics can be performed on any point within the body frame.
Definition InverseKinematics.cpp:1516
const std::shared_ptr< optimizer::Problem > & getProblem()
Get the Problem that is being maintained by this IK module.
Definition InverseKinematics.cpp:1466
Analytical * mAnalytical
If mGradientMethod is an Analytical extension, then this will have the same value is mGradientMethod.
Definition InverseKinematics.hpp:429
Eigen::VectorXd getPositions() const
Get the current joint positions of the Skeleton.
Definition InverseKinematics.cpp:1610
std::shared_ptr< optimizer::Solver > mSolver
The solver that this IK module will use for iterative methods.
Definition InverseKinematics.hpp:435
InverseKinematicsPtr clone(JacobianNode *_newNode) const
Clone this IK module, but targeted at a new Node.
Definition InverseKinematics.cpp:137
GradientMethod & getGradientMethod()
Get the GradientMethod for this IK module.
Definition InverseKinematics.cpp:1441
void setInactive()
Equivalent to setActive(false)
Definition InverseKinematics.cpp:1300
std::shared_ptr< optimizer::Problem > mProblem
The Problem that will be maintained by this IK module.
Definition InverseKinematics.hpp:432
const math::Jacobian & computeJacobian() const
Compute the Jacobian for this IK module's node, using the Skeleton's current joint positions and the ...
Definition InverseKinematics.cpp:1590
void setHierarchyLevel(std::size_t _level)
Set the hierarchy level of this module.
Definition InverseKinematics.cpp:1312
ErrorMethod & getErrorMethod()
Get the ErrorMethod for this IK module.
Definition InverseKinematics.cpp:1429
std::unique_ptr< ErrorMethod > mErrorMethod
The method that this IK module will use to compute errors.
Definition InverseKinematics.hpp:419
void setObjective(const std::shared_ptr< optimizer::Function > &_objective)
Set an objective function that should be minimized while satisfying the inverse kinematics constraint...
Definition InverseKinematics.cpp:1382
InverseKinematics & operator=(const InverseKinematics &)=delete
Assignment is not allowed.
std::unique_ptr< GradientMethod > mGradientMethod
The method that this IK module will use to compute gradients.
Definition InverseKinematics.hpp:422
std::size_t getHierarchyLevel() const
Get the hierarchy level of this modle.
Definition InverseKinematics.cpp:1318
std::shared_ptr< SimpleFrame > mTarget
Target that this IK module should use.
Definition InverseKinematics.hpp:444
const std::vector< int > & getDofMap() const
When a Jacobian is computed for a JacobianNode, it will include a column for every DegreeOfFreedom th...
Definition InverseKinematics.cpp:1376
bool solve(bool _applySolution=true)
Solve the IK Problem.
Definition InverseKinematics.cpp:57
The JacobianNode class serves as a common interface for BodyNodes and EndEffectors to both be used as...
Definition JacobianNode.hpp:54
TemplateInverseKinematicsPtr is a templated class that enables users to create a reference-counting I...
Definition InverseKinematicsPtr.hpp:49
Definition Function.hpp:46
Matrix< double, 6, 1 > Vector6d
Definition MathTypes.hpp:49
Vector6d compose(const Eigen::Vector3d &_angular, const Eigen::Vector3d &_linear)
Definition MathTypes.hpp:52
const double DefaultIKGradientComponentClamp
Definition InverseKinematics.hpp:56
const double DefaultIKTolerance
Definition InverseKinematics.hpp:54
const double DefaultIKAngularWeight
Definition InverseKinematics.hpp:59
InverseKinematics IK
Definition InverseKinematics.hpp:453
const double DefaultIKLinearWeight
Definition InverseKinematics.hpp:60
const double DefaultIKDLSCoefficient
Definition InverseKinematics.hpp:58
const double DefaultIKGradientComponentWeight
Definition InverseKinematics.hpp:57
const double DefaultIKErrorClamp
Definition InverseKinematics.hpp:55
Eigen::Matrix< double, 6, Eigen::Dynamic > Jacobian
Definition MathTypes.hpp:108
std::shared_ptr< Function > FunctionPtr
Definition Function.hpp:84
Definition BulletCollisionDetector.cpp:63
Definition InverseKinematics.hpp:1050
Definition InverseKinematics.hpp:1006
int mValidity
Bitmap for whether this configuration is valid.
Definition InverseKinematics.hpp:1016
Eigen::VectorXd mConfig
Configuration computed by the Analytical solver.
Definition InverseKinematics.hpp:1012
Definition InverseKinematics.hpp:1026
QualityComparison mQualityComparator
Function for comparing the qualities of solutions.
Definition InverseKinematics.hpp:1034
void resetQualityComparisonFunction()
Reset the quality comparison function to its default behavior.
Definition InverseKinematics.cpp:897
ExtraDofUtilization mExtraDofUtilization
Flag for how to use the extra DOFs in the IK module.
Definition InverseKinematics.hpp:1028
double mExtraErrorLengthClamp
How much to clamp the extra error that gets applied to DOFs.
Definition InverseKinematics.hpp:1031
The Properties struct contains settings that are commonly used by methods that compute error for inve...
Definition InverseKinematics.hpp:486
Eigen::Vector6d mErrorWeights
These weights will be applied to the error vector component-wise.
Definition InverseKinematics.hpp:512
std::pair< Eigen::Vector6d, Eigen::Vector6d > mBounds
Bounds that define the acceptable range of the Node's transform relative to its target frame.
Definition InverseKinematics.hpp:500
double mErrorLengthClamp
The error vector will be clamped to this length with each iteration.
Definition InverseKinematics.hpp:505
Definition InverseKinematics.hpp:736
double mComponentWiseClamp
The component-wise clamp for this GradientMethod.
Definition InverseKinematics.hpp:738
Eigen::VectorXd mComponentWeights
The weights for this GradientMethod.
Definition InverseKinematics.hpp:741
Definition InverseKinematics.hpp:883
Definition InverseKinematics.hpp:874
double mDamping
Damping coefficient.
Definition InverseKinematics.hpp:876
Definition InverseKinematics.hpp:684
Definition InverseKinematics.hpp:669
bool mComputeErrorFromCenter
Setting this to true (which is default) will tell it to compute the error based on the center of the ...
Definition InverseKinematics.hpp:677