internal::kinematics::InverseKinematicsNLP class

Implementation of the inverse kinematics with IPOPT.

Implements the following optimization problem

\begin{align} \min_{x} & \sum_i || {}^w H_{f_i} ( {}^w H_{f_i}^d)^{-1} ||^2 + w_q || q_j - q_j^d ||^2 \\ \text{s.t.} & {}^w H_{f_i} = {}^w H_{f_i}^d \\ & q_{min} \leq q \leq q_{max} \end{align}

where

\begin{align} & q = \{ {}^w H_{base}, q_j\} \in SE(3) \times \mathbb{R}^n \\ & {}^w H_{f_i} \in SE(3) \end{align}

A target (entirely or partially, with partial meaning the two components composing a tranform, i.e. position and orientation) can be enforced by either considering it as a constraint or as a cost

Constructors, destructors, conversion operators

InverseKinematicsNLP(InverseKinematicsData& data)
~InverseKinematicsNLP() virtual

Public functions

void initializeInternalData()
Initialize buffers given the specified problem size.
auto get_nlp_info(Ipopt::Index& n, Ipopt::Index& m, Ipopt::Index& nnz_jac_g, Ipopt::Index& nnz_h_lag, IndexStyleEnum& index_style) -> bool virtual
auto get_bounds_info(Ipopt::Index n, Ipopt::Number* x_l, Ipopt::Number* x_u, Ipopt::Index m, Ipopt::Number* g_l, Ipopt::Number* g_u) -> bool virtual
auto get_starting_point(Ipopt::Index n, bool init_x, Ipopt::Number* x, bool init_z, Ipopt::Number* z_L, Ipopt::Number* z_U, Ipopt::Index m, bool init_lambda, Ipopt::Number* lambda) -> bool virtual
auto eval_f(Ipopt::Index n, const Ipopt::Number* x, bool new_x, Ipopt::Number& obj_value) -> bool virtual
auto eval_grad_f(Ipopt::Index n, const Ipopt::Number* x, bool new_x, Ipopt::Number* grad_f) -> bool virtual
auto eval_g(Ipopt::Index n, const Ipopt::Number* x, bool new_x, Ipopt::Index m, Ipopt::Number* g) -> bool virtual
auto eval_jac_g(Ipopt::Index n, const Ipopt::Number* x, bool new_x, Ipopt::Index m, Ipopt::Index nele_jac, Ipopt::Index* iRow, Ipopt::Index* jCol, Ipopt::Number* values) -> bool virtual
auto eval_h(Ipopt::Index n, const Ipopt::Number* x, bool new_x, Ipopt::Number obj_factor, Ipopt::Index m, const Ipopt::Number* lambda, bool new_lambda, Ipopt::Index nele_hess, Ipopt::Index* iRow, Ipopt::Index* jCol, Ipopt::Number* values) -> bool virtual
void finalize_solution(Ipopt::SolverReturn status, Ipopt::Index n, const Ipopt::Number* x, const Ipopt::Number* z_L, const Ipopt::Number* z_U, Ipopt::Index m, const Ipopt::Number* g, const Ipopt::Number* lambda, Ipopt::Number obj_value, const Ipopt::IpoptData* ip_data, Ipopt::IpoptCalculatedQuantities* ip_cq) virtual
auto get_number_of_nonlinear_variables() -> Ipopt::Index virtual
auto get_list_of_nonlinear_variables(Ipopt::Index num_nonlin_vars, Ipopt::Index* pos_nonlin_vars) -> bool virtual
auto intermediate_callback(Ipopt::AlgorithmMode mode, Ipopt::Index iter, Ipopt::Number obj_value, Ipopt::Number inf_pr, Ipopt::Number inf_du, Ipopt::Number mu, Ipopt::Number d_norm, Ipopt::Number regularization_size, Ipopt::Number alpha_du, Ipopt::Number alpha_pr, Ipopt::Index ls_trials, const Ipopt::IpoptData* ip_data, Ipopt::IpoptCalculatedQuantities* ip_cq) -> bool virtual
void testDerivatives(const iDynTree::VectorDynSize& derivativePoint, int frameIndex, double epsilon, double tolerance, int parametrization)

Function documentation

internal::kinematics::InverseKinematicsNLP::InverseKinematicsNLP(InverseKinematicsData& data)

Parameters
data reference to the InverseKinematicsData object

Constructor