DART  6.6.2
dart::dynamics::InverseKinematics Class Reference

The InverseKinematics class provides a convenient way of setting up an IK optimization problem. More...

#include <InverseKinematics.hpp>

Inheritance diagram for dart::dynamics::InverseKinematics:
dart::common::Subject

Classes

class  Analytical
 Analytical is a base class that should be inherited by methods that are made to solve the IK analytically instead of iteratively. More...
 
class  Constraint
 The InverseKinematics::Constraint Function is simply meant to be used to merge the ErrorMethod and GradientMethod that are being held by an InverseKinematics module. More...
 
class  ErrorMethod
 ErrorMethod is a base class for different ways of computing the error of an InverseKinematics module. More...
 
class  Function
 This class should be inherited by optimizer::Function classes that have a dependency on the InverseKinematics module that they belong to. More...
 
class  GradientMethod
 GradientMethod is a base class for different ways of computing the gradient of an InverseKinematics module. More...
 
class  JacobianDLS
 JacobianDLS refers to the Damped Least Squares Jacobian Pseudoinverse (specifically, Moore-Penrose Pseudoinverse). More...
 
class  JacobianTranspose
 JacobianTranspose will simply apply the transpose of the Jacobian to the error vector in order to compute the gradient. More...
 
class  Objective
 The InverseKinematics::Objective Function is simply used to merge the objective and null space objective functions that are being held by an InverseKinematics module. More...
 
class  TaskSpaceRegion
 The TaskSpaceRegion is a nicely generalized method for computing the error of an IK Problem. More...
 

Public Member Functions

 InverseKinematics (const InverseKinematics &)=delete
 Copying is not allowed. More...
 
InverseKinematicsoperator= (const InverseKinematics &)=delete
 Assignment is not allowed. More...
 
virtual ~InverseKinematics ()
 Virtual destructor. More...
 
bool solve (bool _applySolution=true)
 Solve the IK Problem. More...
 
bool solve (Eigen::VectorXd &positions, bool _applySolution=true)
 Same as solve(bool), but the positions vector will be filled with the solved positions. More...
 
InverseKinematicsPtr clone (JacobianNode *_newNode) const
 Clone this IK module, but targeted at a new Node. More...
 
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 list. More...
 
void setInactive ()
 Equivalent to setActive(false) More...
 
bool isActive () const
 Returns true if this IK module is allowed to be active in a HierarchicalIK. More...
 
void setHierarchyLevel (std::size_t _level)
 Set the hierarchy level of this module. More...
 
std::size_t getHierarchyLevel () const
 Get the hierarchy level of this modle. More...
 
void useChain ()
 When solving the IK for this module's Node, use the longest available dynamics::Chain that goes from this module's Node towards the root of the Skeleton. More...
 
void useWholeBody ()
 Use all relevant joints on the Skeleton to solve the IK. More...
 
template<class DegreeOfFreedomT >
void setDofs (const std::vector< DegreeOfFreedomT * > &_dofs)
 Explicitly set which degrees of freedom should be used to solve the IK for this module. More...
 
void setDofs (const std::vector< std::size_t > &_dofs)
 Explicitly set which degrees of freedom should be used to solve the IK for this module. More...
 
const std::vector< std::size_t > & getDofs () const
 Get the indices of the DOFs that this IK module will use when solving. More...
 
const std::vector< int > & getDofMap () const
 When a Jacobian is computed for a JacobianNode, it will include a column for every DegreeOfFreedom that the node depends on. More...
 
void setObjective (const std::shared_ptr< optimizer::Function > &_objective)
 Set an objective function that should be minimized while satisfying the inverse kinematics constraint. More...
 
const std::shared_ptr< optimizer::Function > & getObjective ()
 Get the objective function for this IK module. More...
 
std::shared_ptr< const optimizer::FunctiongetObjective () const
 Get the objective function for this IK module. More...
 
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 constraint. More...
 
const std::shared_ptr< optimizer::Function > & getNullSpaceObjective ()
 Get the null space objective for this IK module. More...
 
std::shared_ptr< const optimizer::FunctiongetNullSpaceObjective () const
 Get the null space objective for this IK module. More...
 
bool hasNullSpaceObjective () const
 Returns false if the null space objective does nothing. More...
 
template<class IKErrorMethod , typename... Args>
IKErrorMethod & setErrorMethod (Args &&... args)
 Set the ErrorMethod for this IK module. More...
 
ErrorMethodgetErrorMethod ()
 Get the ErrorMethod for this IK module. More...
 
const ErrorMethodgetErrorMethod () const
 Get the ErrorMethod for this IK module. More...
 
template<class IKGradientMethod , typename... Args>
IKGradientMethod & setGradientMethod (Args &&... args)
 Set the GradientMethod for this IK module. More...
 
GradientMethodgetGradientMethod ()
 Get the GradientMethod for this IK module. More...
 
const GradientMethodgetGradientMethod () const
 Get the GradientMethod for this IK module. More...
 
AnalyticalgetAnalytical ()
 Get the Analytical IK method for this module, if one is available. More...
 
const AnalyticalgetAnalytical () const
 Get the Analytical IK method for this module, if one is available. More...
 
const std::shared_ptr< optimizer::Problem > & getProblem ()
 Get the Problem that is being maintained by this IK module. More...
 
std::shared_ptr< const optimizer::ProblemgetProblem () const
 Get the Problem that is being maintained by this IK module. More...
 
void resetProblem (bool _clearSeeds=false)
 Reset the Problem that is being maintained by this IK module. More...
 
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 configured by this IK module. More...
 
const std::shared_ptr< optimizer::Solver > & getSolver ()
 Get the Solver that is being used by this IK module. More...
 
std::shared_ptr< const optimizer::SolvergetSolver () const
 Get the Solver that is being used by this IK module. More...
 
void setOffset (const Eigen::Vector3d &_offset=Eigen::Vector3d::Zero())
 Inverse kinematics can be performed on any point within the body frame. More...
 
const Eigen::Vector3d & getOffset () const
 Get the offset from the origin of the body frame that will be used when performing inverse kinematics. More...
 
bool hasOffset () const
 This returns false if the offset for the inverse kinematics is a zero vector. More...
 
void setTarget (std::shared_ptr< SimpleFrame > _newTarget)
 Set the target for this IK module. More...
 
std::shared_ptr< SimpleFramegetTarget ()
 Get the target that is being used by this IK module. More...
 
std::shared_ptr< const SimpleFramegetTarget () const
 Get the target that is being used by this IK module. More...
 
JacobianNodegetNode ()
 Get the JacobianNode that this IK module operates on. More...
 
const JacobianNodegetNode () const
 Get the JacobianNode that this IK module operates on. More...
 
JacobianNodegetAffiliation ()
 This is the same as getNode(). More...
 
const JacobianNodegetAffiliation () const
 This is the same as getNode(). More...
 
const math::JacobiancomputeJacobian () const
 Compute the Jacobian for this IK module's node, using the Skeleton's current joint positions and the DOFs that have been assigned to the module. More...
 
Eigen::VectorXd getPositions () const
 Get the current joint positions of the Skeleton. More...
 
void setPositions (const Eigen::VectorXd &_q)
 Set the current joint positions of the Skeleton. More...
 
void clearCaches ()
 Clear the caches of this IK module. More...
 

Static Public Member Functions

static InverseKinematicsPtr create (JacobianNode *_node)
 Create an InverseKinematics module for a specified node. More...
 

Protected Member Functions

 InverseKinematics (JacobianNode *_node)
 Constructor that accepts a JacobianNode. More...
 
void initialize ()
 Gets called during construction. More...
 
void resetTargetConnection ()
 Reset the signal connection for this IK module's target. More...
 
void resetNodeConnection ()
 Reset the signal connection for this IK module's Node. More...
 
void sendDestructionNotification () const
 Send a destruction notification to all Observers. More...
 
void addObserver (Observer *_observer) const
 Add an Observer to the list of Observers. More...
 
void removeObserver (Observer *_observer) const
 Remove an Observer from the list of Observers. More...
 

Protected Attributes

common::Connection mTargetConnection
 Connection to the target update. More...
 
common::Connection mNodeConnection
 Connection to the node update. More...
 
bool mActive
 True if this IK module should be active in its IK hierarcy. More...
 
std::size_t mHierarchyLevel
 Hierarchy level for this IK module. More...
 
std::vector< std::size_t > mDofs
 A list of the DegreeOfFreedom Skeleton indices that will be used by this IK module. More...
 
std::vector< int > mDofMap
 Map for the DOFs that are to be used by this IK module. More...
 
std::shared_ptr< optimizer::FunctionmObjective
 Objective for the IK module. More...
 
std::shared_ptr< optimizer::FunctionmNullSpaceObjective
 Null space objective for the IK module. More...
 
std::unique_ptr< ErrorMethodmErrorMethod
 The method that this IK module will use to compute errors. More...
 
std::unique_ptr< GradientMethodmGradientMethod
 The method that this IK module will use to compute gradients. More...
 
AnalyticalmAnalytical
 If mGradientMethod is an Analytical extension, then this will have the same value is mGradientMethod. More...
 
std::shared_ptr< optimizer::ProblemmProblem
 The Problem that will be maintained by this IK module. More...
 
std::shared_ptr< optimizer::SolvermSolver
 The solver that this IK module will use for iterative methods. More...
 
Eigen::Vector3d mOffset
 The offset that this IK module should use when computing IK. More...
 
bool mHasOffset
 True if the offset is non-zero. More...
 
std::shared_ptr< SimpleFramemTarget
 Target that this IK module should use. More...
 
sub_ptr< JacobianNodemNode
 JacobianNode that this IK module is associated with. More...
 
math::Jacobian mJacobian
 Jacobian cache for the IK module. More...
 
std::set< Observer * > mObservers
 List of current Observers. More...
 

Friends

class Objective
 
class Constraint
 

Detailed Description

The InverseKinematics class provides a convenient way of setting up an IK optimization problem.

It generates constraint functions based on the specified InverseKinematics::ErrorMethod and InverseKinematics::GradientMethod. The optimization problem is then solved by any classes derived from optimizer::Solver class. The default solver is optimizer::GradientDescentSolver.

It also provides a convenient way of specifying a configuration space objective and a null space objective. It is also possible to fully customize the optimizer::Problem that the module creates, and the IK module can be safely cloned over to another JacobianNode, as long as every optimizer::Function that depends on the JacobianNode inherits the InverseKinematics::Function class and correctly overloads the clone function

Constructor & Destructor Documentation

◆ InverseKinematics() [1/2]

dart::dynamics::InverseKinematics::InverseKinematics ( const InverseKinematics )
delete

Copying is not allowed.

◆ ~InverseKinematics()

dart::dynamics::InverseKinematics::~InverseKinematics ( )
virtual

Virtual destructor.

◆ InverseKinematics() [2/2]

dart::dynamics::InverseKinematics::InverseKinematics ( JacobianNode _node)
protected

Constructor that accepts a JacobianNode.

Member Function Documentation

◆ addObserver()

void dart::common::Subject::addObserver ( Observer _observer) const
protectedinherited

Add an Observer to the list of Observers.

◆ clearCaches()

void dart::dynamics::InverseKinematics::clearCaches ( )

Clear the caches of this IK module.

It should generally not be necessary to call this function. However, if you have some non-standard external dependency for your error and/or gradient method computations, then you will need to tie this function to something that tracks changes in that dependency.

◆ clone()

InverseKinematicsPtr dart::dynamics::InverseKinematics::clone ( JacobianNode _newNode) const

Clone this IK module, but targeted at a new Node.

Any Functions in the Problem that inherit InverseKinematics::Function will be adapted to the new IK module. Any generic optimizer::Function will just be copied over by pointer instead of being cloned.

◆ computeJacobian()

const math::Jacobian & dart::dynamics::InverseKinematics::computeJacobian ( ) const

Compute the Jacobian for this IK module's node, using the Skeleton's current joint positions and the DOFs that have been assigned to the module.

◆ create()

InverseKinematicsPtr dart::dynamics::InverseKinematics::create ( JacobianNode _node)
static

Create an InverseKinematics module for a specified node.

◆ getAffiliation() [1/2]

JacobianNode * dart::dynamics::InverseKinematics::getAffiliation ( )

This is the same as getNode().

It is used by the InverseKinematicsPtr to provide a common interface for the various IK smart pointer types.

◆ getAffiliation() [2/2]

const JacobianNode * dart::dynamics::InverseKinematics::getAffiliation ( ) const

This is the same as getNode().

It is used by the InverseKinematicsPtr to provide a common interface for the various IK smart pointer types.

◆ getAnalytical() [1/2]

InverseKinematics::Analytical * dart::dynamics::InverseKinematics::getAnalytical ( )

Get the Analytical IK method for this module, if one is available.

Analytical methods are not provided by default. If this IK module does not have an analytical method, then this will return a nullptr.

◆ getAnalytical() [2/2]

const InverseKinematics::Analytical * dart::dynamics::InverseKinematics::getAnalytical ( ) const

Get the Analytical IK method for this module, if one is available.

Analytical methods are not provided by default. If this IK module does not have an analytical method, then this will return a nullptr.

◆ getDofMap()

const std::vector< int > & dart::dynamics::InverseKinematics::getDofMap ( ) const

When a Jacobian is computed for a JacobianNode, it will include a column for every DegreeOfFreedom that the node depends on.

Given the column index of one of those dependent coordinates, this map will return its location in the mDofs vector. A value of -1 means that it is not present in the mDofs vector and therefore should not be used when performing inverse kinematics.

◆ getDofs()

const std::vector< std::size_t > & dart::dynamics::InverseKinematics::getDofs ( ) const

Get the indices of the DOFs that this IK module will use when solving.

◆ getErrorMethod() [1/2]

InverseKinematics::ErrorMethod & dart::dynamics::InverseKinematics::getErrorMethod ( )

Get the ErrorMethod for this IK module.

Every IK module always has an ErrorMethod available, so this is passed by reference.

◆ getErrorMethod() [2/2]

const InverseKinematics::ErrorMethod & dart::dynamics::InverseKinematics::getErrorMethod ( ) const

Get the ErrorMethod for this IK module.

Every IK module always has an ErrorMethod available, so this is passed by reference.

◆ getGradientMethod() [1/2]

InverseKinematics::GradientMethod & dart::dynamics::InverseKinematics::getGradientMethod ( )

Get the GradientMethod for this IK module.

Every IK module always has a GradientMethod available, so this is passed by reference.

◆ getGradientMethod() [2/2]

const InverseKinematics::GradientMethod & dart::dynamics::InverseKinematics::getGradientMethod ( ) const

Get the GradientMethod for this IK module.

Every IK module always has a GradientMethod available, so this is passed by reference.

◆ getHierarchyLevel()

std::size_t dart::dynamics::InverseKinematics::getHierarchyLevel ( ) const

Get the hierarchy level of this modle.

◆ getNode() [1/2]

JacobianNode * dart::dynamics::InverseKinematics::getNode ( )

Get the JacobianNode that this IK module operates on.

◆ getNode() [2/2]

const JacobianNode * dart::dynamics::InverseKinematics::getNode ( ) const

Get the JacobianNode that this IK module operates on.

◆ getNullSpaceObjective() [1/2]

const std::shared_ptr< optimizer::Function > & dart::dynamics::InverseKinematics::getNullSpaceObjective ( )

Get the null space objective for this IK module.

◆ getNullSpaceObjective() [2/2]

std::shared_ptr< const optimizer::Function > dart::dynamics::InverseKinematics::getNullSpaceObjective ( ) const

Get the null space objective for this IK module.

◆ getObjective() [1/2]

const std::shared_ptr< optimizer::Function > & dart::dynamics::InverseKinematics::getObjective ( )

Get the objective function for this IK module.

◆ getObjective() [2/2]

std::shared_ptr< const optimizer::Function > dart::dynamics::InverseKinematics::getObjective ( ) const

Get the objective function for this IK module.

◆ getOffset()

const Eigen::Vector3d & dart::dynamics::InverseKinematics::getOffset ( ) const

Get the offset from the origin of the body frame that will be used when performing inverse kinematics.

The offset will be expressed in the coordinates of the body frame.

◆ getPositions()

Eigen::VectorXd dart::dynamics::InverseKinematics::getPositions ( ) const

Get the current joint positions of the Skeleton.

This will only include the DOFs that have been assigned to this IK module, and the components of the vector will correspond to the components of getDofs().

◆ getProblem() [1/2]

const std::shared_ptr< optimizer::Problem > & dart::dynamics::InverseKinematics::getProblem ( )

Get the Problem that is being maintained by this IK module.

◆ getProblem() [2/2]

std::shared_ptr< const optimizer::Problem > dart::dynamics::InverseKinematics::getProblem ( ) const

Get the Problem that is being maintained by this IK module.

◆ getSolver() [1/2]

const std::shared_ptr< optimizer::Solver > & dart::dynamics::InverseKinematics::getSolver ( )

Get the Solver that is being used by this IK module.

◆ getSolver() [2/2]

std::shared_ptr< const optimizer::Solver > dart::dynamics::InverseKinematics::getSolver ( ) const

Get the Solver that is being used by this IK module.

◆ getTarget() [1/2]

std::shared_ptr< SimpleFrame > dart::dynamics::InverseKinematics::getTarget ( )

Get the target that is being used by this IK module.

You never have to check whether this is a nullptr, because it cannot ever be set to nullptr.

◆ getTarget() [2/2]

std::shared_ptr< const SimpleFrame > dart::dynamics::InverseKinematics::getTarget ( ) const

Get the target that is being used by this IK module.

You never have to check whether this is a nullptr, because it cannot ever be set to nullptr.

◆ hasNullSpaceObjective()

bool dart::dynamics::InverseKinematics::hasNullSpaceObjective ( ) const

Returns false if the null space objective does nothing.

◆ hasOffset()

bool dart::dynamics::InverseKinematics::hasOffset ( ) const

This returns false if the offset for the inverse kinematics is a zero vector.

Otherwise, it returns true. Use setOffset() to set the offset and getOffset() to get the offset.

◆ initialize()

void dart::dynamics::InverseKinematics::initialize ( )
protected

Gets called during construction.

◆ isActive()

bool dart::dynamics::InverseKinematics::isActive ( ) const

Returns true if this IK module is allowed to be active in a HierarchicalIK.

◆ operator=()

InverseKinematics& dart::dynamics::InverseKinematics::operator= ( const InverseKinematics )
delete

Assignment is not allowed.

◆ removeObserver()

void dart::common::Subject::removeObserver ( Observer _observer) const
protectedinherited

Remove an Observer from the list of Observers.

◆ resetNodeConnection()

void dart::dynamics::InverseKinematics::resetNodeConnection ( )
protected

Reset the signal connection for this IK module's Node.

◆ resetProblem()

void dart::dynamics::InverseKinematics::resetProblem ( bool  _clearSeeds = false)

Reset the Problem that is being maintained by this IK module.

This will clear out all Functions from the Problem and then configure the Problem to use this IK module's Objective and Constraint functions.

Setting _clearSeeds to true will clear out any seeds that have been loaded into the Problem.

◆ resetTargetConnection()

void dart::dynamics::InverseKinematics::resetTargetConnection ( )
protected

Reset the signal connection for this IK module's target.

◆ sendDestructionNotification()

void dart::common::Subject::sendDestructionNotification ( ) const
protectedinherited

Send a destruction notification to all Observers.

This will cause all Observers to behave as if this Subject has been permanently deleted, so it should only be called when that behavior is desired.

◆ setActive()

void dart::dynamics::InverseKinematics::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 list.

If it is set to inactive, then it will be ignored by any HierarchicalIK holding onto it, but you can still use the solve() function with this.

◆ setDofs() [1/2]

template<class DegreeOfFreedomT >
void dart::dynamics::InverseKinematics::setDofs ( const std::vector< DegreeOfFreedomT * > &  _dofs)

Explicitly set which degrees of freedom should be used to solve the IK for this module.

◆ setDofs() [2/2]

void dart::dynamics::InverseKinematics::setDofs ( const std::vector< std::size_t > &  _dofs)

Explicitly set which degrees of freedom should be used to solve the IK for this module.

The values in the vector should correspond to the Skeleton indices of each DOF.

◆ setErrorMethod()

template<class IKErrorMethod , typename... Args>
IKErrorMethod & dart::dynamics::InverseKinematics::setErrorMethod ( Args &&...  args)

Set the ErrorMethod for this IK module.

You can pass in arguments for the constructor, but you should ignore the constructor's first argument. The first argument of the ErrorMethod's constructor must be a pointer to this IK module, which will be automatically passed by this function.

◆ setGradientMethod()

template<class IKGradientMethod , typename... Args>
IKGradientMethod & dart::dynamics::InverseKinematics::setGradientMethod ( Args &&...  args)

Set the GradientMethod for this IK module.

You can pass in arguments for the constructor, but you should ignore the constructor's first argument. The first argument of the GradientMethod's constructor must be a pointer to this IK module, which will be automatically passed by this function.

◆ setHierarchyLevel()

void dart::dynamics::InverseKinematics::setHierarchyLevel ( std::size_t  _level)

Set the hierarchy level of this module.

Modules with a larger hierarchy value will be projected through the null spaces of all modules with a smaller hierarchy value. In other words, IK modules with a hierarchy level closer to 0 are given higher priority.

◆ setInactive()

void dart::dynamics::InverseKinematics::setInactive ( )

Equivalent to setActive(false)

◆ setNullSpaceObjective()

void dart::dynamics::InverseKinematics::setNullSpaceObjective ( const std::shared_ptr< optimizer::Function > &  _nsObjective)

Set an objective function that should be minimized within the null space of the inverse kinematics constraint.

The gradient of this function will always be projected through the null space of this IK module's Jacobian. Pass in a nullptr to remove the null space objective.

Note: The objectives given to setObjective() and setNullSpaceObjective() will always be superimposed (added together) via the evalObjective() function.

◆ setObjective()

void dart::dynamics::InverseKinematics::setObjective ( const std::shared_ptr< optimizer::Function > &  _objective)

Set an objective function that should be minimized while satisfying the inverse kinematics constraint.

Pass in a nullptr to remove the objective and make it a constant-zero function.

◆ setOffset()

void dart::dynamics::InverseKinematics::setOffset ( const Eigen::Vector3d &  _offset = Eigen::Vector3d::Zero())

Inverse kinematics can be performed on any point within the body frame.

The default point is the origin of the body frame. Use this function to change the point that will be used. _offset must represent the offset of the desired point from the body origin, expressed in coordinates of the body frame.

◆ setPositions()

void dart::dynamics::InverseKinematics::setPositions ( const Eigen::VectorXd &  _q)

Set the current joint positions of the Skeleton.

This must only include the DOFs that have been assigned to this IK module, and the components of the vector must correspond to the components of getDofs().

◆ setSolver()

void dart::dynamics::InverseKinematics::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 configured by this IK module.

◆ setTarget()

void dart::dynamics::InverseKinematics::setTarget ( std::shared_ptr< SimpleFrame _newTarget)

Set the target for this IK module.

Note that a target will automatically be created for the IK module upon instantiation, so you typically do not need to use this function. If you want to attach the target to an arbitrary (non-SimpleFrame) reference frame, you can do getTarget()->setParentFrame(arbitraryFrame)

◆ solve() [1/2]

bool dart::dynamics::InverseKinematics::solve ( bool  _applySolution = true)

Solve the IK Problem.

The initial guess for the IK optimization problem is the current joint positions of the target system. If the iterative solver fails to find a successive solution, it attempts more to solve the problem with other seed configurations or random configurations if enough seed is not provided.

Here is the pseudocode as described above:

attempts <- 0
initial_guess <- current_joint_positions
while attempts <= max_attempts:
result <- solve(initial_guess)
if result = success:
return
else:
attempts <- attempts + 1
if attempts <= num_seed:
initial_guess <- seed[attempts - 1]
else:
initial_guess <- random_configuration // within the bounds
CollisionResult * result
Collision result of DART.
Definition: FCLCollisionDetector.cpp:157
bool solve(bool _applySolution=true)
Solve the IK Problem.
Definition: InverseKinematics.cpp:57

By default, the max_attempts is 1, but this can be changed by calling InverseKinematics::getSolver() and casting the SolverPtr to an optimizer::GradientDescentSolver (unless you have changed the Solver type) and then calling GradientDescentSolver::setMaxAttempts(std::size_t).

By default, the list of seeds is empty, but they can be added by calling InverseKinematics::getProblem() and then using Problem::addSeed(Eigen::VectorXd).

By default, the Skeleton itself will retain the solved joint positions. If you pass in false for _applySolution, then the joint positions will be returned to their original positions after the problem is solved.

Calling this function will automatically call Position::setLowerBounds(~) and Position::setUpperBounds(~) with the lower/upper position bounds of the corresponding Degrees Of Freedom. Problem::setDimension(~) will be taken care of automatically, and Problem::setInitialGuess(~) will be called with the current positions of the Degrees Of Freedom.

◆ solve() [2/2]

bool dart::dynamics::InverseKinematics::solve ( Eigen::VectorXd &  positions,
bool  _applySolution = true 
)

Same as solve(bool), but the positions vector will be filled with the solved positions.

◆ useChain()

void dart::dynamics::InverseKinematics::useChain ( )

When solving the IK for this module's Node, use the longest available dynamics::Chain that goes from this module's Node towards the root of the Skeleton.

Using this will prevent any other branches in the Skeleton from being affected by this IK module.

◆ useWholeBody()

void dart::dynamics::InverseKinematics::useWholeBody ( )

Use all relevant joints on the Skeleton to solve the IK.

Friends And Related Function Documentation

◆ Constraint

friend class Constraint
friend

◆ Objective

friend class Objective
friend

Member Data Documentation

◆ mActive

bool dart::dynamics::InverseKinematics::mActive
protected

True if this IK module should be active in its IK hierarcy.

◆ mAnalytical

Analytical* dart::dynamics::InverseKinematics::mAnalytical
protected

If mGradientMethod is an Analytical extension, then this will have the same value is mGradientMethod.

Otherwise, this will be a nullptr.

Note that this pointer's memory does not need to be managed, because it is always either nullptr or a reference to mGradientMethod.

◆ mDofMap

std::vector<int> dart::dynamics::InverseKinematics::mDofMap
protected

Map for the DOFs that are to be used by this IK module.

◆ mDofs

std::vector<std::size_t> dart::dynamics::InverseKinematics::mDofs
protected

A list of the DegreeOfFreedom Skeleton indices that will be used by this IK module.

◆ mErrorMethod

std::unique_ptr<ErrorMethod> dart::dynamics::InverseKinematics::mErrorMethod
protected

The method that this IK module will use to compute errors.

◆ mGradientMethod

std::unique_ptr<GradientMethod> dart::dynamics::InverseKinematics::mGradientMethod
protected

The method that this IK module will use to compute gradients.

◆ mHasOffset

bool dart::dynamics::InverseKinematics::mHasOffset
protected

True if the offset is non-zero.

◆ mHierarchyLevel

std::size_t dart::dynamics::InverseKinematics::mHierarchyLevel
protected

Hierarchy level for this IK module.

◆ mJacobian

math::Jacobian dart::dynamics::InverseKinematics::mJacobian
mutableprotected

Jacobian cache for the IK module.

◆ mNode

sub_ptr<JacobianNode> dart::dynamics::InverseKinematics::mNode
protected

JacobianNode that this IK module is associated with.

◆ mNodeConnection

common::Connection dart::dynamics::InverseKinematics::mNodeConnection
protected

Connection to the node update.

◆ mNullSpaceObjective

std::shared_ptr<optimizer::Function> dart::dynamics::InverseKinematics::mNullSpaceObjective
protected

Null space objective for the IK module.

◆ mObjective

std::shared_ptr<optimizer::Function> dart::dynamics::InverseKinematics::mObjective
protected

Objective for the IK module.

◆ mObservers

std::set<Observer*> dart::common::Subject::mObservers
mutableprotectedinherited

List of current Observers.

◆ mOffset

Eigen::Vector3d dart::dynamics::InverseKinematics::mOffset
protected

The offset that this IK module should use when computing IK.

◆ mProblem

std::shared_ptr<optimizer::Problem> dart::dynamics::InverseKinematics::mProblem
protected

The Problem that will be maintained by this IK module.

◆ mSolver

std::shared_ptr<optimizer::Solver> dart::dynamics::InverseKinematics::mSolver
protected

The solver that this IK module will use for iterative methods.

◆ mTarget

std::shared_ptr<SimpleFrame> dart::dynamics::InverseKinematics::mTarget
protected

Target that this IK module should use.

◆ mTargetConnection

common::Connection dart::dynamics::InverseKinematics::mTargetConnection
protected

Connection to the target update.