Go to the documentation of this file.
38 if (pointer->type() !=
"exotica::UnconstrainedEndPoseProblem")
40 ThrowNamed(
"This IKSolver can't solve problem of type '" << pointer->type() <<
"'!");
43 prob_ = std::static_pointer_cast<UnconstrainedEndPoseProblem>(pointer);
68 yd_.resize(
prob_->cost.length_jacobian);
86 WARNING(
"Nominal state regularization is no longer supported - please use a JointPose task-map.");
110 bool decomposition_ok =
false;
111 while (!decomposition_ok)
121 WARNING(
"Divergence in Cholesky decomposition :-(");
130 decomposition_ok =
true;
151 prob_->Update(q_tmp);
210 switch (
prob_->termination_criterion)
233 solution.resize(1,
prob_->N);
234 solution.row(0) =
q_.transpose();
240 const double max_vel = xd.cwiseAbs().maxCoeff();
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.
#define REGISTER_MOTIONSOLVER_TYPE(TYPE, DERIV)
#define HIGHLIGHT_NAMED(name, x)
double th_stepinc_
Step-length threshold used to increase regularization.
Eigen::VectorXd q_
Joint configuration vector, used during optimisation.
Eigen::Ref< Eigen::VectorXd > VectorXdRef
int GetNumberOfMaxIterations()
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)
#define WARNING_NAMED(name, x)
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...
virtual void SpecifyProblem(PlanningProblemPtr pointer)
Eigen::LLT< Eigen::MatrixXd > J_decomposition_
Cholesky decomposition for the weighted pseudo-inverse.
void IncreaseRegularization()
double GetDuration() const