Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add more description on InverseKinematics::solve() #624

Merged
merged 2 commits into from
Apr 16, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions dart/dynamics/HierarchicalIK.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include "dart/dynamics/BodyNode.h"
#include "dart/dynamics/EndEffector.h"
#include "dart/dynamics/Skeleton.h"
#include "dart/optimizer/GradientDescentSolver.h"

namespace dart {
namespace dynamics {
Expand Down
1 change: 1 addition & 0 deletions dart/dynamics/InverseKinematics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include "dart/dynamics/BodyNode.h"
#include "dart/dynamics/DegreeOfFreedom.h"
#include "dart/dynamics/SimpleFrame.h"
#include "dart/optimizer/GradientDescentSolver.h"

namespace dart {
namespace dynamics {
Expand Down
51 changes: 45 additions & 6 deletions dart/dynamics/InverseKinematics.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@
#include "dart/common/Subject.h"
#include "dart/math/Geometry.h"
#include "dart/optimizer/Solver.h"
#include "dart/optimizer/GradientDescentSolver.h"
#include "dart/optimizer/Problem.h"
#include "dart/optimizer/Function.h"
#include "dart/dynamics/SmartPointer.h"
Expand All @@ -67,7 +66,9 @@ const double DefaultIKLinearWeight = 1.0;
/// 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.
/// 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
Expand All @@ -91,10 +92,48 @@ class InverseKinematics : public common::Subject
/// Virtual destructor
virtual ~InverseKinematics();

/// Solve the IK Problem. 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.
/// 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:
///
/// \code
/// 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
/// \endcode
///
/// 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(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.
bool solve(bool _applySolution = true);

/// Same as solve(bool), but the positions vector will be filled with the
Expand Down