25 #include "fatrop_conic_interface.hpp"
29 #include <fatrop_conic_runtime_str.h>
35 int CASADI_CONIC_FATROP_EXPORT
38 plugin->name =
"fatrop";
40 plugin->version = CASADI_VERSION;
51 const std::map<std::string, Sparsity>& st)
66 "Number of states, length N+1"}},
69 "Number of controls, length N"}},
72 "Number of non-dynamic constraints, length N+1"}},
73 {
"structure_detection",
75 "NONE | auto | manual"}},
78 "Options to be passed to fatrop"}}}
84 casadi_int struct_cnt=0;
88 for (
auto&& op : opts) {
92 }
else if (op.first==
"nx") {
95 }
else if (op.first==
"nu") {
98 }
else if (op.first==
"ng") {
101 }
else if (op.first==
"structure_detection") {
102 std::string v = op.second;
105 }
else if (v==
"manual") {
107 }
else if (v==
"none") {
110 casadi_error(
"Unknown option for structure_detection: '" + v +
"'.");
116 casadi_assert(struct_cnt==4,
117 "You must set all of N, nx, nu, ng.");
125 "You must set structure_detection to 'manual' if you set N, nx, nu, ng.");
129 const std::vector<int>& nx =
nxs_;
130 const std::vector<int>& ng =
ngs_;
131 const std::vector<int>& nu =
nus_;
133 Sparsity lamg_csp_, lam_ulsp_, lam_uusp_, lam_xlsp_, lam_xusp_, lam_clsp_;
143 std::vector<casadi_int> A_skyline;
144 std::vector<casadi_int> A_skyline2;
145 std::vector<casadi_int> A_bottomline;
146 for (casadi_int i=0;i<AT.
size2();++i) {
147 casadi_int pivot = AT.
colind()[i+1];
148 A_bottomline.push_back(AT.
row()[AT.
colind()[i]]);
149 if (pivot>AT.
colind()[i]) {
150 A_skyline.push_back(AT.
row()[pivot-1]);
151 if (pivot>AT.
colind()[i]+1) {
152 A_skyline2.push_back(AT.
row()[pivot-2]);
154 A_skyline2.push_back(-1);
157 A_skyline.push_back(-1);
158 A_skyline2.push_back(-1);
167 casadi_int pivot = 0;
168 casadi_int start_pivot = pivot;
170 for (casadi_int i=0;i<
na_;++i) {
172 if (A_skyline[i]>pivot+1) {
173 nus_.push_back(A_skyline[i]-pivot-1);
175 }
else if (A_skyline[i]==pivot+1) {
176 if (A_skyline2[i]<start_pivot) {
187 nxs_.push_back(pivot-start_pivot+1);
188 ngs_.push_back(cg); cg=0;
189 start_pivot = A_skyline[i];
190 pivot = A_skyline[i];
193 nxs_.push_back(pivot-start_pivot+1);
196 nxs_[0] = A_skyline[0];
200 for (casadi_int i=
na_-1;i>=0;--i) {
201 if (A_bottomline[i]<start_pivot)
break;
204 ngs_.push_back(cg-cN);
208 uout() <<
"nus" <<
nus_.size() <<
"nxs" <<
nxs_.size() << std::endl;
220 casadi_message(
"Using structure: N " +
str(
N_) +
", nx " +
str(nx) +
", "
221 "nu " +
str(nu) +
", ng " +
str(ng) +
".");
231 casadi_int offset_r = 0, offset_c = 0;
232 for (casadi_int k=0;k<
N_;++k) {
233 AB_blocks.push_back({offset_r, offset_c, nx[k+1], nx[k]+nu[k]});
234 CD_blocks.push_back({offset_r+nx[k+1], offset_c, ng[k], nx[k]+nu[k]});
235 offset_c+= nx[k]+nu[k];
237 I_blocks.push_back({offset_r, offset_c, nx[k+1], nx[k+1]});
243 I_blocks.push_back({offset_r, offset_c, nx[k+1], nx[k+1]});
244 offset_r+= nx[k+1]+ng[k];
248 casadi_int offset = 0;
251 offset += e.rows*e.cols;
257 offset += e.rows*e.cols;
267 casadi_assert((
A_ + total).nnz() == total.
nnz(),
268 "HPIPM: specified structure of A does not correspond to what the interface can handle. "
269 "Structure is: N " +
str(
N_) +
", nx " +
str(nx) +
", nu " +
str(nu) +
", "
270 "ng " +
str(ng) +
".");
282 for (casadi_int k=0;k<
N_+1;++k) {
283 RSQ_blocks.push_back({offset, offset, nx[k]+nu[k], nx[k]+nu[k]});
284 offset+= nx[k]+nu[k];
291 offset += e.rows*e.cols;
307 casadi_int* iw,
double* w)
const {
312 size_t N = blocks.size();
313 std::vector<casadi_int> ret(4*N);
315 for (casadi_int i=0;i<N;++i) {
316 *r++ = blocks[i].offset_r;
317 *r++ = blocks[i].offset_c;
318 *r++ = blocks[i].rows;
319 *r++ = blocks[i].cols;
338 casadi_fatrop_conic_setup(&
p_);
346 m->add_stat(
"solver");
347 m->add_stat(
"postprocessing");
353 casadi_int*& iw,
double*& w)
const {
364 casadi_fatrop_conic_set_work(&m->d, &arg, &res, &iw, &w);
373 stats[
"iter_count"] = m->d.iter_count;
384 const std::vector<casadi_ocp_block>& blocks,
bool eye) {
386 for (
auto && b : blocks) {
388 r(
range(b.offset_r, b.offset_r+b.rows),
389 range(b.offset_c, b.offset_c+b.cols)) =
DM::eye(b.rows);
390 casadi_assert_dev(b.rows==b.cols);
392 r(
range(b.offset_r, b.offset_r+b.rows),
393 range(b.offset_c, b.offset_c+b.cols)) =
DM::zeros(b.rows, b.cols);
399 const std::vector<casadi_ocp_block>& blocks,
bool eye) {
400 casadi_int N = blocks.size();
403 for (casadi_int k=0;k<N;++k) {
406 casadi_assert_dev(blocks[k].rows==blocks[k].cols);
407 offset+=blocks[k].rows;
409 offset+=blocks[k].rows*blocks[k].cols;
415 s.
version(
"FatropConicInterface", 1);
421 s.
version(
"FatropConicInterface", 1);
424 typedef struct FatropUserData {
429 fatrop_int
get_nx(
const fatrop_int k,
void* user_data) {
430 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
431 const auto& solver = *data->solver;
432 if (k==solver.nxs_.size())
return solver.nxs_[k-1];
433 return solver.nxs_[k];
436 fatrop_int
get_nu(
const fatrop_int k,
void* user_data) {
437 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
438 const auto& solver = *data->solver;
439 return solver.nus_[k];
442 fatrop_int
get_ng(
const fatrop_int k,
void* user_data) {
443 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
444 auto d = &data->mem->d;
446 fatrop_int n_a_eq = d->a_eq_idx[k+1]-d->a_eq_idx[k];
447 fatrop_int n_x_eq = d->x_eq_idx[k+1]-d->x_eq_idx[k];
470 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
471 auto d = &data->mem->d;
472 fatrop_int n_a_ineq = d->a_ineq_idx[k+1]-d->a_ineq_idx[k];
473 fatrop_int n_x_ineq = d->x_ineq_idx[k+1]-d->x_ineq_idx[k];
474 return n_a_ineq+n_x_ineq;
478 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
479 return data->solver->N_+1;
482 fatrop_int
eval_BAbt(
const double *states_kp1,
const double *inputs_k,
483 const double *states_k,
const double *stage_params_k,
484 const double *global_params, MAT *res,
const fatrop_int k,
void* user_data) {
485 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
491 blasfeo_pack_tran_dmat(p->nx[k+1], p->nx[k],
492 d->AB+p->AB_offsets[k], p->nx[k+1], res, p->nu[k], 0);
493 blasfeo_pack_tran_dmat(p->nx[k+1], p->nu[k],
494 d->AB+p->AB_offsets[k]+p->nx[k]*p->nx[k+1], p->nx[k+1], res, 0, 0);
495 blasfeo_pack_dmat(1, p->nx[k+1],
const_cast<double*
>(d_qp->
lba+p->AB[k].offset_r),
496 1, res, p->nx[k]+p->nu[k], 0);
499 blasfeo_allocate_dvec(p->nx[k]+p->nu[k]+1, &v);
500 blasfeo_allocate_dvec(p->nx[k+1], &r);
502 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(inputs_k), 1, &v, 0);
503 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(states_k), 1, &v, p->nu[k]);
504 blasfeo_pack_dvec(1, &one, 1, &v, p->nu[k]+p->nx[k]);
506 blasfeo_dgemv_t(p->nx[k]+p->nu[k]+1, p->nx[k+1], 1.0, res, 0, 0,
511 std::vector<double> mem(p->nx[k+1]);
512 blasfeo_unpack_dvec(p->nx[k+1], &r, 0,
get_ptr(mem), 1);
515 for (
int i=0;i<p->nx[k+1];++i) {
516 mem[i] -= states_kp1[i];
520 blasfeo_pack_dmat(1, p->nx[k+1],
get_ptr(mem), 1, res, p->nx[k]+p->nu[k], 0);
522 blasfeo_free_dvec(&v);
523 blasfeo_free_dvec(&r);
530 const double *inputs_k,
531 const double *states_k,
532 const double *stage_params_k,
533 const double *global_params,
535 const fatrop_int k,
void* user_data) {
536 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
538 casadi_int i, column;
544 int n_a_eq = d->a_eq_idx[k+1]-d->a_eq_idx[k];
545 int n_x_eq = d->x_eq_idx[k+1]-d->x_eq_idx[k];
546 int ng_eq = n_a_eq+n_x_eq;
548 blasfeo_dgese(p->nx[k]+p->nu[k]+1, ng_eq, 0.0, res, 0, 0);
551 for (i=d->a_eq_idx[k];i<d->a_eq_idx[k+1];++i) {
552 blasfeo_pack_tran_dmat(1, p->nx[k],
553 d->CD+p->CD_offsets[k]+(d->a_eq[i]-p->CD[k].offset_r),
554 p->CD[k].rows, res, p->nu[k], column);
555 blasfeo_pack_tran_dmat(1, p->nu[k],
556 d->CD+p->CD_offsets[k]+(d->a_eq[i]-p->CD[k].offset_r)+p->nx[k]*p->CD[k].rows,
557 p->CD[k].rows, res, 0, column);
558 double v = -d_qp->
lba[d->a_eq[i]];
559 blasfeo_pack_tran_dmat(1, 1, &v, 1, res, p->nx[k]+p->nu[k], column);
562 for (i=d->x_eq_idx[k];i<d->x_eq_idx[k+1];++i) {
563 int j = d->x_eq[i]-p->CD[k].offset_c;
569 blasfeo_pack_tran_dmat(1, 1, &one, 1, res, j, column);
570 double v = -d_qp->
lbx[d->x_eq[i]];
571 blasfeo_pack_tran_dmat(1, 1, &v, 1, res, p->nx[k]+p->nu[k], column);
577 blasfeo_allocate_dvec(p->nx[k]+p->nu[k]+1, &v);
578 blasfeo_allocate_dvec(ng_eq, &r);
580 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(inputs_k), 1, &v, 0);
581 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(states_k), 1, &v, p->nu[k]);
582 blasfeo_pack_dvec(1, &one, 1, &v, p->nu[k]+p->nx[k]);
584 blasfeo_dgemv_t(p->nx[k]+p->nu[k]+1, ng_eq, 1.0, res, 0, 0,
589 std::vector<double> mem(ng_eq);
590 blasfeo_unpack_dvec(ng_eq, &r, 0,
get_ptr(mem), 1);
592 blasfeo_pack_dmat(1, ng_eq,
get_ptr(mem), 1, res, p->nx[k]+p->nu[k], 0);
594 blasfeo_free_dvec(&v);
595 blasfeo_free_dvec(&r);
601 const double *inputs_k,
602 const double *states_k,
603 const double *stage_params_k,
604 const double *global_params,
606 const fatrop_int k,
void* user_data) {
607 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
609 casadi_int i, column;
616 int n_a_ineq = d->a_ineq_idx[k+1]-d->a_ineq_idx[k];
617 int n_x_ineq = d->x_ineq_idx[k+1]-d->x_ineq_idx[k];
618 int ng_ineq = n_a_ineq+n_x_ineq;
620 blasfeo_dgese(p->nx[k]+p->nu[k]+1, ng_ineq, 0.0, res, 0, 0);
623 for (i=d->a_ineq_idx[k];i<d->a_ineq_idx[k+1];++i) {
624 blasfeo_pack_tran_dmat(1, p->nx[k],
625 d->CD+p->CD_offsets[k]+(d->a_ineq[i]-p->CD[k].offset_r),
626 p->CD[k].rows, res, p->nu[k], column);
627 blasfeo_pack_tran_dmat(1, p->nu[k],
628 d->CD+p->CD_offsets[k]+(d->a_ineq[i]-p->CD[k].offset_r)+p->nx[k]*p->CD[k].rows,
629 p->CD[k].rows, res, 0, column);
630 blasfeo_pack_tran_dmat(1, 1, &zero, 1, res, p->nx[k]+p->nu[k], column);
633 for (i=d->x_ineq_idx[k];i<d->x_ineq_idx[k+1];++i) {
634 int j = d->x_ineq[i]-p->CD[k].offset_c;
640 blasfeo_pack_tran_dmat(1, 1, &one, 1, res, j, column);
641 blasfeo_pack_tran_dmat(1, 1, &zero, 1, res, p->nx[k]+p->nu[k], column);
647 blasfeo_allocate_dvec(p->nx[k]+p->nu[k]+1, &v);
648 blasfeo_allocate_dvec(ng_ineq, &r);
650 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(inputs_k), 1, &v, 0);
651 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(states_k), 1, &v, p->nu[k]);
652 blasfeo_pack_dvec(1, &zero, 1, &v, p->nu[k]+p->nx[k]);
654 blasfeo_dgemv_t(p->nx[k]+p->nu[k]+1, ng_ineq, 1.0, res, 0, 0,
658 std::vector<double> mem(ng_ineq);
659 blasfeo_unpack_dvec(ng_ineq, &r, 0,
get_ptr(mem), 1);
661 blasfeo_pack_dmat(1, ng_ineq,
get_ptr(mem), 1, res, p->nx[k]+p->nu[k], 0);
663 blasfeo_free_dvec(&v);
664 blasfeo_free_dvec(&r);
670 const double *objective_scale,
671 const double *inputs_k,
672 const double *states_k,
673 const double *lam_dyn_k,
674 const double *lam_eq_k,
675 const double *lam_eq_ineq_k,
676 const double *stage_params_k,
677 const double *global_params,
679 const fatrop_int k,
void* user_data) {
680 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
682 const auto& solver = *data->solver;
683 casadi_assert_dev(*objective_scale==1);
688 int n = p->nx[k]+p->nu[k];
689 blasfeo_pack_dmat(p->nx[k], p->nx[k],
690 d->RSQ+p->RSQ_offsets[k], n, res, p->nu[k], p->nu[k]);
691 blasfeo_pack_dmat(p->nu[k], p->nu[k],
692 d->RSQ+p->RSQ_offsets[k]+p->nx[k]*n+p->nx[k], n, res, 0, 0);
693 blasfeo_pack_dmat(p->nu[k], p->nx[k],
694 d->RSQ+p->RSQ_offsets[k]+p->nx[k], n, res, 0, p->nu[k]);
695 blasfeo_pack_dmat(p->nx[k], p->nu[k],
696 d->RSQ+p->RSQ_offsets[k]+p->nx[k]*n, n, res, p->nu[k], 0);
698 blasfeo_pack_dmat(1, p->nx[k],
const_cast<double*
>(d_qp->
g+p->RSQ[k].offset_r),
699 1, res, p->nu[k]+p->nx[k], p->nu[k]);
700 blasfeo_pack_dmat(1, p->nu[k],
const_cast<double*
>(d_qp->
g+p->RSQ[k].offset_r+p->nx[k]),
701 1, res, p->nu[k]+p->nx[k], 0);
704 blasfeo_allocate_dvec(n, &v);
705 blasfeo_allocate_dvec(p->nx[k]+p->nu[k], &r);
707 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(inputs_k), 1, &v, 0);
708 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(states_k), 1, &v, p->nu[k]);
710 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(d_qp->
g+p->RSQ[k].offset_r),
712 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(d_qp->
g+p->RSQ[k].offset_r+p->nx[k]),
715 blasfeo_dgemv_n(n, n, 1.0, res, 0, 0,
720 int n_a_eq = d->a_eq_idx[k+1]-d->a_eq_idx[k];
721 int n_x_eq = d->x_eq_idx[k+1]-d->x_eq_idx[k];
722 int ng_eq = n_a_eq+n_x_eq;
723 int n_a_ineq = d->a_ineq_idx[k+1]-d->a_ineq_idx[k];
724 int n_x_ineq = d->x_ineq_idx[k+1]-d->x_ineq_idx[k];
725 int ng_ineq = n_a_ineq+n_x_ineq;
727 bool last_k = k==solver.N_;
729 blasfeo_dvec lam_dyn, lam_g, lam_g_ineq;
730 blasfeo_dmat BAbtk, Ggtk, Ggt_ineqk;
732 blasfeo_allocate_dvec(p->nx[k+1], &lam_dyn);
733 blasfeo_allocate_dvec(ng_eq, &lam_g);
734 blasfeo_allocate_dvec(ng_ineq, &lam_g_ineq);
736 blasfeo_allocate_dmat(p->nx[k]+p->nu[k]+1, p->nx[k+1], &BAbtk);
737 blasfeo_allocate_dmat(p->nx[k]+p->nu[k]+1, ng_eq, &Ggtk);
738 blasfeo_allocate_dmat(p->nx[k]+p->nu[k]+1, ng_ineq, &Ggt_ineqk);
741 eval_BAbt(0, inputs_k, states_k, stage_params_k, global_params, &BAbtk, k, user_data);
742 eval_Ggt(inputs_k, states_k, stage_params_k, global_params, &Ggtk, k, user_data);
743 eval_Ggt_ineq(inputs_k, states_k, stage_params_k, global_params, &Ggt_ineqk, k, user_data);
746 blasfeo_pack_dvec(p->nx[k+1],
const_cast<double*
>(lam_dyn_k), 1, &lam_dyn, 0);
747 blasfeo_pack_dvec(ng_eq,
const_cast<double*
>(lam_eq_k), 1, &lam_g, 0);
748 blasfeo_pack_dvec(ng_ineq,
const_cast<double*
>(lam_eq_ineq_k), 1, &lam_g_ineq, 0);
751 blasfeo_dgemv_n(p->nx[k]+p->nu[k], p->nx[k+1], 1.0, &BAbtk, 0, 0,
756 blasfeo_dgemv_n(p->nx[k]+p->nu[k], ng_eq, 1.0, &Ggtk, 0, 0,
761 blasfeo_dgemv_n(p->nx[k]+p->nu[k], ng_ineq, 1.0, &Ggt_ineqk, 0, 0,
766 std::vector<double> mem(p->nx[k]+p->nu[k]);
767 blasfeo_unpack_dvec(p->nx[k]+p->nu[k], &r, 0,
get_ptr(mem), 1);
769 blasfeo_pack_dmat(1, p->nx[k]+p->nu[k],
const_cast<double*
>(
get_ptr(mem)),
770 1, res, p->nu[k]+p->nx[k], 0);
774 blasfeo_free_dmat(&BAbtk);
775 blasfeo_free_dmat(&Ggtk);
776 blasfeo_free_dmat(&Ggt_ineqk);
777 blasfeo_free_dvec(&r);
779 blasfeo_free_dvec(&lam_dyn);
780 blasfeo_free_dvec(&lam_g);
781 blasfeo_free_dvec(&lam_g_ineq);
782 blasfeo_free_dvec(&v);
788 const double *states_kp1,
789 const double *inputs_k,
790 const double *states_k,
791 const double *stage_params_k,
792 const double *global_params,
794 const fatrop_int k,
void* user_data) {
795 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
801 blasfeo_allocate_dmat(p->nx[k]+p->nu[k]+1, p->nx[k+1], &BAbtk);
802 eval_BAbt(states_kp1, inputs_k, states_k, stage_params_k, global_params, &BAbtk, k, user_data);
803 blasfeo_unpack_dmat(1, p->nx[k+1], &BAbtk, p->nx[k]+p->nu[k], 0, res, 1);
804 blasfeo_free_dmat(&BAbtk);
811 const double *states_k,
812 const double *inputs_k,
813 const double *stage_params_k,
814 const double *global_params,
816 const fatrop_int k,
void* user_data) {
817 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
823 int n_a_eq = d->a_eq_idx[k+1]-d->a_eq_idx[k];
824 int n_x_eq = d->x_eq_idx[k+1]-d->x_eq_idx[k];
825 int ng_eq = n_a_eq+n_x_eq;
828 blasfeo_allocate_dmat(p->nx[k]+p->nu[k]+1, ng_eq, &Ggtk);
829 eval_Ggt(states_k, inputs_k, stage_params_k, global_params, &Ggtk, k, user_data);
830 blasfeo_unpack_dmat(1, ng_eq, &Ggtk, p->nx[k]+p->nu[k], 0, res, 1);
831 blasfeo_free_dmat(&Ggtk);
837 const double *states_k,
838 const double *inputs_k,
839 const double *stage_params_k,
840 const double *global_params,
842 const fatrop_int k,
void* user_data) {
843 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
848 int n_a_ineq = d->a_ineq_idx[k+1]-d->a_ineq_idx[k];
849 int n_x_ineq = d->x_ineq_idx[k+1]-d->x_ineq_idx[k];
850 int ng_ineq = n_a_ineq+n_x_ineq;
854 blasfeo_allocate_dmat(p->nx[k]+p->nu[k]+1, ng_ineq, &Ggtk);
855 eval_Ggt_ineq(states_k, inputs_k, stage_params_k, global_params, &Ggtk, k, user_data);
856 blasfeo_unpack_dmat(1, ng_ineq, &Ggtk, p->nx[k]+p->nu[k], 0, res, 1);
857 blasfeo_free_dmat(&Ggtk);
863 const double *objective_scale,
864 const double *inputs_k,
865 const double *states_k,
866 const double *stage_params_k,
867 const double *global_params,
869 const fatrop_int k,
void* user_data) {
870 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
873 casadi_assert_dev(*objective_scale==1);
877 blasfeo_dmat RSQrqtk;
879 int n = p->nx[k]+p->nu[k];
882 blasfeo_allocate_dmat(n, n, &RSQrqtk);
883 blasfeo_allocate_dvec(n, &v);
884 blasfeo_allocate_dvec(n, &r);
885 blasfeo_pack_dmat(p->nx[k], p->nx[k], d->RSQ+p->RSQ_offsets[k],
886 n, &RSQrqtk, p->nu[k], p->nu[k]);
887 blasfeo_pack_dmat(p->nu[k], p->nu[k], d->RSQ+p->RSQ_offsets[k]+p->nx[k]*n+p->nx[k],
889 blasfeo_pack_dmat(p->nu[k], p->nx[k], d->RSQ+p->RSQ_offsets[k]+p->nx[k],
890 n, &RSQrqtk, 0, p->nu[k]);
891 blasfeo_pack_dmat(p->nx[k], p->nu[k], d->RSQ+p->RSQ_offsets[k]+p->nx[k]*n,
892 n, &RSQrqtk, p->nu[k], 0);
895 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(inputs_k), 1, &v, 0);
896 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(states_k), 1, &v, p->nu[k]);
898 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(d_qp->
g+p->RSQ[k].offset_r), 1, &r, p->nu[k]);
899 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(d_qp->
g+p->RSQ[k].offset_r+p->nx[k]), 1, &r, 0);
901 blasfeo_dgemv_n(n, n, 1.0, &RSQrqtk, 0, 0,
906 blasfeo_unpack_dvec(n, &r, 0, res, 1);
908 blasfeo_free_dmat(&RSQrqtk);
909 blasfeo_free_dvec(&v);
910 blasfeo_free_dvec(&r);
916 const double *objective_scale,
917 const double *inputs_k,
918 const double *states_k,
919 const double *stage_params_k,
920 const double *global_params,
922 const fatrop_int k,
void* user_data) {
923 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
926 casadi_assert_dev(*objective_scale==1);
930 blasfeo_dmat RSQrqtk;
932 int n = p->nx[k]+p->nu[k];
935 blasfeo_allocate_dmat(n, n, &RSQrqtk);
936 blasfeo_allocate_dvec(n, &v);
937 blasfeo_allocate_dvec(n, &r);
938 blasfeo_pack_dmat(p->nx[k], p->nx[k], d->RSQ+p->RSQ_offsets[k],
939 n, &RSQrqtk, p->nu[k], p->nu[k]);
940 blasfeo_pack_dmat(p->nu[k], p->nu[k], d->RSQ+p->RSQ_offsets[k]+p->nx[k]*n+p->nx[k],
942 blasfeo_pack_dmat(p->nu[k], p->nx[k], d->RSQ+p->RSQ_offsets[k]+p->nx[k],
943 n, &RSQrqtk, 0, p->nu[k]);
944 blasfeo_pack_dmat(p->nx[k], p->nu[k], d->RSQ+p->RSQ_offsets[k]+p->nx[k]*n,
945 n, &RSQrqtk, p->nu[k], 0);
948 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(inputs_k), 1, &v, 0);
949 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(states_k), 1, &v, p->nu[k]);
951 blasfeo_dgemv_n(n, n, 1.0, &RSQrqtk, 0, 0,
956 double obj = 0.5*blasfeo_ddot(n, &v, 0, &r, 0);
958 blasfeo_pack_dvec(p->nx[k],
const_cast<double*
>(d_qp->
g+p->RSQ[k].offset_r),
960 blasfeo_pack_dvec(p->nu[k],
const_cast<double*
>(d_qp->
g+p->RSQ[k].offset_r+p->nx[k]),
963 obj += blasfeo_ddot(n, &v, 0, &r, 0);
965 blasfeo_free_dmat(&RSQrqtk);
966 blasfeo_free_dvec(&v);
967 blasfeo_free_dvec(&r);
974 fatrop_int
get_bounds(
double *lower,
double *upper,
const fatrop_int k,
void* user_data) {
975 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
982 for (i=d->a_ineq_idx[k];i<d->a_ineq_idx[k+1];++i) {
983 lower[column] = d_qp->
lba[d->a_ineq[i]];
984 upper[column] = d_qp->
uba[d->a_ineq[i]];
988 for (i=d->x_ineq_idx[k];i<d->x_ineq_idx[k+1];++i) {
989 lower[column] = d_qp->
lbx[d->x_ineq[i]];
990 upper[column] = d_qp->
ubx[d->x_ineq[i]];
1002 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
1013 FatropUserData* data =
static_cast<FatropUserData*
>(user_data);
1018 casadi_copy(d_qp->
x0+p->CD[k].offset_c+p->nx[k], p->nu[k], uk);
1027 const double* primal_data,
const double* lam_data,
1028 const double* stageparams_p,
const double* globalparams_p,
1029 MAT * RSQrqt_p,
const FatropOcpCDims* s,
void* user_data) {
1034 const double* stageparams_p,
const double* globalparams_p,
1035 MAT* BAbt_p, MAT* Ggt_p, MAT* Ggt_ineq_p,
const FatropOcpCDims* s,
void* user_data) {
1040 const double* stageparams_p,
const double* globalparams_p,
1041 double* cv_p,
const FatropOcpCDims* s,
void* user_data) {
1046 const double* stageparams_p,
const double* globalparams_p,
1047 double* grad_p,
const FatropOcpCDims* s,
void* user_data) {
1052 const double* stageparams_p,
const double* globalparams_p,
1053 double* res,
const FatropOcpCDims* s,
void* user_data) {
1059 solve(
const double** arg,
double** res, casadi_int* iw,
double* w,
void* mem)
const {
1063 casadi_fatrop_conic_solve(&m->d, arg, res, iw, w);
1066 m->fstats.at(
"solver").tic();
1068 FatropOcpCInterface ocp_interface;
1069 ocp_interface.get_nx =
get_nx;
1070 ocp_interface.get_nu =
get_nu;
1071 ocp_interface.get_ng =
get_ng;
1082 ocp_interface.eval_b =
eval_b;
1083 ocp_interface.eval_g =
eval_g;
1085 ocp_interface.eval_rq =
eval_rq;
1086 ocp_interface.eval_L =
eval_L;
1096 FatropUserData user_data;
1097 user_data.solver =
this;
1100 ocp_interface.user_data = &user_data;
1102 uout() <<
"ocp_interface" << ocp_interface.get_horizon_length << std::endl;
1105 FatropOcpCSolver* s = fatrop_ocp_c_create(&ocp_interface, 0, 0);
1106 fatrop_ocp_c_set_option_bool(s,
"accept_every_trial_step",
false);
1108 int ret = fatrop_ocp_c_solve(s);
1110 uout() <<
"ret" << ret << std::endl;
1113 m->d_qp.success =
false;
1114 m->d.return_status =
"failed";
1119 const blasfeo_dvec* primal = fatrop_ocp_c_get_primal(s);
1121 const blasfeo_dvec* dual = fatrop_ocp_c_get_dual(s);
1128 casadi_int offset_fatrop = 0;
1129 casadi_int offset_casadi = 0;
1130 for (
int k=0;k<
N_+1;++k) {
1131 blasfeo_unpack_dvec(p->nu[k],
const_cast<blasfeo_dvec*
>(primal),
1132 offset_fatrop, d_qp->
x+offset_casadi+p->nx[k], 1);
1133 offset_fatrop += p->nu[k];
1134 blasfeo_unpack_dvec(p->nx[k],
const_cast<blasfeo_dvec*
>(primal),
1135 offset_fatrop, d_qp->
x+offset_casadi, 1);
1136 offset_fatrop += p->nx[k];
1137 offset_casadi += p->nx[k]+p->nu[k];
1140 blasfeo_print_dvec(offset_casadi,
const_cast<blasfeo_dvec*
>(primal), 0);
1142 m->d_qp.success =
true;
1144 m->d.return_status =
"solved";
1146 std::vector<double> dualv(
nx_+
na_);
1147 blasfeo_unpack_dvec(
nx_+
na_,
const_cast<blasfeo_dvec*
>(dual), 0,
get_ptr(dualv), 1);
1152 for (
int k=0;k<
N_+1;++k) {
1153 for (casadi_int i=d->a_eq_idx[k];i<d->a_eq_idx[k+1];++i) {
1154 d_qp->
lam_a[d->a_eq[i]] = dualv[offset_fatrop++];
1156 for (casadi_int i=d->x_eq_idx[k];i<d->x_eq_idx[k+1];++i) {
1157 d_qp->
lam_x[d->x_eq[i]] = dualv[offset_fatrop++];
1161 for (
int k=0;k<
N_;++k) {
1162 for (casadi_int i=0;i<p->nx[k];++i) {
1167 for (
int k=0;k<
N_+1;++k) {
1168 for (casadi_int i=d->a_ineq_idx[k];i<d->a_ineq_idx[k+1];++i) {
1169 d_qp->
lam_a[d->a_ineq[i]] = dualv[offset_fatrop++];
1171 for (casadi_int i=d->x_ineq_idx[k];i<d->x_ineq_idx[k+1];++i) {
1172 d_qp->
lam_x[d->x_ineq[i]] = dualv[offset_fatrop++];
1180 m->fstats.at(
"solver").toc();
1187 fatrop_ocp_c_destroy(s);
static const Options options_
Options.
casadi_int nx_
Number of decision variables.
int init_mem(void *mem) const override
Initalize memory block.
casadi_int na_
The number of constraints (counting both equality and inequality) == A.size1()
void init(const Dict &opts) override
Initialize.
void serialize_body(SerializingStream &s) const override
Serialize an object without type information.
void set_work(void *mem, const double **&arg, double **&res, casadi_int *&iw, double *&w) const override
Set the (persistent) work vectors.
Dict get_stats(void *mem) const override
Get all statistics.
casadi_qp_prob< double > p_qp_
Helper class for Serialization.
void version(const std::string &name, int v)
'fatrop' plugin for Conic
FatropConicInterface()
Constructor.
static const std::string meta_doc
A documentation string.
std::vector< casadi_ocp_block > CD_blocks
std::vector< casadi_ocp_block > AB_blocks
std::vector< casadi_int > CD_offsets_
int solve(const double **arg, double **res, casadi_int *iw, double *w, void *mem) const override
Evaluate numerically.
casadi_fatrop_conic_prob< double > p_
structure_detection structure_detection_
std::vector< casadi_int > AB_offsets_
void init(const Dict &opts) override
Initialize.
Dict get_stats(void *mem) const override
Get all statistics.
static Sparsity blocksparsity(casadi_int rows, casadi_int cols, const std::vector< casadi_ocp_block > &blocks, bool eye=false)
static const Options options_
Options.
~FatropConicInterface() override
Destructor.
static Conic * creator(const std::string &name, const std::map< std::string, Sparsity > &st)
Create a new QP Solver.
void set_fatrop_conic_prob()
void set_work(void *mem, const double **&arg, double **&res, casadi_int *&iw, double *&w) const override
Set the (persistent) work vectors.
std::vector< casadi_ocp_block > RSQ_blocks
static void blockptr(std::vector< double * > &vs, std::vector< double > &v, const std::vector< casadi_ocp_block > &blocks, bool eye=false)
void set_temp(void *mem, const double **arg, double **res, casadi_int *iw, double *w) const override
Set the (temporary) work vectors.
int init_mem(void *mem) const override
Initalize memory block.
void serialize_body(SerializingStream &s) const override
Serialize an object without type information.
std::vector< casadi_int > RSQ_offsets_
std::vector< casadi_ocp_block > I_blocks
void alloc_iw(size_t sz_iw, bool persistent=false)
Ensure required length of iw field.
void alloc_res(size_t sz_res, bool persistent=false)
Ensure required length of res field.
void alloc_arg(size_t sz_arg, bool persistent=false)
Ensure required length of arg field.
size_t sz_res() const
Get required length of res field.
size_t sz_w() const
Get required length of w field.
void alloc_w(size_t sz_w, bool persistent=false)
Ensure required length of w field.
size_t sz_arg() const
Get required length of arg field.
size_t sz_iw() const
Get required length of iw field.
static MatType zeros(casadi_int nrow=1, casadi_int ncol=1)
Create a dense matrix or a matrix with specified sparsity with all entries zero.
const Sparsity & sparsity() const
Const access the sparsity - reference to data member.
static Matrix< double > eye(casadi_int n)
create an n-by-n identity matrix
static void registerPlugin(const Plugin &plugin, bool needs_lock=true)
Register an integrator in the factory.
bool verbose_
Verbose printout.
void clear_mem()
Clear all memory (called from destructor)
Helper class for Serialization.
void version(const std::string &name, int v)
Sparsity T() const
Transpose the matrix.
casadi_int nnz() const
Get the number of (structural) non-zeros.
casadi_int size2() const
Get the number of columns.
const casadi_int * row() const
Get a reference to row-vector,.
const casadi_int * colind() const
Get a reference to the colindex of all column element (see class description)
void CASADI_CONIC_FATROP_EXPORT casadi_load_conic_fatrop()
void dummy_signal(void *user_data)
std::vector< casadi_int > range(casadi_int start, casadi_int stop, casadi_int step, casadi_int len)
Range function.
fatrop_int get_initial_uk(double *uk, const fatrop_int k, void *user_data)
fatrop_int get_horizon_length(void *user_data)
std::vector< casadi_int > fatrop_blocks_pack(const std::vector< casadi_ocp_block > &blocks)
fatrop_int full_eval_constr_jac(const double *primal_data, const double *stageparams_p, const double *globalparams_p, MAT *BAbt_p, MAT *Ggt_p, MAT *Ggt_ineq_p, const FatropOcpCDims *s, void *user_data)
fatrop_int get_nu(const fatrop_int k, void *user_data)
fatrop_int get_ng_ineq(const fatrop_int k, void *user_data)
fatrop_int eval_BAbt(const double *states_kp1, const double *inputs_k, const double *states_k, const double *stage_params_k, const double *global_params, MAT *res, const fatrop_int k, void *user_data)
fatrop_int get_n_global_params(void *user_data)
void casadi_copy(const T1 *x, casadi_int n, T1 *y)
COPY: y <-x.
fatrop_int full_eval_lag_hess(double objective_scale, const double *primal_data, const double *lam_data, const double *stageparams_p, const double *globalparams_p, MAT *RSQrqt_p, const FatropOcpCDims *s, void *user_data)
fatrop_int eval_RSQrqt(const double *objective_scale, const double *inputs_k, const double *states_k, const double *lam_dyn_k, const double *lam_eq_k, const double *lam_eq_ineq_k, const double *stage_params_k, const double *global_params, MAT *res, const fatrop_int k, void *user_data)
fatrop_int eval_Ggt(const double *inputs_k, const double *states_k, const double *stage_params_k, const double *global_params, MAT *res, const fatrop_int k, void *user_data)
fatrop_int eval_gineq(const double *states_k, const double *inputs_k, const double *stage_params_k, const double *global_params, double *res, const fatrop_int k, void *user_data)
fatrop_int eval_L(const double *objective_scale, const double *inputs_k, const double *states_k, const double *stage_params_k, const double *global_params, double *res, const fatrop_int k, void *user_data)
std::string str(const T &v)
String representation, any type.
fatrop_int full_eval_obj(double objective_scale, const double *primal_data, const double *stageparams_p, const double *globalparams_p, double *res, const FatropOcpCDims *s, void *user_data)
fatrop_int get_ng(const fatrop_int k, void *user_data)
GenericType::Dict Dict
C++ equivalent of Python's dict or MATLAB's struct.
fatrop_int full_eval_contr_viol(const double *primal_data, const double *stageparams_p, const double *globalparams_p, double *cv_p, const FatropOcpCDims *s, void *user_data)
fatrop_int eval_Ggt_ineq(const double *inputs_k, const double *states_k, const double *stage_params_k, const double *global_params, MAT *res, const fatrop_int k, void *user_data)
fatrop_int eval_b(const double *states_kp1, const double *inputs_k, const double *states_k, const double *stage_params_k, const double *global_params, double *res, const fatrop_int k, void *user_data)
fatrop_int full_eval_obj_grad(double objective_scale, const double *primal_data, const double *stageparams_p, const double *globalparams_p, double *grad_p, const FatropOcpCDims *s, void *user_data)
int CASADI_CONIC_FATROP_EXPORT casadi_register_conic_fatrop(Conic::Plugin *plugin)
fatrop_int eval_rq(const double *objective_scale, const double *inputs_k, const double *states_k, const double *stage_params_k, const double *global_params, double *res, const fatrop_int k, void *user_data)
T * get_ptr(std::vector< T > &v)
Get a pointer to the data contained in the vector.
fatrop_int get_nx(const fatrop_int k, void *user_data)
fatrop_int eval_g(const double *states_k, const double *inputs_k, const double *stage_params_k, const double *global_params, double *res, const fatrop_int k, void *user_data)
fatrop_int get_default_global_params(double *global_params, void *user_data)
fatrop_int get_n_stage_params(const fatrop_int k, void *user_data)
fatrop_int get_initial_xk(double *xk, const fatrop_int k, void *user_data)
fatrop_int get_default_stage_params(double *stage_params, const fatrop_int k, void *user_data)
fatrop_int get_bounds(double *lower, double *upper, const fatrop_int k, void *user_data)
casadi_fatrop_conic_data< double > d
FatropConicMemory()
Constructor.
~FatropConicMemory()
Destructor.
Options metadata for a class.
void add_stat(const std::string &s)
const char * return_status
const casadi_int * AB_offsets
const casadi_int * RSQ_offsets
const casadi_int * CD_offsets
const casadi_qp_prob< T1 > * qp