Go to the documentation of this file.
30 #ifndef EXOTICA_IK_SOLVER_IK_SOLVER_H_
31 #define EXOTICA_IK_SOLVER_IK_SOLVER_H_
36 #include <exotica_ik_solver/ik_solver_initializer.h>
47 void Solve(Eigen::MatrixXd& solution)
override;
101 if (i % 10 == 0 || i == 0)
103 std::cout <<
"iter \t cost \t stop \t grad \t reg \t step\n";
106 std::cout << std::setw(4) << i <<
" ";
107 std::cout << std::scientific << std::setprecision(5) <<
error_ <<
" ";
110 std::cout << std::fixed << std::setprecision(4) <<
steplength_ <<
'\n';
117 #endif // EXOTICA_IK_SOLVER_IK_SOLVER_H_
double regmin_
Minimum regularization (will not decrease lower)
Eigen::MatrixXd J_pseudo_inverse_
Jacobian pseudo-inverse, used during optimisation.
double th_stop_
Gradient convergence threshold.
Eigen::VectorXd yd_
Task space difference/error, used during optimisation.
void SpecifyProblem(PlanningProblemPtr pointer) override
void ScaleToStepSize(Eigen::VectorXdRef xd)
To scale to maximum step size.
Eigen::MatrixXd J_tmp_
Temporary variable for inverse computation.
double step_
Size of step: Sum of squared norm of qd_.
double error_
Error, used during optimisation.
Eigen::MatrixXd cost_jacobian_
Jacobian, used during optimisation.
Eigen::VectorXd alpha_space_
Steplengths for backtracking line-search.
double lambda_
Damping factor.
double th_stepinc_
Step-length threshold used to increase regularization.
Eigen::VectorXd q_
Joint configuration vector, used during optimisation.
Eigen::Ref< Eigen::VectorXd > VectorXdRef
std::shared_ptr< exotica::UnconstrainedEndPoseProblem > UnconstrainedEndPoseProblemPtr
double error_prev_
Error at previous iteration, used during optimisation.
void PrintDebug(const int i)
Eigen::VectorXd qd_
Change in joint configuration, used during optimisation.
void Solve(Eigen::MatrixXd &solution) override
UnconstrainedEndPoseProblemPtr prob_
double steplength_
Accepted steplength.
std::shared_ptr< PlanningProblem > PlanningProblemPtr
void DecreaseRegularization()
double regmax_
Maximum regularization (to exit by divergence)
double stop_
Stop criterion: Norm of cost Jacobian.
double th_stepdec_
Step-length threshold used to decrease regularization.
Eigen::MatrixXd W_inv_
Joint-space weighting (inverse)
Weighted and Regularized Pseudo-Inverse Inverse Kinematics Solver The solver solves a weighted and re...
Eigen::LLT< Eigen::MatrixXd > J_decomposition_
Cholesky decomposition for the weighted pseudo-inverse.
void IncreaseRegularization()
double regfactor_
Factor by which the regularization gets increased/decreased.