fatrop_runtime.hpp
1 //
2 // MIT No Attribution
3 //
4 // Copyright (C) 2010-2023 Joel Andersson, Joris Gillis, Moritz Diehl, KU Leuven.
5 //
6 // Permission is hereby granted, free of charge, to any person obtaining a copy of this
7 // software and associated documentation files (the "Software"), to deal in the Software
8 // without restriction, including without limitation the rights to use, copy, modify,
9 // merge, publish, distribute, sublicense, and/or sell copies of the Software, and to
10 // permit persons to whom the Software is furnished to do so.
11 //
12 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
13 // INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
14 // PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
15 // HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
16 // OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE
17 // SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
18 //
19 
20 // C-REPLACE "SOLVER_RET_SUCCESS" "0"
21 // C-REPLACE "SOLVER_RET_UNKNOWN" "1"
22 // C-REPLACE "SOLVER_RET_LIMITED" "2"
23 // C-REPLACE "SOLVER_RET_EXCEPTION" "5"
24 
25 // C-REPLACE "casadi_nlpsol_prob<T1>" "struct casadi_nlpsol_prob"
26 // C-REPLACE "casadi_nlpsol_data<T1>" "struct casadi_nlpsol_data"
27 
28 // C-REPLACE "reinterpret_cast<int**>" "(int**) "
29 // C-REPLACE "reinterpret_cast<int*>" "(int*) "
30 // C-REPLACE "const_cast<int*>" "(int*) "
31 
32 // SYMBOL "fatrop_mproject"
33 template<typename T1>
34 void casadi_fatrop_mproject(T1 factor, const T1* x, const casadi_int* sp_x,
35  T1* y, const casadi_int* sp_y, T1* w) {
36  casadi_int ncol_y;
37  const casadi_int* colind_y;
38  ncol_y = sp_y[1];
39  colind_y = sp_y+2;
40  casadi_project(x, sp_x, y, sp_y, w);
41  casadi_scal(colind_y[ncol_y], factor, y);
42 }
43 
44 // SYMBOL "fatrop_dense_transfer"
45 template<typename T1>
46 void casadi_fatrop_dense_transfer(double factor, const T1* x,
47  const casadi_int* sp_x, T1* y,
48  const casadi_int* sp_y, T1* w) {
49  casadi_sparsify(x, w, sp_x, 0);
50  casadi_int nrow_y = sp_y[0];
51  casadi_int ncol_y = sp_y[1];
52  const casadi_int *colind_y = sp_y+2, *row_y = sp_y + 2 + ncol_y+1;
53  /* Loop over columns of y */
54  casadi_int i, el;
55  for (i=0; i<ncol_y; ++i) {
56  for (el=colind_y[i]; el<colind_y[i+1]; ++el) y[nrow_y*i + row_y[el]] += factor*(*w++);
57  }
58 }
59 
60 // SYMBOL "fatrop_read_primal_data"
61 template<typename T1>
62 void casadi_fatrop_read_primal_data(const double* primal_data, T1* x, const struct FatropOcpCDims *s) {
63  int k;
64  for (k=0;k<s->K;++k) {
65  casadi_copy(primal_data+s->ux_offs[k], s->nu[k], x+s->nx[k]+s->ux_offs[k]);
66  casadi_copy(primal_data+s->ux_offs[k]+s->nu[k], s->nx[k], x+s->ux_offs[k]);
67  }
68 }
69 
70 // SYMBOL "fatrop_write_primal_data"
71 template<typename T1>
72 void casadi_fatrop_write_primal_data(const double* x, T1* primal_data, const struct FatropOcpCDims *s) {
73  int k;
74  for (k=0;k<s->K;++k) {
75  casadi_copy(x+s->nx[k]+s->ux_offs[k], s->nu[k], primal_data+s->ux_offs[k]);
76  casadi_copy(x+s->ux_offs[k], s->nx[k], primal_data+s->ux_offs[k]+s->nu[k]);
77  }
78 }
79 
80 // C-REPLACE "casadi_ocp_block" "struct casadi_ocp_block"
81 
82 // C-REPLACE "OracleCallback" "struct casadi_oracle_callback"
83 template<typename T1>
86  const casadi_int *nx, *nu, *ng;
87  casadi_int nx_max, nu_max, nxu_max;
88  // Sparsity patterns
89  const casadi_int *sp_h, *sp_a;
90 
91  casadi_int nnz_h, nnz_a;
92 
93  // Sparsities
94  const casadi_int *ABsp;
95  const casadi_int *AB_offsets;
96  const casadi_int *CDsp;
97  const casadi_int *CD_offsets;
98  const casadi_int *RSQsp;
99  const casadi_int *RSQ_offsets;
100  const casadi_int *Isp;
101  const casadi_int *I_offsets;
102 
103  casadi_int N;
105 
106  OracleCallback nlp_hess_l;
107  OracleCallback nlp_jac_g;
108  OracleCallback nlp_grad_f;
109  OracleCallback nlp_f;
110  OracleCallback nlp_g;
111 
112  FatropOcpCWrite write;
113  FatropOcpCFlush flush;
114 };
115 // C-REPLACE "casadi_fatrop_prob<T1>" "struct casadi_fatrop_prob"
116 
117 
118 // SYMBOL "fatrop_setup"
119 template<typename T1>
120 void casadi_fatrop_setup(casadi_fatrop_prob<T1>* p) {
121  casadi_int k;
122  if (p->sp_h) {
123  p->nnz_h = p->sp_h[2+p->sp_h[1]];
124  } else {
125  p->nnz_h = 0;
126  }
127  p->nnz_a = p->sp_a[2+p->sp_a[1]];
128 
129  p->nx_max = 0;
130  for (k=0;k<p->N+1;++k) {
131  if (p->nx[k]>p->nx_max) p->nx_max = p->nx[k];
132  }
133  p->nu_max = 0;
134  p->nxu_max = 0;
135  for (k=0;k<p->N;++k) {
136  if (p->nu[k]>p->nu_max) p->nu_max = p->nu[k];
137  if (p->nu[k]+p->nx[k]>p->nxu_max) p->nxu_max = p->nu[k]+p->nx[k];
138  }
139 }
140 
141 
142 
143 // SYMBOL "fatrop_data"
144 template<typename T1>
146  // Problem structure
148  // Problem structure
150 
151  T1 *AB, *CD, *RSQ, *I;
152 
153  casadi_int *a_eq, *a_ineq, *a_eq_idx, *a_ineq_idx;
154  casadi_int *x_eq, *x_ineq, *x_eq_idx, *x_ineq_idx;
155 
156  const T1** arg;
157  T1** res;
158  casadi_int* iw;
159  T1* w;
160 
162  int success;
164 
165  T1 *pv, *x, *a, *g, *h, *lam;
166 
167  struct blasfeo_dvec v, r;
168  struct blasfeo_dmat R;
169 
170  struct FatropOcpCInterface ocp_interface;
171 
172  struct FatropOcpCStats stats;
173 
174  struct FatropOcpCSolver *solver;
175 };
176 // C-REPLACE "casadi_fatrop_data<T1>" "struct casadi_fatrop_data"
177 
178 // SYMBOL "fatrop_init_mem"
179 template<typename T1>
180 int fatrop_init_mem(casadi_fatrop_data<T1>* d) {
181  return 0;
182 }
183 
184 // SYMBOL "fatrop_free_mem"
185 template<typename T1>
186 void fatrop_free_mem(casadi_fatrop_data<T1>* d) {
187  //Highs_destroy(d->fatrop);
188 
189 }
190 // C-REPLACE "static_cast< casadi_fatrop_data<T1>* >" "(struct casadi_fatrop_data*)"
191 // C-REPLACE "casadi_oracle_data<T1>" "struct casadi_oracle_data"
192 // C-REPLACE "calc_function" "casadi_oracle_call"
193 // C-REPLACE "casadi_error" "//casadi_error"
194 
195 // SYMBOL "fatrop_full_eval_constr_jac"
196 template<typename T1>
197 fatrop_int casadi_fatrop_full_eval_constr_jac(const double* primal_data, const double* stageparams_p, const double* globalparams_p,
198  struct blasfeo_dmat* BAbt_p, struct blasfeo_dmat* Ggt_p, struct blasfeo_dmat* Ggt_ineq_p, const struct FatropOcpCDims* s, void* user_data) {
199  casadi_int i;
200  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
201  const casadi_fatrop_prob<T1>* p = d->prob;
202  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
203  casadi_oracle_data<T1>* d_oracle = d_nlp->oracle;
204 
205  casadi_fatrop_read_primal_data(primal_data, d->x, s);
206  d_oracle->arg[0] = d->x;
207  d_oracle->arg[1] = d_nlp->p;
208  d_oracle->res[0] = d->g;
209  d_oracle->res[1] = d->a;
210  calc_function(&d->prob->nlp_jac_g, d_oracle);
211 
212  casadi_fatrop_mproject(-1.0, d->a, p->sp_a, d->AB, p->ABsp, d->pv);
213  casadi_project(d->a, p->sp_a, d->CD, p->CDsp, d->pv);
214  casadi_project(d->a, p->sp_a, d->I, p->Isp, d->pv);
215 
216  for (i=0;i<p->Isp[2+p->Isp[1]];++i) {
217  if (d->I[i]!=1.0) {
218  casadi_error("Structure mismatch: gap-closing constraints must be like this: x_{k+1}-F(xk,uk).");
219  }
220  }
221  return 0;
222 }
223 
224 // SYMBOL "fatrop_full_eval_contr_viol"
225 template<typename T1>
226 fatrop_int casadi_fatrop_full_eval_contr_viol(const double* primal_data, const double* stageparams_p, const double* globalparams_p,
227  double* res, const struct FatropOcpCDims* s, void* user_data) {
228  casadi_int i,k,column;
229  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
230  const casadi_fatrop_prob<T1>* p = d->prob;
231  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
232  casadi_oracle_data<T1>* d_oracle = d_nlp->oracle;
233 
234  casadi_fatrop_read_primal_data(primal_data, d->x, s);
235  d_oracle->arg[0] = d->x;
236  d_oracle->arg[1] = d_nlp->p;
237  d_oracle->res[0] = d->g;
238  calc_function(&d->prob->nlp_g, d_oracle);
239 
240  for (k=0;k<s->K;++k) {
241  column = 0;
242  for (i=d->a_ineq_idx[k];i<d->a_ineq_idx[k+1];++i) {
243  res[s->g_ineq_offs[k]+column] = d->g[d->a_ineq[i]];
244  column++;
245  }
246  for (i=d->x_ineq_idx[k];i<d->x_ineq_idx[k+1];++i) {
247  res[s->g_ineq_offs[k]+column] = d->x[d->x_ineq[i]];
248  column++;
249  }
250  column = 0;
251  for (i=d->a_eq_idx[k];i<d->a_eq_idx[k+1];++i) {
252  res[s->g_offs[k]+column] = d->g[d->a_eq[i]]-d->nlp->lbz[p->nlp->nx+d->a_eq[i]];
253  column++;
254  }
255  for (i=d->x_eq_idx[k];i<d->x_eq_idx[k+1];++i) {
256  res[s->g_offs[k]+column] = d->x[d->x_eq[i]]-d->nlp->lbz[d->x_eq[i]];
257  column++;
258  }
259  }
260  for (k=0;k<s->K-1;++k) {
261  casadi_scaled_copy(-1.0, d->g+p->AB[k].offset_r, p->nx[k+1], res+s->dyn_eq_offs[k]);
262  }
263  return 1; //skip
264 }
265 
266 // SYMBOL "fatrop_full_eval_obj_grad"
267 template<typename T1>
268 fatrop_int casadi_fatrop_full_eval_obj_grad(
269  double objective_scale,
270  const double *primal_data,
271  const double *stage_params_k,
272  const double *global_params,
273  double *res, const struct FatropOcpCDims* s, void* user_data) {
274  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
275  const casadi_fatrop_prob<T1>* p = d->prob;
276  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
277  casadi_oracle_data<T1>* d_oracle = d_nlp->oracle;
278 
279  casadi_fatrop_read_primal_data(primal_data, d->x, s);
280  d_oracle->arg[0] = d->x;
281  d_oracle->arg[1] = d_nlp->p;
282  d_oracle->res[0] = d->g;
283  calc_function(&d->prob->nlp_grad_f, d_oracle);
284 
285  casadi_fatrop_write_primal_data(d->g, res, s);
286  casadi_scal(p->nlp->nx, objective_scale, res);
287  return 1; // skip
288 }
289 
290 // SYMBOL "fatrop_full_eval_obj"
291 template<typename T1>
292 fatrop_int casadi_fatrop_full_eval_obj(
293  double objective_scale,
294  const double *primal_data,
295  const double *stage_params_k,
296  const double *global_params,
297  double *res, const struct FatropOcpCDims* s, void* user_data) {
298  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
299  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
300  casadi_oracle_data<T1>* d_oracle = d_nlp->oracle;
301 
302  casadi_fatrop_read_primal_data(primal_data, d->x, s);
303  d_oracle->arg[0] = d->x;
304  d_oracle->arg[1] = d_nlp->p;
305  d_oracle->res[0] = res;
306  calc_function(&d->prob->nlp_f, d_oracle);
307 
308  *res *= objective_scale;
309  return 1; // skip
310 }
311 
312 // SYMBOL "fatrop_full_eval_obj"
313 template<typename T1>
314 fatrop_int casadi_fatrop_full_eval_lag_hess(
315  double objective_scale,
316  const double *primal_data,
317  const double *lam_data,
318  const double *stage_params_k,
319  const double *global_params,
320  struct blasfeo_dmat *res, const struct FatropOcpCDims* s, void* user_data) {
321  casadi_int k, column, i;
322  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
323  const casadi_fatrop_prob<T1>* p = d->prob;
324  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
325  casadi_oracle_data<T1>* d_oracle = d_nlp->oracle;
326 
327  casadi_fatrop_read_primal_data(primal_data, d->x, s);
328  for (k=0;k<s->K;++k) {
329  column = 0;
330  for (i=d->a_ineq_idx[k];i<d->a_ineq_idx[k+1];++i) {
331  d->lam[d->a_ineq[i]] = lam_data[s->g_ineq_offs[k]+column];
332  column++;
333  }
334  column = 0;
335  for (i=d->a_eq_idx[k];i<d->a_eq_idx[k+1];++i) {
336  d->lam[d->a_eq[i]] = lam_data[s->g_offs[k]+column];
337  column++;
338  }
339  }
340  for (k=0;k<s->K-1;++k) {
341  casadi_scaled_copy(-1.0, lam_data+s->dyn_eq_offs[k], p->nx[k+1], d->lam+p->AB[k].offset_r);
342  }
343 
344  d_oracle->arg[0] = d->x;
345  d_oracle->arg[1] = d_nlp->p;
346  d_oracle->arg[2] = &objective_scale;
347  d_oracle->arg[3] = d->lam;
348  d_oracle->res[0] = d->g;
349  d_oracle->res[1] = d->h;
350  calc_function(&d->prob->nlp_hess_l, d_oracle);
351 
352  casadi_project(d->h, p->sp_h, d->RSQ, p->RSQsp, d->pv);
353 
354  // Note: Lagrangian is defined with lambda_dyn*(F(x_k,u_k)) with x_k+1 notably absent
355  for (k=0;k<s->K-1;++k) {
356  casadi_axpy(p->nx[k+1], 1.0, lam_data+s->dyn_eq_offs[k], d->g+p->CD[k+1].offset_c);
357  }
358  // Note: we still need to handle simple bounds
359  for (k=0;k<s->K;++k) {
360  column = d->a_ineq_idx[k+1]-d->a_ineq_idx[k];
361  for (i=d->x_ineq_idx[k];i<d->x_ineq_idx[k+1];++i) {
362  d->g[d->x_ineq[i]] += lam_data[s->g_ineq_offs[k]+column];
363  column++;
364  }
365  column = d->a_eq_idx[k+1]-d->a_eq_idx[k];
366  for (i=d->x_eq_idx[k];i<d->x_eq_idx[k+1];++i) {
367  d->g[d->x_eq[i]] += lam_data[s->g_offs[k]+column];
368  column++;
369  }
370  }
371 
372  return 0;
373 }
374 
375 // C-REPLACE "const_cast<T1*>" "(T1*)"
376 
377 // SYMBOL "fatrop_eval_BAbt"
378 template<typename T1>
379 fatrop_int casadi_fatrop_eval_BAbt(const double *states_kp1, const double *inputs_k,
380  const double *states_k, const double *stage_params_k,
381  const double *global_params, struct blasfeo_dmat *res, const fatrop_int k, void* user_data) {
382  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
383  const casadi_fatrop_prob<T1>* p = d->prob;
384  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
385  blasfeo_pack_tran_dmat(p->nx[k+1], p->nx[k], d->AB+p->AB_offsets[k], p->nx[k+1], res, p->nu[k], 0);
386  blasfeo_pack_tran_dmat(p->nx[k+1], p->nu[k], d->AB+p->AB_offsets[k]+p->nx[k]*p->nx[k+1], p->nx[k+1], res, 0, 0);
387  blasfeo_pack_dmat(1, p->nx[k+1], const_cast<T1*>(d_nlp->lbz+p->nlp->nx+p->AB[k].offset_r), 1, res, p->nx[k]+p->nu[k], 0);
388 
389  casadi_scal(p->nx[k+1], -1.0, d->g+p->AB[k].offset_r);
390 
391  blasfeo_pack_dmat(1, p->nx[k+1], d->g+p->AB[k].offset_r, 1, res, p->nx[k]+p->nu[k], 0);
392 
393  return 0;
394 
395 }
396 
397 // SYMBOL "fatrop_eval_RSQrqt"
398 template<typename T1>
399 fatrop_int casadi_fatrop_eval_RSQrqt(
400  const double *objective_scale,
401  const double *inputs_k,
402  const double *states_k,
403  const double *lam_dyn_k,
404  const double *lam_eq_k,
405  const double *lam_eq_ineq_k,
406  const double *stage_params_k,
407  const double *global_params,
408  struct blasfeo_dmat *res,
409  const fatrop_int k, void* user_data) {
410  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
411  const casadi_fatrop_prob<T1>* p = d->prob;
412 
413  int n = p->nx[k]+p->nu[k];
414  blasfeo_pack_dmat(p->nx[k], p->nx[k],
415  d->RSQ+p->RSQ_offsets[k], n, res, p->nu[k], p->nu[k]);
416  blasfeo_pack_dmat(p->nu[k], p->nu[k],
417  d->RSQ+p->RSQ_offsets[k]+p->nx[k]*n+p->nx[k], n, res, 0, 0);
418  blasfeo_pack_dmat(p->nu[k], p->nx[k],
419  d->RSQ+p->RSQ_offsets[k]+p->nx[k], n, res, 0, p->nu[k]);
420  blasfeo_pack_dmat(p->nx[k], p->nu[k],
421  d->RSQ+p->RSQ_offsets[k]+p->nx[k]*n, n, res, p->nu[k], 0);
422 
423 
424  blasfeo_pack_dmat(1, p->nx[k], d->g+p->CD[k].offset_c, 1, res, p->nx[k]+p->nu[k], p->nu[k]);
425  blasfeo_pack_dmat(1, p->nu[k], d->g+p->CD[k].offset_c+p->nx[k], 1, res, p->nx[k]+p->nu[k], 0);
426 
427  return 0;
428 }
429 
430 
431 // SYMBOL "fatrop_eval_Ggt"
432 template<typename T1>
433 fatrop_int casadi_fatrop_eval_Ggt(
434  const double *inputs_k,
435  const double *states_k,
436  const double *stage_params_k,
437  const double *global_params,
438  struct blasfeo_dmat *res,
439  const fatrop_int k, void* user_data) {
440  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
441  const casadi_fatrop_prob<T1>* p = d->prob;
442  casadi_int i, column;
443 
444  int n_a_eq = d->a_eq_idx[k+1]-d->a_eq_idx[k];
445  int n_x_eq = d->x_eq_idx[k+1]-d->x_eq_idx[k];
446  int ng_eq = n_a_eq+n_x_eq;
447 
448  blasfeo_dgese(p->nx[k]+p->nu[k]+1, ng_eq, 0.0, res, 0, 0);
449 
450  column = 0;
451  for (i=d->a_eq_idx[k];i<d->a_eq_idx[k+1];++i) {
452  blasfeo_pack_tran_dmat(1, p->nx[k],
453  d->CD+p->CD_offsets[k]+(d->a_eq[i]-p->CD[k].offset_r),
454  p->CD[k].rows, res, p->nu[k], column);
455  blasfeo_pack_tran_dmat(1, p->nu[k],
456  d->CD+p->CD_offsets[k]+(d->a_eq[i]-p->CD[k].offset_r)+p->nx[k]*p->CD[k].rows,
457  p->CD[k].rows, res, 0, column);
458  BLASFEO_DMATEL(res, p->nx[k]+p->nu[k], column) = d->g[d->a_eq[i]]-d->nlp->lbz[p->nlp->nx+d->a_eq[i]];
459  column++;
460  }
461  for (i=d->x_eq_idx[k];i<d->x_eq_idx[k+1];++i) {
462  int j = d->x_eq[i]-p->CD[k].offset_c;
463  if (j>=p->nx[k]) {
464  j -= p->nx[k];
465  } else {
466  j += p->nu[k];
467  }
468  BLASFEO_DMATEL(res, j, column) = 1;
469  BLASFEO_DMATEL(res, p->nx[k]+p->nu[k], column) = d->x[d->x_eq[i]]-d->nlp->lbz[d->x_eq[i]];
470  column++;
471  }
472 
473  return 0;
474 }
475 
476 // SYMBOL "fatrop_eval_Ggt_ineq"
477 template<typename T1>
478 fatrop_int casadi_fatrop_eval_Ggt_ineq(
479  const double *inputs_k,
480  const double *states_k,
481  const double *stage_params_k,
482  const double *global_params,
483  struct blasfeo_dmat *res,
484  const fatrop_int k, void* user_data) {
485  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
486  const casadi_fatrop_prob<T1>* p = d->prob;
487  casadi_int i, column;
488 
489  int n_a_ineq = d->a_ineq_idx[k+1]-d->a_ineq_idx[k];
490  int n_x_ineq = d->x_ineq_idx[k+1]-d->x_ineq_idx[k];
491  int ng_ineq = n_a_ineq+n_x_ineq;
492 
493  // Ggt_ineq: [G_ineq;g_ineq]
494  // G_ineq: (nu+nx by ng_ineq)
495  // g_ineq: (nu+nx by 1)
496 
497  // Clear Ggt_ineq
498  blasfeo_dgese(p->nx[k]+p->nu[k]+1, ng_ineq, 0.0, res, 0, 0);
499 
500  column = 0;
501  for (i=d->a_ineq_idx[k];i<d->a_ineq_idx[k+1];++i) {
502  blasfeo_pack_tran_dmat(1, p->nx[k],
503  d->CD+p->CD_offsets[k]+(d->a_ineq[i]-p->CD[k].offset_r),
504  p->CD[k].rows, res, p->nu[k], column);
505  blasfeo_pack_tran_dmat(1, p->nu[k],
506  d->CD+p->CD_offsets[k]+(d->a_ineq[i]-p->CD[k].offset_r)+p->nx[k]*p->CD[k].rows,
507  p->CD[k].rows, res, 0, column);
508  BLASFEO_DMATEL(res, p->nx[k]+p->nu[k], column) = d->g[d->a_ineq[i]];
509  column++;
510  }
511  for (i=d->x_ineq_idx[k];i<d->x_ineq_idx[k+1];++i) {
512  int j = d->x_ineq[i]-p->CD[k].offset_c;
513  if (j>=p->nx[k]) {
514  j -= p->nx[k];
515  } else {
516  j += p->nu[k];
517  }
518  BLASFEO_DMATEL(res, j, column) = 1;
519  BLASFEO_DMATEL(res, p->nx[k]+p->nu[k], column) = d->x[d->x_ineq[i]];
520  column++;
521  }
522 
523  return 0;
524 }
525 
526 // SYMBOL "fatrop_get_nx"
527 template<typename T1>
528 fatrop_int casadi_fatrop_get_nx(const fatrop_int k, void* user_data) {
529  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
530  const casadi_fatrop_prob<T1>* p = d->prob;
531 
532  //printf("nx %lld\n", p->nx[k]);
533 
534  if (k==p->N+1) return p->nx[k-1];
535  return p->nx[k];
536 }
537 
538 // SYMBOL "fatrop_get_nu"
539 template<typename T1>
540 fatrop_int casadi_fatrop_get_nu(const fatrop_int k, void* user_data) {
541  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
542  const casadi_fatrop_prob<T1>* p = d->prob;
543  return p->nu[k];
544 }
545 
546 // SYMBOL "fatrop_get_ng"
547 template<typename T1>
548 fatrop_int casadi_fatrop_get_ng(const fatrop_int k, void* user_data) {
549  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
550  int ret;
551  fatrop_int n_a_eq = d->a_eq_idx[k+1]-d->a_eq_idx[k];
552  fatrop_int n_x_eq = d->x_eq_idx[k+1]-d->x_eq_idx[k];
553 
554  ret = n_a_eq+n_x_eq;
555 
556  /* printf("d->a_eq_idx[k] %lld\n", d->a_eq_idx[k]);
557  printf("d->a_eq_idx[k+1] %lld\n", d->a_eq_idx[k+1]);
558  printf("d->x_eq_idx[k] %lld\n", d->x_eq_idx[k]);
559  printf("d->x_eq_idx[k+1] %lld\n", d->x_eq_idx[k+1]);
560 
561 
562  printf("get_ng %d\n", ret);*/
563  return ret;
564 }
565 
566 
567 // SYMBOL "fatrop_get_horizon_length"
568 template<typename T1>
569 fatrop_int casadi_fatrop_get_horizon_length(void* user_data) {
570  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
571 
572  //printf("horizon_length %lld\n", d->prob->N+1);
573  return d->prob->N+1;
574 }
575 
576 // SYMBOL "fatrop_get_ng_ineq"
577 template<typename T1>
578 fatrop_int casadi_fatrop_get_ng_ineq(const fatrop_int k, void* user_data) {
579  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
580  fatrop_int n_a_ineq = d->a_ineq_idx[k+1]-d->a_ineq_idx[k];
581  fatrop_int n_x_ineq = d->x_ineq_idx[k+1]-d->x_ineq_idx[k];
582  //printf("get_ng_ineq %d\n", n_a_ineq+n_x_ineq);
583  return n_a_ineq+n_x_ineq;
584 }
585 
586 // SYMBOL "fatrop_get_bounds"
587 template<typename T1>
588 fatrop_int casadi_fatrop_get_bounds(double *lower, double *upper, const fatrop_int k, void* user_data) {
589  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
590  const casadi_fatrop_prob<T1>* p = d->prob;
591  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
592 
593  casadi_int nx = p->nlp->nx;
594 
595  int i=0;
596  int column = 0;
597  for (i=d->a_ineq_idx[k];i<d->a_ineq_idx[k+1];++i) {
598  lower[column] = d_nlp->lbz[nx+d->a_ineq[i]];
599  upper[column] = d_nlp->ubz[nx+d->a_ineq[i]];
600  column++;
601  }
602 
603  for (i=d->x_ineq_idx[k];i<d->x_ineq_idx[k+1];++i) {
604  lower[column] = d_nlp->lbz[d->x_ineq[i]];
605  upper[column] = d_nlp->ubz[d->x_ineq[i]];
606  column++;
607  }
608 
609  return 0;
610 }
611 
612 // SYMBOL "fatrop_get_initial_xk"
613 template<typename T1>
614 fatrop_int casadi_fatrop_get_initial_xk(double *xk, const fatrop_int k, void* user_data) {
615  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
616  const casadi_fatrop_prob<T1>* p = d->prob;
617  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
618  //printf("casadi_fatrop_get_initial_xk offset %lld %e\n",p->CD[k].offset_c,d_nlp->z[p->CD[k].offset_c]);
619  casadi_copy(d_nlp->z+p->CD[k].offset_c, p->nx[k], xk);
620 
621  return 0;
622 }
623 
624 // SYMBOL "fatrop_get_initial_uk"
625 template<typename T1>
626 fatrop_int casadi_fatrop_get_initial_uk(double *uk, const fatrop_int k, void* user_data) {
627  casadi_fatrop_data<T1>* d = static_cast< casadi_fatrop_data<T1>* >(user_data);
628  const casadi_fatrop_prob<T1>* p = d->prob;
629  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
630  casadi_copy(d_nlp->z+p->CD[k].offset_c+p->nx[k], p->nu[k], uk);
631  return 0;
632 }
633 
634 
635 // SYMBOL "fatrop_work"
636 template<typename T1>
637 void casadi_fatrop_work(const casadi_fatrop_prob<T1>* p, casadi_int* sz_arg, casadi_int* sz_res, casadi_int* sz_iw, casadi_int* sz_w) {
638  casadi_nlpsol_work(p->nlp, sz_arg, sz_res, sz_iw, sz_w);
639 
640  // Temporary work vectors
641  *sz_w = casadi_max(*sz_w, 2*(p->nlp->nx+p->nlp->ng)); // pv
642 
643  // Persistent work vectors
644  *sz_w += casadi_sp_nnz(p->ABsp); // AB
645  *sz_w += casadi_sp_nnz(p->CDsp); // CD
646  *sz_w += casadi_sp_nnz(p->RSQsp); // RSQ
647  *sz_w += casadi_sp_nnz(p->Isp); // I
648  *sz_w += p->nlp->nx; // x
649  *sz_w += p->nlp->nx+p->nlp->ng; // lam
650  *sz_w += casadi_sp_nnz(p->sp_a); // a
651  *sz_w += casadi_sp_nnz(p->sp_h); // h
652  *sz_w += casadi_max(p->nlp->nx,p->nlp->ng); // g
653  *sz_w += blasfeo_memsize_dvec(p->nxu_max+1)+64; // v p->nx[k]+p->nu[k]+1
654  *sz_w += blasfeo_memsize_dvec(p->nx_max+p->nlp->ng)+64; // r p->nx[k+1]
655  *sz_w += blasfeo_memsize_dmat(p->nxu_max, p->nxu_max)+64; // r p->nx[k]+p->nx[u]
656 
657  *sz_iw += p->N+2; // a_eq_idx
658  *sz_iw += p->N+2; // a_ineq_idx
659  *sz_iw += p->N+2; // x_eq_idx
660  *sz_iw += p->N+2; // x_ineq_idx
661  *sz_iw += p->nlp->ng; // a_eq
662  *sz_iw += p->nlp->ng; // a_ineq
663  *sz_iw += p->nlp->nx; // x_eq
664  *sz_iw += p->nlp->nx; // x_ineq
665 
666 }
667 
668 // SYMBOL "fatrop_init"
669 template<typename T1>
670 void casadi_fatrop_init(casadi_fatrop_data<T1>* d, const T1*** arg, T1*** res, casadi_int** iw, T1** w) {
671  // Problem structure
672  const casadi_fatrop_prob<T1>* p = d->prob;
673  //casadi_oracle_data<T1>* d_oracle = d->nlp->oracle;
674  //const casadi_nlpsol_prob<T1>* p_nlp = p->nlp;
675 
676  //d->z_L = *w; *w += p_nlp->nx;
677  //d->z_U = *w; *w += p_nlp->nx;
678 
679  d->AB = *w; *w += casadi_sp_nnz(p->ABsp);
680  d->CD = *w; *w += casadi_sp_nnz(p->CDsp);
681  d->RSQ = *w; *w += casadi_sp_nnz(p->RSQsp);
682  d->I = *w; *w += casadi_sp_nnz(p->Isp);
683  d->x = *w; *w += p->nlp->nx;
684  d->lam = *w; *w += p->nlp->nx+p->nlp->ng;
685  d->a = *w; *w += casadi_sp_nnz(p->sp_a);
686  d->h = *w; *w += casadi_sp_nnz(p->sp_h);
687  d->g = *w; *w += casadi_max(p->nlp->nx,p->nlp->ng);
688  blasfeo_create_dvec(p->nxu_max+1, &d->v, (void*) (((unsigned long long) (*w)+63)/64*64));
689  *w += blasfeo_memsize_dvec(p->nxu_max+1)+64;
690  blasfeo_create_dvec(p->nx_max+p->nlp->ng, &d->r, (void*) (((unsigned long long) (*w)+63)/64*64));
691  *w += blasfeo_memsize_dvec(p->nx_max+p->nlp->ng)+64;
692  blasfeo_create_dmat(p->nxu_max, p->nxu_max, &d->R, (void*) (((unsigned long long) (*w)+63)/64*64));
693  *w += blasfeo_memsize_dmat(p->nxu_max, p->nxu_max)+64;
694 
695  d->a_eq_idx = *iw; *iw += p->N+2;
696  d->a_ineq_idx = *iw; *iw += p->N+2;
697  d->x_eq_idx = *iw; *iw += p->N+2;
698  d->x_ineq_idx = *iw; *iw += p->N+2;
699 
700  d->a_eq = *iw; *iw += p->nlp->ng;
701  d->a_ineq = *iw; *iw += p->nlp->ng;
702  d->x_eq = *iw; *iw += p->nlp->nx;
703  d->x_ineq = *iw; *iw += p->nlp->nx;
704 
705  d->pv = *w;
706 
707  d->arg = *arg;
708  d->res = *res;
709  d->iw = *iw;
710  d->w = *w;
711 }
712 
713 // C-REPLACE "casadi_fatrop_get_nx<T1>" "casadi_fatrop_get_nx"
714 // C-REPLACE "casadi_fatrop_get_nu<T1>" "casadi_fatrop_get_nu"
715 // C-REPLACE "casadi_fatrop_get_ng<T1>" "casadi_fatrop_get_ng"
716 // C-REPLACE "casadi_fatrop_get_ng_ineq<T1>" "casadi_fatrop_get_ng_ineq"
717 // C-REPLACE "casadi_fatrop_get_horizon_length<T1>" "casadi_fatrop_get_horizon_length"
718 // C-REPLACE "casadi_fatrop_get_bounds<T1>" "casadi_fatrop_get_bounds"
719 // C-REPLACE "casadi_fatrop_get_initial_xk<T1>" "casadi_fatrop_get_initial_xk"
720 // C-REPLACE "casadi_fatrop_get_initial_uk<T1>" "casadi_fatrop_get_initial_uk"
721 // C-REPLACE "casadi_fatrop_full_eval_constr_jac<T1>" "casadi_fatrop_full_eval_constr_jac"
722 // C-REPLACE "casadi_fatrop_full_eval_obj_grad<T1>" "casadi_fatrop_full_eval_obj_grad"
723 // C-REPLACE "casadi_fatrop_full_eval_obj<T1>" "casadi_fatrop_full_eval_obj"
724 // C-REPLACE "casadi_fatrop_full_eval_contr_viol<T1>" "casadi_fatrop_full_eval_contr_viol"
725 // C-REPLACE "casadi_fatrop_full_eval_lag_hess<T1>" "casadi_fatrop_full_eval_lag_hess"
726 // C-REPLACE "casadi_fatrop_eval_BAbt<T1>" "casadi_fatrop_eval_BAbt"
727 // C-REPLACE "casadi_fatrop_eval_RSQrqt<T1>" "casadi_fatrop_eval_RSQrqt"
728 // C-REPLACE "casadi_fatrop_eval_Ggt<T1>" "casadi_fatrop_eval_Ggt"
729 // C-REPLACE "casadi_fatrop_eval_Ggt_ineq<T1>" "casadi_fatrop_eval_Ggt_ineq"
730 
731 
732 // C-REPLACE "std::numeric_limits<T1>::infinity()" "casadi_inf"
733 
734 // SYMBOL "fatrop_presolve"
735 template<typename T1>
736 void casadi_fatrop_presolve(casadi_fatrop_data<T1>* d) {
737  casadi_int k, i, start, stop, nx;
738  // Problem structure
739  const casadi_fatrop_prob<T1>* p = d->prob;
740  const casadi_nlpsol_prob<T1>* p_nlp = p->nlp;
741  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
742  struct FatropOcpCInterface* ocp_interface = &d->ocp_interface;
743 
744  ocp_interface->get_nx = casadi_fatrop_get_nx<T1>;
745  ocp_interface->get_nu = casadi_fatrop_get_nu<T1>;
746  ocp_interface->get_ng = casadi_fatrop_get_ng<T1>;
747  ocp_interface->get_n_stage_params = 0;
748  ocp_interface->get_n_global_params = 0;
749  ocp_interface->get_default_stage_params = 0;
750  ocp_interface->get_default_global_params = 0;
751  ocp_interface->get_ng_ineq = casadi_fatrop_get_ng_ineq<T1>;
752  ocp_interface->get_horizon_length = casadi_fatrop_get_horizon_length<T1>;
753 
754  ocp_interface->get_bounds = casadi_fatrop_get_bounds<T1>;
755  ocp_interface->get_initial_xk = casadi_fatrop_get_initial_xk<T1>;
756  ocp_interface->get_initial_uk = casadi_fatrop_get_initial_uk<T1>;
757 
758  ocp_interface->full_eval_constr_jac = casadi_fatrop_full_eval_constr_jac<T1>;
759  ocp_interface->full_eval_obj_grad = casadi_fatrop_full_eval_obj_grad<T1>;
760  ocp_interface->full_eval_obj = casadi_fatrop_full_eval_obj<T1>;
761  ocp_interface->full_eval_contr_viol = casadi_fatrop_full_eval_contr_viol<T1>;
762  ocp_interface->full_eval_lag_hess = casadi_fatrop_full_eval_lag_hess<T1>;
763 
764  ocp_interface->eval_BAbt = casadi_fatrop_eval_BAbt<T1>;
765  ocp_interface->eval_RSQrqt = casadi_fatrop_eval_RSQrqt<T1>;
766  ocp_interface->eval_Ggt = casadi_fatrop_eval_Ggt<T1>;
767  ocp_interface->eval_Ggt_ineq = casadi_fatrop_eval_Ggt_ineq<T1>;
768  ocp_interface->eval_rq = 0; // Computed in full_eval_obj_grad
769  ocp_interface->eval_L = 0; // Computed in full_eval_obj
770 
771  nx = p_nlp->nx;
772 
773  d->a_eq_idx[0] = 0;
774  d->a_ineq_idx[0] = 0;
775  d->x_eq_idx[0] = 0;
776  d->x_ineq_idx[0] = 0;
777 
778  // Loop over CD blocks
779  for (k=0;k<p->N+1;++k) {
780  d->a_eq_idx[k+1] = d->a_eq_idx[k];
781  d->a_ineq_idx[k+1] = d->a_ineq_idx[k];
782  start = p->CD[k].offset_r;
783  stop = p->CD[k].offset_r+p->CD[k].rows;
784  for (i=start;i<stop;++i) {
785  if (d_nlp->lbz[nx+i]==d_nlp->ubz[nx+i]) {
786  d->a_eq[d->a_eq_idx[k+1]++] = i;
787  } else {
788  if (d_nlp->lbz[nx+i]==-std::numeric_limits<T1>::infinity() && d_nlp->ubz[nx+i]==std::numeric_limits<T1>::infinity()) continue;
789  d->a_ineq[d->a_ineq_idx[k+1]++] = i;
790  }
791  }
792  d->x_eq_idx[k+1] = d->x_eq_idx[k];
793  d->x_ineq_idx[k+1] = d->x_ineq_idx[k];
794  start = p->CD[k].offset_c;
795  stop = p->CD[k].offset_c+p->CD[k].cols;
796 
797  for (i=start;i<stop;++i) {
798  if (d_nlp->lbz[i]==d_nlp->ubz[i]) {
799  d->x_eq[d->x_eq_idx[k+1]++] = i;
800  } else {
801  if (d_nlp->lbz[i]==-std::numeric_limits<T1>::infinity() && d_nlp->ubz[i]==std::numeric_limits<T1>::infinity()) continue;
802  d->x_ineq[d->x_ineq_idx[k+1]++] = i;
803  }
804  }
805  }
806 
807  d->ocp_interface.user_data = d;
808 
809  d->solver = fatrop_ocp_c_create(&d->ocp_interface, p->write, p->flush);
810 }
811 
812 // SYMBOL "fatrop_ocp_c_solve"
813 template<typename T1>
814 void casadi_fatrop_solve(casadi_fatrop_data<T1>* d) {
815  // Problem structure
816  casadi_int k, i, column;
817  const casadi_fatrop_prob<T1>* p = d->prob;
818  const casadi_nlpsol_prob<T1>* p_nlp = p->nlp;
819  casadi_nlpsol_data<T1>* d_nlp = d->nlp;
820 
822  d->success = 0;
823 
824  fatrop_int ret = fatrop_ocp_c_solve(d->solver);
825 
826  d->return_status = ret;
827  if (ret==0) {
829  d->success = 1;
830  }
831 
832  if (ret==-1) {
834  }
835 
836  const struct blasfeo_dvec* primal = fatrop_ocp_c_get_primal(d->solver);
837  const struct blasfeo_dvec* dual = fatrop_ocp_c_get_dual(d->solver);
838  const struct FatropOcpCDims* str = fatrop_ocp_c_get_dims(d->solver);
839  const struct FatropOcpCStats* stats = fatrop_ocp_c_get_stats(d->solver);
840 
841  d->stats.compute_sd_time = stats->compute_sd_time;
842  d->stats.duinf_time = stats->duinf_time;
843  d->stats.eval_hess_time = stats->eval_hess_time;
844  d->stats.eval_jac_time = stats->eval_jac_time;
845  d->stats.eval_cv_time = stats->eval_cv_time;
846  d->stats.eval_grad_time = stats->eval_grad_time;
847  d->stats.eval_obj_time = stats->eval_obj_time;
848  d->stats.initialization_time = stats->initialization_time;
849  d->stats.time_total = stats->time_total;
850  d->stats.eval_hess_count = stats->eval_hess_count;
851  d->stats.eval_jac_count = stats->eval_jac_count;
852  d->stats.eval_cv_count = stats->eval_cv_count;
853  d->stats.eval_grad_count = stats->eval_grad_count;
854  d->stats.eval_obj_count = stats->eval_obj_count;
855  d->stats.iterations_count = stats->iterations_count;
856  d->stats.return_flag = stats->return_flag;
857 
858  const double* primal_data = primal->pa;
859  const double* dual_data = dual->pa;
860 
861  casadi_fatrop_read_primal_data(primal_data, d_nlp->z, str);
862  // Unpack dual solution
863  // Inequalities
864  for (k=0;k<str->K;++k) {
865  column = 0;
866  for (i=d->a_ineq_idx[k];i<d->a_ineq_idx[k+1];++i) {
867  d_nlp->lam[p_nlp->nx+d->a_ineq[i]] = dual_data[str->g_ineq_offs[k]+column];
868  column++;
869  }
870  for (i=d->x_ineq_idx[k];i<d->x_ineq_idx[k+1];++i) {
871  d_nlp->lam[d->x_ineq[i]] = dual_data[str->g_ineq_offs[k]+column];
872  column++;
873  }
874  }
875  // Equalities
876  for (k=0;k<str->K;++k) {
877  column = 0;
878  for (i=d->a_eq_idx[k];i<d->a_eq_idx[k+1];++i) {
879  d_nlp->lam[p_nlp->nx+d->a_eq[i]] = dual_data[str->g_offs[k]+column];
880  column++;
881  }
882  for (i=d->x_eq_idx[k];i<d->x_eq_idx[k+1];++i) {
883  d_nlp->lam[d->x_eq[i]] = dual_data[str->g_offs[k]+column];
884  column++;
885  }
886  }
887  // Dynamics
888  for (k=0;k<str->K-1;++k) {
889  casadi_scaled_copy(-1.0, dual_data+str->dyn_eq_offs[k], p->nx[k+1], d_nlp->lam+p_nlp->nx+p->AB[k].offset_r);
890  }
891 
892  fatrop_ocp_c_destroy(d->solver);
893 
894 }
@ SOLVER_RET_SUCCESS
@ SOLVER_RET_UNKNOWN
@ SOLVER_RET_EXCEPTION
const casadi_fatrop_prob< T1 > * prob
struct blasfeo_dmat R
casadi_int * a_ineq_idx
struct FatropOcpCStats stats
struct FatropOcpCInterface ocp_interface
casadi_nlpsol_data< T1 > * nlp
struct blasfeo_dvec v r
casadi_int * x_ineq_idx
struct FatropOcpCSolver * solver
OracleCallback nlp_grad_f
const casadi_int * I_offsets
const casadi_int * sp_h
const casadi_int * ng
const casadi_int * nx
const casadi_int * RSQsp
OracleCallback nlp_hess_l
FatropOcpCWrite write
const casadi_int * nu
casadi_ocp_block * I
const casadi_int * sp_a
FatropOcpCFlush flush
casadi_ocp_block * AB
const casadi_int * CDsp
OracleCallback nlp_g
casadi_ocp_block * RSQ
const casadi_int * RSQ_offsets
casadi_ocp_block * CD
const casadi_int * CD_offsets
const casadi_int * Isp
const casadi_nlpsol_prob< T1 > * nlp
OracleCallback nlp_f
OracleCallback nlp_jac_g
const casadi_int * ABsp
const casadi_int * AB_offsets
casadi_oracle_data< T1 > * oracle
Definition: casadi_nlp.hpp:76